From 7180a3bc900536afd805a6773652ee2d5b480647 Mon Sep 17 00:00:00 2001 From: Ross Hatton Date: Wed, 21 Dec 2016 16:40:03 -0500 Subject: [PATCH 001/286] Expunged term height function from code, fixed gui size problem on small monitors in recent matlab releases --- ...RE_local_connection_from_curvature_bases.m | 2 +- ProgramFiles/sys_calcpath_fcns/find_g.m | 2 +- ProgramFiles/sys_calcpath_fcns/find_loci.m | 4 +- .../sys_calcpath_fcns/integrate_cBVI.m | 14 +- ProgramFiles/sys_calcsystem.m | 2 +- ...unctions.m => calc_constraint_curvature.m} | 56 ++-- .../sys_draw_fcns/{hfun_draw.m => CCF_draw.m} | 94 +++--- ProgramFiles/sys_draw_fcns/beta_draw.m | 8 +- ProgramFiles/sys_draw_fcns/dbeta_draw.m | 217 ++++++++++--- ProgramFiles/sys_draw_fcns/disp_draw.m | 46 +-- ProgramFiles/sys_draw_fcns/vfield_draw.m | 20 +- ProgramFiles/sys_draw_fcns/vfield_draw.m~ | 287 ++++++++++++++++++ ProgramFiles/sys_draw_fcns/xy_draw_helper.m | 2 - ProgramFiles/sysplotter.fig | Bin 145610 -> 150328 bytes .../sysplotter_gui_fcns/get_box_values.m | 2 +- .../initialize_plot_windows.m | 4 +- .../plotpushbutton_Callback.m | 6 +- 17 files changed, 595 insertions(+), 171 deletions(-) rename ProgramFiles/sys_calcsystem_fcns/{calc_height_functions.m => calc_constraint_curvature.m} (54%) rename ProgramFiles/sys_draw_fcns/{hfun_draw.m => CCF_draw.m} (75%) create mode 100644 ProgramFiles/sys_draw_fcns/vfield_draw.m~ diff --git a/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_curvature_bases.m b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_curvature_bases.m index a61502c..af679f3 100644 --- a/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_curvature_bases.m +++ b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_curvature_bases.m @@ -28,7 +28,7 @@ % Calculate the derivative of the local connection as it's built up along % the backbone - % Midpoint-tangent-frame force jacobian + % Convert velocity to local velocity gdot_to_xi_local = [cos(h(3)) sin(h(3)) 0; -sin(h(3)) cos(h(3)) 0; 0 0 1]; diff --git a/ProgramFiles/sys_calcpath_fcns/find_g.m b/ProgramFiles/sys_calcpath_fcns/find_g.m index eca28be..85dc480 100644 --- a/ProgramFiles/sys_calcpath_fcns/find_g.m +++ b/ProgramFiles/sys_calcpath_fcns/find_g.m @@ -3,7 +3,7 @@ % change in p over the system in s % Set the initial values of the integrals - n_dim = size(s.height,1); + n_dim = size(s.dA,1); % Iterate over the paths n_paths = length(p.phi_fun); diff --git a/ProgramFiles/sys_calcpath_fcns/find_loci.m b/ProgramFiles/sys_calcpath_fcns/find_loci.m index 3ff8558..a7f8877 100644 --- a/ProgramFiles/sys_calcpath_fcns/find_loci.m +++ b/ProgramFiles/sys_calcpath_fcns/find_loci.m @@ -14,14 +14,14 @@ n_dim = numel(s.grid.eval); % number of position dimensions - n_g = size(s.height,1); + n_g = size(s.dA,1); % cell array to hold evaluated loci for the paths p.phi_locus = cell(size(p.phi_def)); % List the functions on which to project the shape paths fields = fieldnames(s); - project_list = fields(strncmp('height',fields,6)); + project_list = fields(strncmpi('dA',fields,2)); %calculate path loci and generate useful forms of the gait function for i = 1:n_paths diff --git a/ProgramFiles/sys_calcpath_fcns/integrate_cBVI.m b/ProgramFiles/sys_calcpath_fcns/integrate_cBVI.m index 2c2a5c2..ebb20e0 100644 --- a/ProgramFiles/sys_calcpath_fcns/integrate_cBVI.m +++ b/ProgramFiles/sys_calcpath_fcns/integrate_cBVI.m @@ -2,7 +2,7 @@ % Integrate up the corrected body velocity integral % number of dimensions for the cBVI - n_g = size(s.height,1); + n_g = size(s.DA,1); cBVI = cell(size(p.phi_fun_full)); cBVI_opt = cBVI; @@ -26,7 +26,7 @@ cBVI{i} = polysign(X(:,1),X(:,2)) * arrayfun(@(j)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_corrected{j}, [2 1]),a,b,'cubic')... + permute(s.DA{j}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(:,1),'y',X(:,2))... ,struct('method','gauss','tol',1e-6))... ,(1:n_g)'); @@ -34,7 +34,7 @@ cBVI_opt{i} = polysign(X(:,1),X(:,2)) * arrayfun(@(j)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_optimized_corrected{j}, [2 1]),a,b,'cubic')... + permute(s.DA_optimized{j}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(:,1),'y',X(:,2))... ,struct('method','gauss','tol',1e-6))... ,(1:n_g)'); @@ -80,7 +80,7 @@ .* arrayfun(@(k)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_corrected{j}, [2 1]),a,b,'cubic')... + permute(s.DA{j}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(Triangulation(k,:),1)... ,'y',X(Triangulation(k,:),2))... ,struct('method','gauss','tol',1e-6)),(1:length(Triangulation))'),1)... @@ -92,7 +92,7 @@ .* arrayfun(@(k)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_optimized_corrected{j}, [2 1]),a,b,'cubic')... + permute(s.DA_optimized{j}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(Triangulation(k,:),1)... ,'y',X(Triangulation(k,:),2))... ,struct('method','gauss','tol',1e-6)),(1:length(Triangulation))'),1)... @@ -118,7 +118,7 @@ cBVI_section_original(:,j) = polysign(X(:,1),X(:,2)) * arrayfun(@(k)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_corrected{k}, [2 1]),a,b,'cubic')... + permute(s.DA{k}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(:,1),'y',X(:,2))... ,struct('method','gauss','tol',1e-6))... ,(1:n_g)'); @@ -126,7 +126,7 @@ cBVI_section_optimized(:,j) = polysign(X(:,1),X(:,2)) * arrayfun(@(k)... doubleintegral(... @(a,b) interp2(s.grid.eval{2},s.grid.eval{1},... - permute(s.height_optimized_corrected{k}, [2 1]),a,b,'cubic')... + permute(s.DA_optimized{k}, [2 1]),a,b,'cubic')... ,struct('type','polygon','x',X(:,1),'y',X(:,2))... ,struct('method','gauss','tol',1e-6))... ,(1:n_g)'); diff --git a/ProgramFiles/sys_calcsystem.m b/ProgramFiles/sys_calcsystem.m index ff59968..b896422 100644 --- a/ProgramFiles/sys_calcsystem.m +++ b/ProgramFiles/sys_calcsystem.m @@ -49,7 +49,7 @@ s = optimize_coordinate_choice(s); %Calculate the height functions from the connection - s = calc_height_functions(s); + s = calc_constraint_curvature(s); %Build a stretch function corresponding to the metric s = calc_stretch_functions(s); diff --git a/ProgramFiles/sys_calcsystem_fcns/calc_height_functions.m b/ProgramFiles/sys_calcsystem_fcns/calc_constraint_curvature.m similarity index 54% rename from ProgramFiles/sys_calcsystem_fcns/calc_height_functions.m rename to ProgramFiles/sys_calcsystem_fcns/calc_constraint_curvature.m index 3f45e94..5888b88 100644 --- a/ProgramFiles/sys_calcsystem_fcns/calc_height_functions.m +++ b/ProgramFiles/sys_calcsystem_fcns/calc_constraint_curvature.m @@ -1,10 +1,10 @@ -%Calculate the height functions from the connection -function s = calc_height_functions(s) +%Calculate the constraint curvature functions from the connection +function s = calc_constraint_curvature(s) %Apply to both raw and optimized connections Avec_names = {'','_optimized'}; - for i = 1:length(Avec_names); + for i = 1:length(Avec_names) %Extract the high density "eval" vector field vecfield = s.vecfield.eval.content.(['Avec' Avec_names{i}]); @@ -25,15 +25,15 @@ if n_col <= 3 - s.(['height' Avec_names{i}]) = cell(n_rows,(n_col^2 - n_col)/2); - s.(['height' Avec_names{i} '_corrected']) = cell(n_rows,(n_col^2 - n_col)/2); + s.(['dA' Avec_names{i}]) = cell(n_rows,(n_col^2 - n_col)/2); + s.(['DA' Avec_names{i}]) = cell(n_rows,(n_col^2 - n_col)/2); else % For dimensions not yet implemented. The 'return' skips over the processing that would break for string input - s.(['height' Avec_names{i}]) = 'Exterior derivative for n>3 not yet implemented'; - s.(['height' Avec_names{i} '_corrected']) = 'Exterior derivative for n>3 not yet implemented'; + s.(['dA' Avec_names{i}]) = 'Exterior derivative for n>3 not yet implemented'; + s.(['DA' Avec_names{i}]) = 'Exterior derivative for n>3 not yet implemented'; return @@ -74,13 +74,13 @@ = curl(grid{inputorder},vecfield_meshgrid{:}); %#ok % Convert the data back into ndgrid ordering - s.(['height' Avec_names{i}])(j,:) = cellfun(@(x) permute(x,inputorder),curlfield,'UniformOutput',false); + s.(['dA' Avec_names{i}])(j,:) = cellfun(@(x) permute(x,inputorder),curlfield,'UniformOutput',false); end % Duplicate the exterior derivative to initiate a % Lie-bracket corrected version - s.(['height' Avec_names{i} '_corrected']) = s.(['height' Avec_names{i}]); + s.(['DA' Avec_names{i}]) = s.(['dA' Avec_names{i}]); % Apply the lie bracket correction term correction = cell(n_rows,size(basis_ordering,1)); @@ -89,21 +89,21 @@ correction(:,k) = cellfun(@(x) x, se2_local_lie_bracket(vecfield(:,basis_ordering(k,1)),vecfield(:,basis_ordering(k,2))),'UniformOutput',false); end - s.(['height' Avec_names{i} '_corrected']) ... - = cellfun(@(x,y) x + y, s.(['height' Avec_names{i} '_corrected']), correction,'UniformOutput',false); + s.(['DA' Avec_names{i}]) ... + = cellfun(@(x,y) x + y, s.(['DA' Avec_names{i}]), correction,'UniformOutput',false); %%%%%%%%%% - % Get the percentage of the total height function contributed by - % the curl. First pair of lines calculates translational (using + % Get the percentage of the total constraint curvature contributed by + % the exterior_derivative. First pair of lines calculates translational (using % pythagorean sum of x and y components). Final line gets % rotational (which should always be 1 for SE(2)) - s.(['height' Avec_names{i} '_ratio']) =... - {(s.(['height' Avec_names{i}]){1}.^2+s.(['height' Avec_names{i}]){2}.^2).^(.5)... - ./(s.(['height' Avec_names{i} '_corrected']){1}.^2+s.(['height' Avec_names{i} '_corrected']){2}.^2).^(.5); - zeros(size(s.(['height' Avec_names{i}]){2})); + s.(['DA' Avec_names{i} '_ratio']) =... + {(s.(['dA' Avec_names{i}]){1}.^2+s.(['dA' Avec_names{i}]){2}.^2).^(.5)... + ./(s.(['DA' Avec_names{i}]){1}.^2+s.(['DA' Avec_names{i}]){2}.^2).^(.5); + zeros(size(s.(['dA' Avec_names{i}]){2})); % - s.(['height' Avec_names{i}]){3}./s.(['height' Avec_names{i} '_corrected']){3}}; + s.(['dA' Avec_names{i}]){3}./s.(['DA' Avec_names{i}]){3}}; @@ -114,28 +114,28 @@ for k = 1:numel(correction) temp = ... - arctan_scale_vector_fields({s.(['height' Avec_names{i}]){k}... - ,zeros(size(s.(['height' Avec_names{i}]){k}))}); + arctan_scale_vector_fields({s.(['dA' Avec_names{i}]){k}... + ,zeros(size(s.(['dA' Avec_names{i}]){k}))}); - s.(['height' Avec_names{i} '_scaled']){k,1} = temp{1}; + s.(['dA' Avec_names{i} '_scaled']){k,1} = temp{1}; temp = ... - arctan_scale_vector_fields({s.(['height' Avec_names{i} '_corrected']){k}... - , zeros(size(s.(['height' Avec_names{i}]){k}))}); %.* (1-s.vecfield.eval.singularities{1}); + arctan_scale_vector_fields({s.(['DA' Avec_names{i}]){k}... + , zeros(size(s.(['dA' Avec_names{i}]){k}))}); %.* (1-s.vecfield.eval.singularities{1}); - s.(['height' Avec_names{i} '_corrected_scaled']){k,1} = temp{1}; + s.(['DA' Avec_names{i} '_scaled']){k,1} = temp{1}; end - % Scale the height function nonconservative-to-total ratio values + % Scale the constraint curvature function nonconservative-to-total ratio values for k = 1:3 temp = ... - arctan_scale_vector_fields({s.(['height' Avec_names{i} '_ratio']){k}... - , zeros(size(s.(['height' Avec_names{i}]){k}))}); %.* (1-s.vecfield.eval.singularities{1}); + arctan_scale_vector_fields({s.(['DA' Avec_names{i} '_ratio']){k}... + , zeros(size(s.(['dA' Avec_names{i}]){k}))}); %.* (1-s.vecfield.eval.singularities{1}); - s.(['height' Avec_names{i} '_ratio_scaled']){k,1} = temp{1}; + s.(['DA' Avec_names{i} '_ratio_scaled']){k,1} = temp{1}; end diff --git a/ProgramFiles/sys_draw_fcns/hfun_draw.m b/ProgramFiles/sys_draw_fcns/CCF_draw.m similarity index 75% rename from ProgramFiles/sys_draw_fcns/hfun_draw.m rename to ProgramFiles/sys_draw_fcns/CCF_draw.m index 14bd2ba..0e40d0f 100644 --- a/ProgramFiles/sys_draw_fcns/hfun_draw.m +++ b/ProgramFiles/sys_draw_fcns/CCF_draw.m @@ -1,12 +1,12 @@ -function plot_info = hfun_draw(s,p,plot_info,sys,shch,resolution) -%Draw the height function +function plot_info = CCF_draw(s,p,plot_info,sys,shch,resolution) +%Draw the constraint curvature function %Get the configuration file, and extract the Colorpath configfile = './sysplotter_config'; load(configfile,'Colorset'); - %height function list - hfun_list = {'X','Y','T','Xopt','Yopt','Topt'}; + %constraint curvature function list + CCF_list = {'X','Y','T','Xopt','Yopt','Topt'}; %Ensure that there are figure axes to plot into, and create new windows %for those axes if necessary @@ -16,12 +16,12 @@ n_dim = numel(s.grid.eval); % get the number of position dimensions - n_g = numel(s.height); + n_g = numel(s.DA); %if there is a singularity, deal with it for display if s.singularity - hfun_addendum = '_scaled'; + CCF_addendum = '_scaled'; singularity_location = logical(sum(cat(3,s.vecfield.eval.singularities{:}),3)); %singularity_location = imdilate(singularity_location,[0 1 0;1 1 1;0 1 0]); @@ -31,7 +31,7 @@ else - hfun_addendum = ''; + CCF_addendum = ''; ztext = 'H'; @@ -39,22 +39,22 @@ %%%%% - %Height function drawing + %constraint curvature function drawing - %Extract the height function + %Extract the constraint curvature function - %choose which height function to plot - switch plot_info.hfuntype + %choose which constraint curvature function to plot + switch plot_info.CCFtype - case 'cH' + case 'DA' - H = cat(1,s.(['height_corrected' hfun_addendum])... - ,s.(['height_optimized_corrected' hfun_addendum])); + H = cat(1,s.(['DA' CCF_addendum])... + ,s.(['DA_optimized' CCF_addendum])); if n_dim == 2 - h1name = 'height_corrected'; - h2name = 'height_optimized_corrected'; + h1name = 'DA'; + h2name = 'DA_optimized'; h1 = cell(n_g,1); h2 = cell(n_g,1); @@ -63,7 +63,7 @@ for i = 1:numel(p.phi_locus) - for j = 1:numel(p.phi_locus_full{i}.height) + for j = 1:numel(p.phi_locus_full{i}.dA) h1{j}{i} = p.phi_locus_full{i}.(h1name){j}; h2{j}{i} = p.phi_locus_full{i}.(h2name){j}; @@ -78,15 +78,15 @@ end - case 'oH' + case 'dA' - H = cat(1,s.(['height' hfun_addendum])... - ,s.(['height_optimized' hfun_addendum])); + H = cat(1,s.(['dA' CCF_addendum])... + ,s.(['dA_optimized' CCF_addendum])); if n_dim == 2 - h1name = 'height'; - h2name = 'height_optimized'; + h1name = 'dA'; + h2name = 'dA_optimized'; h1 = cell(n_g,1); h2 = cell(n_g,1); @@ -94,7 +94,7 @@ if ~strcmp(shch,'null') for i = 1:numel(p.phi_locus) - for j = 1:numel(p.phi_locus_full{i}.height) + for j = 1:numel(p.phi_locus_full{i}.dA) h1{j}{i} = p.phi_locus_full{i}.(h1name){j}; h2{j}{i} = p.phi_locus_full{i}.(h2name){j}; @@ -109,19 +109,19 @@ end - case 'dH' + case 'LA' - H = cat(1,cellfun(@(x,y) x-y,s.(['height_corrected' hfun_addendum])... - ,s.(['height' hfun_addendum]),'UniformOutput',false)... - ,cellfun(@(x,y) x-y,s.(['height_optimized_corrected' hfun_addendum])... - ,s.(['height_optimized' hfun_addendum]),'UniformOutput',false)); + H = cat(1,cellfun(@(x,y) x-y,s.(['DA' CCF_addendum])... + ,s.(['dA' CCF_addendum]),'UniformOutput',false)... + ,cellfun(@(x,y) x-y,s.(['DA_optimized' CCF_addendum])... + ,s.(['dA_optimized' CCF_addendum]),'UniformOutput',false)); if n_dim == 2 - h1aname = 'height_corrected'; - h1bname = 'height'; - h2aname = 'height_optimized_corrected'; - h2bname = 'height_optimized'; + h1aname = 'DA'; + h1bname = 'dA'; + h2aname = 'DA_optimized'; + h2bname = 'dA_optimized'; h1 = cell(n_g,1); h2 = cell(n_g,1); @@ -129,7 +129,7 @@ if ~strcmp(shch,'null') for i = 1:numel(p.phi_locus) - for j = 1:numel(p.phi_locus_full{i}.height) + for j = 1:numel(p.phi_locus_full{i}.dA) h1{j}{i} = p.phi_locus_full{i}.(h1aname){j}-p.phi_locus_full{i}.(h1bname){j}; h2{j}{i} = p.phi_locus_full{i}.(h2aname){j}-p.phi_locus_full{i}.(h2bname){j}; @@ -144,7 +144,7 @@ end otherwise - error('Unknown height function type') + error('Unknown CCF function type') end @@ -157,12 +157,12 @@ %%%%% % If the shape coordinates should be transformed, make the conversion - % (multiply the height function by the inverse of the jacobian's + % (multiply the constraint curvature function by the inverse of the jacobian's % determinant) if plot_info.stretch - % Get the value by which to scale the height function + % Get the value by which to scale the constraint curvature function ascale = arrayfun(@(x,y) 1/det(s.convert.jacobian(x,y)),grid{:}); % Apply the jacobian to the vectors @@ -183,8 +183,8 @@ %call up the relevant axis ax =plot_info.axes(i); - %get which height function to use - function_number = strcmp(plot_info.components{i}, hfun_list); + %get which constraint curvature function to use + function_number = strcmp(plot_info.components{i}, CCF_list); switch plot_info.style @@ -196,7 +196,7 @@ % % end - %Plot the height function + %Plot the constraint curvature function meshhandle = surf(ax,grid{:},H{function_number}); @@ -223,7 +223,7 @@ case 'contour' - %Plot the height function + %Plot the constraint curvature function [junk, meshhandle] = contour(ax,grid{:},H{function_number},7,'linewidth',2); %If there's a shape change involved, plot it @@ -269,7 +269,7 @@ otherwise - error('Unknown plot style for the height function') + error('Unknown plot style for the constraint curvature function') end @@ -318,9 +318,9 @@ %build a plot_info structure for just the current plot plot_info_specific.axes = 'new'; plot_info_specific.components = plot_info.components(i); - plot_info_specific.category = 'hfun'; + plot_info_specific.category = 'CCF'; plot_info_specific.style = plot_info.style; - plot_info_specific.hfuntype = plot_info.hfuntype; + plot_info_specific.CCFtype = plot_info.CCFtype; plot_info_specific.stretch = plot_info.stretch; %set the button down callback on the plot to be sys_draw with @@ -331,20 +331,20 @@ else - set(get(ax,'Parent'),'Name',[hfun_list{function_number} ' Height Function']) + set(get(ax,'Parent'),'Name',[CCF_list{function_number} ' Constraint Curvature Function']) - %Mark this figure as a height function + %Mark this figure as a constraint curvature function udata = get(plot_info.figure(i),'UserData'); switch plot_info.style case 'surface' - udata.plottype = 'hfun-surface'; + udata.plottype = 'CCF-surface'; case 'contour' - udata.plottype = 'hfun-contour'; + udata.plottype = 'CCF-contour'; end diff --git a/ProgramFiles/sys_draw_fcns/beta_draw.m b/ProgramFiles/sys_draw_fcns/beta_draw.m index 0413276..b4d65d9 100644 --- a/ProgramFiles/sys_draw_fcns/beta_draw.m +++ b/ProgramFiles/sys_draw_fcns/beta_draw.m @@ -20,7 +20,7 @@ n_dim = numel(s.grid.eval); % get the number of position dimensions - n_g = numel(s.height); + n_g = numel(s.dA); % Set up the zdata for the plot if ~strcmp(shch,'null') @@ -197,7 +197,7 @@ plot_info_specific.components = plot_info.components(i); plot_info_specific.category = 'beta'; plot_info_specific.style = plot_info.style; - plot_info_specific.hfuntype = plot_info.hfuntype; + plot_info_specific.CCFtype = plot_info.CCFtype; plot_info_specific.stretch = plot_info.stretch; %set the button down callback on the plot to be sys_draw with @@ -214,11 +214,11 @@ case 'surface' - udata.plottype = 'hfun-surface'; + udata.plottype = 'CCF-surface'; case 'contour' - udata.plottype = 'hfun-contour'; + udata.plottype = 'CCF-contour'; end diff --git a/ProgramFiles/sys_draw_fcns/dbeta_draw.m b/ProgramFiles/sys_draw_fcns/dbeta_draw.m index ffe2136..4425d53 100644 --- a/ProgramFiles/sys_draw_fcns/dbeta_draw.m +++ b/ProgramFiles/sys_draw_fcns/dbeta_draw.m @@ -3,10 +3,12 @@ %Vector field list vfield_list = {'X','Y','T'}; + % Get the number of dimensions + n_dim = numel(s.grid.eval); + %Ensure that there are figure axes to plot into, and create new windows %for those axes if necessary - plot_info = ensure_figure_axes(plot_info); - + plot_info = ensure_figure_axes(plot_info); %%% %put vector field commands here @@ -20,12 +22,20 @@ %% % Convert the vector field to the plotting grid specified in the gui [V,grid] = plotting_interp(V,grid,resolution,'vector'); + + % Create a set of vector fields along coordinate directions + V_coord = repmat({zeros(size(V{1}))},numel(grid)); + for i = 1:numel(grid) + V_coord{i,i} = ones(size(V{1})); + + end + %%%%% % If the shape coordinates should be transformed, make the conversion % (multiply the vectors by the inverse jacobian) - if ~isempty(s.convert) + if plot_info.stretch % Calculate the jacobians at the plotting points Jac = arrayfun(s.convert.jacobian,grid{:},'UniformOutput',false); @@ -33,53 +43,175 @@ % Use the jacobians to convert the vectors % Iterate over all connection vector fields present - for i = 1:size(V,1) + for i = 1:size(V,1) % Iterate over all vectors present - for j = 1:numel(V{i,1}) + for j = 1:numel(V{i,1}) % Extract all components of the relevant vector tempVin = cellfun(@(x) x(j),V(i,:)); - % Multiply by the inverse Jacobian + % Multiply by the inverse Jacobian (because V is a + % gradient, not a flow) tempVout = Jac{j}\tempVin(:); % Replace vector components - for k = 1:size(V,2) + for k = 1:size(V,2) V{i,k}(j) = tempVout(k); - end + end - end + end + - end + end + + - % Convert the grid points to their new locations + % Use the jacobians to convert the coordinate vectors in accordance + % with the stretch transformation + + % Iterate over all coordinate vector fields present + for i = 1:size(V_coord,1) + + % Iterate over all vectors present + for j = 1:numel(V_coord{i,1}) + + % Extract all components of the relevant vector + tempVin = cellfun(@(x) x(j),V_coord(i,:)); + + % Multiply by the Jacobian (because V_coord is a flow) + tempVout = Jac{j}*tempVin(:); + + % Replace vector components + for k = 1:size(V_coord,2) + + V_coord{i,k}(j) = tempVout(k); + + end + + end + + + end + + % Rotate the coordinate vectors to get normals + V_norm = repmat({zeros(size(V{1}))},numel(grid)); + if numel(grid) == 2 + + V_norm = {V_coord{2,2} -V_coord{2,1}; + -V_coord{1,2} V_coord{1,1}}; + + elseif numel(grid) == 3 + + V_norm = {V_coord{3,3} V_coord{3,2} -V_coord{3,1}; % z coord field around y + -V_coord{1,2} V_coord{1,1} -V_coord{1,3}; % x around z + V_coord{2,1} V_coord{2,3} -V_coord{2,2}}; % y around x + + else + warning('Rotations for >3 dimensions undefined in vfield_draw clipping of stretched vector field (add them if you need them) ') + + end + + % Convert the grid points to their new locations [grid{:}] = s.convert.old_to_new_points(grid{:}); - end + + %%%% + % Trim any vectors that go outside the boundary + + % Take the dot product of the connection vector fields and the + % normal vector fields + dprods = repmat({zeros(size(V_norm{1}))},size(V,1),size(V_norm,1)); + for i = 1:size(dprods,1) + + for j = 1:size(dprods,2) + + elementprods = cellfun(@(x,y) x.*y,V(i,:),V_norm(j,:),'UniformOutput',false); + + for k = 1:numel(elementprods) + + dprods{i,j} = dprods{i,j}+elementprods{k}; + + end + + end + + end + + % Create a cell array to hold the masking term + edgemask = repmat({zeros(size(V{1}))},size(V)); + + % Iterate along the rows of V (each row is one field) + for idxA = 1:size(V,1) + + % Iterate along the elements of dotprods in the corresponding row + % (each colum corresponds to the dot product of the current row of + % V with the then nth coordinate field + for idxB = 1:size(dprods,2) + + % Identify the index sets that correspond to the first and last + % elements along this direction of the grid + indices_start = [repmat({':'},1,idxB-1), {1}, repmat({':'},1,size(V,2)-idxB)]; + indices_end = [repmat({':'},1,idxB-1), {size(V{1},idxB)}, repmat({':'},1,size(V,2)-idxB)]; + + % Find all vectors that point out + V_test_start = dprods{idxA,idxB} < 0; + V_test_end = dprods{idxA,idxB} > 0; + + % Take the start and end indices values from the test boolean + edgemask{idxA,idxB}(indices_start{:}) = V_test_start(indices_start{:}); + edgemask{idxA,idxB}(indices_end{:}) = V_test_end(indices_end{:}); + + end + + % Combine all the edgemasks for a field into a single mask + + edgemask_merged = zeros(size(edgemask{1})); + for idxB = 1:size(V,2) + + edgemask_merged = edgemask_merged | edgemask{idxA,idxB}; + + end + + % Apply edgemask_merged to all the fields in this row of V + for idxB = 1:size(V,2) + + V{idxA,idxB}(edgemask_merged) = 0; + + end + end + end + %%% %If there's a singularity, use arctan scaling on the magnitude of the %vector field - if s.singularity + if s.singularity V = arctan_scale_vector_fields(V); - end - + end + + + + for i = 1:length(plot_info.axes) %call up the relevant axis ax = plot_info.axes(i); %get which vector field to use - field_number = strmatch(plot_info.components{i}, vfield_list,'exact'); - - %plot the vector field arrows - quiver(ax,grid{:},V{field_number,1},V{field_number,2},'k','LineWidth',2) + field_number = find(strcmp(plot_info.components{i}, vfield_list)); + %plot the vector field arrows + if n_dim == 2 + quiver(ax,grid{:},V{field_number,1},V{field_number,2},'k','LineWidth',2) + else + quiver3(ax,grid{1:3},V{field_number,:},'k','LineWidth',2) + end + % Make edges if coordinates have changed if plot_info.stretch @@ -92,35 +224,37 @@ [x_edge,y_edge] = s.convert.old_to_new_points(oldx_edge,oldy_edge); - l_edge = line('Parent',ax,'Xdata',x_edge,'YData',y_edge,'Color','k','LineWidth',1); + l_edge = line('Parent',ax,'Xdata',x_edge,'YData',y_edge,'Color','k','LineWidth',1); %#ok end + - %set the display range if plot_info.stretch - axis(ax,s.grid_range); - axis(ax,'square') + axis(ax,'equal'); + axis(ax,[min(grid{1}(:)) max(grid{1}(:)) min(grid{2}(:)) max(grid{2}(:))]); else - %square axes - axis(ax,'equal','tight') + axis(ax,'equal'); + end + %set the display range + if ~plot_info.stretch + axis(ax,s.grid_range); end %Label the axes (two-dimensional) - label_shapespace_axes(ax,[],~isempty(s.convert)); - + label_shapespace_axes(ax,[],plot_info.stretch); + %Set the tic marks set_tics_shapespace(ax,s,s.convert); %If there's a shape change involved, plot it if ~strcmp(shch,'null') - - overlay_shape_change_2d(ax,p,s.convert); + + overlay_shape_change_2d(ax,p,plot_info.stretch,s.convert); end - - %%%% + %%%% %Make clicking on the thumbnail open it larger in a new window if ~plot_info.own_figure @@ -128,27 +262,26 @@ %build a plot_info structure for just the current plot plot_info_specific.axes = 'new'; plot_info_specific.components = plot_info.components(i); - plot_info_specific.category = 'dbeta'; + plot_info_specific.category = 'vfield'; plot_info_specific.stretch = plot_info.stretch; - + %set the button down callback on the plot to be sys_draw with %the argument list for the current plot set(plot_info.axes(i),'ButtonDownFcn',{@sys_draw_dummy_callback,plot_info_specific,sys,shch}); else - set(get(ax(1),'Parent'),'Name',[vfield_list{field_number} ' dBeta Vector Field']) - - %Mark this figure as dbetas + set(get(ax(1),'Parent'),'Name',[vfield_list{field_number} ' Vector Field']) + + %Mark this figure as a vector field udata = get(plot_info.figure(i),'UserData'); - udata.plottype = 'dbeta'; + udata.plottype = 'vfield'; set(plot_info.figure(i),'UserData',udata); - - end + + + end end -end - - +end \ No newline at end of file diff --git a/ProgramFiles/sys_draw_fcns/disp_draw.m b/ProgramFiles/sys_draw_fcns/disp_draw.m index d346811..289b79c 100644 --- a/ProgramFiles/sys_draw_fcns/disp_draw.m +++ b/ProgramFiles/sys_draw_fcns/disp_draw.m @@ -6,27 +6,33 @@ load(configfile,'Colorset'); % define a color/linestyle list + linelist = {Colorset.spot, '-'; + Colorset.secondary, '--'; + 'k' ,':'; + Colorset.spot, '--'; + Colorset.secondary, ':'; + 'k' ,'-'}; - switch plot_info.linestyle - - case 'mono' - - linelist = {Colorset.spot, '-'}; - - case 'cycle' - - linelist = {Colorset.spot, '-'; - Colorset.secondary, '--'; - 'k' ,':'; - Colorset.spot, '--'; - Colorset.secondary, ':'; - 'k' ,'-'}; - - otherwise - - error('Unexpected value for plot_info.linestyle') - - end +% switch plot_info.linestyle +% +% case 'mono' +% +% linelist = {Colorset.spot, '-'}; +% +% case 'cycle' +% +% linelist = {Colorset.spot, '-'; +% Colorset.secondary, '--'; +% 'k' ,':'; +% Colorset.spot, '--'; +% Colorset.secondary, ':'; +% 'k' ,'-'}; +% +% otherwise +% +% error('Unexpected value for plot_info.linestyle') +% +% end % Number of position space dimensions n_dim = size(p.G_locus{1}{1}.G,2); diff --git a/ProgramFiles/sys_draw_fcns/vfield_draw.m b/ProgramFiles/sys_draw_fcns/vfield_draw.m index aa36aec..74aab61 100644 --- a/ProgramFiles/sys_draw_fcns/vfield_draw.m +++ b/ProgramFiles/sys_draw_fcns/vfield_draw.m @@ -43,10 +43,10 @@ % Use the jacobians to convert the vectors % Iterate over all connection vector fields present - for i = 1:size(V,1) + for i = 1:size(V,1) % Iterate over all vectors present - for j = 1:numel(V{i,1}) + for j = 1:numel(V{i,1}) % Extract all components of the relevant vector tempVin = cellfun(@(x) x(j),V(i,:)); @@ -56,11 +56,11 @@ tempVout = Jac{j}\tempVin(:); % Replace vector components - for k = 1:size(V,2) + for k = 1:size(V,2) V{i,k}(j) = tempVout(k); - end + end end @@ -73,10 +73,10 @@ % with the stretch transformation % Iterate over all coordinate vector fields present - for i = 1:size(V_coord,1) + for i = 1:size(V_coord,1) % Iterate over all vectors present - for j = 1:numel(V_coord{i,1}) + for j = 1:numel(V_coord{i,1}) % Extract all components of the relevant vector tempVin = cellfun(@(x) x(j),V_coord(i,:)); @@ -98,12 +98,12 @@ % Rotate the coordinate vectors to get normals V_norm = repmat({zeros(size(V{1}))},numel(grid)); - if numel(grid) == 2; + if numel(grid) == 2 V_norm = {V_coord{2,2} -V_coord{2,1}; -V_coord{1,2} V_coord{1,1}}; - elseif numel(grid) == 3; + elseif numel(grid) == 3 V_norm = {V_coord{3,3} V_coord{3,2} -V_coord{3,1}; % z coord field around y -V_coord{1,2} V_coord{1,1} -V_coord{1,3}; % x around z @@ -177,13 +177,13 @@ end % Apply edgemask_merged to all the fields in this row of V - for idxB = 1:size(V,2) + for idxB = 1:size(V,2) V{idxA,idxB}(edgemask_merged) = 0; end end - end + end %%% %If there's a singularity, use arctan scaling on the magnitude of the diff --git a/ProgramFiles/sys_draw_fcns/vfield_draw.m~ b/ProgramFiles/sys_draw_fcns/vfield_draw.m~ new file mode 100644 index 0000000..d888b62 --- /dev/null +++ b/ProgramFiles/sys_draw_fcns/vfield_draw.m~ @@ -0,0 +1,287 @@ +function plot_info = vfield_draw(s,p,plot_info,sys,shch,resolution) + + %Vector field list + vfield_list = {'X','Y','T','Xopt','Yopt','Topt'}; + + % Get the number of dimensions + n_dim = numel(s.grid.eval); + + %Ensure that there are figure axes to plot into, and create new windows + %for those axes if necessary + plot_info = ensure_figure_axes(plot_info); + + %%%%%%% + % Get the vector field and interpolate into the specified grid + + % Extract the display vector field + V = cat(1,s.vecfield.display.content.Avec,s.vecfield.display.content.Avec_optimized); + % Extract the plotting grid + grid = s.grid.vector; + + + %% + % Convert the vector field to the plotting grid specified in the gui + [V,grid] = plotting_interp(V,grid,resolution,'vector'); + + % Create a set of vector fields along coordinate directions + V_coord = repmat({zeros(size(V{1}))},numel(grid)); + for i = 1:numel(grid) + + V_coord{i,i} = ones(size(V{1})); + + end + + %%%%% + % If the shape coordinates should be transformed, make the conversion + % (multiply the vectors by the inverse jacobian) + + if plot_info.stretch + + % Calculate the jacobians at the plotting points + Jac = arrayfun(s.convert.jacobian,grid{:},'UniformOutput',false); + + % Use the jacobians to convert the vectors + + % Iterate over all connection vector fields present + for i = 1:size(V,1) + + % Iterate over all vectors present + for j = 1:numel(V{i,1}) + + % Extract all components of the relevant vector + tempVin = cellfun(@(x) x(j),V(i,:)); + + % Multiply by the inverse Jacobian (because V is a + % gradient, not a flow) + tempVout = Jac{j}\tempVin(:); + + % Replace vector components + for k = 1:size(V,2) + + V{i,k}(j) = tempVout(k); + + end + + end + + + end + + + + % Use the jacobians to convert the coordinate vectors in accordance + % with the stretch transformation + + % Iterate over all coordinate vector fields present + for i = 1:size(V_coord,1) + + % Iterate over all vectors present + for j = 1:numel(V_coord{i,1}) + + % Extract all components of the relevant vector + tempVin = cellfun(@(x) x(j),V_coord(i,:)); + + % Multiply by the Jacobian (because V_coord is a flow) + tempVout = Jac{j}*tempVin(:); + + % Replace vector components + for k = 1:size(V_coord,2) + + V_coord{i,k}(j) = tempVout(k); + + end + + end + + + end + + % Rotate the coordinate vectors to get normals + V_norm = repmat({zeros(size(V{1}))},numel(grid)); + if numel(grid) == 2; + + V_norm = {V_coord{2,2} -V_coord{2,1}; + -V_coord{1,2} V_coord{1,1}}; + + elseif numel(grid) == 3; + + V_norm = {V_coord{3,3} V_coord{3,2} -V_coord{3,1}; % z coord field around y + -V_coord{1,2} V_coord{1,1} -V_coord{1,3}; % x around z + V_coord{2,1} V_coord{2,3} -V_coord{2,2}}; % y around x + + else + warning('Rotations for >3 dimensions undefined in vfield_draw clipping of stretched vector field (add them if you need them) ') + + end + + % Convert the grid points to their new locations + [grid{:}] = s.convert.old_to_new_points(grid{:}); + + + + %%%% + % Trim any vectors that go outside the boundary + + % Take the dot product of the connection vector fields and the + % normal vector fields + dprods = repmat({zeros(size(V_norm{1}))},size(V,1),size(V_norm,1)); + for i = 1:size(dprods,1) + + for j = 1:size(dprods,2) + + elementprods = cellfun(@(x,y) x.*y,V(i,:),V_norm(j,:),'UniformOutput',false); + + for k = 1:numel(elementprods) + + dprods{i,j} = dprods{i,j}+elementprods{k}; + + end + + end + + end + + % Create a cell array to hold the masking term + edgemask = repmat({zeros(size(V{1}))},size(V)); + + % Iterate along the rows of V (each row is one field) + for idxA = 1:size(V,1) + + % Iterate along the elements of dotprods in the corresponding row + % (each colum corresponds to the dot product of the current row of + % V with the then nth coordinate field + for idxB = 1:size(dprods,2) + + % Identify the index sets that correspond to the first and last + % elements along this direction of the grid + indices_start = [repmat({':'},1,idxB-1), {1}, repmat({':'},1,size(V,2)-idxB)]; + indices_end = [repmat({':'},1,idxB-1), {size(V{1},idxB)}, repmat({':'},1,size(V,2)-idxB)]; + + % Find all vectors that point out + V_test_start = dprods{idxA,idxB} < 0; + V_test_end = dprods{idxA,idxB} > 0; + + % Take the start and end indices values from the test boolean + edgemask{idxA,idxB}(indices_start{:}) = V_test_start(indices_start{:}); + edgemask{idxA,idxB}(indices_end{:}) = V_test_end(indices_end{:}); + + end + + % Combine all the edgemasks for a field into a single mask + + edgemask_merged = zeros(size(edgemask{1})); + for idxB = 1:size(V,2) + + edgemask_merged = edgemask_merged | edgemask{idxA,idxB}; + + end + + % Apply edgemask_merged to all the fields in this row of V + for idxB = 1:size(V,2) + + V{idxA,idxB}(edgemask_merged) = 0; + + end + end + end + + %%% + %If there's a singularity, use arctan scaling on the magnitude of the + %vector field + if s.singularity + + V = arctan_scale_vector_fields(V); + + end + + + + + for i = 1:length(plot_info.axes) + + %call up the relevant axis + ax = plot_info.axes(i); + + %get which vector field to use + field_number = find(strcmp(plot_info.components{i}, vfield_list)); + + %plot the vector field arrows + if n_dim == 2 + quiver(ax,grid{:},V{field_number,1},V{field_number,2},'k','LineWidth',2) + else + quiver3(ax,grid{1:3},V{field_number,:},'k','LineWidth',2) + end + + % Make edges if coordinates have changed + if plot_info.stretch + + edgeres = 30; + + oldx_edge = [s.grid_range(1)*ones(edgeres,1);linspace(s.grid_range(1),s.grid_range(2),edgeres)';... + s.grid_range(2)*ones(edgeres,1);linspace(s.grid_range(2),s.grid_range(1),edgeres)']; + oldy_edge = [linspace(s.grid_range(3),s.grid_range(4),edgeres)';s.grid_range(4)*ones(edgeres,1);... + linspace(s.grid_range(4),s.grid_range(3),edgeres)';s.grid_range(3)*ones(edgeres,1)]; + + [x_edge,y_edge] = s.convert.old_to_new_points(oldx_edge,oldy_edge); + + l_edge = line('Parent',ax,'Xdata',x_edge,'YData',y_edge,'Color','k','LineWidth',1); %#ok + + end + + + if plot_info.stretch + axis(ax,'equal'); + axis(ax,[min(grid{1}(:)) max(grid{1}(:)) min(grid{2}(:)) max(grid{2}(:))]); + else + axis(ax,'equal'); + end + %set the display range + if ~plot_info.stretch + axis(ax,s.grid_range); + end + + %Label the axes (two-dimensional) + label_shapespace_axes(ax,[],plot_info.stretch); + + %Set the tic marks + set_tics_shapespace(ax,s,s.convert); + + %If there's a shape change involved, plot it + if ~strcmp(shch,'null') + + overlay_shape_change_2d(ax,p,plot_info.stretch,s.convert); + + end + + + %%%% + %Make clicking on the thumbnail open it larger in a new window + + if ~plot_info.own_figure + + %build a plot_info structure for just the current plot + plot_info_specific.axes = 'new'; + plot_info_specific.components = plot_info.components(i); + plot_info_specific.category = 'vfield'; + plot_info_specific.stretch = plot_info.stretch; + + %set the button down callback on the plot to be sys_draw with + %the argument list for the current plot + set(plot_info.axes(i),'ButtonDownFcn',{@sys_draw_dummy_callback,plot_info_specific,sys,shch}); + + else + + set(get(ax(1),'Parent'),'Name',[vfield_list{field_number} ' Vector Field']) + + %Mark this figure as a vector field + udata = get(plot_info.figure(i),'UserData'); + udata.plottype = 'vfield'; + set(plot_info.figure(i),'UserData',udata); + + + end + + + end + +end \ No newline at end of file diff --git a/ProgramFiles/sys_draw_fcns/xy_draw_helper.m b/ProgramFiles/sys_draw_fcns/xy_draw_helper.m index 0242877..5d11b36 100644 --- a/ProgramFiles/sys_draw_fcns/xy_draw_helper.m +++ b/ProgramFiles/sys_draw_fcns/xy_draw_helper.m @@ -191,8 +191,6 @@ plot_info_specific.category = 'xyopt'; end plot_info_specific.style = plot_info.style; - plot_info_specific.hfuntype = plot_info.hfuntype; - plot_info_specific.stretch = plot_info.stretch; %set the button down callback on the plot to be sys_draw with %the argument list for the current plot, and set the button diff --git a/ProgramFiles/sysplotter.fig b/ProgramFiles/sysplotter.fig index 67a64a098af7c2578ca75c8592cb93e2d5ca166a..8f0e04569bb341b5c4779173f3f14ffa70522622 100644 GIT binary patch literal 150328 zcma&NWpLZv-o+bcCWo0DX67`|Ff*q~8fIpOhMAd}8m5M^4Kp({I`PeOo^#$0cjnGq z&3Nq5{##qJw6?Z>Ygt}YO-@vdl#_{tR9;k#@w=6cIRmMZjj_vjdna4I&voK5TpSFf z;!ftqF6L&W_I7-vnxF3y=BA`a2a{j&rhcD zU|=5E=i2f%gq&DzZrr`<;%bsg<0TL%-F>ClU%&yB$ARK;()R)M@v9K(@U-LTDA>#Fj~^b~D}$=DUr&>= zf6eSY0fAFZM}ih;U=9asNXO`1ip^LN6}n^k$hIQQvYtBwqsI}Xf=rOHJb1fl zhZp-Tkj(igoX#Kx3-07E`Ra{n4&_my!V)&CBsdWooo2irv5rs$=?nvC3#xzS(8>Mb z)v{Gie}GW?YEv5P8k|FaKXv0gib!L0hIC;g^={k}vP_PGWC$>B-*BiOM9&HV=Xg6p z9|5dQDus}Kpx2QNL`O_{DVWE0zzu>)l$!(vXAZYr zVV;Xvb&oN=^xPRec@Th2-B6pCLEyPS40>!Rpq~@FfczB;b==QZ!d#q8}cmtN@+ZjNW@t?Hg_k7z^E&{>$1UNcZ& z<3i0(D5%g>lQVCxwBHPI57RWxAr7S-(jBdk7n#FUvGsYT);Z_>5!rrgTwX!gQs61h zI#h)0=psCOIFAwUK}Km24bQDTH1X5FA&3IyKg$pKs{k#A?7#SF-fUs@mOc9pabttN z-7pUQB4O__e{Q#`-pg%J=)NqzhXQ@?eT?oM7Tqg!oNcorFS>8oqMWP{aCl2WIo{W7usO6@9YBSaL6H{8B?{nElqa; zn%}YtS3KWHcqYleD~B4;eoOB@e!_cIaU&(8I^FMjhUAuf?_rk@*tIx%~PZB^lWNqWMs(Y2%&B@#=8G-Qtj;SoXUsnB30 zO5bPtP(3Bzp}^XC%3p}`TRQskqpfW9Y>9FnUHAA@b~R4}9=sUt*~FT9C+vDmQ~gl1 zPLXv_A9PN08s_XAd_=4%Y?CABb@T^Y8f<-k~8i>1gWSs=RYS zpdNSWOvRtRt#{q0<$-Uan?qQ3RHd0TLWwUQ@b|`c&iI%GKi1=43Q{L)# z)U#dT3~1+XE$jIY9}8Wm$#;w#X0)wG35pFgL@hOt0-n0xLMZGu;uJg?Sk5iG74Du0 zyi_!TqFs#0@vHYWpAQE#3{BdO@?7?gxOaav0lmpRnprkllHg+@6+Zu0K{Vb zx00^S=DI0g-EtCl^o+L;mJ4eF;Z3)1(jRXFhkjyD zOTsqf#5~AdqR`G9L`?EPd^W8cv3lt>B!7<7mAuGt=GkrS6$9+Q~ z%~+}zbEEF){c}_WfzGvN?AIl*9uEOntM%#xoHf#T>iHbxR`fi`VtTUg9)aggMp9{{$P}pC=RB>XWBCgIm?b1 z=*2N+HF@rb-u9bao_B`?tVnxSA4qr`T-l@8A9~V$l2z1BknN);`G4W@ZrcRL^LRgE z2m@44epleKkF`x@JF;i`kqHkJNEV`TxYZw#z0$Yw@0s)pBL86$@A+wi)@l?Wf-8bZ z<#l;<++KLn-q@RqTbCNFxo|yr2NUYIFGddzJ^ce^niKgb(?pZ@;s+@{X`WH%S{>Y_ zI`Y#GoJ+o;KlUA?(vB0g&bhsfyEgFrvGO-u5U$dQyV=ECOS)JEJWzdE%TmN<%Mi#U zt;(l)d$CPZgk5{9B=(?JBX9GnrJ z_6KpUb-mpJ?j+Cg&YLX$l&jG<2>PRz?p5;Mp}qSny`t{llN>fBylFh=*fRj^l*P23 zKxokMVqeS2%=2#EkEjcGBzlHeZl-YVZF{05cXy$S{NFNrgYdYe+T}4xiKNPr}azlW7DD$30oyRfAn7_Yi67idxHGV zc%D^QgeS7dhS4cBmNCHJu?w*)jXB63j-ZWw}8)>gl z%!a%PMc*A!=VI)HCQOc-g29h!c|N(hD%DhTu_sjMhM#x_ZtSV+AyIxPVNXbNSbzRi zoo80|-B|pPiqTGfa+haa&qg$*s0g@sOyYa1y%V4zYv1GD%bhn@SVtKMZW7eUxyqZiE z=jyv&7fJJ`w%0I+py}HQT?BXS&QFVN&LnS5^sWi~P4h^=cxJDK0ofaql}DP_BUOtZ zf+nBBixX{?K9YsnZ@d(@mD@&dwhv}!#o3$H+ga=4JHgAgwaI?|+V{kxIC%M)ka<%o zcfGl&V=gmv$?#QfkZX3;k$pmk$SvFMQYe`>l)g>f@6y4lgJn&Q-l`YAt6U$ZmrX%$ zgX*97bPCFyjnj8KG<1wYvLhRn$}o_DhiyRc4+$iJ&Fj zgv}oj50P|Z-b&el=Un%GFF%->OZNBk)f6GG7n5K??9xElBtljko%r*6J#r8n=NHfS z;@``MXgnbhsk0OC>=oB#=Fcl?hR>oSQvMot;ei?TxRQ=+jLBTz)v=LdZ zd43{pefSW>>(HZ)V7>cb1mS_r9nHcjdgqdxF?}wc>ZIwXP@QeUwbsu|d4or-ru(`% z#BK@iPt{>x%=%3{3alvN?$0NF^G*TpUw&TXr3$?X9+ZLfyyOhtZl!_E1^ZXz0&{!p zxhGm4rE!XMGsU-b+INAU>d}j^z<_PT&f7YW{;_v|BM*Z3&!DVnXh|rEn@5>uw2Lp_>qIKkE(PaAgJ$0kqpmv5FTA5xFO|&^83Ka+H zM&0nfT~P>22Z8*1N$~O{uX(;Vq7^}}FkeeBP!kFT_A z-XqSnS7hwo{c$zjtF8U=dyAT4H+PVkLz}QEu$z8}DhAU?9RS|0y}a@vD%g=9 zl<_l?3Fef^j0?`g7p*C`5W~>;ZPB?M$m-qx48yhz)iL?&ZwONCoBEb3t?4K~*Wub9 zNtmrsS2eNX>KSi1wr0!thDcaKn#Bn%0rAnBn^&J8L!q!O@X)+^vVvlrLUR(E9gZq? zULkFBz0O-Hgyvk~ThtrOy*wpgNX@wwvW4n6jUa-8j zP%!bFpxL!^s>?bJy2#; zO0ENbwc4{8+89a1R5sf?9(}3W{{HLn=MoB4FOEL^75?%{Hy`fu?ukgAeh3Pe=C)Tv zTHH<=2XhbYPWeN|_?gIccWzVM;oR(N;%!t1?8I_@i06EQL*@?Es^yH*&$Kl&LE1;F zgeGmO^w6h9Ad^m@XL|L7o2#z2bMC8FZSbM(c{=fr<$f-%Of?v$>)S#ue{e%9k;jD4bhY9*~|Ev2a{6*I)MXS{sASuy~5@cfm%ZRybC}HaaY~%ds-I9Af97} zcapg4E0}jf$RbXI$DWTT3DDHF$Iq1r<|!VWEud^EgeqnRlOZ7h_stfm1{<{P)&Tuvv{=bnhxePfdynic zco>&HXgzpDwF_mj;mGbK&u;uTj?k}K zgutV~2Q4Q_OAiAkCO$cS(B(%vthR9LwWJ#=jT#}wS9%m5=^cn7BDl72%qc-qKdbL- zEJJ{Uqir|~lMQGHOx*dtOIago#_Z4Iffqp<_b>3w$ghTk8MQ%!W1<_M{3dm%d00$7 z2D=Zi2x4Q8xynw+NK#2gI1(>HMG15Mh@(^?VY~%JU4k8I$_7(_ve=Pof%dVIpzBc( zzLC3m%%OkgzQ5Btx@uwq!u?`E3S{GAPvXcsF=~`kUy!jw3M7u!J!+hjh;=hjAB)2U z*mo@FbiC{Vfs&VB3PQmB?)`)$i?b zQ0hOM0M@Z*g79Dzg^fr@zO&B$Tj|F>u=2szy1kcRoG)x@-MW$HafQZP!=5V zJ?X>%lbNyPeK8;|w*Fa!Y@BBB`S#tH4l8IUd>vT~7je(G~xsHUOv za<-DQ2l5280HXhP^t#7dGp^N9X%O{R{`@)8KQ(p4!AZPOXE|VxD_1K#DpcQMV>z*w z7k~a+^85g}FpG!dkR!-=oDl3Ht^x#;mlA07Z2*pc0tSB}sVY;%lCB7gNt)bp4Ai-% z(R`ZCp+(JGy&rnj7cd0Qjt^gZm}egJgvCR5>ejv@@wHR;HZ4l(nLUlY)|<=jy)}g6 zriXq|>$-f!9ju6rvcuY0Y&Uta-c2&srmEfOGY=Q7DJ*PL!Rpa$P* zuSa|d6CkpycrNSX_oOHDZ$+qf2x30h94TdPA`%UxztfT?O{tud3dNO6|#n?9mLy2<1aT7hc6b zkIy>YC;iKO1s0u+R-!s}u6B+InV8u9BwKeiYTjBHbzR24J1i?acl66CN~iNVXPtlBJT5sFTv?{zjfxq_;Tn&yVg~I)&I@I zf@*3#LEJ0tVK7nLX>DNTu@@&;`whwSrR}f%mc*AZe_r9}}w;l!_{DHzqu2;Yl( z=s0U--~7qFs0`ha)IoXWAMqKJg^A-{2~BVgfZg+-ao z-8!31({fzh5!9FoDgQ=idXU|yFdICWnCy-XMjKH6g$nYD-&RDTK^=S+p1VvwaTEU* zt#YQomhtX(*zI}uIK^#0LQyOWS>akdoFBtsL%QJA8$OR&tdXQ+-O{Y4z5H9fe^xom z59O@_s4^AS#U1XGqLk4by8BlAh++MeBSO9^&%e|hjz9_Vj;EGh4@9eEDnKkjJ&0z7 z1RGE(D-v7k2vtcYF7t#6slZDo*ikEnr-WSw1|#zpwq0_M<>s%>SN$tf*FHGZ6^gTi zh5l-WtapN1u^}u*CLcpwjKIxh{}09T{l2w-jeM*LZ{esi{M7Q%6gIQL?S8`{(IlBB zo!PK9d&OZw=HAv}>R`zw{{*VAA6oD9&m7)A_iEYQZLj-_4{PKL-=H%#VPLzv1YLk) zlEycuG_Dv%*wQd!JPY>pd@NvJ!}{vO3QFrQsN@DYGGJ6$Aezx4^*Twifm>#G!b3t# zEb@l_GY*C`W7{jWvD2or%K2xWL%}rSbyC;xFGC6X)AnQf4|Y>=KXHh6fCE6v?Y8MF zQ#Odo4Cc}VbWT^&vMmL1!a$vP6r@uyDX59s7s9iQ`j<2l=Us>JUQRYreI>K?TDgQ7 zT=KWxshF&eC>D*FMI1>;j0}3HDYGvX(y=gj{mso5@V~-M<6Gryb#?vTdZ)jW42g*A z_+Sj-av#3hRr6f!ZOv}bIN{053!=XJd(&xqr%VWU&nA0r;$?@RyN3FJQ(A){CpXQ8+lW$p(OeaO zCwR~#K6aOLGPcB2_Pnv!Rm7X(K8ZEDch8TVXJ?@7VxTPT=Wy}W(ByTl@%Rn6 z_jhyf&Bc#p`T*8H3UC@a`Jg2CxP{vb?j8iVZK*o<=)bxRnn0v8&^nGy5DwSey_=Xh zT zZrxB;wVv{dIp>_dvx{QqBQDw0KzSY{{cJJx3S6@Vk-Q-PSBi?5qPV#lP;t?3V zq(4l=p25E|PdD?s^4VHiVOsv6$v7A4d=q+`T@F_l!TUObKP$cYx^Rb8vimPw$!_-npobHgq z(7>0JzYa^6nyviWO|ijvb*}jQaA8!Ks2kcNpii~>1BNWtM5Bts56i|7)s?i9 zcvYtN&FJ{${7`Dl|9s*0b`SaF=_2w=jqSJD`6-e*k_~_A$USsVZPTvm*l{iYB zgGrn!x1V#1c8$ALcWc+jdn|XP+n&y^spa+d_^1YT_C`GLZ>(-!v7sk042I3XpV+_v zwfjRqa;AawWDf02sZ}1cY=*xQ+BQO-fW^khtlY*k&~iY@k~NgmQbPJ5%5yXg#6K=+WpQm=BAkDP^Mf=V#~MhBmRTp1|}$=mGq8 z@lc(q6ZC8o>SU(ddP9C9FJE+hSPV-yi;ZYCxaLw4#9k!AOUZJi+dWKYGx|$d<+hz` zn4D=yH7Fp-g<)e*tEH1q9ddkM1AV`^wb73LhJ`(S`Z9a_QVZfQV-Yfx?31l!`d6n_ zITm{c4*Ti@U67BTPRN-+h?R$fSeT}q{%Z-jXBDOFD~jE-cp?!Z^YmWPX@}zGjNSkWQieU-)djcxcYkDLa4`Is9%L+C!3A(WK>nSv_z)E|H^E-p zUvU@xQL5U%#}{AyvoqJ6pVlzAU+w&s3O?%AXNcl12?cKgqw6U5n!Y{pCO&Cy=xo-D zZ-OPIRr`-sqjpr+aqERv#Nzuxn825EO7;(3xr&D34@SYrF`7~$Vx*8}C3(hR@luKL zQo#2az?QwXXrF4%CkUyhprOhz39|i36PR;nbFKY#G}>@)TwWR4CCKCnnc4-8R`9TF zsh2!F1;ec|f>Rlu-jVJK!BdA2V5?23O;d_xtEWk3n3*G{CE*msAXkAF9q`(5+L))T z>l?Y)1nXUxvupGk)VF76Jj*kTG+6&_=B(1uw;|uvEj}=FZpa12bWg%mDRDNQkf{gXwkIO2k^G1zIa}dqV|v2IhM4^l26M?o7w|b?48mYaT)~<@ zahWpXXy4?8`a(Vlssyk(I%xemZgTafntos-;RvJ@efM zdl=EAe`%fiMSi+s%YmJe!lp;@JiQreF{>>u4lx3zbFmip~8)iLRlc)W+c`C2{OSg(DtyWhQyw$`+B(%pfW;4FJT zZ@maV9%H~Lo~$o4akl6#@nLYU>JR_%R>iBp@S1(iYkVMKU4FT^`+J6XXE0)fcjvtB zkmqLeC}aly3(c(X_fri!|64ekMB<~6rryjwC=qDGIUyP!1tkTE9*}3FyKzfpwnLQ# zuGW*d7sI0ci!w;~gG9NaE^|+;a|SvOQG-dqHc}ujPyYr2@KsmAS2xxzJP^B>K5#2X~q5~m<3`J_TOCpwo=MCng3U~WeZ}$5$%xH4t zTIDk(2tFm(3Ci&ObjdPaE*iniWZ5gqq-{xC66X0jyEhk!J7-LP{aRlAlMq%D<69o^ zF4Uj%2U5FDg6!-t&j>zzR3d@{;4DkjlH7Fk&zF zPv-uk;PBME^>;#`voBCg_s!}0Hl?oaa@`9T>xkmjJoM$k>5eXW2FF;aS+>bikDDb+ zgZaTZ>u%5WdT$3fpOlbkBVR|~d@b21(g2rT>7obp;yuWUo3Qw0;p9d+KY38G+~y;u zr$&=dZM{6NKCMXSSaJnW;;VfTe;{U{ z_j%4nm;icA`%cCuZ!e0r_QD#F0CM&5(5|*0v54RBm>4?r9NLYX3+iS-miHq%lI;$y zeLgy&FG@t>sR?)e(=VN<^b_H-Bbv_HTJF3%PULBry#{|sP^#4XBO~dL1~qOL2xwQiK!_1l1*xzx}Hj)q)tUk)3|yd zy+XKh*%f_uLFG>Dy{_`?eDW~Cy@XN+qe?LT@zefG{}u|cAZ*e;I@nN%_!TG{dDVhe z!H!m?#O6w5@ya+9Kt0$2pT5X4i{;kUXQq;L@;z#}0EdEKb23=;Yij8|3 zmwhHoM09b%>!-p8gIrYpzCCtx1`e*YE`)I**1A#XZsBRxMYwl6a0}%yzCFY02~p9G z?A(!2k3?&sdxREC!6-`-gO4@>KI)IkGi9MN%Dk|+|2J33!bdAp!)(1~GSNIH;cm;k zgh70PRbz4*MKTxzFN##iH$_cfK?2W+uj4MJvn(;fAY-kzcD5avQ~%r4vCQzW*x7K@ z+{@A39KFC1S#B6i*l#rwD9<-;dZwV~TpNsCBL=gN3ZeM+_w9pM+`I9NrQX-A6)2~X zA{`Z${jHnMo8G47wvQ3_k$*wudAg!BmNMbUmfeRuhal9#P`((WOj3FN?`k}Zgth~E z+5Y>(xM}AR&$-Dpm$O}}coZs+$PSki;`weA;&aktvIr5{>ThNF(MsW)YdOEB1pw~) z-_p#91-|##Z(jZCee&*o%GjuZ0h|9zT+qGQ*|>Oqf~C?RNoeD>C*N#X*gf1-bu(P$ z>qjmm{IKb9D8z+l`p6E;bx{O;UL~qdjZ=DLbyfBkNjIWx(-|aaEj}o^7-Co^zwsmx zt1p4p+IGnvU%~68K$Aa{-fFPMm4J{jrY>!Cco+UBIQttbiMr>aDrAtS`ReefNg(^1 z7Wi9mkl-ASTWP)w-wr?OsV0 zaSMO5#k@<~LSgzwphjfrVJ9l@&I>gMfW!5Wwr#((&%B6Z}dzCy)T}c0Yc_P$( z%A&R|Pb-aU5q}r)ePT9G5ZL1&t%W+5c^&F2+@@rshdmPdL`){A zPd72@Jb<3hKHAatAwWdRIC|2_bN~$OY3TUL!H0@g4yG=c&LfD8s`=LJfYJ&P&Wt%S zZnvqQ7t_Dmwv@d_{H@al2!LO6`GKcZ_jf0CaTI?Sy1I?h*ujh^@1f}iU3~Nr{IZUG&mvSo^YXD%W3E~V7a68e=?^nscXop0f)FI3F@a96m>Gi?C-fW$f zj<#WCKgU@9CvG-AtDT-&BZ&=GPWK3BZ#ojoMDwz>sK~`m98vd#E_>I8q1nFcfFJY$ zY=*ldpPv)i+D4m`>Q8-58Im{psC@x)A~-tWIDzCy#x`pueP{5y&g>Rj(m;maH?Odw z{69%72qZhLFkZ)EVzg~)WRwmzXd^NSJ}8HT)`xJwPHr5*g9yo-j9Tc75&dld!6(Hj_d*4{UnbZXYbRR4IIW zH0G54KRn*a&p<}m4<(UzzYTFxV-%+I42<1shY{?68O($`-&*XB?ORmA?f;v{L+({# zWst-hW@{&AhRrE1laG-QOJ2C%A6!Z@$ULT~I3puZ z&qx;-LN`hX39~zgh#3z(K>-eR-@uYz$_`E1^Ryf5W--duEfs-WB=kV>YFld)#LIS+FO1~io6~jWx(53xhAzdf%WH-bWgkpiH5aU`C091%e zbV+B_2*XV6#JoJ!YRyb|8TJ#&ml9|#pp**l9vGbk$0&mZJ}z7uJ6Q%5?E!)p?@o4- zwo-r^MnM|8cm*LVsSyffCNGO`$oYuI77u?XHdU$FApu#2_^981oQ2!D*-<9p)H?51 zQdKl41bKYjUY>CvFx(tC{l4ZentE^3|m;w%+-nCpLv zA$ftWG9gJKMN!`a19O^cxZe@HdVvZHahdPQdkdx#OBt^n8*qv(JCX3$3DOuvj)d$j zl98Ks4CF56XK1_OWGZs!KTbLZqWjGWV&9K#rNI5F;3+cWh^)oyWIyzl{pDZ=rkT(Y zkMbY_@#i=??uAI7AP2J|2I(FycF{#7I39_)$40@D5A?|VQ^r_0Yu3qp4&xC*k31Omewz$_;KM1FA2IR=YT(t zUe!L!eskwP!=CtC*FZKu;gS=Dt@4zg_eb}8Rj)eok@qk zMY=B4XBq0V=rEz_GW`>R{WR*#jf}RzOumvH2F;R^f*l+k01l`R%`{3%MFw92mcb%c z@?W*`Pqh;!jYZgDOJ{-tgittqN&P-$=;Ws22QBRnmgvXD@Twhu?+noZfp+!ZUHj;B z?tN1^T3Tt!0@?k96EM$H{dd5txoGIk|w48dcEhh#)SlBn>YpD`(L zxCcI$WQ@IdQc1q>N*~7WF|oXfa4qX&PZo#%0!v1XqWS;U{Xafjs@dUD|MN6n1}~jt zg@X_W{!U**J}C`5FM9D1RRblujXw(u|G<9an5GR<`3}M^VBg{}kWfLc3u(k@M@PB; z@Hw{XG3&cMN7q)v#s_M>TKqpJgVpGBM)_kbp8>$K!FfI&3R`qAVA&p^!_>Em$lzkb zd|mVcJ6KmP_q8G&wos3BQU7UOZNwqTr%F(j zJ0BhHj`bDdPyZ?6`M0Pzds*O$##?(D@oj$^TiJO6Z4VVvMO_JJ>AIq0@LygysdBh{P*5>W=np_ zo$dZ)E9>t;6D09p)7v4mCO^$q>33+hGfr62X?cb*89Dm#8Ro!IKp74t4pr(tfVJ=0 zlPbfrqW*j+UL!LNNmlL#FVd5)FFBeRWqH7mm=P%I<69h}U43=4pYC6+J%{a?%QnXixwd$2#!4HS>)afRp(rk znY@+W1073(V&S+z<~L3c zI{)ie!6jd_^WD|X(=-afwIgPaLZ&WvX2;W0JWc}Cl)Wx=5`(|Qi~i+>^>_FsEhK1= zgNz~4m+rbFeGpLE2qV;irPIH^O|M}Bw~s*3i6A^X43yH1=8|q}=eO78*u}$C?3)s> zJ&_}_{T*aFdD(hr%D8C0z1T4SsW@k%b;jq=w~A{15BrV&-hNeO_xb<)-lFMndCw}x zvH73bla2m0pREL|L|>#bG8hIyoFaZMx``&Y1wi`9Xa2jR2oXc^HNjOZ9Gn#=Ir4K$ zutdtEK!%KAo1DSbpc%uRoeCu-HtqUck4=y*V4btrueQ;EP{2h>@a0kT$Hr3DX-Qn& zoT;JIg36$yk}x*GNN~X)#ifPQCMLf+?FtW}nb<^QXkEB7oWKrw=)y16w$;{XxV0NE zi=dG!y1#-4-cd7NWnO+SS(kK6Ojmx3ZSGq7Ma0Bi!1v(Sas~d)+vA4HnA~39)9aO6 z!4e-ux-C^7504k!OS%>@{)J0A=i(RK&9sn?gl+AH8p@~S&trB5#a)h_#0Em#@vN1Z zxQ;;OC@*45o<)h>_s6#cT;0Ptdw;#$nRpON@_zw>Pa`5{P)oOgvwI z4PGYG2-z4mY=yh&?l8-~$CIDm4=f;Wznw>=WjQ%fEhX880m(JKM76-c1|UjO9++|E4mNLw#L|}Dvkzw$Q()SX zeo4q~8ID5Sf+t%-XHw;ES$o(ApGzK@F5Zn7g>^DkI1uM9xlma4r3D)6HN|93gpac; z({+XJzD$d|S{uVH`iIT$*gymUk?o4b4~+tnAqFKYkfV|iu}?k=afggwd#V=6>w^J= z#Yb2ABrrbLolX;0Q-iAB&)f54mQf}m!<@oJk^67m$14va=Dp>as&t zZU`9FDVaEhn&-fyuMlu^EwbC7{nb14@R&#w$8N{yb+^oYaq-lZg2A1e-3C1EY}OI8 zx0D(_WA2|=6W=ndy5Ywm_rx(l9#1vi*6Xav{1dcX5B8hyYsYviAfn7Q6h@T;{sA{q z?=NZzuvhU~cu16q#1iBc83H z;YA0stN6?$zE$bZl*OMVDsOpDie=Zi;VeJHMyP2wA)|IbK?uYF|JY3nq8kgN84%0; zfLPe0y>&xDd#3ASq1`l%g?MP^TKZ#c+N1S#UAabI-u?3V_#=*Eue~rAgzibl+vsz% zmiiIb96a#yk8$Yf2l;`jU%psdItLA=uMbwsZd%$xVSlFYjW9<-~$$x*b}qOY(X_uF!8NpjR= zrID*t=Y1@17ng5`7g=29_bHN6Nm_UQ!6=a;e40 zQDlaEm0K$OR+{6)Q2qmA%RI0yI>+9;?Wd!&UzGPdg1WoJ@P0Wf?V^+!(c2X`5YZ%NIH8n7} z^>}8J(l+Yn+IaVpPW00S(Xn!&PGO8WYEGIH*(R%_Pc_c4eJ_jUXz4bvdnoG&SHJAr zU=}Z=akxGp&MK>)iw%Q(`ZUwQchv>01~GQz^P*eP0dF#AXlDJi5fLiJBqNONKJc1V z@{{+J>1w-DEfHC4GDh=bml~O1sl20*=L{&VeiaTy`KeX)7AjzQ{&?sWZ!Aiu`O=aH zvv5}coqQ-Rd_uy7*;ynk9QupqbyIlU2eJ1;T~lgtE42SINfXsh7zOlA{}`fVMx3>x zm%s%4GMs7tRCDfRfKd@3pijFH+H!T2MAJ;feLT?h&9z{%u5>Px^S@1zO9V7=)qbwQ zOp_gIfN|gtK7Eg*rO=DVSC<`VOTB-TU-hYcSLn(Lh)0(qGdX*RpiL$5X@c^;FR$WPTh(`hIAp%)CPehDR=Yq~siu77 z1}n%|}0)VOSA1<{F0IuakME+H1E z9}^TSOateauTMB5#9>DvZPz^D*)4;7)b6C+_aR-bFsWz?ST6`uCF?^DB6Y%}3dWrQcz5s!dO*hcg9v^6`|&REOe|2(UNQRF#=nAPd;` zl*oS`k6H!yzq%6OmnP_Q%;^yjtQfLW@NxM5@M{7v`runTzgUESx6^-zy_(eDUG~s2sM79IpwE?fVKCn% zUH#!(;0~h@}Yrp%NK6R)>V_0tcYAWGY{{kFHJA@3HEQn!2%^ZuO9@ z5TH8KWZeVwlSPj3i)xxj(O~zI&*X{>)|GNjO#GS{tT-0SMiJ3Q5$W+q2T66rll)FX z8P8L{{{2qQgAO*u!+WH3vdbi)h%4h+;yOb$~>tc)Q-Kfv~`#2q0iOjk~0Q8 z>6%}J9@_$wU_&~tj4HfB77gZ;s6=6?CY3?2Hb?RjM^KD91r%Tm(!gfHb^>ipPDLCT zTSQ`3Tfbig9&UV0hjqLX1==djC00gLge`&p5OsPmyAUYdh;a7wWMFTI8;?$*2^hfl zt=+{-B;;o)K79{^c^Udk1|ONYON052FF_7=!)FapL`^ab`ng%-n){1Ry*M~;dU2m^5lhf)}(GySp2kf%x*CCh<$wyiZ^RuzgehP zI=)vp`x4y=2AM92nCeVFn7xm8ICs-{)#fQE_c}klpSNGdxnH_(;rfr*ZY?<6K3vSK zyYLF@fIKoGNthMovvpQ{^AECC3nwbd7xq;YgHfu)mOeI(&jOt5ulzh zGS;xBy}AHN5~>Zg%Mk6II^yR-we*jj+j|UnZ-p>j3i!oc$)@XEjt7|kmY@B&?W)hN@uy`vlz>kUJoz&03Pub1{0=1l6c7k5~&=X)YK7O%eWfR*&x>q5DI2&QJV` z=8=Xn(Hki)r{2PY)qSb?aOMBV(!eY_>keICz$pouo0}Wr7&C34=LD|VG!)G2EZzT6 z<^c3$2zjM>7Xa@ID#myEZ6K^OYQyEOgfn1a0y^}QxHapEFai$E6t+%QZyow3LW>(G zBl@+NjGUM1zW@loPJGsYx9G)dA9CC@9tHO+F-f4zI)VTGhvG=%G6KF%K+ik%TR-9H zm*jc}7wF+8zr)#F;=3J)K^E&B|65?$PU`FMnxZ{o-!}mbPM?fO3NAw` z*%X5Gzor{76@_&pn!4=eJ`qn|@R%l*u7j^83JNMFPF&f-IA|pq5&i*bo9koKrA=$g^18NS%Ynv^@{ipw(^(lamx(Z7B2C(mdL<>`AtLE3 z%1umSg?%BhtPOtLX2_@UMnuc4vhnm^CZWcv=`lhUJn${qLQ+H@&dWpCWf zIPHaJ2(pw~Az+aGG)Iz)9jcAfkDWn6MbVeO7nlDsOmrVX;4p|B0Nx}RW0?H1fqMB0 zEeNzEUds?1IT)J8B;}Qd@sS}PT4{)Rh$#?lnD2~{#;#@!<;ceD+)pJb@~sMTtxNL<0!pcy12|JZ7V!U=!{^NPR3>q%5$+;H) z^yCNh&T(*I%+vrmRH^it)@%vnLI)ncM}FUXZ1~oMGoKUZ?A0`b#b|6{^Pybb^V6yG z{DG1k?rHR4vu;X>KC!_JEYx_OF!S3Kld$!M&(fP7Lkp=`ZyRa**?BXk&jX+cr27_#kWjhW?SI`N;3o{<)nh2$@NL^s?ErWTsM9N zKlNSzDS%%=PS#-6MDM7K0{_q^8O2`T?LWbc>4(s{3y|FQrTsfn;S&GYSARndra|lf zEYTIh_hr)3)5>bY^J=>n=ZPy71`}=KU5`8xJB@RaTFX`A-&;EtsQ$ej|KGJdZH|ZM z&uKK5*Pob(Mqc_2XSRJ~osGMv+phWn!87nQ_-B_9nLA>YU)nH!xiEFswO%zHJL-AD z|Cok%sj7c*4t`V6uJ^O&xds2L!nFUT^*a8jnmz;G(c_BhzAnItCEnMbglsC*XeK15 zQe(cjW^Cki5IQt8TuiT1E8%i3KG&d27E?%z(4A)~iIU#Rz^Ed zOuvk%RYJO#;o38`_YfGa)~`J^v*We_Fm=1SwX@W`zMLJD$AL4{EIh18FJ7E9Wwu}U zHk7uX^mhH*jE}g9L&6P(SDIb@*bbj@TyoJ|Q<|Kl->0`A7l1C&>hs^z)rpp6;be^> zsVh4w#G05K%FZsnZ)89_$2=7#AIdv@3rRIMdhcwg2%hUpDCiS!!+t@$Cmwweoq)M+ zlXy~4e^Lkpk&)c3mj`XGnfW>WCO9e*)9dGf<})TIlZ7T+!Y+-_cV{TmuuwAA>9_b{ znBG9f7zDLq$@)Sk4LoR9^Yj)uXCj{H3F26f-ZB{}6MyHEjXc7JR5E(86)m4`DR;aI zeC`x&bY?<%Pl?`iy|raN+$D*BBjmcVu)nWndgUhj*ovlLq8Nj{f_%6?&4@Fnr0(l3 zyYeZ$v}nzAKraA?p(DWMn%ps<1_{(G!^0i;c%q{r+WNu1r<Hm`ATHMM&r~EV-4f$@|#20G5{4V%SZJ)jx#g2iYXaXKnUa zKG~aLNzygMBY0!zD-E{7gH1O5bsF^mzE4AiLDx(r{_-pB7wO)U*%^85g+#tLmu+LA zN;sOXwd1A+yq=aLdzUSxDHe~^Ot}enX{0kT55M874l*o&9El?|;Qebes-B3MBw7J< zInUM$6WNH}+qTsn%P20Vs))CxA$BOQ$9BR$8SG@amS0$^_HZ+3>Jge5f+Edw*Q5oo zzFNYJDSg9l@n5{5&Jr{cCr*mlp|O8!rWdvg#CiArM(QMCWn@dyuS$=phsC7|%zV%v z`PHYp{i?ya{g%Qsp1@r2BvfaA(N<{2w(F&Pz4zMB4gT3B|Adpw({#^dZBUGBXw;aw zFa`0KDfxTxqTr5%x0XhxHNlH>@Vte7eZf<)T>XA~8kO9^Xyytf0MDJs^Y!FG)=6n) zY)u?x{OQ5_PEfxk`Hg_7heIQ7aUwb#kv(^lU{(iYjU)Bz6rB@cq~a#x8w)5-TjCfdxtA2|I9=QMiVRgSnyj1AW{iLeNfP z;bf<)nZLOreWI_3zmtWGg+Iyv@NeN%6jlf@|3|C+tuI5vkrHA=21D-fnz(=7FX-rmLn z#g3o)BLZ2;|6k|rukFTSNDwlW(JP|EcMy6l>Z)ksB=dnKST!FxD)U0@2ea*N?AhO7 z0@b8C(PMmnq?U(MVH?UI^OQWo;dh7*r*au}!cWhMf9JmPtqo$u_Kt_v-c!mg*>SBJ zLft6Mm+0+?-=Om-XhJMeiu&!qWR$^no7EJQ_y4$uP;~gz6`qQ!z)lXbbNI6-X67a{ zJOezXxw_bYNG>vb@z3I!t z?0rAxHy_dO?+$_yp}|N6|M-!U%(SBC;{#J!eIlFJLF*TU?gxV*bIvA>*&>WIM(5$| z>bAld)02c)a8!2I3i2qjf?9%FnIbGQ zy6Z^ewjUE{m&2%I-$!JvwK#Z`W^@v4Pjamp+)_lq*{H><`(X5iD9_0;?e&S<;R-Cu zAv4PMQiQ%MA!{6&?(}o;aIe4bvTe4F;b)nAao+;JfnOa!0ic`@w9QOw9^*n^^X0X| zX$%^in>lj|U0$MZa_Z5?yCv`41JtXgMp&zUHBW)NHpORX_(U^kK45<|w88DR`)HUJ zce7gf!;x;z)4FcLN6}26Bef;za8s6``l{^hXY$o@5K8OjQ zl_x?~v#&B<*Sm;(#X><9T6v5$ZJg+SKL5%yKWa{B5@Uoy7xgt>B-hXM(N!k&xW?Ll z8;1U^nx$w}1tt1=lZ5>bu6r4ONCXF!eshuVcf=0@D(4Q|e{j&68_KzDdj=2GCRg}B zQmnkAe^_&=4-mdn4A|bo<+*;Wd9c{<|DNWdeFK{o5JtI;b4b%8fZpZ#jq%1^V|VFX z<XZ;-yOq%EXjkRDFc$RDL$Cyd{dqR&wK=Z zZB^Px@4OtHeIyhQPa3(uLno5&3j7e=NNR%H$vTTzcuuLtv^(MV!7z)|jh)=> zdg&ia`H9ENUHEAv+_7h&Ky*%$*nDo{;o9vO;eGL1vQ_oFKBM> z*f~i54A)-bHCh8}UM$0b2J&pg1VVg2uNI7!Knj_pqQKa1zQkd~qD-idxLX>&uY%Q6 zg2!>E+A9OsiFEiYf3VQ!O1HM{kJLP?mA!gD=PLEC?-dM;SW`uyc%|+(29PZ+R4aV- zkmo%8VX;}K)1B)!(o(9_>Fe}hSkk_)+Hmo0nYa&qs@-&9kyt4xR@cMz<1-G^7ISjk z*;snV1fmD z?1qa+;YCd2=RB4_IGSS|bk0v1$ssJe3AZikSB+4aV~cu93^|*inXjeQqA-SrZT=R} ziaRY|_K&kzUPf}pW-d0vVk7p;{3|?&xS9OXz3wY3>->@S(t?nH9g+K-F{J}LD(P(; zr|a4HJqC@fHI~2i^&ZO}LWVwhg6`kU+h6I-3?I(C9Pa7$ya=~j-JHwGo$!~GvS=<4 zvH;Ypj{pnKw=J(;y9A<$YOu=SPgyRYt_A6h?-AgQS2N25y@w0y5OSj?G5DNtOp;B z<&L?ViGX8&W{;oyXAT_>B8~^qp{E|8F#L;YOT*_Ie4e|DDLH@;NZ|Ty3-&+z$_#`m z!pX&}G-AMGF2om<4*ZVf$wDIEt|cCmAX5Cvv0~x8nYiPuvO_IDo5%BNXU20@f@Am* z(UFCkn%em)KazT9Y;aUEw2WqdEQ^0*jjh9Wef}NC)L+8y=gZd1{Zwa7$3AT6vc>HI zH5AP7s)?&`*7iVc+-c~O1%`1O zvMbAsClUnU*bX|lM+PKElbWrT3z!5)G`@wT7vvYNa56LJV?3;{}sU5Hh7Y*70F_d|i61 zR6YYue){>zrrGbTX>vXtdmnEIp3L^DL;Ok`_D=I!jiio z0%~GXruv{QL3C`=rAru9I&frGZ?1%$)ZVMfI7Wkoj-bNhL?h0!+pNDPR}h2PV|oYU9E?f`UkU2~PR%{_0~ z-Hl?{{d_*vrHekWQI0}x6hN|$a>uR0(7QPsD(l6W%{1xLzH=O`kN*QMlZ25GREe#h zUa6*^ZfmQrb?w@>0N=qB5pbBJ3QiG&q}nGDjpl1-?4>P?8KKjLr^|lixHfToR{TTem)-kstcS1rGbv zlpXl|IcR-;cxq}Qej`DKdAU)xUEGE<4D2XCfvn`wPk(SV?r`1xUk*BCMD!tdkgM55 z>~xIem50`@ZdFrM07)hW4qh(W?qsCT)xAMs*w$ki0u|wW&m9cWDoG1|cYjiDsU#Rd zOR<`z%;3M6L=zw~lwroL_){*4T6V7;cHpdm|B`>E^K!DG0~-bkb@pR^Q|vOHGD8*K zz4od-eDoJYyI|r0=PwBjSh?o+l-Yj0echoA4yAXrRWGhHFd7T8=wN>V>nHWQf|~x zm^INVso!;4Je)CY5#w2SMX7NizsFqgo;GY?lSM5q@yh;+d+~(Cg(<4l;KUHJm|T!t zn=-5#dD0$bHY(2~0)w(2SJ;*~VSTRwl{}JSOiUSzSwqeI0_PLPX)8Zx&RtsUfAfg% zwmZKw_^T>%%3?OOj(RE7u2ZiR#i+CQbYN@U)fj%U28H8m8?hTqMFre}EwWF$N{jtj zW6zN9%W=xg#}>RUy3wiKyDMwZ#X=LnuwRMjHjH51pP%UU+E)wwz}Y=Q(Wod|C^puc zj+2)ah4x;$7TUHFvzYGw9wv!b!6KS2BS%oYZHmDxxZgNsd~!~iH-AMwB)u z%1oO%qEsP`RHx~SOtOHmHm z9gkj|1sreG*pI~2at--_&N)n#-jIDjtc|Htm)DQ7u2E$kzRRh7HW`qn`1i-#sqpYW zW-)9z{X#j-Y$yTPXjZKB0i=PCpCHlZe`WK({Q5ObdLXLWDD_ICM>)-LR<$H5D#hpci)Q>U$^8USay~qZ}AZFRKxN^eV$6n0q%E>eINdvQc zlLq`*2NXK@3_*#S;x;-ivGCK*rG(~QN$q|TFJ(<93?pUJK~x3N4-?*QDV4#2yy_Sq zfi@zdsy#gfw6ajrZyLGg!?}()iN6k-e^U3&binjr{UGfVk+imjl6?Q1{a7xyKVn@; z+VPm|vfU=HR5fLH4tGgj7g>Q7CVeLr_>qHViWvsz5eED^4x}yYW(31sD*m4S!+J@7 zd}nw#w2oV4ls2;JwGaa+bTJvBT$P7Wh#FN5fO@~8Cfq_G?8W83%7c?hnZgFbHQHgy z?=?b1s^P8)<8a#bN|^;jrW0SMvN}1BPcQ`(DT~oBC-gsRqcG3YcWycv3_SgcZpkvK zS7fBlQp7c}5w3eEZZajVFvc6f$?&=qN1%G?@1MdfgLC7JJZ7WTE&55P3^VvAnGP8U z+}M?#|3r%3(W>JU$-zDJF_@nG!c4!}S{6;rv@6zChpU$ z#`4LF7b1Q4ebJZa+x^&R)ja<~!`|<;7Sk64KfJuxZcHIw?oapn&-aI0Q{j7GPQ(bf zNrT5gr^Z}67DvHq1`so;h*y8~SWFBbuV{vOhG8+*5Ggd#q~c6#n{JUB@%eRz~&MSJMkP}e^iRo36}GS6W`5_B?nzX8f)VpxFI5t80x zEJlH+^M41I7ks7ja93SARQfCH=TP_BDXx?bo}}T?$f@OJPgM64+V;_{r>`N{_;%ZF zKTY5A`t8rh85FD@=s;YIS(hpi`u` z@an3hJk{9sd^X&9LQLIo{N>n*gpAe_Fe))qxcVBQEMG|*YtS!nQ>QEBf1zLO3{&!O zBA##`=y{BPKAm=R*wgDtec9f=2ETNv0oo0=a_~pGm9`z;YU3+mE2aG6mpD6~&i)*V zUl}2d%hn=VrB}@}uWa7UhTk2gx$&`PE<|Q47N1C%tAO?+@rBtXXuR3=XwIJOzAL`| zlYTLQ3|1hqY&-;{zfN6HI<{;`AY|^5nUS6MRW&&e78d|(f09LoPo;5%0bHx9r=}T{*uwX5O zZa{=5`yp_Q+iW$j_VQ;&V^Rsw)tGlvN3(edlzI8yPa{SBF!jG5y@)&uAU#Tb_?u+c z*0Hcwl$G`uMV_<_bG)%&iBC1~`k$_*GMsPyg`qE_V{!2;>d*kGbY7PApum@J28t{a z!J8Va|3sN*olPvY`eqmzXUcRGG2SUbBdCJ|Ya1GL;hd@AGT4J4nS0o#-;l62eE5H7 zDZj_@Kx#^Ud>_U`M@4m*j9UL^7z2rNdw!%Qdda#nV@XCK4{6lvb^L1%qCw^?MF%j} zZLO1JKO)iQ{aD=E5*pe`hhh7@RsxERaR-P$QgoT?%b)7vd5B_ZDIBz(1p* z{8SX&6>Z#*Zx>yQ>piSC{>sE55j(BR_TP^O0e}W;cHBpN4s`!@4#{9lH8CDK zKmGemNLTv%%F|nlghY*TTSzUz`z>FFaz|7!-4@d%CP<_h;~ljdq}9acZ>tG?auU!; zn&X}KTyM}La!g(zEFuyKi>SEC;-D}hdZy>CNw$^8`myr*yveuB95c2T_xmodm&2}Y zMO{RwZ)BSTZtEu^jNhEi_)cbri0qQ?&-m%q&-m<+Fp0AF3 z&eybw6TD@@Jab$y{t!@l*4UehC@|j00Mu9!4yRg3c=8tf`u&Pg&sj+xGS;P{fUaw; zWR_iLnAYrXump-khCYwi zBSTdjG?TD@B=Y-t|6LFeg}o6jw?FtSCvcZda0vzoAb~3 zex>fafI_8Aysg}4vY?&&+5TY*MUb+jMa!pf{VmexSBuDPPT^yq zl=)tnt=$DGD(jI%dizT`R9iSWLAcM|z5YEo$NoR3=>i4EYurB*a2piLiZ2yycq$0U zpN&Sp^StYwz7(l`$iUf?Gxxc+P3xiLqutiTJyW|(v_nmLeppA|Si~HzSemQ;s7x(~ zIY=X=EhWn^2(@srQE(PL$jQgnVBm248&Va4rA9lws`YJKYeEC;>-*!~j8{ZS&{m%@ zeI6YDH8+)g@MDfG)+>bjyf62qaC@o?%d&ABcHa86=n^43<9+7aTO(zzJroZfR^z`h za=24IdaX0`*Vt^^H#qstx(^a6uW*s11B5jFf!}pir$4!^E+=l>|z{6$ok1g)h_NJSXBC zn&{jrkTTp!=Bx>)wT)$Vo$1eWm>H$NZC*S~Ido@0489cE&aPF zv}+jOu0U((pAJ1daeIuB-+qRquHl*tH+=noK2TAK`KZcM(Fp($0cePKX@;KGWPH}K zjg~*olGEe|En+S5Petd|lzHBC*7sfdPm(a-Iy+gXeAV0;s*T36#Udok&ZFwoYV)|j zjaxaMT;JQoH{w!~qRZN+rck`f4X`keS{+^V60rI9`$guAEV!0n&*VKpMHQzbOKdEg zwKjq(89PBZocEhj0sH$j6M@3Lb@LYYNh+C>24`WiI(#-qv^Ry%f^-*mY(Hz4IFrN?UYN8FKH*@CyG_TaHk$jSKB z+g;uY?HC2zlPtFz_`7LDj?=$Dwm|S{qe(fj?|y-1IRScZEE#fXhL>}U2AWus@8 z&oM6T(OQJ<#6jUAIZ~v1HQ<==1F^$hPQV@I9u>RtG>p3A`y=b-QRja5ll}}^3}o2X&?6}5 zcdBr_L+*Z~ojmQa!rJ~Oqx+C8@dWW3J3TIfr%&WNd=t<1uX`#5@XDEAy|9J={z2#i zOcWmor;YKSY`(PA*+|AX*nz{J`Pk!?Ee}OHr;{X_01W44=}iu&FG-j8|IbjTRQ?AH?<}Mp>C!^{NZf$w|yfw1_jaCZ&!+J zAjQK^Yi;e^pqb{I#10)LZ#e$2E`|E+AGV%C*Y{Ihl<45ss$$Y3Izy5Ux*Q+MQj()5 zeZFhB&np|_Qp*+5`$ZsdhD(0Kb4s#Q=}nv%YTVsy0{9V2kEi=G^FeWX}yI@!!bWBp}hI*qMGmr_Bxtf zj_u~g$QKYZnVnpy&Ld2PDZ`GzgNO6SjG896v6U*7D)=0Ix-ys$`8p0BwqKY*>vbUP z4=FV5zu>H6{Qq6yCjy6y(KFK8Oe`c7#w;s8HmUR%n??9EnhizevRa!y5Nw720;Q67rrbMUT-Lj`yZ;LroYUU>|xEEEGZoewn2O4}61ArUh=iWUgd*XWdbA&Vkei zP~;x9g&DAW`~Uz1X2SrWk^D`>$@qJFE7BK=khKWR{-ctQ6W%zc{{pq^=PgyYQ&aD{ z?Sx|mxrJ{=D5Az;o%d)6aG1g{-iRR#AU>_zjH3-H66;`WDhg^yji1Qq8_~CCk=H*l zi+|3FU*9=T1Z|f-=Dy~(ulR5NhZ~)FSxvIPc`Wu5-A$rQda+PbM}vss|AW^ldICU( z+#bE`fXVrq6k=*3ShnpzY)gpzEIa5Q2KYaeOxHBb9077XRW2I+NQlSbg&L6u>ZZApzofC@~Yc1dtzM0VPpn~ zyhe?`24gK&3;g~s7%AlYg!!M@h?2Cr=!d*b%>^+PrKLUr9C~T%a9WJ53QUB|!~n%U zu9y2`pL3V3)2_AOcZ;9mBiIUQV~*y@k;c^0%D$t$kyq%7k|!96Vo0WyiL-aGpKh$# zfy*ly9E{Q*vNA3qB+t_!Hz_2{bX6-W$62mX2~#^_IPsiQmA5F%H8S%2`NKU6v7RCE z0Hy*LMle}OHA z@x20%ll)hreetj=<0%oMhl)&+`eZ7SAT(pub_KN+GigaQan$`&bejd4ltN*)rzWi8 zzktpx2B$!t%Nq5lS`4ZU*2!S}Yy~kf?=6(5QuqB=WM`a-3X1TMFUjNRL1(}n*mB^k z#L4C5%obShnToNJNO%3t+d!3hNzZ@dQB|xoEzh8hhbHm`^X|I;?wY62*^l>LjrlBm z@7pAc)6A+$ca36r_i28uXO(e!GhZX{18*4yN@Z+qP5Mh~xz}Fh1U8crmFHeo4frDb zgn9n;w-{i46888$4h363FHg>b&I^XlQ|)Fj;OsMhuIJwM_X+HB0hK7X`rQe7)0Ay#2gvw56H$kKWN30HkdJB><_wAvZ`$T4R z-IfoarL3fS2^>~2$ zad~+pfbknqfxX7_s`%(G&^_LeDAL)VntPvdGESi8qZL*7Y0?i?`-`&sHPPoTNV zRgis_GhbU#0G0EBg7m6nRu$g1GIWpplZgq20ljm00s7Rd*Wq%v%N*gfo7{vdk z#yok0p#a+zGJtalX9Xn0Ko|9;v4P{~!FPVcxs>+xzvUbLsNIq3hnp4t*ib12aKK+K z;`u1&w^N?0t-R_tni5c%rf;6+!O`Xwp5;+IQDeDftdM7@_teC&NhJ7ir?|5J2aL&m z>3D<2eMy_w88Y%}G0ATodPl4HYN+M6Czs&y$7aPFK>W1cGWR4!%7fFQw)(pBO7RVGmYEs)>PPKBacrpsjwV$h)4&fU;b0EEfxJ*!?j8IQhZX))Q| z0IG!NZwX+p9$rO<>Mjz)I$32-W;8e!wdJ?saBYSO?dV%ARtJ3o3wQeaVnCk#7V zo!ym_VZR`R{2~g3R7R)3x)+^8g$3ClvJ|8b48~)Lf?tKV=N=MAwnFbw9R$oiR5Gs- zqJ_OW@Qq&g96L^d?~9)Dj4=+tqd^m3=B{i3cZGJy7lX;N&{;nIyn&`iMJsxP-0&2! zwg~cIEfwL1fz?3keTEJxB>G@>1N~*dRY;@+S{1F5tbs_YR|M=#*2vR@qz5I^r%aD8 zZHM2=v$u@+pC`qCbC)Iy96%jiWsI0Is-RW9in6Ai3w>MVy5d_bQk{eLmKG20a|_Fi z9J?+N^2J~cTDb4DT2#0t!IC)7%5_G4Y0{)oS}$bDQFi%8p=3gjKiOXZY#lybT^+^8 zSnMokAbY^e{evI-wu2=TG}NkyPt3hLU|c7WqOeoJ`{>PJoj==&c=~2g|BTP-vPA!7 z|7E3{KNo-6Rd4f6(pK~cOK6*OTh=MWY0cO~$=3IIFGQTn zV>@ZGR=3bx^I))2z3ijp><;|s&N|H`n&HNuuCFmh<{(Ya5F=NT5*5-?gNry*y72UN z8KCVWcDB3cTw{Wir$|Z~ra(&>YgFv)ud_R}olYP14;5}=VKGNYx&l^KmnqH>OZH8)oOQcg`Do4`t_e6ZYAUo!u7Q%PCI zx)(b+@g+}i;A4N1YnuXH=qHkL3}L6ZJRaI&!UkQh&EEdK;XE$=$=_I9yzQ);J;F~% zFAWcp+_^H6zd-szHr1fg^JnIo6|i7An1uv6k2DOu7;(WNXlW(r3HIy6SEe3H)E+Mo zw(r?bmYbs1$HMCZM+^@ILBBt@Z*xJr5y!n(U2{QS#U5>MfX1ue;mDU(?fW}rkmhAS zWO&CuW^SOHG5EWnbEI8{6TN;yI)O%#g|X9?)G*T=pfs2HOjlHoFiZ|af<;;uvZJJ5 zbc@S}!-0d7?B5+a{k~CHj9-5LNqFp||6`}_X=xYdriCxfr$Sk;7>v3+!YC%=NHSEt zO3X643rhqXg{jP1qMTZo9NM1g#i$on!{4arPA;aX=Q5CL*gWFDX8YZMO?WT^Wm~{W+mA zjZ6+2uo0rl)i(4e;EGZz83bKxfiM_rMGug2hG7_kpo>h7=qV)n-u!Nb5Uo@W8Rkae zqw5@Mi{mSjgnR;3Yn`@x6F2%2k=L4fE*^t|mLV@{VU6QdZ2Hj1S(Yt8f4z=4o{p(* zC)N|InNh9OT`3WxF2HNj;mWx^Df(A-Jus@U?Y2Rj%Zzu1rKNUx+`f0XKv; zsjFt*e6}`^1oHcJ*_7Au+1@-_!Io*E9?2BFq>A?tc7R?VzwQFw9=mQDJic%6(|8Ye zx0C5T7sNk*zN>0-$bg<&@>m5Kms~H7dpx7H#64PWZ0^ej8tGl|d6IaVjjOmWyT-V} zW0!ppF<6fvY^M+(1K~*Q{;ofm7y1l(!kb}qF?s^vwNp=mCwPCZxk#^5m1*ert3p%w z$m!m^8J|)qUjF`QE2*SN#ZE{f3~ZX^a=mW}t!jZwC^S24zB=Y+7W6saw3*;T3_U0! z^t|bF)ZnJdR3DkKKGiPjTwVuL>WVDyxjDaq6GmT!*`jKj5Ornzw0|g$j*J6H1n%TC zXdtggii?|uIOlMZ_S*wM9Tz_G>QjkDSBfHvCzgmGiodm1y@9vDhPk=O&Yb+wW4IBU zspCOc%~$k)j6ZFqh~MfT0@(RG+!=GGtv`D^N2hECnS0;>XND%HlTC)&&nK(HNr<+n zGR9mQyvV)kswoyJ)X{?@)X_;!3e?LYg2Ugv!$rqC8?){cp9seDrbQ~r-x1xO$Q#Q_ zb7kk}ci(R(#ZEL#yqtLOyPUZ6V@^VZ()$2o^!=h`juAzG;NB^0qw|JW`3gwaem;Vr z&4N+)cKXVi#8($TcL=Pnc3wd@CdB+63-vX>bG5nFlvbnC6h)o0_;c!dn-Ds$sk()N zniQKE^}Q&Je!$7m(lq6@s}I(9;DN~=;qKn&$JN16qac<(5Lz<}2fULkEy~Pr1uSaQAc;LQ%Q=}1(Fv@x! zHgpMzk!EEp+{o^(dtk)2Mm(!i1W^-+0^Giet66D%y#~cT103F_{uDUpPUzM$(>!w1 zKaSLfm_1W#YXQz~_wkc_rdRZPnmws=1k_w&-tT8buekfY%>ggLF9N2#Un;z)hkHbC z^=t z-gqEm5pyxdM0#v$Dtz-QxiAeO6Mz4cebyP(qxYk0FAkqFMcmNPTRsN&0Q>LNRdz&6 zKwefAhjm;kiB~7@`>Czx7WuSI)O6@BU~Ade`@3oLmDCYdQf5alSTV)IEq5@qCR`u^!RVR52s>c0;EV!=BxICdh|-xE>meoC|o7o^5H54H6jVu zndPQp>Nd{(%VtxQylI>t=USXhDykBHq#$1+XaKJySR475+%Yzks=Wj1Ry_>i-`g@U z8`F@*7dxSSZ^1qS-b|!B8iwicY32N4e}#%z^bsfGNNDju@`uaDT(x}kzr2!7?Pwm^ zuA!+eelnGxHEpdHRU>{t@O_1@N>NGbI{JSEgK1OhHLMmUMESKLX3 zq1%tfE#0YqhAJ#kNH+x$aXmMek0W`jLA+y`5j2NKzR2b84eRa4;6_EP75)aazAk|P z{v&^(0Z5JRz0SrefM!W1l?1+X9X&6bR=xS$>&E4{=9vBSiu)V21|7Y6wOnbp=X2cz z4HHdu3rwUg_oo9&=0733@!Vun6&@FgH`+D+cHNh(Br}~$G&8kMA8#Mhrv^XE_@kn@ zhi&@m*fVoU`)i{s5&7%CxB~cvJv{gJ`FpW{J>WBPiyxo*i1lz0D+R9ODFwO$B_v0# zDWuVrMlT*V*y;8ne`Xcj0ws=Ce(py)+YPKR>VhwSgZKxn!IY4c)ZZlU|AJTwRj||) z-a^#n>|_+hoTDBALtPUoCQF$dX^&*d=Jp;J_LCM6M6Ag`GQPVEJt`tuh;|T>uIv%< zoo3zap7>`m(#GYqW}HM>QW#atThZB!H;)FNw6gvReM5&q;pz=7az0K-s<3enKW)P>%lVaWv#Grm-Sb(X!=2T^LaUXb#(=?v zP8s{uT&2cZx-5?h?`Qf^w-8#&TD^>|{uFlXkf32-rgdTdmYf3_@4&2Q)Q3Su>4JSF zXi_8+%vhx&o`*ok>^6Ih%9|e?Nu|0J_j)Ulydz=z(8bHIqk}uHp^ojn$yMCu9*mxc zHxnV--2qqXz3dyH1_9G`Z>byku7LBy42!qlM8Kp|uAkq(EtkbcbCpN{To#~g_H)k3 zE+2UV7EZ1m!%G8TPP`Bo)zFh*=HvU@$PI(M3C>krSz@gs0!0K%S;lNuS;Pi4M%43j zeFb_XK){kB&$5m%_E{*Ym=1RTc3mG~#{dA?lF=O1_x3wHw*2E5SHl&$?d6h zEb4~uC|ktHhTYGigAjN+8Z6fT|-DdzCjQD^aCdcp+ZU&bR4$i(eo zi`$=-+Y$Ixn^}9%YgUDF?EUoN-3q?~BF?d;^>Y0%oqYL$Z}oKZOnve9e`wz6^&l?B zdhlj8(mFgyzFzSTi~ycD?SW#dWgCZ^EAusH@7z1zsxbMh@hk8oU3713KXAk@koN6* zdonaN=TelY66bMrFts~4dYC+CNFJBsPjbhR=psS6h_qDO;RI0(|W%9#a#TW zNQz0HL@&8J!Qbm@tEEQz#!%>Kv~6W(=%T^bs?jhiT8b2DB;*v@K?F}79pHVV-QaK6 zdC9^w(>X^mb0yI9!aw*u_!`{fyEC0|csPm`fL z$+7p!BUL_dJzPXe*{yxpIm6idA5|j~J`MHNvZsd~`r2fr zyCt2dSd=$3nq&m5BUE{I6cjlC0Pda{dRt<-yx;`r;95wWxsJiQCbIW^jYeL6uO7_LJ3*f``I8fV1% zJ|uNoeH4(IgtRaeoGKxAEqQ(?%F}e(f-7`7T%|&~`O%nE8cyX0fpPKj`-tYmgzH(| z5h&adddU%6O46c^N}!gui}f53Dh==pNot}o-Lq#d+vB&JDv5g9_e+)Hax{Jrzh19= z1_XTlV)zvQ#zb2$Ty+-pCe4;CO_ljfehQCu66)l``x6`|4Fs&B4c8qQc@YJ`ENfos z`b|Pw7mtlowWgQ{J9Z6QyngBnd&v4bpOMK%7%TCW?J3K$kY-V9kzU3y;pz$ZcpBMx zd9IEa23c%DPc04<7ZbLRw-qRdxBk3TV@;Rj5EIGIP)o-_HOs`@vo@ihl^5zZqyWRs zs|h5(J4bD*r5uK+Cw0pk*ar`2Rai|1v9cBWQ|iV})d$v}NT+?S2o-4V*qRo|3tEL{ zBsNQzG$sBn0-yd2=dS1F`Ed&C3*E}!9|P!+ti>vjC|0&r{40!lXq#7P4s?k z9HdhO&I!hKE(T84tEEy4Y>!#f|BwFsU5yV72;U>~Q#W zX#CVRP~pg-mc!Z>$?QW-210>)%kaoqyUv63w0W%a%{QW~vg1Z$^T`g;6#;=%T^ub%nvnVgcDvm}24>Fb1 z*-Q5d;8MTD&h0V&dyICvLc-OGiD!nrzjCg|)@JT2U*FzZ#_z_G z(rPZWH2u{?s}cvzoh&B-LB>na~cViCiJ7-Aluad_EXELp##5vT_1MdHf*kzpPz~w z<)Y7N?rcr>KC*J>40e8tr^!0miNFzYZfpJI_IB*wILl{58?}>JZnKZbud|#nC)#Y z%|o5*k(w=C64B6cZzAzXiM8XE#~LY0f&zXYN^k9D( zpADo*4#L^s{gkF@rZ1!WBOxs89WDXoM3YBw!&kLIgYOMrrE*t$S-MW@WAi8@HKhL3 zHC@N$)eP-TynLN`hRC#W%CRp@_IsR@GcRz$bnawdq+2|AS@w-$VpvglscH4TmORUp z5TCic3Dh-p3N*63B3rrU#C?osQZa;+HrHCCUu1ZSd;vNfbSCRc-| zfc?=IOl~G_9d#<3@l){zf#8Xy#}foJ7Y8bHIFy!05DQ&gyhf&`l~RY5_h7RvAH;-W z-21n1sx|-4xG;qk7hibeF()2S(8{Ee{}hSkRk_-_@!d)7_t3%c#YgE_BI$Dl^m9dl z<)pPwSr#&#ACXsM1DTXR#zlL}{Cx0I@N%-X@Jx=5CZ!21o!X(A5HmI)6);Ae#7Bti(llUctAt+tYE{m^UtAUSy zw%9^jd1;=>su%^|RLWO=VB!m3Cn3ku0C8RC+G9HGag)o?i)r2bvP>5XNt8J(!2SI|Ge3hyEsL+&4QLKy1Zp^uJy=IF-zU{WE=$9uZ&?HBK=u$QVF{jcoR zETDDjBNc(sLlHVJE1X+8wCRHJ6WZh{yesMQyV*MKo=%qe=PatOc30D@kd65&n{D?V z_Y<4rGcV4%^yo7rFCkY=$>o#}su%1`wx zHv}byv|C#x&)TY~<)7I>r&Jpv(whOA;(HP*tA%)Xegt$k*ZVo(;VjdbII+c4iFmQb zl)~OB9DW}#t$RM23ZKEP3&WI40^hVr3v3q?#mIVr+%bHGhEglV{-o4P=8W#iz*Az;KH4o!5D zC*`y8pH5kpJZqf0sH7X(OtZ5?Ug}iHXJ!SeQZ2dIYra3J(5#lb>|3=pedT;A!OHb4 zyPHY-)0{N_nh}{dEw7jCyY=Y!S4TZloWg$_SQ5-O%=$so+pC`oMHo$Ue0j z+iKMTHh0}L1bcw>n}mm4fO^KIm!?_^&Q)yXDZ$!ig2^=i|Bj4Ba1*V?Y zp>vo2oN)8s+?Aa8FS|~$p~rX~6Pu4n3brLUnD>dlM2qVRWTJ3g`PZ_#Acejb89AIk z(LW)H`C%9DnMOMZCDZ#U`_?KI9)+Ci!b?g>R4|7MJZf5AxL+PpXKi$K8O=Du4qR|U zX8PSvpmXjl#Jgtk+nhqnWTuVyqwPbe52%L?tfwA<(DCR;!ABaS#I2LG2X|iRZSkUt z1V~o>tfGn{FdH;@BgyHw(z0k3=fdcjFX$3y;F$UVp?sQB{gpnvWUZ|~zi;=-j|pxj z=gI+b%%nlpx&t{;eN&A)7QJTqaf(mxptrr7*#$4&AAOQ!{@=)Y@3a|o|x^w8rz*_0ITZ)>-0 zPX}9r+S2hxMwqyRO&zn)*2Ixs-cRk4gHtV0;$8DK)ho3ZmIX^&?b#;T;N0b#_T}e< zocS$f?K#t65^ZQ?*vrMmVCzu6T0a+W{VSIZ#(s{H-|eU)LXFzbA8DH(9=zI6VsI&f z1^hQ`5@LjUz21`yE0%&GR5Z^1_lqX3WgSG*_|+%Gk~x!ZxGWGg-z$R*Ri$+A$G)cM zTkZs(jam25UwCG6t2duf3&nG@rs7=hl>B&vYQWI)U+yRm$fvEzmQUIF-@Wf1701dO zsOQAIi`P|{yznmhwRf$__ug5|M{U{fPp_qf?|g6Ut!mx9Yh#3qFYXq3$mxt9<({GkthX=Em~j?dI;6>aQ-G8_%C4-w0@0 zWb^tJC+K{y_4A(K<*@26Ph4m-xkUu?OFM}^mAxi)7^ikCsYN8)?5UU0@r>CX$iv=s z4RYQNO<LNq>gJG|PZ=8PI0oohs8{3$N4 z${ApJ_dwSaGr%xq=B&jmY@6{1D?mdJ>EmFABgNk}2LztmBwqL0Bk8`u@iETeqi+i| z7H%tllowF9;0_ww(EpR)y6@$cGiCz+@6xPSTvxqSyuZJZZC6eACvl|QT5Zny(>n$% zJx-ds^P3}{2RHVe)ACo>`5hK6zcYS_e$MUzV}*=V{nFoEMzMR)&0z~gi`Q;@x%kl1 zR5+?TwM<(Bwa)rKY88rZzmbZ+vGs?Q&X~O*+22qvJjIM41vLfGf|`yJ_TN>QRnr;w zC>RuGoIs-IQxN$_@k-Xlt(`-fkgdS#j{Bs)7sQ`6B>3}5n7k&odI$uv0B+X7+fsf_V~o-ESNgJ6LhlMFol_Ea6qEgruR2i z)H*Q#&ojgRf72jkeXp$im}|hn!ow(2^}vSdkSml7Uw>fA z#5T%#Pbf!~Xx!;_dlYdJlcN!yRmKK&JS8m#uHR*=-*t#qs#mz~BlN-V_XUQ%E6|{_ zzn~hK8NrPPKY65G0G{cj8Wu&DzuQB<6G69K2-3r5!tp`$0&=V^R3QEsw+SWfjcK_I zvr;|w`GCnY66nwTBj{f}ss6i9@|bUZ+nZg%NbUudcOGJD?;T~`+rboipBzG?2@l3a z9|+%HytWXe0F4wv@!>B0xp$ST`h!x!!D84r2N*&Kq}~wmji##GPd{oKe-iqw~>bZ0;pn zw`+W>%pKF8d;<`NUc8K+HZUDDOUJ9f<4I z!|y-$WFl4})=)!RZ0X;;R9-rxW;b<4ltFCvK7&eM(@{5nUwW+bTvgHaRyKq1_@p3V zWTOk*IyO|<-yE=iYboVgyza94Oo!C6V+eOOn-FJq%KiqIUziElpdI~-#^T1d5oFbax{;#PL7HrP7O> zr)Cq1er5b5YWocBJKEcYNZJ}DzG?Wr;WM`18beh|uP*vkwyry2SeI!tF7VdhH&CR@ zI`(<}S(a}bwF}ZWZA`wup%oa~U@n}T(CaQ3P)>7pKB(Z_*c+v1`9jmOgacNdD|
=vw9@?ik*xtMJ#eA=)mETX-<{BItYO965ez%SgIe8&qYJc@RY4{a=^fdSc`{ zs>>w|7P*ys>zcw=LDEa^+ZJMv&h6_Zs)@;%vR-?kuW&W>>C|L~lal>pxtPG?KR;!D zY!z&sHkRvmmg25m(h@m* zkN9Kbg~NZr%N!s9E%=+g68OUYXU1?A%D0WPHKONhEIEtLhUp-FCxdx+A1iN^FW$Om zqVE^6dFDyG@7rmoi|!~zlZL0Wq2{zL$P4j1_Z5fUh{y&%C+b!r_411y`0|n_vi0yzTZ`pnH7^(HKhE`juWIWz zn_+L+j4lv zn{5JVGgdt3Sd82~-Irffi`BW7xF>23R{uIvP{?O; z=Gu+ryIXPd7lfNJ^Z;qa;t!VA$a|JpRY$FN3a0ZHP)&5{iHVxQB5jv}nLoxc%yYC` z#oYpe-9$kj29nd9eL`ymAr7K4SO9CuN2_ig!8RH0%UvY>}qo&B~@ zhyUaE`S45JvR~ z7mt0NK0Wi%`ahGSn1P(%&KstA#nn-2U+2#MUD)3e9OC~I$V?jiVR$S)>6rXZa`iS1 zQ>w7=<|jS7@99etW_2h_LEG9UuXm)w-!3py%YQ!1i!_=Qusk=cTxhpIz5jc8E^V%M z6s&)I2bgLF?3lsW1w5ud^$AF@^u>Q;`FkXFIVE_E$ z+n$h@jF2%h#tNnF?TcMnMX^D3+%#pOZQKX521sg;UJD(ZuU zUPakD+3LSCwS5s|Yv~kV>16y<_zTljlGdj_{9PZYKpchtEAsp~k^*O3y28bfK891* zZi9;d`BhkZ8t^OO$&8Pn-X&0XoX}LMgQg$#^F&g{#L+c;o8LK*$eqT>?~H~w-;{A* zy^}g6FymHHT|YVFBc}8A)0y;VaSym2LmogLJ~HK^g3z~iT0}!h9jqKki0NJO=C+N= zFY&HNM*AnIDdm|FWm0{jM8ZQd5>nuo6WVC8?1pX<9i$`uhb>)mn9N1@;cc9QP#=GF z)FVE-gLF_iL6;@#X#GWbI-U?DG~n}t2;!em+=x6pwZ{*=E*lYJAOE|EXE8{xgJW^| zu!l*FV-NbHv&x2SXDj4G)nmP|r8gKkKtLb;+CGicH-N+28Zadv9d8{Q2+@)Uc9MWvV4~;QO^G9F=65oq9K7J7rip zsNB-R)mXvLJdXFNElw_@v*ridizyp+}JQE9p4ENt}ix4|zQgWVq=quMz{ zqA#*oB)l%=fITP|K&@B5Lu>z$`VdEz{_wEe!IqGwlD6~pq7mW;Pme*;sj7eTQEE=btRm{TcmAvykKk^zT0{UU8b+4!;X3D|c&pMNRJIzna z2|Ipy{^~NqYwlv}%Z)#88N@cP?Ub9Y9SNYGxQN}FgK#@P@bXLmwVaQSG0#=^<@WCK zC%#~YF`JNGBlT&R$fvj{BMm23Qx1=o3w>+fx9;vpTnY)pJbzd5JnrW23~p>l>sQ*K zSmOFzgu8C#2J=?id(WM#iN+#N4?ol=x$!tpYM%~ae(jlB_?xTMC)6Q0Uh2mq#@Y8z zZ>+a_I=B3O_}d9_UP`9?V*keX#qffeqW0?(a;<;8H5g3IrP{302o`}?r5s8}yaW$3 zJ46mnnSYDv3P}&2d{9>1e|{$E{<-9?mA55qLW@SYoeBMS2F?@DfBdMYw+8(Z!}pv* zl=&t@fPC9!`QS~YB~?D>OXByak6cb*pZyEGRD`7@P| zmDlOP-t~SJ$o=YJwxFO<@9b7ClZY>*sksnNxvE>@?tlATZoaJJ7UzHP>a@FcZII8+ z!qgix9A!$gw~JLDW9M`?uD*2f(6S&id>w9y-XF6X(rx6-y^>nR@#?HXhS+-e*1XAu z#W{vH)9F}*RAtreG1+2n>zKCHz9thh;i@}))#qhgpz_atwZyn28#83pb8vWVD_xwq zQ%(Ev2dgB7ezPTTQ{}&0;TGlkfL6PoyJ`kkpb%@{?5o@NJv$fq#Ox_)i`L^?V4@_S zhecbbU8QeIsL;pUcBulkr=x3U@_x*HbYcH)FgaX6_pVxHX0M_ z2WOw3R8LaK=T1%?$DZr(AaeW}>!9QKCcnihp(E!N!#eqK{Y2rgqgg0|AJ<7lg%KPN zPqlKgnJ6JY&Fip%oDQ|aVy`0;<|+Kz9Yn7%lk3R1d1gM;r+G8BET==ZRv>dc6l~>C zq+V~u^EWmTMcJS|M0+;q0Fjez_QfHYjUGR4-_~BvhJmav_=b5XQ>{)=$&s@lpPdXZ z-k_4S_Nk49EG23&O#$cM)Q*s_p&EwSK~@)H`B9Wlkro%~59PxM!d^R=*t$bdr!_Tx z5twJQr9H?&U3+Z-sz?Qe*=Z~2r{R%S+rty#7t)yICp`qwq+LoxF0}y=ohnVpx|*~b z5A0qoO@Q8!Tjl`3ln=SoOE08@5}x$Tn#e830#u6t;tYV$msKna+9Bhz_6;j?3LNT0q>s&vOQsci3wM5w6bri)|XcFF!@ZvmGf~|UKvh4 z5K#E_Ei8e(a-LsA;Z-X>!Kzx4mEt0zFt+hDxSF2NyZc}N;qOlzuR8Fd$Op=eQhl*s zcG8=2oRI&0i2SmHzQ}uHkqNNui0moUIU@H|T;#1>`q`9|^ay|(zPhdbLtOda#?I-; zT5j_<0CzH;Gqqm_WQul|cmIp7l~__{qRGl-<+Esl+wN{Xy$Bo4yek44%?txd#m4>H zu=L{BT2w=8e(3iy#C`#mxMsew_D?%(2+-(*SxGq(fsf}*;~OQ~+Uv=_A_|%99_PGv z?!SDFnohGgBmBBTrtPjg{PBlK%i+rl+2)1kNjV)bhFHsCo`virKEQo_JwR8c&=-4U zj2kw}X9pbZegQ%ey9fZJv?$9x80k)dMv?Ra0!$9|&&Kf>sA*KxFiftyr`r~PzlKA{IF4-6ouZ(q z@f2Q=QlxlPwmYmi^Mb`;+3`g{+Y+{?w`1=!ZTUrjfvt94@}BvJHTec^`(p!-+?3!l zjQ4$L_pi3SWZX|h#_!dZeOEQ;ulk;8&@KB0Q{Fv=@27++rs|Ygc|*g+*Zlu{;1?$s z^DA5LS}KYzWfpfvB_PIP_~jAnZBd`m?tM?XH`=4((Wt&dF$KzHM%N>FuQ`X|Dqf$j0 z3ST%Gcxf=e46kb!<%7$APL9t zRK10RQqTx1{3O_FZV>bNSKMBGiCac` zXUU&9`-v}NGzB)RG{E%pMlSD^YB$Q2@?cj)QQ$i-N!5T*lF~mM`FzR|8U{@C)>>r% z)^(4!b)6Dvn5fb_u%9ySE_F-Zdoks{)?U)!E!=w04QJE*1h~bQ+Py@xA-lgmS<;j%MSjmuRNb#@Rdx1+Gjx50UpyVKi-f|GDfKsC1 zT6+s=3Br>J#w!wT*GjI~$dH@Skz$>rk-5CA;Lo;w_4fhyWhP_c$%Zin7WcqBw$cDu zB|x@c1|k)G7BnkPw3R~}1E{k=kX8=Rl^H3GJe*j=6Il5k!&KpLFM*-m0jkTBB*+?h z54^&iXxk^N0C0qFc8*?-v!8bxjts3f1oPme0h8j*&X#(yPINsG)b_vPO#&46MJ8iI z$%Zj-4!~SXsv(73viD+ru?)lt`YcEi2KW&FoIJnQKI#latSzmvq9qQXDgYGE2 zl%&P?RM$I7P8Q0{rXUGr-u!))+}!o^DOoy+^3*h-v^;KU;_1`vkp9O@+9{Ss+aVb@ z9H4%UG8%r3Ktr&$2~e!e+k4?GG#Q&wDb_hKp39r|+7O&KmT0?))H$$s*6J=TZ`^y~ z!w5L82DC1LUeu`bM-~|9E1OPP+!G3)aAZb9F0UxX zX_yXb>x%FOMF~nZ@J*U{yKaNY%>$?Z3B(ZBy-Sw(H12pu3Cd`wa>V;T$4hC%er^@- z?7Fn85G5#0Xqg)Vm=+zOx-p*xMLU7M853{ImU$IlN^%2`gf1;b?~l{WqO*yDA(HxF zKjS3ZsC1bIJ`LG;^6bb$ZPv(lUd?>Nn0{rT8gH5b)kx?LEb+>QYkvnK&fbhH*I zfCSXgED%raEpJy_pb^yF3n=v|1v;A&5Rai)=L*MnUbAGNb`+9rH?8F#ulDYN{gQ6CA}k&NIRT(Tps4z?MmuqD zXf=RyPZl)u?*iP(pJvwd?*(=+o1H6KarW!B05}i;GXvg3Khq|V#81@!JEF`riLpe; ziR&yVyQ9i2$L+6rf!kD7+TW^&%2mLQTfXzuR4On{QeWEC(Mta$6ujm>JbXg?qoF15 zW`uM!(LAz9o*3&Gm)1v&PmFb1#C&hCa!p&56?Gv9Po14av{jkbXxUGRP1}~bU2-Q( z_;t~=OWhJ1JY1*VPl2npTDCw_#`70GxD`)>_@)#lncJ(ZYC`O%M5jecw>Y;4CoXi; zo|kSV2f|#L-)mm03TYAIpL#wY^Kq+Y8YDDzX|l7;?@^7ty{5#pS82w@?ZXKr<%a~5 z4_ZbC5vBRg-@PSwI--DSJSNH=zI*2rd1|3I4t|%JL~5mZ=982!ZnL4zwq)=lglnO) z2kB+l7_DSad|RefjgLK6b{byFn?NDiV}|j4>4!DyHHn^Hp1^Q|x$?M^X)AH< zDHdLGb-a*sbuxKw<-)G;G_nfKtd<2Pd(kz@7B_uDBh#>)3hs@!YHE%y*Tz!72|~_x zV%F2hQco{ZZcBT=MNi;#Q0k^S#e05XMfQDUTJdE7uDynB@LeFinqSy_?U2ts4phdG z@2+rqUma&pohf((Fzip?4-KU`8F$Q-9Ho0;staA>iltq}AdpvvB?LFa5% zEQrG;V}hRIB6{r-{TFtPQwzvmN3UDjmy3Iib#R}AIx*5g99~BV{UDAh3GLZ9P4yGE zNiVAAuFqEyLJ#&d83QIX?_`NJwU{I!a*(L?G`-N%#aMEF_Y8hMiBAVB=LV;^Vi|i1+()-2|t@*};;m8y%Nn9+gBMe6I+^cHMY;@cj;OPR|3b zMF2^Em(oHTS)zE+9VT4{xQ+sc-WU8&1UTc|8#oQs@tcO4)u=cpdAhU+9-*e87L6b> z7C0*>?YqK%%WnC7DS1#+6Z9E~{W4IKiTsk}iogY*0#BC#rAe1|Z#ak16A{9<^S_p~ zRGw!{=WG0O%;$dn-jH*QC0XJ(;O~SS*=67?0M!NR(g=vs3Q+oW1%4@i>}OeO1VmX6 z6m1MB8@#htHi2k1c>pU>>n|lHH7fI;07?o#$qZOs04N0krMdz@c?qC21+44=N=ZOj z=8#FHTZGe3bWXHPB8MIGMfg(-0LN1Qw|%N?HcK+$T+;6Eme4HhQn0rCtW#5QE#K4S zt}Rf(-rdHW-oR;Hx};##C29S|?B4dsM=DT{3;;V*s39i{Yw`+LGNmH>!)8VH56>gD z+luqUpDwrLayu?*7fMNM7D|a*TRyU^QThHG;JgcP_H-M|_OK?KKf0(8{Zq{P%0nZ7 zv!`t2qYPm6IMgumCu?%pXcE8~25{y9R`T=1**9BqMc4t#AF`T-KP0U!P3>wbeth$E zxn~AYUI8et0F)}16y#q?SYH{o-lqTWZ9CT_`>5~d`OZ4~JN^3#`S&+Alj%0)j{x=# zu8_@#q3)OhqnmaQ*C6|T{;D^a%ky$8@0%D#cDm3nFuml4=)D77z}qRDNQ&v%;eK;J}A@LlRBu3t8jIaHs*LZ6wnSt(9D+A(KQwLvF_ z^e53|nw`!SUvbTY{bEWJ$E`Q7e5lqf35}R-uvpiyK;H=I=d_ibK-T8_l`wgmWIT&p z%B*Wn>P9s@iwqs-sJeq@e<#oF(fX{neM)NL)ue}@Yba5o+5BU*OUdH}Hy+n$SQ_)x zRf_z(LT+Q9v54fA-@M@dNhzFabCo!Xj4QxP>I>0Mh;vA%l`%2TD~dT9H}dRKk}oz9S~ju z%ilCXSFA1ol_a?ju|um68RjcCZr6tE+K7>XM+QqYmGy^kC_5Tr3+GJt6YAH0&a{qzhvD=Hcpt5g zuGn^(SJ?s_&zq4U4^~Vq3x9!E1O8~fAF0r6Hyqi%3^uCQL#vQZPv-jqp1Y7ElJjQ3 zwqN{ip;fjnP3Grvu;lx4075M}+b;({U@m{-%S@C(oW>i%ykH~5Z2%>`GhBgp$a2z_ zPao3~1yH{M6lo#X1>CFMkNi))5Mc_S!~v8=o8buVQ{b0_pPrV-UtlgX8vx4VV{%@D zEJbBYeqM#-wliGk{}06pHlo}+aQRDVaamzr$n^yQs6fHu>GQ@TC!Y{6|Kb;NQ?t(H z`)2iMscb0&@db)#s%#ko!OG58?7g0^*cLdluGnUV(;b@|xs4ey@z}c?jmf|U#RV>; zJU(!lF==u6iv=9Od`QltNf7c~FufF)wJdMRLW;%qHo7?*Y1E@5%9+ z)>c-4@MSPNL@s?y=riKwj499(gpv_2UA|B=bQn!OB#&hP^qS(fmdWCx<;h7-oM84o zne?$-XNQB~x~Ql=Kw*QfPyx_Tp^kpr-j9hdROm5AiA8$4inHyPV26AuquY?S9KifUmlHmp0t z!{z{R%OUG*70l_DN}SsX*@v73(yJ!9i<-da;D7? zQ6HJCdcXw$fksf0?0IFv3awHF^d@^K0Q?UCQdskY8QTo)nLj40Uf=<<3o1}lJU@6| zQGbM1@k@cZES>{^iU3d#V9Wu4dH`b#H<&#=VYR(!)F&N)z~(Ew-c9QuB!TwgQwDUA z{9bLh^lRy=#@yho3<=vW8an6-ub9n|j?@;HMY)~fj>(1GZl88TW!@eDD4DK0zzcS> zzH0lo{vKMz2fpABN(fNk0ry*9OLtNLE($A3wc!%QK+{~iGMS$$8#>bW7-*uu+708! zKPD%+Cj@?}HCFGp2D(=5e`pmrP!VgY05A;z$^$?v09YNFoV2Y^-3~Fs3N7U3YKD#s z+jw)x&&ZPp*BiV!qG!OAiZ^!XlmCs2>q}w!^jPoWU4f&T*Y864+CE%T2?K6v)f;*O zce#MiyLwIi5A{}R7`y$=S&ACv=flJYH}=!Y%L6I>1Ivx#5_hTbVAY|Qwq80gl#@NI zonxLUC3=w?{GQiAHNv9rqV0!CSQD#q+Nn2@*VE3uiBw8sdlRXccHx-US(S-+xi61l zCay2<^vuIPr&BY-eJi^k=Sw~wYjCb6Jy&HVmi0M>zr7o?%GTMs!qhEh+SK(aMwpcoBG_HiiSpJR z;l%vbo!Lq67Col#0s}5$QsnDY>g4mUQ=yZlU#Ai$&kte*%I)9!JNpT)qM9~!zD|Wq z>VKVzpL{xq;Vn0NOLp?RvU>2`@9gS!XyF&h_p}D#WjFV+jJk8{1?={6ni>(lXm8xoB@z${gW5p0_50#at1(- zI{!u-fjJ8(XG2cnj%H6Oq*CPv6E|rW0OiRkKpAwJCO#E(##-q}5-69V{7=dKPkH{> zu!?@R#$lIm%c6|T@lVMMD5JSQOxu-ZoJzhQbLqoxiaLVvv#&V9p848_!GXlNJAFGn z$NYek-Cnm3EQYW(&oF4wHbx(Vuuf)RBYDQh-7yn#r}`&K0`T}KLg&C@1S|FoLPP^l!s*Js)lM{WNXa=BoHy+)=^XA_vr~ud=CGN$~883Is0x|AOGWFb2oWNmv(7((9y_Gty$w=I#H17PP;)G6RcsCn4G}7 zv|lzB3Tw#reQrBhp>PfV&DYe{DQK+{$#HSB1;zBQNFg>E;`oe_IJYOT;5VjaGNIz-P%fbI}d2fg2L`N}u!zPaWD=+v@)H`};vc-6&?TIBKN$H_9e6=j}+& zS5yOpNo#SZ#WK=vI!Nu~`Uwjc+-W-||d^uqoad`J=!o>`a`sp1lvZ?)N z6g8Au-H3$?yicwErtBf=jO!Rc8>Pe3Zjw|-Q0LFlr)A!!HaK#XU539$O6YCh62nC};(lC?U?K{l~8DD1>oLNEr1ERaZ%wz0SeGq$k z-8VBe@AVD`a#=)c+D%{OeE02558yRa{-w>&LG`A0=-04*3*< zN$Km=0kVXW%4@evM2-Ch8DkP#08{bWZ+$GncGIdw*YYwQ) z|5os+Kz4TpKM7HR?g(TeB>Ll)6O8T( z9hjDx&e4@c2T4c9WEp>kLNg>b^OYS?Hw{`1cH_Z_L;8kp^@ zw)K-6V$&KAFC2H%G`5F9vm>X_{t^elyQIHPollK7G1%^=Olh*aXM8Bh6>eOK4#LBW zrZGcC!ULpbq#3og%)`%2io&CIx6H%WOpc4bAE7XXa`VaRJ+xh||h*wO2AZg7N~2R&Tn05Q(lf6XSJb0mDaMR>4xL5JYE7juhnZ!gAR zkn|)M??r?NXG-3IWuC#t&%;?DCZTv2B2o+jV#1EZkCNCpX>>UDNd+lq9xegNI){~P zCUp~$22G>_A~I%}RBM3cl}7eGJWdfJDl%)w1jpLXFRCA^3u_xc*vrh@%n(@B5^8Y% zO1{6B8H$6iYH9w5#Y<~tabS6yNTHW9!C`pAxub`$Mz&0FI9_({$N<(TqpxLGxQAqi z*s)@(n@L+lBr{}|pNQmzK!5L1KMa$Qp|KkY+C?0PHK(=R-^ZrSEjk_6FloC#-oq7c zHb@R4zySmu0&O+$R0Bsg`P&&S=+8YW9|U>VhJrI1d)nrA~6%Gxx*w21MI9U5}m!b^Qx)yHF4)A5`7xv(b8!} z+^NbY>o^khf^o4!l=A`5y9DP|nqUL4K=;w>T)fBJkrnJjp@qajq>4i5XRy##5|~Jp zh0xDpF_Hy%XhJ6aJsvX$*MJni#U~QcGIQ`75D)VJT=t&p5~E*dCqr&*=xI>o+@im*wit^KpD>G^L}O|fPB$_zp47y$7VxIt?DM$ z==Xq+VJP197wNNoPT-OyK@=MRIvS%$mEiQ;HUhb10t^!y_8A)Xho(+7Aih?!HLwp& z-3zG9Oxw=Z>hVzqSgLV8k>{|5bG0`h)xr3xe_dj0u2u_TAy$Al$i>U-P{F{O=9_3wq1r41)uzXSc6>TfC!8>(3dsL@5-qVBWO&K~%3Upn)WXq@J8*|rR zX}_&oqs-ktJUuk}Sa{cQ!9oAG9~|+=DpnwofVw}Tcd;b_39ILR=|#p=1VpV$h0eka zFhdtGibMfcj2BT8gyL-?+};roCeC&`ULfq)z+#&kq|3CM8~LRJBL0|WC-;!Tr(_?$ z(yvOAxH-B0W~leKt?146b+)12!U3*^mUX!y*}?&yhMx8GxBkLD-$-9c-&h%N8uE7< z&eieNo!Kxn<)B5ETc{j!i*A@t-7Wpm8BtVbabx{Pnf9L|LdY>gLH=Zb_`1ONO!p1P zAIXMVqBXw7w{LRRK6q~}rK^x|mDixKsNH!?Kd?{~+~XSfan;*FuTV*IJz;W4a8o$^ zslkPEA;Fcmt=66?%oj+_&rhq%JzDCxnLEo8KD$q}I*$>Ut7bv{ny=0auQe_1i$1%g zE9#xoEvaVtNuaPRT6IZR(>sT;b|_+c;=}aBXm9PM^#(h4SHGnu9%e##FuAoEnA?$d zhlsiigHAT@OFuiZ7VpJNKW%){+~EuSO19%|)>L$ZpOju?nY5m;kaINq>{lsk8%L_})98W|vV=QE2Luoh$` zto_#GSk#TKy4Rc8xZez(_BhbJFzcrSJ#B!?D|&vwphO zL9}T4iJJ$S#;S%pVZRQfwiEW26L#}Mp@Kclo_T*2YE1BKDY2fBx_u6#8DX~t`CG|K zK#^Xi17)}a{Pn#gjo1Sf9OQ2=P=E(eY9LVJ!3{uw1q4BWfU%EGA|C`BWO6WI7n?~c zM2HXsdkTB$LZ)c5PgETKi8wZr3n}<}Y4IX6h_k8l4pH$u^8Q(nSyShu&{?V6+0+Y| z@;QH1>Ok;pEm4yLm4oQ=Nsq%H&B0H@Y*$-JFNlI1nVe0e%S1F6MDiV8jF>*%3kg5o z>LisZz*Y$NpjBo~2i_$ar>m5k{dgt@{7Nzys|*ueK|dYpTi(RRa~l|&-&B9fWNaQ1 z|Hw1$tnqMj_Z6n`S_2IH0_KQlbqW(ov^s-nCt3~b6phQ&Dlm>O&jn;~jBhmiir3&y z75!@Ry-`zidc1P3t|+;7?4a6oa#mumnxE#jv*saiJQZ`|_Z5?|O3>Z&=RB_Gr_Jnw z$Yjv}z1F7sdOo(e7!K+_pWB>Khj96P$JFjMRIg;jMZUs`*QTt@#6`ZwiPoM$ndlc15(7Z}6fyE2 zq_y|Q6*Y0^c4r~)rww`aT)!4Q3cu|OKP-+wjkY*zUL7AJQ`BekyIm!aug@<()McYx0TR10T)}b+R~NwxU`qH*J=w^ za^uq4sc_erX@**H?_Vj<{6bTYkaQe8C6iP#4HGs$Gtg>~9{yOJNS8?3c2 zelTj%p|xM`WkP#iQ%tx**gynRjtop5Zq1_5r1*TUk__@fLm`fcO^`YS2ZZqqf>?giDKl6c&i*O}&% z(VupQcgx5R-_SjeR@2BJOC*zUOMbXC$XVQNU0lm)+_gC^4m3W5%s{j~hl@-YUq8xq zDba(YQUS7UG~QyBJVN@FPNu%XYhgOz*y2$9cr$5Z{)nAO?YMscsU(|b^0LD+kLd$a zSdVvDwN||5oR9RO^%d>p^M^=DWYNpL+PES7&$G~v{4^nyH53hmDfBb+8Q%*nIjyyxUOa4h_LwPiziu|p&XS#){c=fs(w!kItp)Eytc5q>d5A}*IoMeK!0ngBMUfm32Q&2tGjzQ* z_AD_+g!=Lf^ojt?>I&S731$^i%?_J-S1kma3L$@HJEqnQ;U(vMm=CEA@39$kBr{^I zGIE2CX<9JQSWr0H*f9cl6` zRx*w=8~+k}W=haVpBVV@uPo#6gsdr6@@(B|pz=A2)AfUXzCCZb0F4U`f}qvqGn;9t z9f8WdH6AMhE98rdRN*Trv#r-L;r6K5CaQ46kroRHQ4#E){n`KF+yA#y2K(QHIXid) zOB)ZgYNUkwD01NM_O&vlgtIDg@IDt-=zv(igV%78Jo#7VckgG0uW4||M&qA92KrV9 z{7DF@ga`jzXrMJ9J)Av^R6p5OFWywojh}cVFFN&#xKv9KRBJJF?=8t}9w-|Z$@4V$FL znsKY=jg?EP?rn;*=40SD@%GoD<}1AIk*K0OwwvCF?$_2uV0d9KyI8SL?YE_U1+^Au z)ubbK_r{Q=3Ja~MVqRM|wiNL; z&|h)Wh=>y|L&aLnKH9ZSPSeLp&Sq`tnxtyZtpw;BBViuh`U>RF)*Z`@alLiZCf?J_ zCvnlejAB;F%pKG~!S@h8__^J|6ij~Wb*Lcx%(IvP>4hb@O2VskYVa=k* zkWLuZCz=ew!mzSmUSdhnWOUvT+_rZW0v+b+7m86U(8U{li8zp$fqBUA5sboia1K`p zMoB;>3u8?{Co-TDo2{78kDIO7(SMq)bYPX4;|gI~J*1l*2-|TOHue)CAFszxfNQ}} zDiG+|Ob{zJHUz&vf3%ak34cMzfj~v(j+UNO;MwPVbPlJvwADhe`OWwdM(wQASyM8B z?)iJQ@h!2s2GA?aRP{@!^fOT7Fi?I|tl7LCClevn09Vd{?r)xAK+88zv7if^r}Exw zXBF<%Y9Y5zWohajPV;N~2V-sKebf%8g|x|UvG^vu4{#O9%HKOe9wJX8h0kR%H{+X$ z@Ow@8Z^Wa^x!7cxz((tNJ(FBe0|RO=3=}x0XLmTnf!YfPF>;|>6VR=UXwfFk%jldY zga{1GKxh}=gI5gWd*?`ehY-~k;06L5f^1~awmY9C*@TZE!Y?B;t$Vazll?z>2eFo7 z%t|pM*AB>*n}j!;1mB6-jZ%!-vmlSQ6Wn`RLu~?CZO4D$%;xx=r~Z)$CH>uc1v~L0 z<>cayV`(LNE#jfn5%Xvl$W%1wb~IJvfoPDINuI&UpJkUg=Q?EcQYgJ3;nuzm)6L+@4T!U+l9T99-KF>_ZN z4XWV)&1oY)P>7edTRUqwvVeo1H5fZ7IEIagV!{MXw|GfG4NGvnTgObu~lQ-vB$?oSbdyZeLPWp{IUA@ANBDY z>f@Ck5j9V{|9=-dgNghD8Oo^kUIA^@jQQH}qqzORpHV>iy&ov!9+;&xMwWgZm?h&J zm}O9vOGh9Q@XLh*Brbt1_|N_SL)MqTL$&{ZmnB)Ju1XS9Nh(DWl9|zln{Lf*)nch6 zZA?s=-B^-)i>558a8$0;tw_t2%#7`3k~o$MVV1}lkvW`UR^~bG?f3uxp6Bs$eCN!( zj2F)NoX>mv9H8i+j0TJWfiHvza}e+Hv;_!!CPY5(hiJB6W#7l<07ZxMJm;Q$;c5Me zk#UOWc@SM9d7fVA@<{yTao>}l#7|6wr^Qb!gbTz^jD?5v9*%LNT!)N7jNX5W?SB6` z{@6Ls*1g(Oq<S>(iwNaDN+KsW`TH#hfDJyv>o{hJSn%=SbGdULYQ|jXsOrNTWH8 zajKoe!{v$`Dgb@$bQBSKhTK;EjT~Fb`O9nn==_|n${C$S8$Z>3e!026_pEa|PS}5} z-tw&T^@S(M5Bq-i$leAVCztn~%W)b~40j2e9&Ih&TwNxx}21sfhgqH`j*9AO%L#b4qQ;o<3!J$ z^)@o`j%lPN)QqYeGvOTgzRB?iR?Mq3i*dO{N5RPF?}Ugd=oe+~Trt^#*^~^@U@t5I zOac)JqNn7Za~z{xZ-w-fK{N9oiOKHF;so%eMgE|eoY4x+4ag5%p)oEq<%f*sM??7`7b&_SGRy>r7ite)W zuTHWqB`RjiY$F*qFLw{y z3Hso3a}O{A?e+8uZF(4->Qh9Y&)zw(`dq9#y6+yWE62Y@gnkeW zYdJ&6xs4yvRU9Z5KB7!$-?gu?W3 zSPbY`g{+|xW&^}TNCM;Z0RPxhs8|=_=Y^w8_>k8!0loZ)YN!*YSun4Xl?yTXZCQkf z<*cTCO4oe@f^{j_Hi`c_?QaR#QaEge_U1$Jj$cQYZTO!vFOlL*ZQC$FzTXP1Qs$cH zll7QQNuUa**)ai3zEu^J4AW*aojbO%ocF4O4Dzo?$mY!AWbgu9E|ieT;oX|ir!3W2)imvPZcTC3XcMNWW;Pu`5N#EV!al8M7!U|ydANvse~4boA3_k^GY{8 z4V;lybaYU*-I48<2Vdehv``Gy#al)DKDU3PJ!wHUP(v`F%@Q0b5o(0FhCo>j;z1Q! zfZk$S#AUiLT+X!t6jjJ3YTQB~KOS<_pHeik(|}M{dR&`0tfWQ2kLRRFdS@%Ca|m`x zoC!F(s#$R=OcbHV%J)TqoPs82O=pE}6=kQ(wSTrCXJG9HT;*(uYBe>^2EbG!N2vro zP*#Ohz*?d8cy0$J6H=rBKJgGnqB5mU{sdGeLM8e@<#pPrMp4Z;=+{*_KT>DygLm{# z+et84ubRJ;kdQ%?^tr9~n&Fsl6U2@f(y;ExFj9@Z+Rk5ODP{b`Vh6O2mH4$+R*%Wf zP556NtQ4zBuXbjt+b_(3f+Nlg#|}1CH1%-@-#feOh!N2q?a@%MHxvxT3NP59%LP>I zwferH61m}W-lM_FE9Yy&m?2Rh=xpk@e{^O1dLs?nnWwm3OT(UO(!3qua)K`L4O3aB zGt@v5AG#-_Ne|Ctf&L=X7bPE&H$_srud1IQeCRhW)F4ljs!Y(w16=5lSaq7}YzF#@ z%a`LqGwuObtnsKWg)#&?;Gh{mLk+n+9?FrR1OPd_0Qxoq`zDPLV8G10$k`3=T0kgH z;n;|K{kDh>r?N=qa-KPh5N= z-ET8B!~nb^p>4ZN4>>L8ngQ9h$PB7*CYU3pk*kn-RN)yp7nIT}s|6+noUG~CN8&Jd z=Hmp;OSsg6@X1CU$cIEmpXc0^A z6^X1h!PhF5P-<1f9h}O5&VAZUNm9o9(et52a;_cVS%uW0|2+xK z6h}&iB4MsAK&e7@QiWMWybRSd^+AS2H6Mpffh=KWYp-e!PLSI4+;szJy^P`FNf=+j z8d50NPs18XdS@{gUgFrp(R(FcYhLrWEqhIR7R@r9-|qS575`z~*bcX1(k2!2B~ZKY zwLfjAXA^mGFV5;lJ`wayMS?!82XEEUoKNIJU(n@fE|iWg;iE-Rs~@CV*Ne-K%7u_L zgqaWxxU6eJe3yMj-qg|fhX%@XTalM0V0b2>30AJRBs3**o=bWcqBjC1H0_b|wstCZ z6GaWpiWoUhk5#f&^i0awmk2aC;REBL%P@1tMQBj0qEq?P0jFwmIJH<0^sGU4(1yI? zFkAZ0ygZv7ryNo@#6?#4Y>Ww0p4H1g2zP$yMPe&_ejT;-z@&G7?ypX-(1NS;ZTEeB z-~9e$ZSC3%mr^47n`#>aFlAI+w+UvSf;SeLcNY*3mGGpZwkWA%~zw@8WVRbFn{52+zOyPfTDbrWSZWZm6b{$mT zFun&x2ZFfa@IdU4A`9vHMV>nxrC=PXEE*Cese1I03Ksx_`J#enp$h}RaE`=b_BY8K zGZBsT84?Vny)1i8WoVr?&Vd7!fx1Tlx)PeUa(F~H zLtAOA!&d7Au+CV^{x+hs*0LYTb$P8iq6v|-0?+$CBDcWtOo_7UHVrJFj$=KLYRaF< ztN?!KJz1bsXXZ9rfk}g!N3smaNC)p`FAF+<8)H!h` zG?Q5D^(5VL$X-I5gF{=rdKhO26wz_SBuEtinq~s1aV2%XTG`bbX2wiS=0wA;c7$c9 zn&c}Qc*l3cu_ErtR>||y_~d4av$|<}GqSl5@`btcf$Xi+kQrcugl32oqOCDu zjDYW_ju4mrWDtH6lfmr({BCltY3hV7*$X3(pX&!aBDOa@_41Fo-&mgh{A^P#>I9&< zd1D>Qd5t^H6+P@TVXXXqYI!B+hQ@Yi!gXzlhP5iB!hn{m<(>H>?#3*wg0m z(S`jZqlB-cYFlJ$dHxZZ<56H0velcIm3tgT)yH$%9E!Gn^C@_pdzyT|Z=J8G{~dod zj&=AR$w?lW#*b_+Tdn>p*{%D0q63vMz^I<2hQ!BNO17&^Xq4>Lk7c)4OR&4 zEppvTJh}P(U>p-5X90-V3kw+4Ad9GWX5bbakWzyP13>#MK(L%C-=&rgjRQ1x zn??G~lxXyOcGC%{(I^2bT>OvSNUS=CHiuJ} zY!hmTG5F}%2jp}i33YDBddaJdLw5vz_-`38VX zGDpHd*hOBpU|VG2K|nL^G4uzTroGXeC?Y8M08WJn-ZMN{MS zfc%RPdKR6c#x3*1`#h3s7vg*{AgKz;fwl8+mET9S7C1I)ExOf;w3}dEmb19hk&&O6 zTr+G*mEaLPvVh4gmTHQh$ru1%RvGF7mMjGRIx?$)JHBt+dIA)*Qz+1x3|} z0@mu|bTdJpY6Nusrn2Hd=9^wYp%RtnRR4bg+iC%try||W7a79Z^UEXkif*bq zi<*$SxQ{j^lj;ZJhMmp>>hoLaHkB7L9htx+285N_f<$IXe zfA3cDzWu`4tibt#kutOSgZNiht;ykAPE;8MIxGPkiMnkfmv+iHjEhWbh>MHPMps@~^;L z-i*$%ztSxuqa0~Z8^1eXO3Rb_mgaZ|?7aE`Uy{tb{iSo{?d;B+V@cI?GQ<7yq^)X_ zJ-9lY{bv#C+1s&2bY9-LQ8ZiXy}QM8Pp4-?o2Lzn-0W$^LYh6XEYmqG(=65%9P3I; znE`8iOPLuq4 zN2N!6?hZ!(dwBRg@Qlz7Ajy>|cCqv$Xwy7)N7LiI?F>R`_EE%xDUaSza4)BevdThaqNaekwxbKD$CO1-v^9?E&{ zQ1aZ%f0Uj>b|5|VayeHiVD{mR{=Y$7J5+R!`fV7*=-y!KeR>;|oBRD5>8pORZ$_@i;jwI~LJ=w>1{C283hS)i7ETsfZu%yO9^#c90>3Y`a?K8@38Gt*2j;#n z3`BSK$XWiKieREh(X3#}C#JD{wu(5-l)zN7+_DfMO0;h1eS7~_WuKdzo69zbL{+M? zbCb5YYz*Y{;W^T@=@o*-H#sGqgM4VY=)@SuBfOwb>;zq?#HVS!E-e+Q%#WV5$vLOn zk&1|Fq}sA|8+70M{Kwh2iTiSSg`f=!%N=nOhD3I4n-4r^x!S}1HD8kh^BYqK8S&Aq z-n4%TjcYN9yyDK7=rp#cR$J!L#J1_xmSv?hvl+cw%98YDKE8An*$=Y1(>0GEb6=5#?!NC1)H)TOR6#y1F;T5}-(tGmgR|3IoIC?2_p&{14 zR^SRpKfXr_3>RhKS;S4EC~221i*biUl;hp~zzFoxVhr-c<&@u`=VBFl7kDE81*Uws z8v|%+k@y+kXm?u4dN@oXw3ljU0iJ?$hevX!gSP^}g8`t*1p9jcHVIF-ROSB@b7`&M zSLOT}*cF%g_L(eyx*AB~Lj^KJskaHszd&|#K0d+;4^@$!aZobVIUXv7gJy!haF7}3 z00*I1!~6rXz7QILanpfE657hC26Mm;bQ9AOTBlmZLKE!Q0PI{ll)rPGO;}bfIIg^@ zhuwFX@0P_ngLavBWoPAiNqlk(#ZKLXg5M>D&>J|&6x_ZU=aK|{g}HhF+9Rx_hM0qA z#I#8LG49R*8XiZAhjzeR>#1wqe$EtB3m%}Qv?4o`Icc%7%75Fzj~AYP*f&3A#8hv| z(B18GhBo@HNSc*(E$Y{SoepNRO!q$ZKDlbaiUG7A+^KI_(M*B(O|&{y-Xqy$?eKe2 zzc&Q*Xi)ue%PNPltX+1FL^|!ycNykT=htnHVAX+u0E=Ac1F|UwIIK9*Njs0Zo)@V2 zwNrH-laUvyfDe3w-mpWLF=OWqJ*HDGcBfg>{b$hq?^4#$1$QW`=z_Zx?u_HAK+=hx zG5znBZ6{sQ6dui*jJ_D_o{aG9k9c37rP;W&v9o{Xy0_qW#O~>73-@fpZ;2)MxP_NB zK1t_YKI4WTpXe3e1!eMvr2K`e3 zP7UHpC76SuHAo<=y-NC|qtn-i|uuySWA*BfJt#JzizN;3i>h2vtz6D?p= zn#zGqGKF+vI?v~x!cjh%dj}Gw0_+sXN2~&8g6wLtHc2;<+e8Bg@)S$}0o>NhP*ELl zD<=<@9|?E?A;BGFVy>c9b1V1-V%o=bYN{BZ?T01=xr+RDnofl-BAU)H=!MQSPr)vK zuBxo*)P@f31}8a=&{^PF`AH(m(Ph@sh^TQVvw=n|M;Af!;pPs;t~-ij@_Cy{N97@j z!tE`LTjPf<~voGIgj|hy4b|tQI-V}|CSxdJ&E7t( zoGlPxfCDc=zJB19G$3$3Gu2bATrUpOWBziHvki8&Cfu(QI9?JStP^%72)(3vS5W(Z z9(u1wY4FWEkb@t%T|%?Qxo}|aPe5Qba+(^V529$r7FUu2nQ!|>D`-KMQH5q8Lrg;l zhbKW3(?KJ#>W>y=MFG?{1A91?@Yf9H*(A<)xKy7ITO)8*c0@|?Cx`HJr1(^!y%c|0 z7$(JE6fD$_;;m=DhxJ=DS`{(12 zSKfGUO>7e)0nB7^pWk;&K*>ecvwG5QTi;!qGSzP{5brXcbw6J;+t+tJg`M`Sr%iayybF+tS;oldx^SEnTM;yVW9v6YX7}Nq;!NJ^(q5jIUwh7(FAOAA)>E$(GJ6?k(0I)e zCh0Es*G+SDtj88Fau$5<#U1X&TiM9Uw}#{c4XKJC)PwW2j#0cuNG==!1{cW60d&cE zFYm6B;yl+0$@abYG7sTYkj51Jt_O70l06Hd;7p*x3Fow`%W+DsfK89F*0td*eP8aY`A8Jl2PS%h(nQfh>qkn~Pd&Yy} z^#IaEC`YV1LFGG$Rr{%Y;sAOdL&$#)p?I(Q)k<;iY2~XKgkm&NBkrXuUu|k(|AkPCp zuo^*N?F?L{F-WRLx~5NwNJRl){t7(%2|SY6D!4Ko>ryRffJaQ2ToY_bwP5hFkdnod z8PY}mC_*ci~K3PHsSOPntEF2F`{ z^jv_Q^e@4tONJb#Pt}zvKCKX1ZGx?IVrgf?BaTe1A(mY$@PSLG5$3I=XRlyn8_@&r zP#oxicPZ}l_B)iw+koeCJo>jnyCbhUWIt6n1MHG`sqSlKUJZ1x^An>uoCht;xdo6T zxm`F4!3HAt;Y4Vp=7}QcG!I%kh;J_ylFQQ+K}UJevi(r`!;iG6@I4XUUka+eG3R`y zVtqepem)?pML!S83OeXmhs(l%a8l1k5?=nvpQJDM*h;dOd)x?l0-bPwA)rM?@t}F1 z7*Q)qh~Seaitai(7>OKL*V`BrTe$ z{_NBi!W(k;_{relv)=DbH}cLZ=69}$6*TO8>Ah+Ec!g!sh0qq!t)M$!U$ zTT4y?I`z-S>Y@&N1^@kE&kM)iQimAbSqA&^(AkPT;m}(I^D^*Z?$^%eYdcl3*$vK5 zD>ld8?a6v}WvDnk_$=k+&`%X-j)SEY9_LB~8;0mZGluG_csp~>2~&F#doF9b&e=^| zp8VbhD+01L{hy1?a>2}=QzeA;vQZocfNII+xb_;dEv}t`^Q3T2}IV$%kC^O_ekw$KjZI(MSL9QN!Jt%^C2uI&(6>PG@8r2FG!_mu` zk1uiD;pm(96eq)Fu7EJCg|U#%@s}A(@w0i3Z=|Zdg;1MVb)HJF{~I|7Gd*zm`XE$; z&|oG37dj2JiaG)oB%K4TF7(ojo3h_cSozoFg&qUDqJ@j0>>6D-%*Ja)({!FSx*c{p z&srTmK&Mza;qwQ4zPz<wcVgj;Ki_1!kW#1!$WOa38Y(kS%3lX*=RCh31?=l+9(6RkB_I(*;ViCuJ!p?Et?R*pRD}C58t`;$LQb~1 z;Ym^FfwDDC$c;Lhuzo%0U5hxw+(!Z=3eNpQj@volbx=ZcD&#!D6aGrzL`uTEl^u43 z*m#cZTwa9}LjlXLZbIXvwpWBy`La8nXv@}{1)#lm`v`)7-80C0WxOS`N=H(48*SEl`#u>t4^&nZu%) zx*f2{Ot%^qndl#EBJxJ_i-tz z$V-aJZBftMKyGIRuCqJBEql(DHv#WfE^=~rn3qwa!)|+)+hp|i>5Kk^^oEmmOUoal zT3o}aof$zPi<k-34kJ)ZmMAK!3+{>f)1M?*pt#O+@6x)EG(%ofzV64;8GSHc^wEDdbo9*Eh; zJ>j0`a-C-1h$-4yiCNHaI#KlS;c%$ECP$)(x(eN2Qr0XZtx?`QDtC1ghs|TYzr^u^ zU9AZH)dJ=gQDGgwLGQn{Uw1Vj^A7aV4;&Pue1gwU5|ryF{l89?(T9+K8h}lL1QHdE z8aEvXy$EIN0il-ZJ=EX5sJ zh`c9-uW3=tm9yM8fu#BPA5Fz^JNfjUV+xVZ@Zwo zn|TsS2^U%+aT|07lRn8hl0@gN)Y(n4XDW5GCv|Jpx-Mzu9q$d^cEo&Zysa@+y%6BX z7r96VoT%yr0N+)qtM5=i8%3ebia_~ri72M0Oi(~D2bgZ|+{|D#fq%%+Sc z=4pV9HQv)x`Kndg`)54ok)(Hl@__}`U0kq?8FWT^xT~XV=N(e8{7DMm^Dc=ckBsMg zI!en+TgaBwC=;-839c+2x&e2a0Hg%yuteqY4@LU62smtm|0np{Z4Ok_PBq}xQ#KQ$ z`FPAaI=@R?kk{g`iRW0rEwc$5s{JFBQax<2Ig4SV88?>mELpP6BEGZ>!_pLxPA39J z)_BY%XdQJY2WDb$B2y5hKqg?E!IXlwhH3{0fGzoDZZRVZ$7tSdzTRL=OMV$PUS}j> z>uHG>b=zPcFEQIh3%aZGBjlAG;uT%eQ^%{?mQxp)6T`%(R^if;ibgK+_oT6k4AndR zMb=Vp%OCt&#vPr?PiHDdi=oS9xYA$}y&A4nhFa*H#B2v`Nuur}ZAe7tpGk!(=0Oz} zPzB)&(^Jg!M88Uyp1sU6F|+IovrNJ)gGN+!B3-ANm)GjB1##{sS44x~tMO%?=fLk7 zwEO)N>Ce|;ui-W$)nUUv!p4{9!NpcAD?1NivVZqTkCQhnRH0%ms@2}OaBV+I&iTxX zJ$R#$eB;nl?_X>5Rv8!!{ObRDkFoyQjlT|Ata)1Dee%>V3r_9b{JH`s8XC+sf`AL6 zG0b>QxmzVoHZjcNGx}9|F0S*g6qegp+m3Z#w`-VK`r5wM*0lBBe*S&<^WOKmEB{{rXE`-uB`v~` z8j(b?phAfhJ1Ue!Nl2vJO{eUNr?^tH<0&hs*$EUcYT!)LyGm+?gD2)`$@?VU0)E%# z;?S?fCC;>$4em=(oyvytBD3?5=NSiDUc(cI5=wbmpSg2c7PsYVY`SN8cgX08Z110i zUt;`^rm{CIruYpfcJGVPYI@elu6FB}I~L25XjeT0-bpWT6FV3H&=8+UnHV05QObovZp0e5qz6r%@_I!u#UL8N&XW97{I)6=k&-`=xiN4YDC!^SZ#NU%yX%=Kb~J zk6EghQ9>JZ21{jA-=vTlH4ww9&uhlywP1pqF~Ry1&5eyVKM$X|$EZBI>hnb0JDuOe z+`*oJa^VyG!JZj|J@W>8ECze*279It_Ux+e3a;<6uj;bo@~RkkDrp*t1dp!}PqGSP zbbMotqOqfr^m|98(GeYgu0|1w?g=JYM&mN?Qno00LNi>zWv6Jd59I7$t8~@VbtzT4 zyRdGy5^Yi0W|Ka4sQpB#)9!HoRj6e6ao$Vk$*1s*tRD9Z>C z7U^+`NeXM2U@C;FyccrqO{BUj0lLscoxMcYFnhAnL>HQ*E2-6aigh`#ZnaY9p=CqM zHCVP{*JNc*if$KBX_PNY0Yj@$^ougOs=;^^07J$B`KW;fw@)H43h*JADMw~&mGk46 zdOn0?Y<@KdoXZuhq*a>2SM_8k;j7bS2jHvvGNqmxw`%}ds>E3nh-f-z0TZyuM?L*m zF^Zy9j!LZ?bF%Q7TKlLKx&_nbF+&XUt!g0$n0BfP3WsTFtx#nqfwWiYdU!yP8;>PR z1URKDHf~iswz8U&Y$E&`Ae=j0D5};NQFR8g0JvCB_DxUC-9LbAP;%`Eq~BngB~xgY zUsi<*ax@#J&?28w1?44wfPw?^DYYo4UH;n`!SR5MylarE0^Mw#P{|ND_{l;wi ztNgiESsFNi`dP6WiD0@idRE-RL~M%0|Cj2V;}^JZBG-|gjd2|wLpw@=vOmVS4?iLI zjY~d3?{OUkOmxCUL>Ld;4-oUWAC!?#q3@6GhCfl1=Z+B|^e55=S;a?m`5^n>xpM7> zsBaMUKu_W44BwTnwlBK0wEEc6zYVwleD2uXlh<#2X-2zBhUwfNfs*ehVs1{jkv%gq zZtYCJ<&89+2o)-ZD=MF7TwXNu(2NT{S#S5f{g{5Z z=UV#fzQXa-$zx`nqOM^uvs=)=s(wr4)pXqZ{*(2!kyo$dYWfdo8`mGio@#&Yz$q;^ zAAgaR8&(p;ypQYj`7{g)Am^$x*^8~-$ugDK3%hR&?vo|Rf2l@sG#lWyJHL`RFOHw!n?0o9AE#@AV9mvRf``Msk|4Q1uM)FeP zv+`d?kLNTv5KC#rsO<*YwzHJR@7tSWWiU(&`i(o2<~o{Qg)f?0t?TvLG2mqj6xEOk zIIAl1Vw@EXXH`qS)k-c$Wv^t8Ss~{a4(Akn-4NReU)RT$!`F+X-oc%eOGUC@b z=l|;4l%4i?a33A@wICAOrr&-ztg8NT#*pXY0&B@T+{U;itw2m$oDTB$2@6CE2#`;Ux)BYmosMH0gQ3+(JFHC;AZ4-m zkWtFhiHg>7Y(SUJ&*Oc4N`NDlmdiAA%&)31IyY*a%d~I|T^__P8PX&b$v9GtrFt@z zUwKDXBGnwW57s?AKVcQ5GjG>jd{sO#%{v%H#22>r2FXt34(_ijkBZD4^r$Nr_N<%m z;`zl{MOHk{$UTD4y9MUYfRpW>0jP`R?Ct0iZE0@aA1~%KJ{`dVa`W{|V3RWU%$XXf`w-*F-|Cf}l_|#g?AdjVm9ce=K1qyD zbHy|7;cyJd8#>kfelX&^TS?_8!Th@B!!@r~p|t;JBTIt+h6SGf8?4dI#?$}xd~`$i zm&`?NlH)xMZ4{Ec$B4zaOCrg?C-GT@C9%Wi4~iHa-8Lt?yKRo6+bS7Y?m34{n%^%x z_ntTVCd1xUac_;n@8~dklil+6YtUjp74C03kg^_!8KK(MiD~n%Kt~q>DI=F5&uyKQ z#3I>NdEP~SMhnG6y{v$A`JQZDxM&qobXMNDNfab++#+JiSN|$sy?cE1xIFJF->sRl zOx?6u)G0l@gvHW@f)Alw6K~GDb9Pz1xIe3Cdw)kBm_WN;LbyMxX)l6kc29l<{2$>( zqW_^A&wh-UDwq0omup!Gu9PXijEBeZH9;p1@Ti7=&2w^o)6=u~*6|MJ8VaTCeUE29 zbRWH?%E367u5#TAPg;g!Q6)nokMwao74TTT@8C{%uep7H)PPA-`jm$Mkf9gKi{)NZQ(Xp8Q!Jc!wcb{JN})!5Bn*N159j3zn9(;to}^gS}YiJ@%hq zxpOkQiR9A0$=ibMc6VrreR~@%9g0o?OTB`T4-O zmk6aC1E>zeeDmQ)PY9mA^p~|D;V4Vo)BKv^dxI~(lk9unw~3~o)itwT)|*ii%7Kx@Pnnh-Ul*?LEoA=S)L6VmwL9ociKCMcaD_bouO#oF-oY=;`vnRAmHax14p zq#D)XbCVvqmHLqEMk(S~dJ>Wu=0bvdd6n36lL_z1u3(!g1#Ql>Y;&EcN>>K!f~#~2 zSXa@a!}{sw1`Q19sOk>sKt_BKQ8M86U&ua5hfQU%&EyltEVkdj$R7V2ztUkqM=a1) zighF9j$nTLVo5#t7Nr=n^f|Nt!ez-?%#aAeFXq`J3bkf3K2$F7&O55!=Kl zmT{pOO^hh%JvLz-A3+(I78KL3K*@oRG_c5*O3(*To%J8PN|YHI=|;-o z?mu$rQK#kIW_#5#YE0PyEMx zZ3CdcaS#=-nhK8u&c~OmqlZMmu5YAa=rp!<%9|EgH*tZ%KOWXCBEveqsXoiT9fHFR3dSC%y=-gPw+5x-86%U55 zUlQ)B6SgD>U8gwTXsInnXe`Zpz&oY;)>v4v=?-i6vhQDE;UzlzS+`3G!NR< z%Tl5}KF2vC?E-kMXRG3u&K(!P^qyZ7XFD4&fY*CAD}p*#UjQ?D0&FZxK6OMs?K)Q0 zmPchXaw%2Azx5a^ynAsY0nG6%n6~c|11WrD()8%t@G_!DZeW|n^vghg^f8yr;4O-k zoemdDZUhG?7IYR~D9H+*A$tB8D9J!>zb+FL=qygx@3E=eW6P`DGTi<~7L1X7znUkZ zp_1T|0?wQ1KgQi9alXQ(dW8K8=9qgj%-k_e9 ztH>mXK0`yJZTb1KvpUe_oDfMyX*@lk{~pP4l|QlkTgHg(}o#zT)qn@?mebl zJ{_A~B`AcWt(ielQeIsLBl1q!9QyWxGBbL^J;erjNd6yCPAbq)O{P(cXGv7^sQkGA zDQPOE;*ASTgr*olUwoiDov#l(swU&9#Td|BTz<3)35L7hOUuh!$TmrwZ+=+H4CaS; z&TV*?DdBXjzpe7Y87Z%;gF(Eb2$2g@gnrVq{*;TlE9?(@y zW>ANxfwq!zOC04Aq}lTU(f0#`#pO;oA2X0sg%rTr164>btmU>Krhedr8R4}x>pVtD zokg%qMKbcWP*2WwXYeUb#tDCY`Y0B{h4m--aqSKuRq#lWJ!zQ5jJu zX9Mg+D1Ry+!np*w!Z;6KJjac0hXF0cv<)~g9!1hPCo#TL!0nwl>|Tq&WjeO9 zMzBZBi~pXm>(1L~wk?qn{ZLZ8diUMppYQ7Z7`@nY z`19tXjaObkJ5j6O1~R6$Y-+-66PFy5&5G?5o!zx+-u7qhH@+Nrd|-UPw_ayg%@)ni zWr3%^rxtcN?HH%3x+)>-QSSF~+O75Av%qJ(OP!BQz`R8Y*;7SegYXn3Z76tDts1|* zJmP5g(#~zM#3{{rPUnRoU}Z&dPuuaL4t#LzpFM8J+n+P;ue-!K*zvp+Is#_d64-W4 zP?$?q$Zr}e366P@M4m<{Nr(x({e8hjr21L*C7CI-ISD#VElz+!;O?&8atsc$k8XEgjth_!1Pv6_^rABJ>uP_BQaT-rmlOoFbOm;H zfo)w_o_@3Utf^ynK5xqxIXAl%IY+gd4%*xQIAG@iC~T!tfoUM479kjaqlFei6Ji>h z3K*j<74*ObN2ma5C7lX8;jw?huDb@p(gpuIQ1?i}(8e@{V|`gjdnZ%@Q--eJguYVz zG@j8tN^~xey#kLl0F7#q#j~eUB1d87dK`8-=wE~Ef|=`ZSj2~6p~J3=;v{$Viet^Y zi<7%DB;#{9U3It=$XSD#6vrQY@jO}|-@Av2ZyWM`fxw^(5ZMSXLYp>_? z`FPwPR&a_sjo&0xH>bfMrKUU0e?3BxFBp5#NewZFl{HaK1!Jr6wW_eNCaU922H_qV zhQm5J^NTpsTI4*USW^^hTm**Q11L!#e?TgOd?JlP55bfT9MY}$4@kYya&5qF)idz3 z^P67gsPs&Z^&O$p0OZP4Xwx>a;TFcA1H?lr4S<{-L}5-)6d>F`+54d0CaR9)`+OKl50Yp3hTXiu+rPE65(p=sZyx_hiL*skf(T?>~bL4UD4D($a)|@9k-qpwnLo3js_Q z_&gT*JQw*C3i=KY6CYCltLxIozqwAZy~#N6k7AfF=E7X62m=7j>kaOwQydbVm7*-UiYKNdk22O zO4SnoJHo)8w27}u;Mxc$I>RF~HxTuRTOJK5na@K?=Ht=28Hje?^jMfqmhd7DuyUmF z4pepRj&>O|p7`n~&si%Lj!tiIP>7AuVT+^RO~tt3M~)K)D6|_*ymhFI(f&|-z7@?a zQyjL9zgFzpDOrmO|~H zt~i^eFpyBTx;W9oykY^S4h>Z=Oq`X(LAx3>+)0B*TZ@=!yWMQ0=DNdB7<`{LOk7VT z3&LUeK3$mZ8Z69f0?8YWnM?L45U&*>(-^@WvWxcs|AW}rg@8WK%s*d7V(=qv5og-0Rb%c&eN9XdhUm-f}R z2o&VfK4}U%wA<5Spi7r#Pn%8?!t1Z$%+KY3W~uGMbVwj$*M)uOfUGgeC4{c-b49W7 zqK)mY9?)rXyK5M9@)R|%$E6ja7GNu#`R_RWI^J{{5$p7MkdjRI932SeK1E@@} zOUM({s>At^Ub8{Sm@zf#CV(-OuY#HUUfElg16Mrycy*t2<6^mN;B6OUXvb>#kWWhmEYOrZ0@1n)U`~oWiH^-2u*vp9j0gJbN7oxs~_7LlZo`~ ztBk{<^c$UV*ExNSuQg=aF)ypYcOI!6+y3r@A_E@3lQE@188Z7*Xi5 z;tu?d$n~lZ=GR9n?<>`RP9rEhzJ*Nl6gj_CoHZW!`TSkY^X5ydUqM=#TQgdjXG0Bi zk@!}O-+@}x@;^OwO{p=-xXJYG%sc;VFh-)7{j$|SmtEG78o&#%;rJPpU3w;?w#p-* zMw?ZcRC{`AWwpuh50&E~FEIs!s~=gog}%U444!>dv?sI_^J388QIT8db4<VxSmxv!x4MgZY^kN11bk7v=+ z4|Xekj42;n^eAhO)pN}A!9$O-+^o{X8;B!qLFA`H+H?Wm*|PcqJM0BfX7^EEBO#5j z-V#=HcY~G2_)oTz57=Y>^e~cRb6}dRfIE-*8Uf5qV1|XTb+Xi%`IbY{iRq>eV>0Of zI&V8?SnN>WZ83mq5Qd^>83-8v)wt+8muWH^h`}*}h*Bh+s}d$wFjPl;uS_qPqG7b1v)npr8-E=PgL3Qkt{;5T)t3q+3}^XCUJGl06hd}xax zGoFl1uk+96KewOG+cc@rkW;QJ!gfr>sVkUG3SEI>#gsxt;nbwC7AQgtrsL$ zFr^OnADByX@ELGuPz54uAQfOueWX&b(5IsZZWuls0zw-DB7p)&%C8gR2H5_R6m8CH zWJPtoYxGX0Py09Vazln4T{R|>lpkhpDEfS>PTFBdnRtsm@G&2{wgU~(R)ceCN#nxd z>Svm8!^i{>IyoAm>%OZ3*5L`@US9~)owXI=&$|eeT}}XhS_$yVaOOOkT|?x20)$qP z>JUN4G=OhABU4%Nfz4hgse-^N34{<9dz+++(IGYnVBQ7l3Og#dOx|~9o}`OyMP$SQ zT2R{GD!6X_dm%!Aw}vy-Y5D`z%l}ga-}kuysU?wACV9rbzPOni+c7B+b=#oJZc;Dq8@_zo< z|EP3x2dZsmz8eTZ70@a+YGsVpk&*kqCOPtl8soy8loTF~3Qd7x`4mM(fk4P{4T|kV zg|mxdr#1j=#$tc4pF6_Gdtc!&86asVqD-IftKZ&zx`1 zykXCDvuC#2GuPTPpW8FfKg8FS^D&Q*cK$V@_dVmC~~p@*0! zj`N9_+`+m>m3t3-#Si3Ew>rLHoKO$CmwkDkMN$@HA;RCzZ8^g{9 zFg`WZKD>pop>2d2n#ipFh*}9go@3Z1)k68L!#(YVJ`L5rR=9V) z`W0Z6?^;}G0Sc%<#pa`wu!aSwg;+x(YCbm0J*+(r`#MOh@y5FBDOt7dU1gs?i&uG% z+&Ox*!n;*$9qs{hILU6G{OC6l?bI{U$Fs(fdzAyjF5~jKX`#Az$*rRe6?P=VE)#ay zfQgKrj!x|@6HOnGxfNOk|N==9$GL10b4mf~!r11%EF4a&;q zFte?A!#8QCiWC||Vc5Q(7ro&hQro>Cxaz&o+9H!?+{cX!ucu=`MJg2fK+i7YTFw(0 z6jaV5f8ba;hpol7J@Fo)R6Lqkqj(ENu29j6BY&ocnI^L#EF;EzO5K?wFg778yC1sq^BJL=RV;0Xy;Fw)wG;qwWG9J5O%^!>4i)P46oOzJdN*ahp zs{Xf9U(Awz(HqA<>J$zO@M`~DABWL(O9!Mo&~@&^Qi#G}s)t;?HfEpBe-SnT8u%P# z7`P5=eQ3gO35Tpg&MFXZ7Wt(!)_357?gC|=*g6BCED;=m#>z8GuJE$}uL);r{0m-j zy@{>!8vg5dh9!WmEa@h6EPOyZA06vCEL~LycIzW~o|9E}18k(E3WhX~CqN9JWfJr; zy6j1X`1y8z7bixIOe+vOh>!$^A%q*N==_gc4I*r#V;2L=t6(KdYKD$A1el4S80r?P zyU*0eu7atp@Hk}}vr&jrnh|S5n=QyiLs^T*zZ8wR)l-WEW5#&A4$Qxvnk5*^ED);) z@d*ixybhTSHqIFuCFfpe47*{0LJghNo#*Y3`BeGC~FCaUX5`jn&|*!i;evB8y@`QJw#VH_ChpEoAw)zs6x*U)EbKctTz#i8GJGo~z!T|y@eSe7 zNX$KG@$JLH^uNiTy@3*0c84K?!eUSg|Gz?Mi1H6bMl~C1+*`iPz7Tiv&2E#FQ*N(} z=DVew+4NIGY2CGVDq#sTu~C0-9i)t=T7O6W*@!*{pR=X|M&wSG;#O^_cH!?A@=wer^&yi!Z%adbQNRtfo$F`~+tk2g?oHju6coM=qRpzZ;WL zQWp5dYggH;V$I*rE8^T=6;hWWzCs}?uS?Pww$%clZkbS1be|k zUF6e5g7HAWYRQ8_L3V-2k;<~uhe&%UtEs0=VQN!n-(`RoSJ4~>91P*mb{-CcThF0s zHVBtP)E~HEJh(&P^Cshu4|f0)QlAGx=@BaM?yKOo8561L61cT0O?@54uW(ShKowT# zj{LX;e=m`sA@H1!d{OVZRr1VJ;`>z8%Mp;4#Cq5B-6j3HvEpQ=@{iWYjJx1hXxt&d zztW{a^f()|pC-_q0FDn}lp&lNU^l7)hvbu`Z~VU9tZV&!g~P@^XI>mJ-NjTs%2zEG zCw!Hey+ocGG2QKSZhSS}<2d=as7(>@z~SyvoQrWB;A(0{WAEF0X-~Zq)7J4%Nl)pK zXLhafor&^llu<;OW(5D3=#RbV4_fp`#nswl7caN)6Zv&!H7a4b>$`Q4f!QlubzIYz zBrI`Q4%yz~%|Tx*~X5iJ{{yQX7An}+Ci zA2Fhm2=nPDRdHqO`ApMvnRqpid9o@lj4dZ8%EVSYCQgHr2j#B(o()^kq4?MHvjj5z zso4H@j3_t4JcfV~DG$*JNFgWq6VZPoA@&1&Qd`JDeIhz-B*@>xCyNt7&u7e7xT3$A zpBsBoq5Q5gag^5_fU{$l_cx(0inquwiZ`40DyOB7I)CI3;vT#UU$k-Cfo;Zd2ez3K zGJI31Zieje&add4C>wJN(no&sJIQE?$aF~1s~+3Lsw)QTgp|N zY@~}h#^Kj-!c-<5m8Nr3OQCT~;X@5dt22$H*;vTQRowG$pVanFA&Yr2}{+d;fXuh6%zC1GRH<45K%KJC)@*h7R_+ z(=a+gct#yu^^TD;8Sy;ps$#RiUsrBguQ(*2d}@eWAqhM5hjOAd?)BB8h*ci?I>5RH zFMae2HIJx4qD~)lEM!`N<-8-na@%-?Dd%VLu9oFsJP}$83 zEfSx9!;$+NyGJc9++f~%s$8NP?az7>0idDf&iJf(^@PW#PZir*t2so;n7 zid}c!G%4nw&ghY`J_D@cR5j%hZ&^k0i1`b?zfb8mtnI$`9~^TlQVDNiMenfrS`wM( zS>ebrw%>m9&2!eQ}Xq5wY+(1ql25Q^Uz;S?&GN^PL(5DB?TFw#JP9iE#&APdTMkrSp^ zzRd&!_AfJTnFyK6aP5$ty9?xP#K!)Oj9USB()?#|oeQVTqggiy+XPeYH?gr_Isb%m z2@v3L3TpEk3Z{_oILP^5NEf2iU|~ivwZ?)m1N@Q%0#OjIg-mav_FiY`rjlW5Sf?F) zDrZ`SoL3;W5yb*ez_L_;a(yN}u6N!)kJ|q?J??%15NC&#E6=3I)wbi>p?nmtTyYK) zGQWJr&_3jTj+`GX#MiVTW!6af=1Ga;02?Mrap14W5+WlU`D{HfW^j|}sl&-ICBy!c z9a6>)j%6xiImhxQn61I@0N%rF-81^6IHhKZi>oP6d;T@nexG^Eu$N!0?R)m6eR z7JHGTN)KseBRaZe;;4q`s0;rHhipPV(t*>)mhJD1yh8lPQd|ZR6a{!2cy~Pb2m+e` zAx)8H=+f*0V8j@~oJ$*LRjbZyRH4c9k$T}JL0>CpM#G|;NKkWuX)7a58e9V;=jOup zvxvs{Ep{SCDEE>X=Tai$9p_RqV}dgp&q#N}^3I6*^Z`;sq<9_;!KyZ#AuS+h0|)2R zVptB-aT7ka2BQuu)M>}%gA)Bo@Zh;V`6f*2SaLcro7 zu;VQ3cmC|U)^+7}<`Ia1W%%9q)bqj*-y<)ndb;Z!+_mHAHof7{RTsA_eVFU!xLsBM z;zB*G8d4Ut%I*5a<+5|EZTP3rJbzR$qlcM;K=Dx^FZfWzf-MjMD=}tuZ@p7&SfdU;0I#;j{455Ftk z++N(mJDX>pC0#@*@P9c2BE^nkl6+Axd!g||qOyXqJIA)?F*m)k$T zDr0xFw(QG$=Hb1(vPy9Xn_rsP9ZfA=@5H>D6MNsLYAR+?`RmsH;}fCLIpA%v+nsJj z9I%&1dneAg44iBSzYA+Cz#q9D6L6BS4am!p8yAkMMjPHEAEc9fdPt33q($W7j_jL^ zuN>b*#@o(pqib>Lihx_@D9K-F})Bf(q>*k8ep8j1E z(WLB;e~B)Jv#7^SzcG+Xc~-gt+38op^R9wj=Ct4esZ${cK@q6gqSwV^;oFDV`BdsM ziMDiUMp*K!=QQfITQI1XUo4 zn{9if0d#`sZUy1MYiJHg3I`$|d>7?(ap2(Q_Q<>8fTl4hJ;8?i2j_qz`>Q}x2)dL_ z$JF^k51cOIQwJZnJdFxg0`>9=Y|SAA2}0U+f}cTw`R@ zahlk$OvuOXcy9)6+$iu_`99L~A2aKWz-I}tw?5JhZKY2H_(!l-+K{0OS}3uJ4`=_zXD*q;Ouwi6FDW<8NWFt z3k$&??zAfd)mHFs%~=67#LAngRA&(_)tlgUH#}+kGlA>|s2%WMdCJ6W9;g>K)^E5v ztI<`nkZ|ApADShB@J>M2LH<~e%{w#^Jtm6Y9cCwrcKuh;x(rKI3qeCxwK`m^H8!;f zPSK)~S=uRW*AsL4!(QRy^ z6J9HxP{|5dir2bIXt>D`-y`#(!S8l{GG}@o8AcQ@7R8zrg0y?HHs%3LV9E>?0U80B z0Ip3!BeYy?b|MUs7{%^?@dyx83erPC-Q8rWFi!yY8phn8jZMwFhm4(&7-_;N^;CO_ zk?xElCF~}Ha*vz=Cuh(dRmom-M{RN!-EjrPtH}J1^zJ7{32qIcUS=t#^}<859Mga= zLXE2r5HLd41%eOyp7A|8bj}sA`h$&p7?1+ z;Pl^O#6W`lXQG*J>L%fx1vKh_)E=G}4`vAP8h}TW&=`$0B?8cJEiW0=6y&V^38(JP z0VOHIoCWj6ISxPJ7Q0K^g{%JK6h4@FdghDMY&hZLh37Sr0O1b-E z!Bz$rRmXk6Uw1qAC+acx@Xj!ki{z4py#4Apn|j8+S9W{H-+7WR71~Y5k&30b6-o zF}}xl%5Q1f{<5SC)`xKAKlYxPa`1i8p7osUGphevp830W_^XKFT`Vqk;jN$Wefzui zz=W0j!sB*o+w}G+MCgxp{*4ORr0;T49<#7QCi7iQde3+M&EJqERFdQGa!=1wEZH~V zO`Zfy2IZ_*81oyF%WBA?`;Va$?? z05uV?hzE)ifTBde)S1@1oQrYn5c+(F=4PLTXWrB9j+JX)M6O=W4Oqkp*vuiCi|BJE zAIzP6aDmg$_)glni=X}ib^Uklb8PT)M$ZdWI`sH7j}G%cwR1$Z3q-YhfHH)&62e*) zVXcg?R!5Z0L6oT=_$pY2@#ik#x@-NV6JYTd=>-RWWh_HqRIAIu_;(0n^TFwb6ZknC z>7MUUP;xfNUg)&9nHu^^`rYg_3>T05b`|+80Xd-(!&RO9-rIr8FBj*hFcOdOm%R`l z{EB<<8{so*= zLT^d0GYu6F@Kq2@RcxK92(Jsl<~xKj=Kz48{8^}+52`!UJQ9FBHH4EgHrC)Yjg|mu z?>-AnUtwYm$6g2G;VRjLkC4mUAOwH*{2x03=3E3t8yo8iy)P7XY%EMPrNoi$>=3%@`a+Q#T;pHhtPT+P7b|6O13o9)54tJKZ9E(l0~*K|7BcuNC(v}pAhB@ zVW{hep5#vT?utjnD1N8*XfW?ITh2UNW1mj1(~& z=y7+5iu823WA!UVd%7IAEnDH&K1883#Jzis`51oMqdFbRk8#ic_&=S} zJtS|-R5YCY9`}VWTsD6yIY;*hkh~U30|(1LM!x;yvzS$V6jN%44c&+h-6Amx6?raX z5f4e99YVUSfvw0Scz&dw+ZmQyj>`ExZTN4t{8u)Uw8;I=K*yl~kCQLnK$xsE2`VZ1 z;dV=}uB;+C9*&=3=+E97ds?$*NHRUcm5P-Qt8Mr>eL;B}WZAiCnn^oGN58)Jo6kD< zjL1D5jk=5Ik{*W{#?2OC#Vf8?&k<@6t~p!Vik;;!~PRCJBD zXXc(p0o;8gVd17fUh%#uzSn#=IR23=%E>yDbvlbJzhO_9+T|xpK$F#4V~)QI+1Q@k z0%a!KXLF=bc?DkRuWO_vuZgG!or0{x(A?|W+*VR@t`J4x*T0+1Xx28S(bD&8Y&Yhz5 z?`QzZQh!#ffo~%eM_8vo?_Qxsj`v6DRzaNQ6jM!6*`zQN#1&B$z5>OoPQ?m$g~vL$ zZ;>d9OzqMZM6H1Lt9aNoby*6ciVMV{L3{+jz|nCqEZ>!{%!ye**8RXycor(C1B!4- z-12&bmq4*)%1K#4Yg9xE6!0m^9EG**t2ibo-Rn7}?ht1T`2P?5L4cMo04RsB@)N^S z^(2CKCelwRL7O2N@dP^-+fsryMKU}^u}`?u-@E=dpgmvQW`u|%ivEFM{!h~@HAMdf zN-6#c!dz!itDBaG6!ypAtBJ?=@_O#Po_6Sob&?qGw(1o_}9%$q&Y}?O# zX3I(G6wZMtVtPm&uSpJTEZiQyL<#2FNc9wiZ^17iaz=^V(UD<Y$f678M+1RZDPe?b zGga=4I3{k}R4{sm5_6|BuDnyRE2${3ut<+kbQtZPSVR|WQ3IMAyX<#|-LJ6g?aEGM z_=tuc+rh}HP^W<&2Wf8BPGvR3Vd7`t494>H1C&Mb;sJ_@yr^FB#bpwM+%Lr-&1N(< ze@8Te+7>ou6C9dW`4x+5-B`qxJ_MDU9HzYdYsf4HZA*s@PwAUqZPSiwfD4J&;F(*&J4H7E z)1~AWXZ-d@qA(EwemiNp_k_le)MtS)gPo74d#s3$IH-#}*ROXEjdowCzm;~!$4%%Hqv-l|{^e`w=8ytR!r;?K zhVG$HF?R-s9vSWpeT=y=c>hsWqp(76yta??H~ipltFB)7Eq(?;%j8Jo=|ay$!Vwo( zu`=>oJ@tg-m^y5P6`+j2xJA?-$|bGnKv_)kb};)nB=s0^0l#h~0=5MUiQbc0(mkml zB*9$kIvRU0O%O4L0ucf}J;%eTvCBgcwFHQ@l_;9Ni)q`Lln!y2 zXj(mH1t@#!z_iO^Kwr}4!NM8jY0);mQ(m3Zbde+9i6VrIBz#IfbaLQRUJ2#5px>Ug z9anslS)Q$B{;Xmys$$;VB*v}gRqFA?8~XS?Rm{lC6!2#(t!Wy_YZ9AI#tqLkr1%%R zj^Vbjrs|^F`EBcSnOTL<;q5@NE{h(MRip}K6<5Rkk8a_$oz#;3X}lp9^K+W^P_vd0gp6k!1+?q}5CWkzZn6cLDzj2Zxws+#alZ87TVaE~ftT zj6jvRDo_j&Q_-b5w5?D$5R~ULD)3nhm^KK_1b7QL6YBQa!7DdoLobQ?8U~2>>8_*k zglz&(L*(xU*BHsUIWTSQ82+Y-OG`MtDlypwVK$;m>2;PJmC*3H*9cLW1V#(`kj*ok zR25n-s~Va;&+uKKc{&ejbCOIE;&@QT`U@PCL7ovMnn(SNXT;hBK{+cJi>Ff)m0-FJ zt{xJODonSDxKFpK8K01<8{5i(TqCinfPdQ9OyCuS z7Hbrq6inH|Datc-Id1K5X$%q69jJ!Eb(6t`f|+5w>WpT7tqaX74G1>Ii|i(i76>*i zK&mxRPf3jC!gjI(9z5n71u)AK>ewA9_~e1@%p0>8kHs+N5nULC29#(v0dU%N&_Mt< z1i%I%9_2U!?TDE{c8s8$7lE{?yEUjvwc`Wfo!B~dMu@08y_-Ap9>f?9e50e=V1 zf^s$FHVUI%D_eXdZTj0xBI&g=k58c#9*~7vjQabpPbOBJlW0ls-k_kkw!l};X8 zw+3VA3Z{jo<4K;?Ws0LZSp5f?`3K7B7XE@Dtdu!mQbb)#u3?)WH~I#5RcO{nzZ0H9 z<0Jf_(5yB;zj7ftB$GTcmpnozDUnU-r1>+0{N32s1rl2L<@^|&8 z73YN1f}7chEQo+w2dPpXpdscG1c;0R(&(7b$AX;TDCD30wS>9s7(Ej{u>}qL&@5ZC ziQ)RZpz=;dWqAIqZ3JZ~;@xEQcaTVsVz&1L1Xbmqu7#q&`{2!gL&0#3ks-4@!Rw%{ zpwHF~QR#)9wUkKbppj6E7lI!s&m?$2aU(JJ0Cfngc6jo;#Xx|+XR;puh1(k-_^>p01tAK1BLYxT71#swN^*6g@mSegEAjCr5>Y3v0v=G_h%w-i0D1+$^K@vz^}>e&ya7B<`>*pAj&MUjamM&raG`hO zKZELG0p1eMd@902vSx$^%y3zyUU9H^2BJqkAs7j40L?)!krJcF1h8 zOt%i93{tqv5|%wvL5~5c7y2Kfa6q~jE!O}j5Z0Ty1`#)#2~sAQGKDL2XmKiV#eAAD z6EK7%!bc{1DLJwvIOug#9RJP2GN~y!0V+r=K>kr27!1VjRTP-?UBG&jMclX z!H({Qbxks`-^6E+GqW$ngr!f# zy#<6J=LtfeQ)F<*2*R*c))jeU9N1eT_Bl%iBOq#OC8Ts2LD;>4;J?{9fa%Fxa5Y3d zg&rUJgf9V3)Nq zSr^*`_p@+x2or3(;?ADKcX0;`xG$EAqXru$u~~sVFYosq8N;rQxYGamZokQc?t6|q zdC-oBBK%Rq+&3|D%Fi489OUO8sR`i-D)03jj9lNEw#8zV-8ZgQZAn^fk2%A3;F2aI zdf<{SLuX+0S?xmwtK=yrC3#v9@!gS4-g$+R!9~&W*9J=;IgT*PEX0>{uVfyt8(Oi7 z(9yU5&z{e&Zsvv3bFIX!uoczYBT=mZTfjZ$#i`Fjmi$2v?iif^$cvwsB3(HMQ3}83 zUB&!%kC||g)M7b)x~$(fFxH>Rze-avuzvo-4YE`(D1Niji20i8+#%is zs+EBrPjF`-!$X)7IHhoot5zS_hpBNoG@<^pk0ivrY#=aPoF>szElDtHBcV<}giUdD zoz#rb$tIX&44RjlRLL97$d}h)SzAPn z!<;0Wm9!5wd!vxFF2lmjPWy!TD5^s<&%XP+nc?atc+P3j<)_r9GiZBF^Y-h>kpnCr z^szIXG*uTyk~w4d0Ag|Ntp<`xZE%8^t1;1xX=WU|$*_l!!=3kq`CMaE8Ii;1W7&s9 z%|V7Xf*M$9dF|w#xToQlR>J-*`fJL zeDZ*=cLM`m|J_u#!0sE-&iv+ZnrnwCp}@{I-_Cqz*u`C8@N@=xE_p2Q5w1xrW3BZF zlf*i~wV8Pd{IYuSXTkIlN!out=;!( z_e8F!91(x!aY`N2d~2Kb=X_=<`#jL~H;IvaWH)sSSf&zzC0?R~#OuOhH%er$?}!a` z`DFvs+O?EKv93TqpFz>8J(81F`QjGX-@Ci^tIvB9;TGD)_x;KK-L+eN?87Wqgk91N zGyBUP`=%bIEU-Q77vf}VnT#lfiLZD%@xX%EK7R#LHn!bxJmCJV$?}KLQ4JkQ&`}5- znYSi44R`hu;7n(GW`jL*nLYEdy?;oKwJ8{qD15tLD3wztxa-GruWaU_H2d0mM!%KH zs+*_bZ23lZZ0vxa^MK#!0YA?H#+!Qb&wBFRcyg6E(?o1&D$aV8GDSOXP*u74a#&_? z-H(>H&9D3!k>AvKC7OLFVO5n4HcTTyEH7*`H%pxJIRST4S^Q3wH=6QLF6rWTv5vtp z`rPH$7MTBm{)sH#>8JJQwi$Qn*H7nlY`XY&j32a7`O_2y|Cbb5cX!wFF-sQZZk&Rz zsTU6`azV5w|KGyea)(>d@+Hfsr%ki6`t7`th!B-mHWzLm4{c2GsJ4Uxx zs`o2JC3l!PqqKZu77lH4=O~R$E0}P=9*$oXaOmy)T}=yia@_&Fg*PwNp=Oq zUUV*DW^C&$5Yo!j~g?ODjsm{E? zz_O6spEagl$Gq2+A<#Oy0(@Tn$S$!~e`J(3oxHm{k*8ck;2`x+n|C_og;T6CK%!nL zOsBnf-cWjh=}x=!(7F99YX;vaNEe-y@jpI0+rj$JM77Z~9~W=;zEP^t?-F&AKDw*Y z&R$o2lXzndk&~{DvpvOgiz=e$YEN8j=)1)^LHE_1xY*R!%i$H^jJQ2_nu6<;=Q>o- zZk;OYMpO9o@q&?^-GtCN{Yz_>MXil$;<()0s5_hkt76jNky6cW1@wGipDZo6+AZ$) ziPG$_bgrE1^Uj*u_m%Ul;3Of`re>5AP3$Fc|?D!g7a(a zThA#ahGd{@++uD|#>}(1OhHCXbJRMt3ru%p?Xc70{Vfo< z?VEHGH)t@(-DySQtM110CSc%7na zxs!qP+aR&kS|-KiUd$S*d(0``m-ood`8P~Ac1kkFrV?OI|NnPjt%_Ou)0x2dIY-qD z)LfQ+p7%?rG^VrktnwM1mElL%Dc=^oK24`xeF7{_(KosrpYmL1flIP-4e8axTU?z3&+Jw99DL@l z`;s}w%}LW>df%Q&)%e;e_#U*De$3$e-gOJm`onV;W=73ZO(+>&fPGP^{I;_Q`K6yY ztU1@keX@pZDV}&&c}M5!sinjDKONjYM0(XU_1J8OXajFWLG|%_{9DFSKF78Es+e;x zFDJu4=fu4e^E&;Vw^PszN(3ZglHQcIp;v%Q4B9lz^C(#B*i_Lee=ylT#eHRA@gtgRixm+qMtx(<6{ zXHMs_ot#mFi|mChY@__>#5u}Z`HvFArV=uhBBz{H8f!I8PpT@NU9-O}+}LN-Vh7ud ztMzQuZh@1f4f)NQuM3*|F0xwU4btyTW=xGyG&|4%;qe_B2TxqRz}|EHpiI3vjsm3@$qMePI`Y!)$OlJuH47gEChZZ%V{3X zowH;kkUV@sJNL%nL%9R%jPNC!8b!v>P}06WJ=)Na$LptcTbdR#USrTDr^mh>tIa>1 zExEs>F0H}4Y9P^;qLQ#YTmF50)uHy1z3C|b>CFOGEA8#>pzu`OILCRA!B*u>XYyJ5 zWN=rs%$TuFy-a_vfi>Oq6ZO|pVUO_zI~Iv1Q1#^oO4n%@k32hYR^?*fo0@jyb_xP{pdnKl(Wvvuw5*cZa)2iJ@m9z0zm+J40|$>jY_wGF<_ zcQ-75aW(KndVt%VB)xl!_w+@{L&Kx=zOz#}C7wsN&Rw|3ihO0`wrvX#7O6R*j$aps zB)m9r(0BfKv~vE}4}_!vw5H*Pc0%&A*oR}cep$rZyqI^)&Ap{=W8t~QH5%-ZVy{I9 z+$y%$t$DVfXwKV_)4=pR9mOJF58xa-`;cKk_j~*FlJ?pqTUfSiTUMuHZR_B>%Xo7ivsd6+`lYuz z63m44U|Z~`*P*ZO1aon{w{W(3RR17?tYk2{GL9Mj-dR_`@0G`p?D1*J9->&)RgEhO z{4Ug@27jCX96Ab~Jy0iW=x^zh)=WhJUZ%2+PH^f9jqiU$!v7la!Ta&}J!M%@+-Gm~ z7nkh4JdCewUwp-h@@@Jjn3W~{kk~JadvIQRWq z4tVWIb=YJcj0eJ9rm~KT7X8eANew!*cDWb9#XqDVZXX@|bIEM^In;jBbP8c@>w(qv z2ToLE1oeGDtBe>9AwT^h<*~cj)|6ktZ=DFk-QH3e zec5~}ZKUL>Ef{>D#e}_T&%zBq?(Ys^nk8;GJ=CTKq&~l)y>i#V7pHO`8Ccz02DrNH zM5_M!b^c&pmXG<8Ro7P84!+B2Xr({ALEoD+%zFG9ys3Qq_I0#M&;Bnx`{Ntp?XT0j z;N-!fpXePes3%qE@VRf?wU&Cd?iydb{yv$r;8_{1^ue2pKj$jSw=cC+W_5S1mQ@$O z&uTj`{OR_$lXXXGgE?=Q$Iepib=PtuU+6d+6khM|4KPhlTE{zYQ1Z1gDCOY7-?tFc z+83rZ^)m=SLtWj*={3cY4?!uGKE4&}3e2`5tO-{q!}Z3IYExLIj?<61Q=HpVb2@8- z%QEHMMVS2RfHHZz8Pln_6_$7If|F*&dfCI0UKD6BuKs4@m4_-3_>6e(uGr4r8@RV$ z;gsc5>FfNx&S)*RmNICYTGwU1ds4KO-j*=A?H9L-zm&rMaAoL&Md|A`Biwa@k$rWQ zO|=$3l0Lbrm~GR%$j-TgLc`Tpx3!KVYfCStz$Xfal{kV32Iey6`I*6Hh* z(0hn3HlidBNzK{fAKNy?qE;BPQLn@Tnf5?8E|nSJQ+~2)IhXw70>D&BHl}a00a_L#L*`A_@nx|TS>2{N&$?arz`_GocV6VUFSFEG zvOPooaO<}g`Ll9s7nbQobV1(7dG?#`n|?GNxn|)u_TCI#pr^~)!(mTnWVY&>3O_wI zHRYC+g?!3xEU0T3|zl*)MX} z2MWf$@TZd_=?@;nx|0yh<&Li@C{x)e#n8I{`?`kDyQ9wrzkd9B@`3ZQUBk5-*q!2a zW%=;N2=jfujaT2_x~|c4_5Eq*`-dD>2JNc*DbM}MnRg6Y+!4w*3)Gh{_qjl8sh2!V zX!ydp!C=P>hdx=OFTea#`#5@M2YY~e;quEHn*2`$b?xc7zYM!P;3m40Y0NQM!_5HK?NRVR$*x8NNL5+2fhkRO^y6wpR zBfE?PkW6~}2o!cv<#S=)jWZ_UU8BDG@uknNZayxj3 z>GVOa%jHU0=D|IxYKntaZ*~ZwzfSvIr&Gm`^|u7(4}m@=<4gW?#Sb9i)!RnH8vUbZ zY!J&^-119C7&~rl?2;vTb&N>?>Uzx`-&^)Oto0=D6&LcxZN1#l>yt=xP6zfd=`L(( z9QHMH?fuz5^?-gIKO_aHnf3Ky=CS2hXsr6IO zZhz`7k!1(ug$D8>Ih|U(-jPZ33eo%MRs30RcE_urCDYrk8S(Dp;r&wS#e?I6pJ(Tl z#HH8u4qq9Bel$W0e|@Sz-}m;IqlLNc{%ooN??78-L?63+Uf9JR{_f+5{6$}_7MDm9|vY+?pp5sw*>Bslhudenp%WG>K-U1AK#ZQe*V4J#>fE5 z7w8=^yR!b?JUT4Hs^EzXAaoKdJ%iK8c9*0=g-KVkeG;9e)IzG!0v+p#$8?<%eTo9* za^-@GDkh^3<#T8VLLq}Ef1fe=y*sb0M+j1`zZ5|dvWHx}ugoFY-IRQ_&-9h*AGoVj|KD;D1HEU(kFTYX@hvsS)aUX7s zoyckIBu<*B>>Nvv_0GA4S?Yv2?wjgtlnr+fd&MUX0TyDhdRvhWkgWftq+P;^r`a%} zQI!(@d<4OP$T;#TZaIHE8Xe?w=DqOkw2K5T=7MC7y5ayBPEgk3`gt|6ya|DIVQO*& zq_izsG0^y4)`-A=Pfd25ACGlbp^NmPwV>CWKLN(8wN?6kAtXOhX`XCJ4ZrTa?k!vF z&06lB8YV%pltn^w@C&JN0?E10GzGa=?^xI4R+3xB2oVhV6UI&>;lry{%e%c0I?VY$ zR%Xa*@h8Ab2&0I}C>!DB-`Q&L@=SND0?-#ovcT!XM6AP-hpu#rBeHrFj{9IpYeKOR zVcLsWU>XD*6UMMU`5@XwA>u1~=W1|=AbqV_wq+(d#samzvB}1YO6>s+*B%7_!X3x^ zW%k;SE-9X!U7jBjCEEC21NQ;rqM9?GQFbxrkqxKKxqpzFlpw~|HJU@dWe4yFvp^dz zz7>t_53Em%b}7;rzy`5nAS7pVvaNK5W9bc`0%k6p?F#a&C^QK&fBjf3Wg{a|PXQkg zr~)>bbWlI{3gv~@2J8RJ>FfNjoqq3`HVA2ETW9rk8yoGeo{fEW~Lq;=VKyn=@eIuNnVCiflJz zuoQ@u$BL}6B!>ec2J@c{jMcWbCvoN}Z7VTi<{C`J%8p=-e#)AxYtpo_w{e=u=r7S% z61>8a8L4PGo$!kmZ$bjWHHouey_s+WfxJZcof;Nj*3`Rgn&$DdqAtzcc{YQuhDr~d zo@XijEUF*=(n98uQvYe#{(zZq{3NQyzSNPZeKCrxwod=)i|8Vy2478z+u zguZ~G{~D?>sYZeJBi{G8F^GQg2lKf$-HomG{?GA`5_lAC> zvrCdLJJ5K(!SKM;>)dWhMLC`3Y+TtUy@*oww7rG-dSqZ+hocMu;w z{*57;44!0_v&=>ClwkPn_ZD&PeAoqdw`-ka1}s|`-HHM>c(z?u`+^d40?OQ`!A^vB zBR;>0q7PUMvRI*U)*)CKo#Jn3iv1=>4Nq1Doqw=32BW@~AADO`WO3m(n51e>EX5Lh z=Lw5*akI3nyw;u@vkLvm6ESL0@%^SbSHNca@Kw&z=81JfZM4nO5YD>dxPV(`-O8B2 z&YSQCi;U}xMz9AVe5F^e_in+1OlhnO)Ka<%I! za-ap?CS$mEM=jS@?HM=S_u^BJ%}vtxWpBqAMmjgMpBGB5z(KWT4&#=(C9$Vzy2fbo zohwf2Mz7KBX5YCh?JP&We&^F-?~b9tYa>poR6HUXAS)be@TRRJumA(p^z9b@OP$EE zcLZ^e>ilZF?3wG-NSOEPJfExhWQ7c4BZj0`;@Cx;l*`Q5x4TbW;A9Zk$8n3}#*JZd z4;Y1nCca&|#<-oJMv?Je`VoP*uefUtKAmKc#3&7-Gz5h)DFo*wLln8 zj{@idL_Z_8`BerzJG6c3PA&nbSRc1w?O2m76PI6A58JWJGjq@{{BZjqP)!Uq!u$j4 zb0WhFW_0+uJguV2+IX2NEf<7&3icn9@Q5mVhc1LIf}lh>c`-cQsxS5VUzk7O^^__e zH9hmRMQGOTD2>MKhhj}~z8WCX9DT#Z_fi&h0h@oSi0gR?SO!PqdQOcWR9ZieUXzwt{JdB4Pw%H$TQQoq zRU(@#gePMTnc4|KZ1^Z6Y9qw=*l0_p%kPY(s;0tUs(BcGzvT}rG;49p3_mA&C>1|9$2!51 z7_X=hZOc<@$dc}W8vd4Z+u;4OM=WN;CzLS82(wrOGm;GyV?^kM!%p!`UQ3;Q&>nYW znB#jUO=KL+Gou%63&yLU6%m9X?UcBB6GDQ*%qoWp z5&CMv&}>5#SuYGjC!J2qZuNZp+CmmdWy4j%$y&BHvk2frbvrb_+xIT(hX)+WvS{L; z!JlVkZAmVSaRz2R(G}HMHh&Y3mr}1)O>`uHD|-KA`1{KTbn)B?0&ZD*B2b#&t73lN zPNW#ED|nn(+hWESJBihD^ON#d&HV{;%{rz87~i7}Q=IXMu;cGVC%HH#LyXCr6xQEK zaSIRd9J0QDE2_qW8w%npj(fPe;Ey?|Gng3z-x$0WF1Pc_?HGTEBp_|s6*@eIwOzXp z{7Bg?`7INJ#NZnkzduTb>te$5WBS#!i=o6$0B(tp%KlljqRM8e0^!B`ihVMU*0hMr zKCUQ5@6)@EaOW2)v+hF~RxfohS>{|SRJ!AiI!Q&g@$nd!)Pyy!Oii0J;I`cxaz;7U znjd&NTXfRb-w|IJ_xIxLE`X|+J8NeQ7H-gvJ|JsccEPDU zZ2s%+E)D7lA^P^4KnA{?|_-W0UdHlB)0y9aM#g`tPjY}{gy zo6%c!{toUA$sYTgutfB2uQ%0@hz~#QXJ-YK(OrA*;Gg`vJxxt7oE%~NmoT@yNj;|r zx-u}R=q7|yqs)P(cu*>i0P`yN*>=J|V+cf;>&r(BarO4IghUGc=OdYD7(-5QTe}%2 zSeXMXZz{50f%Hq&2_lUu5>Y=9y&~tMEw80wVx#4tree#0w#jF6M0fht{3*-cj4n)E=PwJTEWzzQEcL&(~%ZFP@rEE2(kxx`UQ zRYk|b)=kazqMWmkDvPeAm8aah@tB*f6f5^m{FUoJqKgSn6R~l`Rs3HNV_ZtO`uwZ5 zr?MRb?A5le!mYMp&aK@I_OiR%tk9XAAEC{6;~Ras9ZJ8N<~}<0m3jc25BS3K;o`yb zz?u}wK=7x~1W(-48Y5AjeuUCqCBD`mLpAnUP6=xt1}F)0W^Y%awoNP@(k_0KZ9T&xt;6St*6ZYjfC5=bjC# z54C&Vz0)@cw)gx-mdPJ=b)G*y=f#Is*O_QI!(3T7sit%3Lk)*^8j-oo>7JFD&tSgQdrtL4 z>g^CFE-#%3FV&IP1TK%T4XmTEaeWEsbxbY=B!8-k(}CD>noOXcvCLjk@rBxt_~S{l zwH?@x%#N?%yRp)j_0vgsp4P{G3wujzaQamsOIss;m+Ts6FRw&&|6)pL6jPix7$4!a z`4jJ+Go}zBe3J97O45=iWv@lw4I^c8SYE33L{ONwS~lscQ+J6-6ns&^e@W2;3gN(L zFyLo7vZa0&V^4VtQYa}3Is9(JoB)9lG8s$wfz-?u^C`IdOG`;3rs98GeI`8-;-#FFv1!Ye^DHNDwMg#$=F1meKJt;Juj((n3zHa)z=gEQ zHdSk6LJ96Bq--`$R!xTigc(Z5cy7s*AP9Y3kDf7^B%OX({PYxM>iy(mQ& zN6!VA{R?rPJ8o#VM&o*2Zw7r+p}hWQqjh4CiX+Pz3+v8z>S@9gY`nvbKLMjjRA(}a z8-JMA!60jeqNvY-Pf%vpj&+&iA{UX5;1cWJB@1KjUBy+(pknFC3A*(9re$#H?-f$3 zCI$w}2Hwzuh(hERP@Psvws@aV8RLhabiM+(CAdco93e0}j|EDGj0n$zN&5Pwj|Oyb zO{QU^{r!l&n=lILQC0uawAria=G9eT<@>)@8_=MC3d*XSNU~E(^!lX8f_(Txvhr>B z0H#{1RQ1CUZ=arRyob@!jhe}DdcoScyw6t!At9$;y)Jt!Ox?CaGH&~n(Sd+#j3+|V zx#RxrVYqV6A>;x0u(2;;VXuym5eRkB4eHyVMES)*S3b+P2B20Q6DK=%@=aPKe!@wF}mF;c~CU?&WQ$z+s8z?dVpksz<$Wx>u9E%<+vrBz9 zjDX03H#MGL^&RpbjK%OfY!FT+m35VV_p$a*+m5E;A3o*3OB79r9*D;zG=uoYrsaXaTDSr`N~+AkU?ws@>~>M1jE(F$%#(eNAUVUI zH7-nZWiQXFcuxt3fxY8rm;wxx3US#Ev1^9PqHC!+k)R(FNk!Q#M&tOGLCG&2kAH=nR^fv+7t3@?y<4pNLF(QK?r{(^guDDTjCk=jAc7+B=e zKYTW=`M%w{V17wDRnR_UnInAM>%FT5KR+}Hh6ma)A|Z`8Q`76o7-yyxXr2MTgy#- zxUbzm(976Mj38yi>XU9)NQq_|kg~>3cCpK1b(`Z<6*Z6H@tO9`&47Mv?dCgNrv+qM*pd&GKArk(?CeP074HV(?mQrhv^YNSY%B3qWk^-qD)I}>3565%N0Rwsw zs_l*CW6!^RqqTc@TJ%9mo3S8}CHyXa$?F&$jL>rQrI5YPNPzx-ea{8_R^*b7bQ z`ndSw-Nuc5J?_ENLL2rCq1vTsy9=VT?@3dQ9vJsvw@zl@coR}FY}ueenN_0Aw_z^T zP^nH)wJWvN)*}>ti{TXYx)q^X?WP5aGsv zpxd2kE{}FUNf4X-voQv^ce~4@ob90P03gv&lMgh!lD3n|{t1G>lc#hCb_p^`Lu_Hn zVVFK3r;@Z*N*+VAdKf+T_bMERUI0%INI25c!rIl!0p_e>AEjI0Q#Lm8AP#IXPtp|! zw&c?oY?}j*`_#-}Poo2~Hp*tlE25ilq&an+^qK`B1JCI|#{QaFRYs2t-+CgGOjzg# zTaK&(Crn|$IYq^#-p0#DOUNXYs$jUn!9MmmJ($)w_yYT;Us)nUyP&Du%aE{dv*kU| zQFqWIfKeS)USwpNisY%fL&}ZV6ybUW2n+(pI{ooEWS!YK)(i8M^M-xAg@h0$+!0ps z)$zJ%VL3G2U6noQpPtbR-AJ8mn&0O+-V1bi_keS^->v7dxK^nSv6GMCf8NkjvLKzg z=ij7r>ry@s@i%)cq_?)|5KR!(jZDf^{b~} zonOvvZPp<4D;@$7^B_7p;SZd`V<0lYF~+*9BY}=XizuMZ1zD%VE|N0-Q+e~FSVHZ- zb@YLbSuzE(^gt~sOFTx7Jyw`pJC;4WswmbtAwdt>X0FV2H~g~!1gbmbaWegTKksjV z^{qn!;O4U)UcRWdb8u*M`4G+%_soX*Gdxa`8=3JPdgi1%>nt$Q;}JH zFL;Z#F>47ClFr+x3Fk2sQfsqxYyP3ecZLhl3h70_ z#NXb>jN$S^H92;*y!1qdPbC^0fd#;2TN=$+%w9+$mbrfY9JRF=k%H>TZl-&KLWsDN zWD%51%nxKbsBaDuSFN;5lW;ZXiQW7BYW9#Mu<^+Smh_kS8;?&kD-Q3vr~4bG$Z+*= z7ReTzZq!%W;#6t1c(eoFyBD&RyOY^hTlZ01r$cxhbQfDF946oKn&C2I-=r@Og2DRS zLlg#A(c9R<%%|gp)hO>7FL5iuo>aC{T~lzH9jB_rD%&Wu4s8*&A0n-}2V#S9%GDg7 z!IW~OlIfW#PtMS46j$(vw~(K-vzG6@1{HjKN`E}hl!~~jxD{K9w%HW*ikT!;%Qblk zYZ2}EwjR~pbK~UQ!^sZeASU%z%K>ib8?uAuv&iAn?8DoZdgWW>Sw&%3us;98QRq0P zbH?cHAz#?Hq2^Zap;G0;MXAf%pMd$QbyHoarT!?%z(a4(x2lnE)r!9{=V60KW69{w zpr!RXbQ!T^X@E#eH>z17t!ksNim_s@d8tTz-liG)fTwY(_GlQ`-|lBtC$<*h8^npP zJnuy_qkX$8=(2X<$+BlsX}y*jvbai2UF}^J$ONB&CSQ?$QIJOotCyl}#KAdHtgX;G&#nv$-L>k0kn>-#k)gwpVv&R>ik(kLJtcHf-~De1396 zj*0w=6iNM-;e5Y-ck5pxHPSaY7CnJ`BbMZy5L#4A#$@^3_cP_u(zwLTmwWg}p{8#j zOtF7JCW1wpsTUCVgvf=UJFP?ppgWmRF1(0l zBBmI7cM}5{9kE~-R)&lvRfzi&X|fQeK1_RKzdzLlj;!h`y8AUjw$T$0Ce+A$>ML>& zJn8G{vMn)3VcJlBp=rNUM9h(4-vWK;;5qp8mpIzo(+`u{_sgGqu-(ka6hp%xx+;sWLXPi&+@8hY?aYCKDcykI{{70?jGeujUj& z3nLdd>dsAY-2Y*~j0Iq!tYH3AOYfb!DMH?8p0aNX&7*XzZ^TBv9hrK6c}xZuPx2`N zT@QwhAJ)_*Y|zUH_0ti;sv874?TbqYFY{-MkbGWhXo)NM<`DSxgqjeS1k|k!WVY?6 zDT+2;tx%u$q};EW4!4X=L^@x*A`8}6N{x?8c|~$JA+0`~^^;!q0e%qOK#TGUDp`o_ zX?x2!ua?&+h>Z6L(wvxkI~;*{?ujR``Yx%ZJSq9m{AULK+#W0>$h!8MJL8X^rBkTW zb0O2Wv_0Obi=f-(@J?SfcxfrEHf)UpkqxPFMy7O0Nmt#4iLI8?0oeag=$e`h33%_G zc_K{QBCO^{yj3=NFux}r1WycsZ2&Z6&*>47ekxIV-p7w1e*L^^9))3$a?Z=?%hJJ} z=Rx`1b>VY22q#Gm`009nokJhB8}*^{2rlY_Ax9G7pw6cU0+F>JTc=wuPs}|5zjG{5 z9|ohy2m%$|!j&GRhygu0$~+1;0Rl}(pVAvb4O{_tg+{87dliv-wMPm2yk$^?J?h!o z;OVP}-^`Q|0AdZGjU*ACEW;VWli%NwJ^2Ys{0fL7X9QlpUyS5Mbw&qSS#1g|nNkEa zW(71G;solWfDVGNQKT^bR?C%g{(!mDw>~KD&{u0M?9*hV(vahvlzs#*Y*XexHSrs` z&RtYYr{`%w!12@F`yKu@unR_EF~vDaCd4{nXuD>LK4mi;4ccXSlhxbf?s@}@5IqP~ zZygUj=TkOz@>RS7j7}Ch`M%y)1(BXAYlGBP-n$N-h1YkB2N$Gs4jx#M8y@673x>o_x@OCwPJ^XT@aUk|GegcM^lA43JoT|l~v!$)Wg0n@Lqs7BmWW9z^8uE1f zei`_`Iw%;~%4irVn952U@xj8{?mczQ^8)O`mAV7oiKNXOKrpz&h9HE~4KE}yo0u1NC7z1y3ToU0JuCM(we<*!imVnYR=7r{b% z+&+?;;vSiB%ugjx2$|f07p{{T8w7EoG;b49uGw;Qxc0EbZBowAh8OCyAdL9M03DL~ zRzix-Hdt|%asum?oP0lFK-QlcJ!jn5Q?I$rSyw~o>u+kE4d=RTQkR-5H32?W{rAT{ z0Drqa#hLT7T5*Cwv$8|NL9>YgGjiYLbH+bFt-dr4hydI)t}3?&L!V8a+m20Dx)t@b z@~edTY4;e_?h3)d`TpeO!ds`3+8}aB0{c!wx#=2dZXa|^j?zA}|WfND(^)ncQA!KI;TdcrkvilxWBZJZuWa=!s=3b$7WMFwQ>TqqWdJb*WTxWh8cm zZ6)RL{Tk6-BlMHR&np3{LqSWw;Hnt*y!Pol1BG5fmUD1aM||+CnkFwo!u;(<&Grc_ zUH(Ts%C3{Q%e*Hs-}?mtlJ*+d*R#QOAK2|(H?1Y$o1j)hC%&)(hDO=^!N4k9D*8P) zQ@sn)Fs#vRcon&Um>5L^-a0@G3p*H_O!H?b#F?7fenKy11_&`tDYkWsmrbr~KZp>$ z;#WD)g)#tO`F;8Hp~tN1$iM&uFkdV(7EI^1V!bz-V2}`qdwOt%;%Dbf6C0B zt#$j#`eTfv-uf9Yac8;wVNkA$wTG`%g{)-+#$~e4yB)~HB&`a}wphzua|v^eN8JD$ znQu0g+_oNXe#%3TYwXr@sWO9NMTOjv|KcW65s`Z{KBC-}7Y-R@K%ccOd27hav=E@h!d`)7+yi$hM7rLqKTH@?UE zb?w_8bbJLDYdoj|Gn;$*{jL49?=LR&nmu<$-<>-fUtOt}EI(F$xit10B_yqK(9eIZ45aXfK6{18(ps5*PESff|L(lF61<;Ssm z+B}{>OB(*o7`T?9bj7S>!vg-~Vcv|v$0OsZ)dSfZLr1qAj*GM7KR`54dte@G4<^*{ z@d*LJrMDIAuL&h`Q=h&H(W`LI5q$5wD6}vkJSvZLks_#0&8X1grJ?4xUc6sE+4ooS zoU<^AUENOYl?i`%*|i+krr;J`_g7_S&Dg&-O~=Xim&IyQS_rB@@s{U#1P`0OFkWcVIc69TbRGyE6i+25s!@g4Pd&fNI?AWC8O(#YT9<8@!XzGbJ z`C8YjQnLE~x832Z!lr>)V*=mqoGSjPIbautZ)OVPwl@|ay;QkEop0(#>2TuethYhG zN>27YtS`p-7H9UMQ5TlpbLo{XKn!dZ@oZdNOmuUbo7F-rGw}0)?QBt2@>~Y$Jg_n_ z4`5<*$yNS>hz)!sVoR7JhX?wZLI55XmR*HC4qNUxO!8#Tpyv@PB2jESRu^EZ>)+^q zKF}Nw=xWywzl(n*Xa#S5tBevqo^qG?-luC2z^^e2kzFv&-nU2kGd^0|AOh(!j%YHk zOc(0U5`WRTwfyefP}sJyes^x)Tv(l=zYfDh2}vS|&$plYT*Bwe@TT-mj4E0-*5%Fk$xUXchCUl{-lEF@}j+^j3^I*j5Up>GJrq$69xn6TamfRs%|@B~;l`|KtJdxk^iSX(-w6=WuVO7a$#=z_0b5AC( z{6GIT)8X#c*5yBtNaHUg;@3%-oebTVq{ddJb9(O~joR=#Z)aY1pOIWwVfY7X;GQ$`y2INyDzhp}9wcXsa zuB)jjF8=rnn?T9ol85>p!;*}2V5HTBn?s(D`N0KTpCRPA6CrQV=WmBiAFDxs*317b zJj56N@=V&3XJOa~W+KpI{=HdASv9b3QK4Mel;wW~O???xfWDt)Qi`>@%r@)Um5Lq@ z2*rSQ%z5_|wRRjAAJ(*f%$v1s8~F_j3KWtuc_NIFi_$Y=|1C0y4f#hD2n}4og`mWS zL&Cn^pT?ucY@;UGpEi0ND1JA6-9H-17g_!oTG*rN>_g!9)jZ)d?4_U1%kTW-(8-Ea z3g>8XY}L0D2MIav-m=n}J3@^=>qTrm4GF=#&lnnY6d*Z81DgJ7f!AilLU(WN`eI@y zLa~fHMsK+Yj(a~0=s%Ob`U=}CU|Fe+$ken32N7#-lHI#6hnTy4tZWJ`08cn%u1b6I z4ZAfhy>n8HxkD@o6L3q)y=VCL(E2gPENUFvjr1me62&=bn#WumsmDRS0x@OB$ApUaK*@aT8O;pF$W0F1f@*PY@|9ux|H50(;_e7X_?Kr7$?&N@kAR=NKP z02ib|fm3G_`1(}*KEzSpkS=P&5Z)AeijZwor4t0ECSz!{nwpJ8ZjNWsr;_qs?pGKv zeSj6(OOU*6$Xm17=mbmvYw7ND`R~$JDUh}ZwgZzLf(Hs~gbko(1d{oCen=@a)Bg=z zjMs%x=5Of4-icN-mM{{4XYIxMc?0zxFiN6mv6(i5i!TiK35%sD3`~CHt``DAk8;PT zqh&}8b%9%X7d9-cr9j&)Zz_w_33b&;{wTTCQu{Fy*IWQ{CIH+6P$lPT%#UmYW}8W@ zmtsGGN#uot!C0!XF@Un;=n6jAa_cod5WRtK+hEbt;eBUg-o&m_XI*#aqfLQIG*}Q> zZ67iwtOXup0Bp0FsS(xoa^V9~f7)hKFutGva?O5#;#Q~qOn`oM&OmkWNvXKWl5JLx z#JZGSiJLSHOU8xwVywT{cq$KtvLNHP)byv&iS#IR0!dEEmiw2`8SD@8#+LZ+Z1b6a z{@qD>3ZxA*x@A0-dW4_ntLOitZJzht|2&Q)P5&Z}XalZ{Ila)%Zr}RFx9~*|7>jaX z2$E|0ltBIkVNEnb%N=NVcTfRTF+(71?Bb_w4CzH>+pIUYb1+Db2m{BsX%C$QN^2;c ze@)|)m%7UjeC?Fx>C6)|5o)@FhV6m0&4WsW?2hF@7Agv+>>p3#QioKZ)3Iz4EIRkF zYUn?&OQ)<}45~A$Bn|M6c@q_z_Go)20bK9Yl7F|o6C)b`7uS2s_;1rY{2d!L;b-a) zAP*%aX1m|-2%NJ#VfH#&?bCGg8$JJN?hz`sB$5Y2pDKXLfaq&8zkh~$W%3fjQqwlA zm(K}2DY<*EcaIK)exH0acS&Dx4mgG)*5}wR@*-{R6f*n2b^M+dk4nIhvG4&;_x4~F z{w`XPx+Fu*iyGk%jQ)nXGirbD*aGqPf6bvMA;}DdJzae-`tQX8UvD9991l!S8B2+f zZ0f5cID~(qeq;>q2?q7W1if4+H%ifem0htYsW(|)U9#OVGvYLKuo9EwQm|r^hoHD@ zTF3bDmRW(p^VrZ8?>rvMYuH#PHR4aW4?-fo8PFB(U65ZYG|azMq4fb3nr#e?Z5#8y z_B&DO?y7%MRQ{_GPbGvY#o%B!HqvJuqIToH0C#NumxPfAB#eT`gz@m0FtWS;JhD>n zwrPbwj!bR$i0tL80*Q4YkR5;oA50b(uNB)P;^H!ON^TJ5+l70>6<6<|WyVyczIFDn zeC>Q}?v_AzmwQHEJceJsVbNpmR@FJ;4m=lu?(D=T>RSd@r7Ee5eyoona(R#tfUQ|>K2~(y;%buvi*Zrh-9iHyE|5RN5H8-%G?f9G# zk#GNt^$zn18D1r@@;eS(7?8P}f2)}{h~kEQBmYU7k=NNkPKvmLyfMp!RqYu+ng%d=O+ zDuQA?UZ|+kCtc?C#Jt;fgL%vulZ4uP*w4c@#dYS4$yjHo=)iBkHf@ZWXtqR6$R!^cfRec4$) zVNu-O^sjE#v8-6~Z0pW+Nb9EE!$l{3l~Qd=Gd)it{fi7EMqu?)q7*PR6p!$nM=>3n zk0SQk+Lx+{Lc{8C0$o2#ma#8{ia&trtP7#$4Uv(!x}wIsTAlFi%;}81eU3mNTuQ~k z!iCuPR+@28j=6VWIBZxNaFfV%^^i@EWeC7p*25m1k)R-ZlT?dGYj#~XM^XqyDjb0% z5duwRTtndD#q-T1aqI~RPs{x&*{+GRu9=dhQKUe0!Z`Fg1}mLPDw@%K-l${j_Db-5 zCt=^hP_W`wayC+^2~%8-$ODexL#PQ+m7E62m%*Hshww*X<7#Ncob0!8-&Eq{98~(f zN0VbUVn1o>XrfxO1I@F=r$Pud4Ro<=FB8JJ%p=}78Vcd%l?myc`N>C+`f*H-1H?I? zAuo@RGi#l0z7KnZeR6!lV1FVPmc1Gu&Z9)RM9cB~Sn$O>$m)jZji<_lo_X*GsBw&T z@=Dlvh&iD(%Ls_9_@|g<-U-h4m~s7eW0Ao^a!-l3o*)@JNlQCN70-Ybb0H$stG6#9 z6>53z+|a!OI(v`x`qwneFCj2<_x%*}m`a%RQI??EEO5yZX&xel#o4mxR|(6b>Q~=n zcosN076xYbixDwMJN0q$$@SprPxBC;BI~J%H)=Czlp$icPWq+XR>oP+$~&oQ%ORL9 zHOn-!*eo{kxL~7C7b8)LgwgX>sD1|dg^S4#MztZiHvQQ3oryEG;dV13G22PE$Jh+7 z;k~wkH++t3@|iAYCR~ua?~uyF84FdhZ#TnWXELQ}DZyG1C7wsOqdB>|nLwo8TCu5? zb#v6}&QbHEw&$=~?TCg%At~u6$@$U-fxSGN7drHuLgKKEXScW0!l%q1Av$B(j-WRN znv}WJ{!--VkkZ;97W6E=@(-}6%n(20O^LOb9}i~&^WTr_94EqvrV+Y*BC0;xs&&6r zR?Yu#ST*?~c)`9EYz{7m^7C(V z@fDdC)lpg0yZRx%{86mOeP_x9z~$3RDR;Zqujlmd8uOak`*C>imr^pUBbk#ukg?E0 zsr`dJ7NXghK)$lAKR)LC{08|XLcfEh9Fxf?B3Rm+b}rLW%a7D(D|L1c3Lk6@i0|Jb zBP1pwCGOMZjT=hGRTK+{?c&&6*$`=oA_D|7L>|n!6tbw7*RQ{`lz^c=8xWSsD{~#R zqB7v3q2`~B5+>lN2};=v7)m3zmhad`T+zM0&#%u;mqif_=wHoaiV?c1uM2mPHYinQ zD+>&+vp9F?=ffG4+IZa&n-iF4v@bBh`Bb)Rzgd2{IpmvczTDg#QPF$p*E3QdKT$TZ z2lNGUEcP@LNiKe!ms~suB#{?#B!0UKHBj5H?sUiIBww~ZWvh)GY1K@@S-s@M87$mH z`*Hq3i3h=jEb!@OT)MTB#?dn;6Ty#^D)E6IMA7CAmj_k948KY4Kn^~(5?=2I4OBdj zGjk$rCjTgryLqY`cF^GZFSA{6QV= zPbsYSAa|rEC(PKfI!KhA3;qMfT}GKtVqI8UQS(EPSWM#&jZAwK<#MILh|nIsk77e; z->q+K<3#Lw_{92d-Yv2i)kPe(jll@!3RD4^Kgb-BZg3Pv;Q$YAKmy%N0b%|2IVk&n z^p<<%su+jelJhOlLQCksAE zQIFM%PfA{kO-qYqFS4>uwpRZ-dfey!f!<@f5tCN1f zzLJFh@_6vWfX!>aauT_{(jpx@ZI>2A=I~kNA&Ll3DF;bfrQ8LV_Y-8zA~)*f8Cn&%Q5OL za#@xY5Cwx-+StKMX}8bw@DSEJz%aG^2FqcNl1P$!5b(f`LN5j7M71R60x za25H+|7d^!uqnb5qaso*0CtyXfxJ~Hc+yfb! zvRH_k=W&A6F+9tW@lncd$zf-yf>ZX0f^azhF)}a&ZB;WSu<+>ad;=UPqHgZq!h(LCp4a9LxNwp?s=w@;ql-_M-b)ZVJ{vSU{6oa@@GDu6?Q(bw zGi@NuNKT`wwWa2YfiQbdV!8Im9KhpDau6#pk={DG+KQM5_`lFP1IEZ7jSJ5WF_-;A z#k?O$u-0p|U)Hf<|2%!Dp8jED0|MD=m?!=iC|Z|vP)7%QiV18=D`PDWr{^nvD|2-G;FXI2dqmWNWheHd< zI-Q1wds&Rgg`3_o%VP>+eFzZve`SIdvgsjg!zn5Mr7PR5L@;B&3_z!Fx4B|kLyBpWB@Dn=K;wC=($|k;9 zJ&AEey2W5y9*eV9pl3djnd0!|sH?cy8^^7qRD3B|0Ur4hm(z1Mw%9`e$Ba?p$n2L2 zn>;4%H-ZYmy!IY87kq{20UHBg|Da9uTu0{5*E+=XB;aR*>bY0QZq2Dd@uknA2XZBE z5;M2m?e`xk)EQ!ed!Jda%{_{5lIR8{cOzs$`Hl^a_vQ_bmAYXC;Ah*G=#=7j1|(6x zQ_!lhfk7FR5jQ!+`yV4M6P7HRQ)Fz|S3(#&))ShXML5dGkZv1=98-wN{E-4|VLqSo z&}>}NbL=*4=-yY{<<;RzhihP-Ci-CdM(?tE@Gqy{wR-@3#&&Nkazq9fy(9cb@chx( zLKmVOk0$^zE;UYF;+%F-PP+g(QgHJj>a`-908gh`>u#r|eVn;RG`kjt*zkW!WX7k+ zm;2AIK?T4y2*1kD-+)V9U;-ghXT`S-#DUch9DQNB}e&xp2Nd?Nkw77eb&*mR2I+WHrp71rgb3C(7ip}z>ywCeJ#iT3f zJC{$NyEg`k5e_tN*5U}B&5zGJ83b7QjYU&?rK9w`RhQl#=;!a&4>2avE6A*q*t5EB zW=9>j%^Ps!h3#A=6xDldTcKVTLK*sw<1#5E!GydP5eRykgJ`l3hcMs_bVa|>$E!zY zx^;FuEF88`ErEPIR5tWakPPQcz!zmo9|G~Cv4QtB4%^=<91D$Xh+mx=1PddvjruvC z8TiuV&_?Kugh{bbAyBM*LPX=4-`;QEt**V(6zOR;;q$1tYi@S&%CL9=MP7sv_)Odq zgl5kAk-cB3gHkCGtK&nsfXxJAVN`TT=}fEj@efsZ`2y0gjQ&=C{~QS43So}3sD!g6 z9cjBQoYjkWJN0FL#4CHY2WtXdbIZ$U&~Ed=i$;yQ zs7k|nKUqGumc>CBt6Tg40Y67ysVrGJ%U$wSdr^20yEKWnrNuq+?4>UhL!CfLQagO; za{86@&f~r`b6{VZtZmanE1LmFHD2VFWnvPwq1oX_bb(Q0={CAF`d0jYCqBJ1Zm(Mt z#^NN%%;C)Wy{2P<=h?(1nBVH%=2m-G47Fpydl;E_!KVJ4QRqyF$fAofDb)Ch zv0qAW{lv0N;AZ<0a1eOv_XHn4Z$A=Pf4LpfEu!X$DY6##Mp{?j1K%%N zDncCGdI%2qN5=FohdR#?`hY7CR9i$J9R#hsui+}GsArm4L)b0k1KPj;%=1@`#iAt( z|B6}YZ82q>bVo&UPhFpAwYM^>>UUd9w;b%OieU_6G@ZS{`C3xLCUws`2gc>@D^_eG z*o6>j+ZnZw9V5U&I}eJOuwT}s+MJ({;Q@@wAl)mURb*PCKJL`?>4s;(bipQw~zL#s%Y+fhE`$Mu1GOEPb-|W}>v>AzSa-22YKW6nTfZPw<6&NK?#<5!cyHaX`FIUY~%md-2-ErpkMTlL-7_G+h3eUf`2!--po|fIEM+t6oM=8$Y;|TGx*V$D6B`a5x^q&b^z}@Zn zNZ87%Sjrel|4Cs`%pAcZpgl!5xCRmUJ9>{1zrcY!It?dIW`uro8Z^M-$+Z~VElWK* zGVx6+yd-~Wh)IDzRRM>{pglRJ9;f0(t+yY*+VVfLwm|@En}B`}`-`;4`%T)T{aez$ z5g_eNL|D{=WupFDTbbxlVE;mVyb}r`9#QB0 zMd}e**U(4;?;*ba6-d|QKp?&Ndm!=r4kU!1mD;_f7(&x=X^P}0$~Ak0&u!pd33#-5 zq9-2P0UL=Ph4oGNWZ}b&M}yt3;;g6$%m{$@+mR7bsU&$nBcerP-jl@p_2QjnNj_(j zrXrpEKkU6_Sk~FU_Dx75A)p}LQj$uS3P^`2AYIZR-7SrzbW4|XcXxMpcQ@R>3(#?D z@Bj1Md%wG1%`nF?>ddvSwZ3tlpHrt~Dx2M`c`K`wS*=n>`cTaUW)oDT~W+C%m?LIU`~zfdRP^f>^IL-?Rvr|4NfGl zm7=EJUCL37km9Fc6k3_N-vlbP2y<0BiXC4E&?yVF+F{vpEweXtC2t%Q1aIU|X%X;A zP^gQL3-r(K3k;;X%~!OX{-dZL^ne?CW8R$?Vq_C38&x#E+N zI-b<1)_WQky5x^#B?62IYT_ZxS?|*cvO-PB30}cV3v*s!*Iv1K*Cpu{=k)A}Bkko( zt>6zNcy+BK{*blf(4Uzk8#gvivgGci2R|1gkIA6JHErf8Jcg zm)oLd)BA$KQc@`dKNW| zTj7pHjuZ$fGoqa}RuT4x7Z!7)?P{S4SNofFF>d+_*4IiVmwr^r0}A|JGUI4DOtt0J z6wx>?8(>PY42pfvq&wlKan>n)E3fa8Cqpegv%&%4c8aM(y%LSXPWxhra$4_<29+d5m$ggcBE3co=69vq28adqnO$21Kf!EC`T)b^P$|+wp8V zYv3U~K6nt=iRQHbj==|k=m0_JS1X;cPjCPMY@!>~@DPHm0X`NoF)fP<#vD3U4Q5%A&!c`+nnt1|NqLG08j;E5W9vSu3(a1hDO7 z$DO_2&5QlH!87JTw$xuHst67SXT=3^!Hsy@ixMRKq#{B4ZDqz+lcL#&?TE=huYCY= z83-71;_+_T*fG@r12*W*v#p0x4%pONvKgt4z-5Vx09=-HTiO7?0k;FVEJx}3GzYkc zCb11#f|4BzmG1BiS9HE0o$?`E{Hp70Qhq1OqORQ^_zU|t?OJHJJ@k+>k5wPX6yqst znzfkJp52E{usLj2yHn%`$H1cuU1+we13bLrhMJhC78@&X##U1ak%4;_q+b@l!_w6N zPdhO%)p4b&L0q1fRaBK|lNH^mzEz>C}#g13UvMDGr#Z@-rRCV##7! z{eAu11FUWyQ!m32M393u32H_JoD})nVE$gt@1-Iq8;5;4A9uz*Qwa9c|A;A#Odj$jQSUBZPg?ou*Py&30SkTo|>pJ0| zH;w9pfoY!{;LE-r?A;JoPOWclK4t*wECtYVjWHk*=3PZd256QA6k!bU$&mahz{3ta z;Ik9ihMEXB>8V^mNd`KP_qY&E)u($~AJ)6V{FVy{qk8ThUK1+$Q*q9t^uPZP!H0x& zg}L=rpd2vpfKh!zex&u=L27|tbUGzCxF5I?M_OkgQme3IC0P8m8U_SXP(IcWZ~zLLlW>3T7m!xx{JQR_1*wn#wP54n+p?GF?UJ|KfM?`V_CjBOzivRL zCckrbV3~dbY)`wifK@uy$gEz86zx>Qc=o$@xCEELdH7*g%XwdC+f}?cGsQRE>%-A$4RZbOyZVo{x7giVmPsosnF)E+2RPl`L?@6z(ESf$r zb!2~&didGNi8H?Nh#fX-Ltrn!J^35-&_EF40Ht4&855$U&e^`)sU4VZM6@#ZGx0Ev z>xmxKr#)KDlIhAfj~(!GtBX_co1Wpm3n^v1ZW=ZyD9v26wXD{}f9QBAXEBorj%_~u ztww>NNPRkotUJ0(5!LjdUEAUD7)~X{_<@pVn18|JT{i6>{WV$w=i@cK0+~ZH>Gp*Y zwmEDGGWbzcYl-F5GD|XNwwK-oJH{o`lQxiU8(Y0UCR^CDZn`?BTBHhA6Pl)4$}eOk zrn!cV_D)LziftIDM%WBi7&vdVC42o_h8+Ni9wVQfYl-F_arY70yL zIzc|4ep-IiM#0+oa^*$qW`ncj(E$HLFU2;Wyi6$^k0hOZUpP+^Zo_+pv&&1&5mE(&YUUIYPbNrZ+CL#x0=OQtR;^XpMc`dy&T$ z9P@pR!*Iw$=@w zK#XhFpk0B3dM03;;^GbqY;AT45MQzL==ePbgpis*O-S(k8#MTbXK|=-u3+TSI1m7= zD+gxS$SElf%Ey6>kZc`PZoc|eYqt5*(g70oyZ7)N?`;Y6Ur8W2U?ArB4uJI) z3ntRr^28Kw0_(R;fYhG{qg55)2pipTgs1MPau&b`e20dr z=RB7#{YlZC8tbd%=tiZJqGD{0GUe6h+Z(pW_#Y;HpTO39;$Hcuo_a9#+pRF}YoCQ4 z?;`N-N-TxVh4(PQs8)pN{xKTq1%@xTPy3H4_>ENVV~%O6iY@mm2yN>yx^Y8N-WzTE zyA5v!`?w*EC-9adWn2OxxQOY$^w#HhD?mu|@$AJBps8u=A`duAn>en(!DhMEopC=o z2<+&%6Fvbp7En(uQ)M*3gU-!v@Ydry5#gYlKVXWMHW+|_hg}rrg(ab+{Pv-ihlSlj zeSTcPPN!|y8Fh~^REVzDv9__c6ATj4G$G>wMUy-f<@7l?5{u zaWhpj2L-TTD5LTD6If58Q7!rFv8ME^g4c|DuB3Oeudklj{DA9J_C6rDxrD=u66=-p zSP|CmQraE0JxMz8*LRw!P@Wv~S4*`($m^QhRAn=3rY3?8@(Jb37%{*|BqI8NS_;Hk zy?YT3Ul^2*GR06}t+9+)D!D^mKzc zgyfQ+oT7}zdW6Z*KB+ySfi8=KW&2qLkA2mVZMA*;@no7qpV`M3Xjm)K4?_?cbGnA#M3&{?i6_c$eV6G4p(-ZP}6FX+YrZlSUfH}magu2R> z-ojqjSk9(-9T!P<=X-UC&>@$>dk3iO#Ppj=qmY$Dk-?JUC(0H?Jz~XjGf#D=bI9q| z<(vKxcr zxVQ~(yRT^+4H90dJtTAgEQO3oK*+<2qUOsESI0BhwN)+=PC9z)z$~LM$4MuD#Y+$ zs1?d25Fz3L*8zttYcwideZ%@4s44OXq5-*@Z0)klDS6bIsk=C%R-Scw`*p%}RtCkL zv_i~omCw+vjx73{BQ!qGbFqjbiczg;CA@kq_{JE9a&+aiEuR)XLv8F`j#9veHvJ5H zm$@%vDIBsP&g2FE64FMZ4-5{fpR*>p&q_(P#pfODkO6PP#~9T9UaSg1U)#QCh^l0> zIW{R+(bo!%4Pv{GpSHF;+Tx0-@8Pho4`E-sDm}0`8SYEW|1hs92+Lp7U%jPe$;sgu zr!2_v@uD%?Zcr-IvidWv!(?2=?iM6-Medo!QQf;Ak9wk1X?w)w@R@P8Sq{FA>J%?w zY52vZW}}X&cPK6%Rp39@)1u1dSk;!O*^$^EzX=e)UXm%YHv7UV?mDa2iMP>~sQY{* z052oHr00wiZS)McSq@Wc7GEpzX1eMH%5+XmBzcZ-8v9i#<5aa%))C_OY=i#N-D!9{ zJYTnyVc>7-CgnG{k&8=h78*suQb)>|mu!1RlpK~~&lWpI5Dgn$JDObz{0QdT_ass5 zuJJOv94u}sk8N*g4YziohvfZ+K50eK5cjX-5vo_GWw;+zJ=ZPud{_kQmxUQb)Lsl* z7DR*@l%cUN+txlG%dyr{!8p5&8*=e3lHb#ZB6ONNFtR-IX`2E*&Re8Cd)a}EdDBKW zY-b02?hlC``c-q<1`ZrL9n6?DEDjKfSzfip(Ige*p@V9?Be}VZ6(m^Jf^EI{pP2L) z>xwr7-HsMHu9Nd)*_oZn4@OSqzpEU2`)FVnjMj46$c<_8<`+kMPoe&>qbqFXl3;gq8qMhi0dzMg-MbN`ktQN@{+>x*yea!~}UH z9h{BSz^#`I)RageZOUH#1yfp3o9G`1j#@%zPvG#=#)0O|tgxMuRB3wG&Qr84;pT0D zh1&wkAXrSDBZ@N68iz@{aOx>&Q*%2(D44AqF-#UJuc@MW;;DeU?X)_G2;=GKi^FvZ z191Vgn~)#bVE>p)l;5|$z(@+z7pC3#hUB zBuYOj+&4h+0}>n!>XZa2~!8=iiiF;ZQFvA(5D3^>y-f zBY-s9%60Xy_eD&X9EvX& zE9xZ5dg39Nx>?fNYW!<3nQ>0`riYf*G%A(@dwdE_sk*zb9>!jAHDr%q!2E&O_36z5+UlBiXd~EIj_B>|Ba&bKV;wm!yqstTshj(;Rm>^-um$Rk%@&fZ2*o{!8=u9^~Sg}!YD@zSMHU%=whb8XWxEsH+YwTA57a8Q_Mwc`J5 zo;k0bgVtj49BFph-jO5c(wZyBAeuXLV5&OU?VZ&7nmFU4#Wg=FsiN-Jm;1&R(8p61 zyqCG?ZgCL1XBbX->qhl2ObrFXluu~5ti$YgkB1gK#JRPe)F{(z-t02iUeC9zl>C@# zYkt3?1;xBwy8iyq?3_^t5}uisO7l`VUD zBS&@uE5lAMwf+xXZ%*Sg5*Wzdk#@uan7 z#aw=47IG<$GV^sFG4hF}QRxRy&X0aX8HE?7J)Di5I-MIGIHzMk+)1~ zs_4P97d{_O*=@5O&p7wC@qZjt9a24$8eENWjRUaYI0n?W3 z59BWoh~@fQ-lxY#Ex;~2A}_ZXyX0f%k7YCJM_PDIrYS!^P1k~ejSAQ%H|Wu^s|YZk z^0brcFZKP>q>kfX@O?NeFhnWq8?!RFPZe0b)bpGXzO^&l!&T!U7tN1KJI3K(i?z-r z)0IY)5AC!y4MaJKsN_DNKiXam`&gppAoFO2R*L!6JJX%-BV1imTQOHpW6tPV2d}O* z59?b!QcH5g1%MnR8cN@TnDZqUEcWFq-OJ7rFJ7`4TBKD@^}{+UU;F8p&3=brVm73w znS(}C0p-WEgMGRSnUidk=jJt2-Xl(ZGExGXu{lEi6bUky7o4lzCleivv^@c)u@B!_ zTLkCJbaN4Ev?e{t%Xp|F`L;aY$ed!^=Y`RXP$Vf5iP6mZmV6-l#c+EK%uHg)vS78s zwmlkOkCtHd$aN>#%HjKtuZ0c)z98r3jtjvRp=uqtd{^D{J3lJYso} z;+QC`w|?>&wfZByQogQq?`L`vOi@uRa0R;=N%70JAHJcjok~)BQ;Q`<)kC$_N$?bBnA+E~^t%tNperFhIgiwGv!kiKavtGY-s*$C>Mh>8&6ajP|o*{{LEeLvAbH}zy7Lo z3`O(H)fnAr{IdSej)}O>Y4V{3N=ejX;XK+)- zfo1+=*;9E|`v#Lnamer3U*MtzG4X1lP8zwdAiC_)Ol3>aNo18!&yQle?)2lw1v@3= zXIy!X%qQzJ9$L!pvafY{GHPJY{GGvVt1(5xh{+WVV_L5?b;e#?;MnHCl$?`~d1$)B z&?R%^iPxNPnG9R5CwDZX4(2Rt@pQ=mr5=EXvlHakF_cnL`y{rfT@$IwsyX-$KrSUA!{vLfj5eiHjEp5VYUf-AfSn;5V2p49*H z9255a%I5-=rl^!2S$}}9uE9vI^kokV2-a2rIz+hE-;tn-z*fyqK3(o4_f@HlrR5)3Y84EVF}-oua#zm1>HcVzSZwTn^=-w2anr%5 zNcs5Mc&%dwa3$itU3(PwdomX5k@C-F-h$d6pMtTjU?u(1HeOd;;#u(cSpgb_qhCr+ zU~u*7(DSwLuPVM=p5Ca48=hw6c;_k-pL9;Uu5_N53_~6ZkObKx`p4v+$jXnQm1+M! zr{e#GQ}Kk3@J~)f*k>kpPQ}+OUmpL-syK~0_>WG-J)o1jb1L4e`qaiT{uXAZLhz$H z83ejU2f^pyv4G5pKgQ7U_`n!C{-zSC*u>P#LHBc~_`_s}^B-SWAg{1m=9ZT7`T&Cl zw>{?Z0QlYguHxie*cmMitsxPs{7q3IARO@tO%HWjYo`wkg)aym3Ffs2zK8geHk6?W zd>whoUhANsIPL${{V4^o#~%qldf`Lm12WJ8AabU`cL$GxojxRMJa%16ioRUjv|4G5 zj!tS^)HlaP>|$F>jv#pYDJzAn5wKNEwsWgFa_2BG*A!w>A~Cdp`LhC1dq^U2 zFhN{OO!oQ`oIsNa%3ue)?}m@izNCb(%jT87e$a*skR9njsu5Q&Vh<`nHWE+w-U;iG z#NwTq%i}XFP47Gy!-$JhS?l)Vo4pc{e*_2CjrJ`*fOXb~_IY3Scb6zJi7f+6GY;@T36B z0$VuzUmJD2-1N}DJIJi>9ArOGg74WhDtbnN|BMxSHvPFQD%#AUo`%mlcvko#_n26C z$l&Fua%sSI{b`4wt@9I8OHsX8(cDTvY6sZA?w12>>X=3Ha3OIZ2iTpJP9v30d=L& zuCNPW@(#IGc$#g)>bAgt2lh2}M^;L@a35cAMb6C5F-6X#Ma(QeRACP_T*C*{o-Kgd z(_%AJC?n80}@d3#I*j}eO*IY*-{)9&nzFdZ3 zLEUwy+u@UDWwCLD%J2%kj|cj;ho_5tjA0?*FF2hBy@1pLRUH^IF)#Kyg7{W&5pG!5 zUZgpckMT|5oRfJGKAU2I`Oxf^xdo#(|J4heb^7)(^4Y2TZUm5>sdETYY45C$lSE{m z73m=$)d&5Yo08u$2pH`TY~MYB?R!pIC+#z1_ydvqD0(`6lN)UZY#@H1+sG$ye*%%@ zz*C2I_pg~Z&d#OBkW>AC_cD_5AhAPUO*jIJ_{npAHTL7HkZcCaY5fvzqQFUYtIaP} zt-#0p0Dvk`-a-{t_fZG^FkS(EI@gW8pzn>;h2EgUQh$eb%*L#>pa%UmbmM+d;NK2& zO#oveXt`f%vH1qX8;K2@y*fciT*w1{J)}D;kiZCHqQy@*BX9^czV)U3mJRTjB2E<0 zdOY2d`MI;Zx141W=TF@cThsumCko^(Stb8rxRkR1%Ao3Q+!vQ9y*< z`5)*)IIv%ybPaIc8D9aIt7`V#`XPT-uG0k;NFgN}DJ*4B2{*4DxRSzmV_bv+n3h*6K? z!+ZPI{qx}cXXJuXRcXr35Or(G!nHWf1*`6X1BW(n(ZHC4@7zI-vdC7WAZ2Q_7Ts)3v~l>jjo z!4$1iA%G1Pusu^htZP)A6Y=|pJLEF={th|3zeDzMffw%*gg`?LQ--;P8|QMkMpu*E zf%9R)3AR%{+{T#P)5M5VaRi}5Ae+Otn;wfJ0y4`70B61$rz>o*I}9dpUlYjQZ7ihy zn_>?D_1XJGi?@pHl-7bDfD0N89ttep!PYMEpBk(H9HzcQU{0(yDf*Ffw=QyA@5WXOp~eJ?WWAO(8P_v~!1RrafX7Euq=dZ!bN1A66$G(cM$RaJXLj zj<+POn;J9Wb;<1RVs^<4cFME_?!Si&vL4i)>F177hxlw|@Dj&hbHkS4ej%hy)lj9goh!vf$ zqf6QI8FK40Df&g5wNX9}>}@UYba-F9O-ZHy5^ zCBO{`k~rRb39A_Xe^o~?F;OREbE6xG%% zor=drurJfOd79KHisp49Gzz9lbsh!FZP-YCBa#|?jVf7*Ub)IG!C@WH@6($Y?`8}#_&9ls|c&*#p|GR&0g3k@(| zd0*q$N{_RyFHZ_r?6cjOMEax2}yYq^A485B$4P$GknUwWXTyd{>XT!iDP+-NwkZdM?bj z;SrOK3FOTS0H=cm7m1i$@apL@2~!fqI)QX%W{yO6SmW0)mZZHJB@fa6( zJFA+t%p$mWHCM3}^`wG|9p*!X?!n^Rfhqo{eyHV>ypdpk2O7Eq{t%JQF2=r)Fr&C> zTggFo;kAdXhy7(L*$w`c`F4u}965vUKXF$%ie1Fa=+RkPp&o1l|3K@T$}r{vieSJ1 zI#k5Xh70@)PxObfvi#qv-#&0L6I%{UYi&dP_AW?5ioBy~idV&--M0cpdI(m*(|m2p z6_Pj%T8!Mo|Cq$jR8itRXOn4b3iE^Vj?+E_f6~h8&zcUC!n+vlw4rfe?U@kqq%=au zFlgSPL+@L2IAc&G`M(99HYLGJLZei~mSvG|?b0^eoWDh$2rTPVd}1|7G09X+4~6Qx zVXYW~u7Td=XTj?py_fzi?TMC{)T#bH;x`hc{juZjMVvPmKFY%bS)D<`NOh!HE zzhSU)|5!BJw_`LP@vl^d&snjj+1wppkv(Eu#TFT(v3CtS==Eoz-Hfk}HlHg3vyD}Y zo`3M*%(qsHb?JjqfYt<|vV~eK%{%MkFa0Y5j@{*_najpCfw^8c)#A*iX&lCsXqB1{`Ql zdUgVjAURqYJGgmc&my#Dig%|!9+b|!b+M&-ERU1LvYqV+bm)Ml4w!}kV2q!GFj+*< zAne;e-&mmfrDPzc7z8OH+pyyOHZEK85RHdeL{UmKJu;KxQuy{EZbnpw?|pJ+QST;SlVpY{86V1 zoYz)hM;{@X>t?0ES^VlWbG3%AXL{z~H+sG%Do!?Xf5xe5p7%8PKq?xtP{+((ay1{T z`FRXXA+qjh*7&KvuA+5$snnC{>dEboeJ{TpRbGD9w}0JgR3&R`vQsw8-J=vYgSflz zoW;IROY@wC%~JVr$2I_nsKKk*9vRG4*EUaIS=~@i%(C{09>6d`v&XNjRznU$K3j-XWhKP1t?jz4F;))fe*# zvICjDUVn*8!-hOJfu@07-gC2&67iH&F8Cdtst!_nJ%rOmdmD*MczFRwa(k-Eh{J5$ z5LyBH9#|drY@@GVPc8)eOCIg*IxPfOzgUxBSd*V{#J58m?+RufK*;H~zb3jY-#xEO zj1hM}+Q(f8J2*QUeA8RG1FNW9XPE8NzCu%7bUJo$(6UpbJj^;L>Qd2B@>t7noCvQ2 zMMokZ5t4Pppy|uwH||gh@&Xw@v#~{v6QOp9G4FNJyG_)s= zl#g3G7bg!Flk1Q6`tp4G>6p4C?3OtkSm_?+`m25>Y7$NQIMJd$SY5a2Qy~sEBm$Ky zCG}#bF+=seK3cn@mdtzU4@VGkvUG%$kWWVn$a>!GZ_(y$^^XDcP&?7`>{ji!a&;}T zUtp2OUrY=le(_o6srmjIZYCpb{2`5wy8?xRdn6feSwD9n3`e2#doMuIh~&P3ZDY5G zioNcxB>ytwWsJX+j2Ow8gXcb%uj>jH*SO_5{_XchO+}@&qtOYh zQz8=C^C5th@nm%hhobBTz%s9f7+y6&0cn(=|bAb^|VjWBXocR<7Z@+XrV@8@6te%4{#n#?EM8v1cR zQsJ9Bu2mY&9h(C*7*ctlhWZH_nv9_9kEuY%?NoqDnv+->CrJ!&+uR+dry8-~LDtmT z%k-~?>O0W@TEJ~G5HC+00f1BDCM_r>AgYNcVI_XS%1%*JkJ)ww4gkzm>HVSFIDqx4 z6Vxl7K*(?h6zBxpdcr~;AHZOQ0I^Ku!T3`xzrrJO%8>8{4P-Ym-eZ*orP94~sbmTh zv(})s|9l=I*J3mp7w~qQp2MPEX|`!naUfD_0<9fiA3%}4zROf1_x=V-Vf!y|M9`g= z>=J7?+?ZCZi!%UXzao7Se4dur1DQb87HFXyHCEKA!Ggj-@Bq9F; z2U|1WB3bMR$rS%nT-CPq7FS~CpeeG_Ha&{mHtNK4CxHH|1fu`u+|hqYJtWzOfuCux@ZPQNJ!5f;BZNpkN(c9<6XuAJ|>q> zc*N2)og5(G&^>qRr*YF0AlLoG)~N@u0%s{#mEHrY4F`0VthxR&Mb`KM1#TMH5QavH z1P;pLF(n{Vh`U}oa~ZWu zarv{#@ZXSDp=;NmQzRk@z;cK_u7d6P2R6V2u8dl$ST2`6Yl9qeio;2;2ADhgfy`a2U4057c>7ML!wSGa-L0Wu(VfQV^8 zk$if{w(8cfA_(>KR0|-JCCr!hI}Za@-W`Ns*bLk`=RiFcm`VNyAy@}~{ONXWu}fhF zOqJ4tC%G0It_HR4dV0xHV=VL%kNe!wge^}k^!Xxi*(u*V=EW?V7 zxUrvK>DamZuk-;u9i0^zJvNFd7(FfIgIr)-Z_NMflhgiv>?MCEA|e6TpRm6H*3iIZ z6Ccq6`yPQ&9N?tgVi18$BM4x3Gdea#^QWsxLkuj4RbRGKm6yQ-DE(Dpk^i*DGzN>% z1LBVtcb9%b*l<8^9Q5L!A36A#{RsO1Zr2sR%!&d_`!VI>MrC$sS4AGccF6Dwa#NW3ao0EwqW0z%^9 zMIt92lP8!+U;=?*%AuhVk-?8#6fo4yxr?pTRd~KKhgbL6u|B#paHwKAd?=G7SStW#T@>Ln%~|n1K`J68;+pzqtn~1 z4B)to+KSh2kz&09LHBMciWWa9iY4lzo4!wXvh6r;->%(EnY(rFrktqApahD;1!Oz8 zf}>igAOu7dio@4AjS3Z~7bq_u^iG@?PiRsl8;r}Si0cBtie}93&tu?_9}sJO_h06IM=oZrbbWe=T_oGlXucH!KI{IUXHq5nAD-Q*1)S^D~nUm$0T1HY0ZQl{GSvLd@OV3&#?a=VH%~qq@ zx}Dr6@sd_S26t1JJ0$-ETiK)vE?MZT-IKi zBfN!lC9lJL_7H+WJc{F5=JI;kVT15|>$&rj!nv^x*#tgCgHhQ73EqW(mHx!f5Kh@w z6`7YaVyk|Nb8%rk2`5sJTNwB@FSs@#x7RJvWj8#wN}XiooGx`&@im+$!m6x+s-F#1!tl4OG(1IF0K2X)b=Xv8k0&Z zTxwiz?M>V$B`YOpZZcz2KJWHa9T<;v@${gOLl3+zs~3`RfBVf@2f-6fcAAct9|N<| z>lFin8&i*AgsGdADWa^k$5wGTiB6*{rmzmS_gAE5n;_ztEnM<<*%Cntd-N)G51oo3 ztj!h#q8#ex_pN$!TRcG~#%JVtPTvq)1(7Jv6$fO~!pl#_z}G>tCY3A!H`a@HTcNKj`;y*g-Hjwq>3FZ0kV3l2UUs zqM5UKGgS#wHEVt2Xf~aKdx-?57pFGCwo!h`HPPxnqos5_2G*ywXglF!`f@8EC;y<@ zX|T!YMI*B0_1So{YpG-PanDG6>A{hOaajF9v)iVt-q)S;|0a&2awd`N?B|k! z=a+{CIo&l>=NG`d`l3+b(u7?A=A^f}sChnhLPso+-z%>5ii`1J;Upr={$-)h#c=+C z1AE!w&870{liO#1Q|7KepE_*8`}hH6O%z!daPcc5^!t#!M~45Pmwm;n8le$vSU%7h z&{;ec6_57-Ira^TxKgF{qsBy!dEQ=EbUyglq!v65c(yT-P5sF7HACI7Aee?l(S0Ct ze8)C8j0>z*^JV!cOFcjBZc^~Zwv9J(?UBQd2{FxN1sQm6*K)N}m7f#m$=HHR72-&a ztaJ&D=kqn_ECMzibp~)REu$o7&h+ls2l4N-=b9fVustB(&J31&d~{QVto+8d8oz74 z`Py07d28~VMTQ&$BjO{+DZlkZ*N!0g2!_iB%4bgfXpM!1RJX3aIOQeA9LL449vk}= z4qK8ATUF6xcGt&kRaz!=alEmXE-@V3%Zi4llY1lbdj({{#ZplLUh}z z0I9{+snzxR@!o5pZQK!p7<;)XufAaKseko}2x!=0cU7LR$pfq?q^k(!Nnr#=&=f_8_H@`KIX->I%6!r=w%n-KT(@YXjQCfJ_T5dP=w7Vo&<(fPlAlVnbu1&T|1Q{B;yK%%RirIQ}MAp(szd#hgBP zA-$m&k*>*g*~)(%e{5;qltel}31lL{CXoUhpK%p#euC;B+nA{W-|G6!%_T>)#gsqk zP``pN5E~+deP^MKgtYotdMtC4yz*rxtlm;RpJxDk(LRqM3`>aw{nQw9R2M(cl|x*Y zu@&aNSFFeI$SE<|Zk9YLN!}`-LFNv+F_Q_p@%T{fVZ3`OHp_j5{P!Z6mx&nN6$~52 z2M|U?V4^r-2_1mvflK4Qn+iDr?yth5IRoF+gS*foxMaw5w}& zilDvUoaS|+Sh{wC@*scdd#I;e{zKv`FAg1UE+fyRmp0CgZ6t3>pFaU`O_|*rI zKFkM=IIoH)CwLYY>F#bdT@xxTvDGHL+_i&2RQ zO+2N2CGZ>?EbwH(7|)*t&vs9{qz5Wn+ECLBjB|&;bw$G0#AT#swy1QM=uiPB2U0ka zmpU)o*+M!N11lWM$K0y5=G6?ErdD0cxFv*j zxEU@T=OtgeCkDsj9qNZ(kjb&-V08rXmPTb5Z{=$zgY6 zPfupXk+rR~x)~<^@lmOfS5wJqDWZOHOc9!Pz20<3ovL`;OTHdM znBR7=16!npnSdN}3{q){EV$PLErCkPReZW|r5oOHRvJr=RY)GP94&q}NAB0(pMXc% zZmgop(e8RvKS)$In7JHPoVc2Wkui$pur*nDt+q^Tc{q47^dzU+L>TXApVSrGcrL$e zHjCJ^(!>t^4M$FsZb94>cgfZEM$;Cq5}6INdePVzucoH}o*eu1H7dxfbVfV; zeskqL9EygoPDvj4SF5}k%;?!&{xE5FA$vXxG>mqyH5ZXm$cc%Kow9^3P5i*XjP&Hn4|HpG#OBPNl_Tm= z)-#Cgm&cr9SBMudQ5M2CvnvjmZ=!p)zjN8+KkIo%wBX=oAXCpVu`3>~#k(Al_toBp zals+MhiMh%M}YfP0Q6QOq-q>e$k_)v}=t&WqL6vbNoe{_gg$8~UDQi_w$h`1$Fx>cY3DD$g&g->j5)yPna+ z%HQ1AH@vs&VEy7DJW49hO;Kba`DX?rE{CD|GC;l#Q4uA2sNl=7M$zDa&W~Y~(gvK? zyV6joj&4%6hXhsW7`pjIoBoe~5(EGuS@U6qxx zfw)q(Fg*%g13&Y5KcAee%qUiYhjNB+EzGs%7oYtUpZQLqUa$<%I3uu;A@~n&h10HBrz4v)8=I zMSVre2J@Tfr)*6vO|BK;FdntjC$@q!<(%7&oAPd?n);gCz;fcHn>Y~q(3F$5vTD~~ zq6GN7jx)ksWwlPmbBw;aom5vJC4W22-oCWpD2=-h! ziz~$`pYDE@f5=K3Mo}YD3*c<0O@UHp8n3Bt<)MYv-oP0`Gk&FVYVh0(mnbdE$6C!r z)*PP*`r}owpiPDi+HQ9c9Ka6Zxy}!`#f;}fL%lxmgTj%8OVNl6Q*g5@xOp%KDPCR( zUbMEKIk>GUxIb2!e0pa20n;f3%d5w?hZYk0^)WrXpQSNzdd${>e(;7$(}6&z;=Gcty;{l;DqJbfq5U}1i{a@% zD#3g>?kia|b@riqie=p)@Jjxq;^z)Rd&wRXrU!p}&+^>puG;yFMs+DQnI6!nf;5Kj zTOdNTNMFSP!x;`>IAf=!Rr1H2kL53LDxNV!aK3vaEUZT_1Pwqpqk#=aXrMD?Ras^L zLFIa!!#``jg2TU+7JZ*r&s`-ZpSH+tq+6p`DiM#X9w=IxH~ssl?^ibLZ%Jc6VzA~7 z1FQi;oO(UTy(9aN330c0ln%2vOIy%12MLK6$m=6-B4Opx_C(DCSHR)&Z_y<&TY9!rG!w8CcS*hJq-87J;er?~oRdi4wvO{- zVq(k%QX^EgJ`{w(+pj?=!e&d?2R~O zc!N#17w6P?nZ01fv4(YpeWqLP%i%KpIdwedTbN~VQ{O$N1`Dh>bF76imA1OsZ)njzlHKT62xA({L%59Gh9tsm*$XxEVeRFd_QNa+FZaFW-o3Xu-3saHbj8`W zYD;WEe7apVFgD$VGS&6XFolnKieaa*yN`CJG~G4^kJIqGWl+Cqi&yZluxlFQ!>B`| z4@J1L=nzMxs8}}oE@zR)m2qi#qy<5i7F-_H9wu@X`|$|-D$n~Dl8)v%XZ{awZyi*=Wm|paXi7VvS`YWV&$jTwSGX>ge#wm-XX!D{5-cp_2tu{FVRx`eTPz@ zz)=%EmT<)j+RND`A$>EmQ(TSUV-fF?7EtdOs#{0%9@sU^Ih!$N7ggF$Nm@_dN}Z)& zPHV@DS+6dbOAH(KW*+&R5Id~X*@myTF6s8n&t?tx+^s!0>pLLuczTZIOih%f)}p3E zHYB``-BJ8uTE!VLu!uS^%2YCueCM6+J00O!R>4@e`}Byy9xqZ}$2ro;y_&+U%2t;r zw`T5r9{MtOtwOor$ef9R@zD{Ho`^UtSd;k+qawaBY0Qp3W-Z#${GxS~E{EKnUiYoO zF?`ZqhKE5#@Od_sYD$kexW{Ns?hEclVV~lE@{hzF9!2Q6Rocl^G&r-W#||p(nr^a9 zjI;DM#L&Sc$~ON<(S8@d>zr4s!Q=R&SDL76?L*tH8cbFEi+Ho{y>Qz@c2R`Bq+&$G zwrUOo)!7H^u?9KjU}E{OotyzpATaLSGg1Q%=j@wpD)I|~m!JEPYU^?A*^S+HPC6E~ zG&yimAMSP$*Rz5yzs^rp?xA&uFQ4=5m7PbjyU`N=T0*n!Y3b61a2Hor3}Fm%bvM@} zSC+X_=_+oE9&U_-r$b+`)ATHzrAsB&0}aP)sv${CYqm}{!}$`-x{t6aO5Nm zWcG8?8-7xvooV%^#X(Se8}rCep7R?fC!ZmHQ^5vJf@>P%<+Z1ym+Q{#im} z2CA8OTAdg_Rl^bJ(CK(&j5eNjvO1on@aL+wVB`O^`pO_jeulb~!ii+EIT3DNPSJKC z#eK}h^UnxB`)c^F;=nFWyV=zyo;l6E^VNrU9BM@>7$)?)%pn>w_6I2qmRqkjf505D;NwBrxT%GY zg|LaB$n-{kf@Mj&BZv-l*G212;HHP&*$6qa8&O7qcLJ*;n!pK`Kys35bWFVB8?ZK9 z6q5|YGkOVnz@Xx_vnTOn@40Q-i-6KT$b59?Ipp|t6XZ>@;_Gv7hRHUTv=2Nu+S5g8 zeJ&2bJE7s!47B(&b{xr~R6 z1H@KOM&`MmP5BqB0Hc)sJ}Deb7G;GP?`(&AG>K;d=S`4vNc+TjpI$a+x|1*Ls|6yq z-3uEd;hHReo*;A2#&%hojzP#cQ0q)GtEt&>z>}Cahr004Q2)RO05&_8;qRhJY~X@9J(k1kj<$U(hB0+=vo? z>w(D!IA=%3H2yQii&t1BL~`*o2b_SZK9m2I!fR zcUM(29F?mDz^iTx#y66XJC2V(MghNX_Qrmu23+R_q5qT*0GqelI@fb4oeQLAr)q`E z#zK8eHyvvXDtB0f24oG$BR^@b#e9c)4;hoSj!gEm4bL)B1c^3qsS2mlW5cn;gg>(2 zfIIQWh4X}qQBalOBD55P8Vb;D_5a=w4efAnNH{_36F>2~q8N{DTTwwT1nL3xYgT0a zUo-;jF#WJR@J%VLi@Mk5=zp{oHTe^#-w7juYM0l@WJ>3*U8??%$1 zGibEKMr(w|F+V6#qkQrbyL6f#xQY|`5hHoU^+g|{Odk{5J6xvF&o`O1&x}Ff%`CvB?Z^C>Yp9&B> zCjN0|=m;`mM25$JuFBY-reVZE=!6$i55G4xMS_u0Bd)6eB_r26+6QOwKMZp{dY4sf z6x(myW&TUY_Xm{mEdKr`QUV9yYNw{(6lRb3dqc%j2eR_*cVee4=uj=%1yqX$$pExy z`-Nojq$78NLa)8T{{q8&=UWGn-oFKTQ!Pw=7`=zN<@l=N3YPvLV_tU57)YG_NG<`T znvJ@qN7hRw)!f^sNEFcM5~+o8j4aK>SDSS#%PRz&B`b&19`-8y^pc`%q zl0OcgSl5S79}%)&`nO+UB@_xmF9WQ5gtn@Yo!|ebr405uXaXRU7IeH|p@?BXYYaGy zf8^hM{aWOD#bh9wbhIPH)7FC?{XevhSEgYoZ=yk_VENllR}vTo?2Iq5h^x2Grl6|3g3O zZ&v!(BzG!#5M81N&NLT@rZ&j?d|xZ3p_JqJ^nokiCQUw3t=+hzUl5=8%g=_OFg^~@ zUdy}QLppf?2Cj5%`RgCIv#7nvCI8-){^jxdbGCs9>;4LuZJf_Tt8WjG3jYdZ_{SF| z>?FWtFcfBq^Myr%@?(KSoD-0ULx(2f;N^E7Uq|BD9!a_S7J!O}=R9Uzb|fp@#ezm+ zGGa9j`$uf|SUl;Ae`z2KOA&r=aVK@5;Yux_$0nr;y?~+nHuzt)d#^;`Z9>Atsl!jc z5|(%wbdC+zjx`W+RaJLvZ0uEeYm^sg69HK`rhm%9Rc;G0(fk|#`EAD-W$bG%nH}F8 zM+{HZ^yO5@5tm9kc=V@+O}k>A>xiK*ApbZx%1A4JDTqpe+aJ^M1DFA|n52%gw<+-+Ah#PM*AD`6NJT zZY4|fi%T7bJcyeV9(^fFUOV`a_9Kl8o3iTT;7t*xF7OCYkW2CiTJmuhT?)zmY&f2y ztj#C#v7mJ$FziD|R19NWf$J%``4yaNKGBfcbQ5^w=~qmq(R+3bRi5c~G=qH$CAtG3 zYx1;+7+5xK?_V7!QAMj?{_UQq-6fOLyId=wS{uIW~n( zXwIZ2Vsj$;iVqtINL`=;0jbODfK+%5S^dUyFrdCmYb9%B)^@)wyzv~U-C;c*V+888 zPFI{`j3nl9?^eWQ3YJ&UxUg=gt>TkQS$*+oUV$f{qr$1x4_Jmx;PLkUvJe6f>uK}u zjN2Csy2Zk1{6+ zv}hny>C7NkKKk!9Fj24z(T4YrYTl0(B19>{@v}!+d<;PLR%R#2&@jq}>4K!gIb1Z_ zalrU|dEoTwYk85?{i21}UEKzZoyqN*sl?#;Xt8v2u|5`}!Vd2uAo1{BoYXSWl0Mv> zv_`18IpUT804lWWw|l@@Wb!s79P{nQs0ayx9g7%g=O_+=*V1qd_w;+_9jcMu@CeDL z{-L|}N`enor6I4KgJuc=QemTzQ$O)tMd^ogDhu{m-0cCG__kT;x~+1Lu)@zpNfVgX z4EDRQu&XY`?a$Zr&L7-Pj8#)BY!By{Zm+o~Hswj=uvGw32J^aQ@z7tQ1Ss{AueI zrR}c|cl6doCHvK9#qFK=$m6pRmJA65Gt;2FLAHeX(dkI0E4|cnI~^3Wq$hxfd^Vt+L)b=iM(=;^}3 z?K$W=d;YaIY=0w*rgnc)+tjI6a#gu6daqRTG~`Q!&Fqyz#U}Rlix+&gEIi0g(Z(Kb z(Y&E7JxmH`cUYT)qg^t$gaC?;OIB%(YF(lqY{%--e~J0u+#jdgdva&y=yQp z!9XsY@qHY~Bd}Rsp^L*W_9H|8 zLrfAjtzjeiFt7stLUNgbQSbhj8`57GwEv&v)idij9-ZQGH6Z@1jMQnz2&X&cpGguA z6t9W%WRbO|1u~fQI^-=fPTyRYtz#6z8^*x%tG486*v1zm&_L1<{=s#U6XO{hv{DJxf!39l`?HQuQJRePKsbBS3qF;{kxPWaJm zDq2QwHjHtCgXiX?RR#Eq=V4vG*mu*e~^2%;mp}E%jI!gc8^Y<2zK0TZA5;u6+Mv_ zNnhJ^(qXSE)@8V=(C)H%e^t3!;o~PqOdXn@2#tt)SdPg%>gO0o{ioxDzS@IBy;w#d zOrHYgsv`xll)Wr%o*JJ?i?bs)CksBg6Pw$6>+`U@6-f1G#dxV2Ih9UUw7eAoOUgK% zp9ilzw!`+4XgH>8)T@Ut!s%W~w6KE;tfwU>_Ozc=;$kx znF4QyGDz%;@wd3WlN=Svh&eEXUOX%6tk2mQ?U=ijll$Ol*P_o6QU;X^rRKVKIPQE!LJ*i@R^wZr&NxO9raZU9Ovmf)7@tm+YcaF3aDGy zW$S^0+mJQTmn;r=$JFO3Q!4Rm67j|wJE(i~t-NdbbA0X~XKm#MS8f6#Y#Fj>*PpdH z11}hU^247CbT;QTnL-aBQy`@MJ9ZN6QAzp={0_QAjLnmnocCnlD&5n<&pa^VWcLW& z0c0eUaM3h<&#gLprpUdKK1RhyQ)T_C^k%Bb^pmE215P4<;w^5tC$}i#zi-|jPWgw8 z9iWEeVZWw0XIx8{!fOIERZxrX=8dQ{xfYT^qZmd^4Wm$22 zRDVpef88|Qoaz7HGqt>qfm1yZ0dF~Idt$3*;KcRNQ~d#4CNQu2WlM8$1AsUk?Outb z0;|Hmm1+OCo(n0}Kb{L0uEd{6PXxJrL96F#M$i6`i1q%S*s+LQ3uPXBNU1|#@cp|a zXzU6p)3xqgOxjamH!=jitk3(-H=Dn-(AW0a-Mc&6|D&W9`aicp}I`zo9SdLy3=9Z1*Zh)3(->Suk@j>F}pnu0zOJ+fDnjDZQ z09wPzHmrZP@pOQMPUIhLy!XHPV~aOcx&Hx_1|9l=u1uuLxF=c<24R7uU_<(OF(0d)Ke+$KQ?Gd{HCfy8INS!WFUGs{? zf&jmLy=}9sSoJ)u(r~LU`Af1yei|SeKzRmM*F1xBB<-rVw7|ppL#Vt>^UdN%HTLIn zK@B!1zRe(9pjxcV_&^oA_yz%gf#{f;@bTkq*aZxrVEqw{_%VW@jn@c&Fa8eR z9&P<8edInffR+F_d;}&>o{(is`+8Lm>?33Rkz)31zrXhTWdVk2Hy!_Sn;lfkaqJ>r zuYZ=&qtq$8R9$-2e;4;5m1iG+`gU7Xn|sMd?_3N~*9&E&fqj_gG{5)0o&RtTcg@;^ zUV~6v+c<&Xl#{-mKsX09IW;@$TDW{KXdkhIu60H7rc6uJ1ZT}r22BZ3XAyTn8+Byq zy9$5Q#GTli>O{GNtMW(0|cyZ=Ux+@_x}o5 zz^|zkpYZSPO~BvN3M&*)1OC7y z1`+>~>W!bR&)Q9+7XUATKRRgoz-ItDXnIhI=<#lsRi|ZbaxgJ>oz%s_Wjm2LN-ynpj@@!;NXtZ@yxe<;p1w$mc*>`STFZK5b5j9 z4#wkL!7w>B-o~boc&+t}m3b$F$k+tE|I4?{K12|ATgQG^_g01F6y)es9lcXtBqQ;e z&$A{xot3b~x#w?AHl7oEX&U4|uo)W@+p#7hn{@U1K5n-1^lq%pT}4?5wRjclCt2@t zgQRLKuxsLdnUK{Q?y%Cl`9sc0`{EshkoT{nnhO1(?(u75RWi9RuMHX86CtHx&95#&DLxc(sSJXxZf zp7;C1E!zN&*;zyV(L*xVtFrtHk3Be5Tb!LrV!AGmp(~5C$*Z`>mL|coAM`UvKM(gg zQ^erp%C)X=vwLz-BG}@rap|nxRb~}0Q;h5~qfoYEV0g;#UZT$Zs(JPUD(77Is-`bW zRGsgej^(>|q%g5bWx;D3n=3@z_l0U^nP+Fhyz(hL_I>BfUzDdSy>o|+(-l*~EKv1Hc40ch78BE#r1Ek zjIPI8L69x5tri~*rj+G#be6DP`8g9Bqy|f+7Hye>E`;+k`_=rBNc}%Xi`QH0?Cg+U zel(b{WK9g*EXQE8;=ywiOl|B;C*;rOZ1tNS{(i*vaO2G7K~+caUQ$IMnM@vJ!D#a+ zZ=k1U5l_rhtJdm}Dlp&8#d>Q9zQ={=Fwf3!t6!oyZkn6>lI$SQ9xFM=7#}`USPhQ` z!Tk&H<$&&MUpDi`I2Kyw0iTxpIJMByzS$e^Fi&?H&7sD!OUv!x`}X<0P2?O0v@FyJTc@N)szP&c2UPDH|2 z;HnO2WxA2A0l$^x-XI`Y*Y7+K`hsfdaJg-yqoGIkwUhC}Uh~3HCpfU5quY+2#nHI7 z*7@)l@u^jTd}SBbM113>pCt$BaN|JLtATGxGklrb4U8^*PME4|Mlm!c7;Nrn?ayE0 zb;I0>V9+gizkl{LnB-IN^vP%J2Laq_wdXM3Bfu~LsjR8vmoo5YpK(3#SA?(xPeRBW zAfIIC@$HE}POUF=CgBixvlKY(h$VtH-BpF>)Lay4Ic$Pnpsc6lQHeRR^|aw_MY!eI z@;uvmxjWh3Fsv}m&L5kyb+^s~WXVE0%rIRvl-tWvDQm{0f_}A|C}x~i4s2>JoT)&+bKjwv%AG+Q|po4VO3#`}WoYUGQ!1(IkIAMQ)EHPrB~EIN|Z zZ94jG$!60!ym(evdb!gyuR8mDckx@@%;RBXrNJ0b;H%2}-?sF`m~1{h;=p6<38#_1 zBs3)IkP%?|2$v@Q#^6jyu+5N_V7Dq4QCwE?q4;IIVtOjl2dy5-buqh`yXOe#NQf8l0LsSS)}Omz5&bxa{%RgV6Ort%+&m# zc|v@C(LCAc|B+M81VxkN(6juy=?~KV8OTy&xasaQZy>0CLG0xUZl=-==1O>UKX?U0 zZVws|`ny|p?zDw3T{;fvJ?EGvu-}wA!ftWM_3E4I&&uNcYZ1&GxZ?g@1p8!q zQv{>Qb^@H^b^#fV9TdnxpQ0KAuLN{JKw?@z61fZ5-U6G}#<~iP(Y`BY&!inI02v$m z3mIE#4)~;?lgk^Q)ZvX!DzHqWezg{#Q@{Y&Fjw{oBB%U}L#(UFLL=0kXDa>}z9_+U zSOI7s@{wO5FN=#i%4_^#N(#8FYSrN#>32ohJVE*cO4`#1~{RrV?|8;NOKB1nT-Am#Ttf`;OI%Qd)Z$ z>-4qgD$DvqqTwp|?yTAe)~d0)tUb(|GmgdMbp$0muY4c$;;f#d zN=D$OK=gc24}Xjn*>dU5`&+~V*43AN=S~7~Ot>D*=Lm0nn&65vIj4A;sTZFV`^AGx z^pm3({SdU`BO{}czGz~Hy2-ZBYSVY*=xY|Txu=rq-pNcMQHo#=#vh<2G6*IjU^6W* zFNAwHm=~Q4;p>C68sITE?Xl`TVc4kk9uM3jCdDi>H&1jg405+8JS%*SApg*y8S<$| zCE9T^=xn@R+gclwM~K~lm~tJa36frr456j(GK_QSvvS>aCuYo@oye-B9u9A8-*wmb zKgL?7gH6kO#>#u;jm_IrbCKiR*Jmr(Na6|p+=;*u$nim;JN zG<;I(R6Sle9?HVhJrQ0~C7djcdzw5zaPZ}|7-^dX@y-hy6ioP;^_o2DtsWVUBWVt? z?+}Tjbsv~o%kPBVNls}LRSi`(HFL7kq3K4;gxJ)BU1oLDSG8pwNmHJuQbPI9)yr(l{IT|-Q8R#zOM$b)->k}+Li->)fTo9c& z(yx(m=(aTZyLu#9dxt7OWm#h8NXxFpSyvyL=oE<{9de27*OW_Cy(|qE?Ib`&P5t#f zSuo3_X1pdE!-k&xAyv#I$Hv*l_1IpE1;&f!fsiQt9bFxXluYDSlj2lGb$UL+Dl1JX zaXs~KoBMdx39oUHXr3d`bk49wTl-*?7C$cPiqU3U53WSpo6~U^HKJK!Vuq{{EE8FB8LO)mc11 zjUd8+)&2JBLNncb9Xf1~O`WDn`}J_%exzY`)I;&*aILQ<%&W~jb1{29y6lkUF!vny z@$M}NCy%XqIgj0rCqx&QXU#?DG@F4+TNV@Qt|!YLD=sR?<-6xWCtqILwxkw(mA&H4 ztJY*VRPIAQD)+6HNXz1cC)0KWI->B!2vaD0>`|ZnW zf=Z|Df!d1GBjuT{>ayLvnR_axskbvauDD8?7%)4TnDRZRvf~t_s$Upb!85*KCtA06 zic)cS4Vl?$;sIa@lMzNilR+?YFHL0ifL(x6YF(TCF`K)WN|xVRON(TLHcjx@sE zfEKMNiD*L@tlBF_fhhm{ZTUc(9>fe@W=fuqJA2KqGE(nO@AvxN^m^Oi-0Dd__l7&! zYlb^qGj*6=CQ+QR`Yjp`7xk0PJB69RuwJhPbtah+7}kr}%SgRUC{2HAt?%%>{t+V8 zGTANerbjv_Y#Mre#dI}_9P4$#M^8R-*#v234CUasa7IfJn+ z7caDqzaOnAo?oUX?tMc~?IBC!zrcYWf5dAW%IQ2(&6`?!SeW+K)iBTYtLHBqo^v8! z@TY|MBKKgMfG?4+cR2xCz+SHdE?e*>)Zn_B$fJ~<)|1vop z6bYR?t_w0CMUi`V?Nj-D#_1bj>5s`fzhgyKZJ6Ko>*<~KBHg@> zco9Wm{YZF0n3>62?%hDo_*9{JMxOC%$n5{4+lKpLaO~0v)3OJX+%>?!_T7<~q{ebv?Hy`k82kvO!V?)E%X&^?6F?m)Njd(@^1c(;FG#mbIG zn^$Uxw1B_!2XD#(*hj&wZ2_7~y2hC{rbcG4Iq{nf<@VpPzCzRZvY!{F@c@ZL4#!K| zVZ2PeltB0+GQp=2p%t(y`g3+AL3Bb5^U&tT(`e}l0Nl)BdG?+Z!CW5uIUV9vT}%i? z&^vQnPr>tQCtMLaG?#4(K*|@h$3DuQls{?CG5&GBzGYneNlY6gL41l)0L2{EO@K7g z_jQz6J4WG1^2$Tj1tfnIT*Qtf1Y9x0K79Ey(NFhFVY-!M^qBZR9WJ*D7qI(Z@h6eK zEqh2K31K;nIUyOAT&Q3QCe`mvO2P@;^7uIYMhMjMp%xB>1jA)>!)b21=WWH%g6H1V z`s66Y?!@+L(_Nbs%x%qRrOSO;Y4gd{ zbb%#CCr*$+d^SFu)NFOoslVu<1O3mVvA(P3h5Cwwn_c^T&Im#wrEIR z4St$WiRsZDkYip`Bz;}iwUico!9IRAZs2~4jxT)OY{K2e=+wUxy!VnMF<#~U*B(_Z zrKBas`dKY_3%JHQ%^6%kg@+1((}Lgfim1b$i5s@!B#KAIhY9tfs(X@l`ypbxH=6*1 z9P%p|c6beMqcqGB#C0TLatspzd`=i*I2Z3Z0nlTVWJE?7BEYd{KSLO4sTP;88MF6l zP1x`Y7f>QYRg5@Wa01hF%^r$tfFW~-;uW&*axTDal*=sHKrF2%5CqzA%>eJzj}+Kpo5C*UW0{5f1*ZKjXlU47(w(Gi#CF!zerT7kO$RyT9#Y8U1#fZQ75oto z8{KryZ;|m|)oHq3xDx0Bru^jP|0P26aN9HzZos*Cje#rop9-79mX>iW!k$u3+BZ2> z{R^?x-Usc^7Rnb6kuCfmzhX^#d4oTJ-nsNnz+cbT4TaE*<6T<;&j3CvkC$oKJiN|n zlQ7DaOcuOLr9KPMXi73h>&g${O4B_+K>;l8P~yt8uLv}YqN*h*qm75Ns7X!v`RU&u zTE%2eHY?c&XLsUH4YpypL0zfufXiFc)KvX>cYN6|Be!VofmO{M!PcvT}PRAl@$MM(UyA zYMWiIK!UQoB-oEVTV+5IUO-yPSpCg>vQ zany`!zrXMBcS{Ne4#w{QXYozwKeq)qmr?})b_27=^D*D!Yh^G1mUQL{3A$>eD>U1* z0W9?D=V0Kt3|!&mq=7zAJ}9G%I^UlfGCPWLZP2Gp#EN9#wlGFhwjVc*Yv8kxJAFmZiLyP*WkAEBU1=$_#rfI5X{wXa<_ z1jhcm!1EKz4-LMj+qC|5*da=Z(c9CCgKGcRiy54X1N94z@?=BpqsjDznhki@r)zJc z+RZyQuqV)TM@-lUf8%Z6eMY`vsQTe|KR$|Fllkw?;PpjaF%Q?B$o_vf?;!ez3;g8W z_mpMtn!Z{6`p=-sI3EOBKEF^s|E=O`Env!to+^R~1nfgGia;@?`ns6%9w??9*J6|= zr@)rDH7{OQQ{Z;~UJ%ntr~Mz1@AAXNXQo-AkL9$wtz9bTnNj(O&9k6*9MViBXj`M2 zeN2Xdne}#;w(or~M$5Uq`{QzjN77rWbtXInuIJOY&9lPG74AGU%X-(6q!3Rty26`2 zH`px3vA15al#J6C<6$t(ofj4%t{dgj@A6p+|dM&&JBN za<9I|maH4*xl=`)@s)FwYTe11D4)2j&%+4_Gg8D@ADnko6;x9#l5gSb|?_!)7a4r@EK0C>U7MXzF=v>s_6`3C6 zsBHC8R9DG92e7AlYmZ@t2?%+dyiT;RP<6%t()_*A6GC*ac@jX0)O_^-IxUM|pu3?x z5&a|W=>&M$1xHx~i3i>!whPO60$;kmm4h(9TQ)WbGDw3YYxI)TolC5=nebfWL?7Px zw)%S=UIugh{_>4|3sWSlU0UFP=K=WXKQZC4FHLC|P~&0q@!qxRo|oCyNZoqBG0^Ms zhW+5-wV-`}(1fR~={4Z>{IPjmWBKN3&u_W^U- zGcuMC4iDb;9y1=hAe=0>3gvrR zaD_bF67vsFhSfhl89)f==E?YX2MgDpU(W>%=%+-jJ_O)_Gl}OtWH$Wu!+8Mv$kQHR z_4*l+y6_gmY5q437io4?GBMMU{&#bd z7L!vpl<^$=EJu2s(v%RsOV5ZumX38*=~wqe@JX)_-?86+_9%qnxhU1c;MRzkrw?iS zxTUkRO(X^~GWimAT-Zq=p6lITcQ8@?W=7sg1l=M&=JE3L!&g7ggk?rTt zCwU|;2Z&TsJ(gG&4hzg?)=t*YhTX-#ZN%8wM)RG!`d)Tyl+G-DOU-a#54ccHFAC4q z2s`+yM0RzkC3xscquJZ7MgFz^8~;haKj%^`((LCV-1-&`mdLp_NQ{&FAn9tDzYM1y zM7zUP0Q$uU17qo%YGgo|8GZJ*L8l3>`rxWl3}W zq=w$_R_rUoQOtX`WVmG|xQUtY#0HsPWQHp>$5=UVV@K((`MDSppR!3fs`ims45wHs zg~gFQjb?0-6z*@w8m-%ImSzn8UMv!9Xj3iWH~gewl7 ziwh3M6b?qyyrrb38oGp|aP&w#Zq8O2Q>*TqKoXAGU16g;vB746$~1>!3URknnVZ?{ zGxXq-SigmDMa)HC?l`y`@zj4%pY9Eh@f4%f3^$)AZ)Auq(%l$|gIt{}h`WHU22EOP z+qbo+Bn zZ1Qis3Jdmyt@%a8;kTAfI(@oUOG7GSc}gIK4i?|-b{bxIIMlF)z2fQRP?RFyjP@?hkRij8(8VSN3z5A}b)$Fb}^$!Gg*lyK29I)e(bx zmNt_Q+%O4fsC_PG2gHPLd4GQ_Bn zKe)R1>0vuuOEGnW`}>(EcV$va2AD9}dr4A?);+*w&8Z!!L`X3OEqd7;F!a=JDr zjT{SkU`1wton_4brUNn>iL1It9Edo5*6L4c5RRN7b>~BnA4Q@1fWb(*D10Bc;DfdM z?X^8HgSFm}^6y^|lH{yT%rx$et8nDs9@c)S1$j{gqsbvZVG!WNqQlS-E^f7eQ^9Y~ z$;0Tki`mTBC*x(Wi7?R8U~nulzLQvk-gP<7ZiFd?x%0Hq{}ZfGHGgP=taM31r2E=u zJ?ESqM%qM7Eyz_@hfbn4Kt z%$keZx33vyI4wI1i!pvjufMu}=vgc0y@iV>$a}}~mIAne`pIgmgV09IUh1Gz&!KYx z_r_Z5h);?Nea8%Pf_!~V5_Q4M12?k@LoeAy4khhZdcs}#vlW%c>ffA*kUZv$t2d55 zSKPSH2vgvfP)p6pzuY&tsNiu!x;7;+a z5xS2uFEFinm@Adc-R@5})wJcN2$hAI-*aXnWX!{pN}@v?(B&l(JrJ@KqiyxEnt<$h zS%2*g)!rj#B1)q{ZRuLd(5e~84dEq{M;=D@AfW->{XTj4czWP0^N`XbyhKGYS;^q5 z)`*{$P^zox(MCX^91{YXrC!LZ)tiy71N{E$1Wyfi6o}O)ujwmM%0@YR>c{K^|=mjC@xo&n|B_Ck;9g5mfJA z%2yIyZtzc{JBDxiD|{wm#SI**T{`b4i5U9a=b$1`p-J4nrr;~73erb54F zifMn2#mC%Rb4qVCMMlF=iVNcmu}Kkdc`M_nTKKA5RYgQ_1bLlyqhpjat70TZ`%=W$ zg1UX*o!a-Dtq$fMsVE@8eA3s)M9Ie4 zq+}eZ)9UEnQ{qnkw;@=tOz+${vx-za5~_FWn7fqPCU4E#L?>4+J*%Z(M{Y=%+rZsU zq=Y0>D(LXU95^RxCtSWuF}PSb2=S&Ov;ACh@^)qP?k?@Un8>k0A>u%!X})&530g@3MkXv910@K7Y9AdXLg zl`FWgfP@_7x!tpt>Wi(`{fIL{@Pkqtt^rBuZ@FrHp?f$yPDXt@)!XiU&LWhv!ZvD6 zXI~qhLxw+!MUxCk+9YciS9>WqdDaB!DR&a-d4y;<=9MxoVHyZcf5_Rtl!#t}h}}=W zE68md{w$&hA-UL30qfB6WvK*C-z#)klX4b!4AW(Lkr9D_MWyu6rkThd9*Yzi)0FO` zycoO!%I|OWw!fk_)nJO>g0YK%yQRXKb&u&pZfs2%>Je=bnPfkW1&TBO__y~oY36s{TM>J`Itxs^;14Lr=sCpb z*~|}}HvAkx9^f+Y={&6(XJ6iQcZj<1e1a47T5T;X-Tm=$qiE0^slSE!ky()Olh0Wm zo$kW;!(zjs`G^r69W-S-fg7=_;C<79L9d!OU%secNhHZ~xQkw?3`HY9Gy?{LrcJ|HI5c2= zH+$5bgBY(kk!f`f&xrePD{}e9?_GSfyUY}=9a~nRIuT7dv03fR8t<1f+Mrp5j?u9K`RqYjfSu()RP@RBFI1<_Yte;o*_{p8MVg2g`6E z&Rv-O`xR7~6YwL{uD#{(haJWSkYwxAvq7fh%W;kuCvhq)zTZfqPTBj{>icX&k?&5dXl5FLdfZ$>7NRTVj zHqROgIgQ_Q%73K*zb1T-Yr@;PqNH19%>z8Sb&Ktae{0(vJb8Y4H9ve7r|r7jkVJ%U zZ@N1x3#NY*S`d*>;*?vt(s86(yuc^NeI(wXgSjR9?S+u<#_|Et|;_cr2RNqKcH&v=$vSwApP( zTd)Zy1R9H1={m0>V9QU6wEZF?MPjD*yrJA^LE1=4=Y93XowdD(s#)*m-)mnMTx=(5 zgE=A`oW<0)UA~=;x$xe<=OFn0rSb8ZD|=6FOYc{Rx&v7XgqywvtKFFw_V%qE#ALWm zm{jCsM4Y-%7^Fg&J+C<6V#EG>kL;Ny4PK) zMP41;Z7fQFj1$BJI}K9M^&ZM`-{3uE7UQne@Uv5#WGF2}Y#E~+^m{{@=!aP{ zvn5viy=0;|vb|*Iwjk51sQ7bu=956Z-J|CDCB0oS{oS~?PUpz%BN1Obt<~9ttwS2f zP`3Tol}hpsu0)rrb_&vmcF3NF?GV|x1l)?rlFsuH;gT{=c=@!q%*kbTc_k}?KY^b= z#nUOoIyK)+*XG5FFTvoh3&V2m5o0{-~bt$g@anHl;*!>3p0RR8vV_;yg0Ae;E=77>5zzXFv zB4H5Vgo;DJ2YWss>42o41&e+zB>e(VeqMf2ZemVmRcZ=E9Au6G0dts9%wcB8PfHt8 z`T_`qGYeWcD=^>!AM9Z?$Xw+3W5QxC0}{;&v;{dnNA(Z9{thJloLKZnAgO19@);OC fePQ}N2-uHoAIN@IC?7=oI{OF1%mD!aaId99QP^KR literal 145610 zcma%BWmg;~|=(ROTFNZ@Bw}JQeyBhv$d<`7KiG`=lOw-z|I02RHt#)53 z$)^WF*!?0eHiFP|4*F-^*sJdd;q6SP@mYLB3CpGHdYalBxx>WW$CnQTN}E#tro^1r zlw3SWpOIufM3GeMod^>>h$X)o?4OMM^7YCkftgs2hcV{ojI??FDx@MTR|-Bw`hxe4 z_KI*(_YG{0T?l|vx;~%(5(Zy}0tdT(&!G3xGIeJ8q4BOe#yfgw!tcFP z(Jq#f;8uBG`snS`Wh;HOz#w$6H*XgaXVCjJXu>a3)_H1=j~0O9Poj3RS-o9DfI`)n zQ{2H-e(xJtH?YibK<&`es3)I8NjKbjGt;%WU5WlUuu7q{jxPK-^Vw;=)-A|q{qwa3 zwRY}WaMb;4UnsFZ!nb=na|mx~AALXcq=_87o-VFG*HG*rNgty_rr5(78PGL6<7`Ai z0B)B(DUN=Q`_-i0D5AENBuQUrnH7W6$kTU_>AP|mxLL~FE5cZ;7`6RH>xG@xX09)i2{kAk4h!6 z1rnY^*EMhU6v?bNRSHo=2PupZ~{DK2}K5phastUc;B_4l$*M9jLE(2zHHps}Z z03WVSSTyevQm0;qpM|)?Zk3kLYwxd8<~pkhVeLYb_GAtS;@Z${F=*OFq0G!Zn|63s z!lO3lnyC}a@`EIST*}pbtPQNEF=wCucL&>Zb`-WdEam5|YnFgpsZEmv2Fiq4S0H;k zviOOMR%@}J{orF!!AlDBxF?jV^_WTN!$J=zVX!tx)ir{0=#2Fe&ots_T4D{?j=Tov zqk|xDqC}cD9?vG^B`H+elWC(4@&+v}h)_Vx`22D|Jo~_w@{CrFdvJk3(#JDvh;07z zRR7JV?h{`h#Mb>O1|Qhl85A@`j9h=!O_sCz$dgsn#n@~aA%BTW21tG%qNU6a@jx2m z%4ZA&C&z_wQJE*bKxwoD#TG@$+C5hX$=A;sn?GMZqk=x33G*1wt&xWS70DjQ$R49f zA6L1r+w2d}uwDvPoJ@{z2$&NdF0Tz}&--6gZgwI^_UKayxGZ#~ z&tm+cd8|{eJB=e4@w}#b%JuNx5JE3JkiB zgO($T_AMgk+@TPk0WTqg7pKn0JEtt?Ul=&KT!QvYFx;-bN;J=Ho>T`6*(haTsj%@@)m1 zeT~jUn0jn$ukwRe8ypb<0S-UW{P%#&R+xH^kFCQ`%=*Jvtz=66!8-meB=}P!iZnTy zSwaNz>|84JB<*G)aA4Y{r7PZKme3EiC`;IB=W8%TvMZAcZy_BTGf(<1;nU~0VT?BW zV~;P-oqG=t(Zb%_Q5jXkS_xOWk7csr1?gclO8(|tZ&(tqgEGE2#T5CN2n#jPW~A|E zU;3(a-4!-~bI&&yOg>?ywFzP2!x7pAmAFrDp#rZjIJG>IvD!7a?SNQT>Azhvdt5Oc zuTESr(E=u*A5h5RiiAF1c9?Clc$M|yAC;lon?y*nRHLO4xhXRl5U==p3F61%nJr8> zmOb7ypQr_?HaX5br+i4m8+7$=mv8%foa)TRGT-QBG&mAd*06+2%McC{Z0+mj&cYMS;ZcV-Hx_x2E6ze`muuDFl+v~gK$|so@=yUJ8%P5>7-lG}o zhE6fRD0811B=MQY?5G?1SH~0bb}sE~Z6p2+j-k9vx3E}c6k(z$(X>M8evVI{nB|L^ zx$`P;@;k4MQ=2{JNpG`r0m*q`hPZFbJ%GNR$K#iuZLa#KZqh|Dxg*~0Mt>~Q?gXlK zI>_Nz3|z5x*e!fq9>VWH7v4kXCI!`ucnHS)7W8O~{D?N4q`eUF`#`8fHx~2yp{KSg zcYEXLr+0<3`~DZt(ea$nsb~ozM}f0Gd?RTZkR8(*b>|ViH9rll=;ZPE=&4Dn4YTHp zb@ieaN3sr$#+o}OYhK4U^Pp?rc+{?A;^hxmUdEw^|eWy4LKlsPQLsjGRI$KwVs00GP2C z{oJ0D9h;l%jgYMkPwOi>7)>Tsv|#To(Gns|l869-4c9fweTh%=5SU~Ve?GZJ8vLp8 z*R2=2G_AH0jyO7qd^6rB{t}qOE_1cNIJ-+){$(DDXA1qn|H1X9KB&sBf4SNjHh@H3p_^6;Iq$=!YQ*_spaNP?W zfEvAct*i%oD*h6dyy-A_As~tLjx+SbY~;_ii3Q!i9SebaAU>(JR{WhV1=D7G55uJ!EiPTWadOju87BM^58SmB!}c z=vVojsoV636ul(+9TgooJTW|0!}p(|f`2*W-{VnBL22ea36&$QF^beDyo+kG@ABxE zj8NHKlfZBkI%_^2)(@hqI4(sBqL}5(F%;O$v9Q;bWPU&7!X*O&*Ay}i2hOm3@ z1fD{Mu1{}$A4dnCMqN@;7D)nQkXsQDw#)15oHBo5p_g-9>jd>wr0aOaGL6B@=Pf9!c|2 zI9iNKoLDH0%UEA7j-I~zNl3EbH5ezH`i{2dQ;8u!{9CuM%?ceMaO<&1&Z{z*mSdu- z90;cV-v7yLY)(sZB(Mvbgwn1UE+;A^jN9xd*!(>E_BjdTSbM1;1AibJ%-9DsAXBBb z5K`^7igy$#xMdj1#==`qN6fd>`gFgRc<;2HH(5{`$tN)Jv+*e;sMlA<1+gFrHvRR( zD$6AnPq_+RhCN16TU4HrhDm~L52@0RX~s>LAtBzsut}kq9W<@c|EI?2fOAdu?Naco zPz-_ror)jxT$?u|?O2*!>Yo~HmkF&fLboM`!~8)L!q>#Yo7dn1tW!5Eu9_g4_`31z$q zN0zL|2Gi@BqrMtOwnr~k@OmO&+Ji>&NyCoBiW+d53$UU6OP`lxa&!;;NPkWk5pvL9(Ll2X#B#$fqPvLY>ygVUSRi znfIB{n>iX>EyHC*_>0ZG38~6iY%?f&?wkE;&iO)$;}&4nPe4t#nCH*!Td~qjNQIok z;#$93op2Ppc#rV8m;4{jUst^L`e8sHeN(MPF%fnON?7L0P?@x%Fo{<;jEdD8_Oh*& z8XHBf6+}K(#IQZZbc1&1sl(KB@9Wso`i(8Se>$*DqUxrQN;jM;#3a5E)|k&Kpgmtxe+|X?8t8J^!zz+ORBF6yZpdnj|t%YH4fd zx)sFf z#vNY3Q0TU5?(!Q~J6@uF9#800fLXjok>iM8QdhQ7DyO{9&=KdzUfsuH=JU`h&&49n zn$8eti&fCs`65*gq!H=4=F2GIJjs@lkc_$62=HsJiQ-~6QRLq>2lU4MfrgRK6GX+Z z4a6w0XWa{3U5fSWYn~eej%OS@mc>djfc5c0WE9auY%v!R#?ek|R4ZVd9sKe3;mN~d7+5qpHuq^0JfgKPMy{(+Mf7r+}xKmylr&Uwk=D@sQpCI^CZ zKkzC=C!DM30v4N&24ioq7I{<}X7+wG7`nkdI*=T5MgY5iz^ufO^|?k+{Pk0gB?nCv7u`OQS~0=D@G{vV^3 zQX-Th$_j2I!qyZc2}9%WM!={kK=N|_JS$HZAkX9UcKXy_)Mat?L@~f?YcT$L=TCN* zl<*T_6muRARPY`%V=z^bd3rLQydwKG6 zb0KRdl)twhg}gPi&a9l6qafe`%Ky2akDr~M>5>9}XA~T>F8Dn}++w;*gttA@xrKI+ zmpwT?*fdx3wuG_-L0lz)3d6RM6=3x;g6zE=JE!X;PPs(wB#~`_#5myy#eJ zuZ$jgIPgGD9wrn?TFyU%6z{q*2dZMacKc7wPF0Jb-t3>?x*Dy0t@cjOLFy{J;_Dpr z9fKyl^;oJk=<2pdn$eLH0>q^B6-Mrpk8PRE5S;H8FYBQ_&_136F{R%U%Ho0!@6*)Z zI~4@L^Td$Qy_OmzIS2bPABbC2xNif`e4*`V2MLgU>|Qok=JjUeMTd@*;4@1K`;ziz zPjtfTYbNc3o8{g$IN2r0B;lMUH|K{L352qVIDra_hke5+)6fn7Dp%b#RaiAkuBjQf z;ufA&4aZ{kjj>|Zc-JzYTJW6iVr^e@fu3q!-2M)uXE!fygc3*BmU=*F?cy}DNeM)^ zBO2PU7bD(Vy1?|4yu&*su_nucYfnLD*njzk)=<2(8jQ7k)Jv4XS@ouoICb=G+cilf zAI#z;ZLAWD%wt+LBIdPADP3b`<8M+Y#&i79nG@2@MHS+@IaN_!!mOrv`-29`yd$8= zWQ%8k+Vj($#a9od+%)ytvSTbIe_mKR05{;!dv{upZebIcQ}SH4@ONFr9! zz8I}}V-HeI9<+#Q^S!0ye&=L}9>ndFm3ra>m)>pUYb$JzJGRqDD1hCKyg5E)T)W5oj|VC_Omh>tkHB2Q6jom? zgi}T|ej+3n#lj2o#G+;5u`?zoE7~fw+U8ftg{-P`I_?OaLgHh)5Kl+tHqgKNpm0*O z_#14yR08<*Fm2R!KPA1`g7>qtw+$$mqwzjN^GRFPhZoUI+QlZOXo(jS8(3V5t_v;s9fRV4{S1LB|#^4mqh z5=|#UOta|smwR(bO<5e0!x9E5;Et5Gj}&Mn#{_$Ve>MaI_GHAyZ9;=r+jbtdggCG5 zSUIIK@XAC)eipnR>yPkV=J3S%bJXyZNIEktJy8B3B><)J4*!ak1^Q~0Z6#x1y5GxQ zV}7B$b0C>Vi6j+Tnq{&Sb$E82Xdh2O{Z^?%JB!z@B2kaFFqK~0%KA16YFi^si@P#D zdVlYT(ux0y`T$Z}VZB)Ckt<=niWL76)Muf4n7olSr#>ermHpl#YrVV`edD}j$KiW7 zPY_u)@?_OhAN8jaj)VE3_B7~E>*T}}#{?*WvErr2Z*n}6?r_YW30jeL5XrCSbchL8 z*rzL<{QD~4svQA?V2)kDyW3903@Uubz8JKRtV8 zHx=S1%+;EbS6w<<$s-Zs2Wi~~24qEo=R|TdPY5{|FMwdlf`yX(2)A*xHfBfel&%IJ zDDAC|>isVliF<=~?!r+tmjyr3Dby2GuKI|wa}UIUcDyTTbS?_XE|878=cZZg<&S^b zH`PWldARs4dyLF)Sn9l}pDI>&gDa?ZUlD7pLwj_x0i8Ha1DMpx`|VxxrBjK_kQ-^e zSkF9@wdTR65hX`oPbXsJWeT%1BXC2!!`9QtJ?vd4*!G%GegSsg_cUVU^2mAG@HE0U z?D2d5w%A8u;g_>qS@YxB3X~Q`bvWSsk$IgS40rT&MtiCNT!|Ch!u`*|nflLF_#yv% zo%1=g$KZb|OG;^(o5)SX@RZ?O%hzo_CRZdr6v{Nbrqlo?ChP#&)DSlo#WaCJD*{H& z$xNX$q0@TmYU=7Y{( z;-5@Vir7-_l@*OGQ+-@c|D(%!o>ufell7XgzH(AT)+T8Ve@$Z8Ec%#lEo;Aa-#8Q{ zUi`$+Pp-zI)`*sx6mlI12N8*GAiOHlf!9Uo37o9+9kqIoo-{E&)sQ^l4@t-!^Hrc( z6h+rfv)*r+1b~u^^2d5!-m>{+m2N8oKjJr&T8U+D30Fpi4n5MY5t?Xk2~jg-e8q}k z+KigY>Sy#Jf3?G33k>EeKED2vRn_b<0^0TPCaOcqh})W}Fc9wJViK&8;_Y^~!(a|K zD35xn36%|bE}iDPgNl&jvb7dzCEToQS85eLflpCW7+d1zRrC+oxQL{U zJ&@?_3_NrAez!YzSLJNKG7JX2G-pNuI{nu?1IE>^RI=VTR?z2xIE&i<@H*%wtsnVV z93=EVDf9>$kViS5N%xCHH+|urYP`bcC2D>k(Osmzh1~^#P0FuO=>(>H=NaQAxWz?y zAU6SVls_m{^8v*Ilz|+DwZR#$^;)bcwzm8X!X*;`1;M23_LWKcl@e@V?Y9#8bAY&g z*9NM30bOkNA7^v%)@UuOPouM2LPNWHtekX;{`F$Qv4`Xf_6|Z$FJ2q8+wC{#gqWgc zx5kSfAV@1!N|gPoYFi^azaOj7Eh;!(y7&g$J>`pPq_6xqEnj7w5~O+5@fHTUEUCRh z+ibFLlkH$fH#dj@;g$m27}&FG1WbL(=!@MdgSPULt+4i!irEY8vJd7lFgA)N;9-GSb4lFyrXXW%+uvxf@LD-aB88YqFKQCbKFu3yX5}*&M zMN^HZKl42)UzCI~dY|?6_a9ym6hmL*jb9mr!`oVzpOe-I^+&`vKjGd5!T;N9sT2Po z*+5;b8s(HMGbarvG1=1F8}3sC`L7$wK^y)8CCJ?+uG6N_G!f-37q%_j4I$vxpk(*> zGctPkaS&v^3x@biR^&QWE~)vkj76#8r^UXw-^+;)QAw+unk;)MO20^B;b0*l?+VaX zSYf{3y6P^4J8<%?m}UbH?{9}+O{#0P?Yka2L=&7CegREs%|CX7&yVgJCktydB&WWs zPc4y|VUIfgIc;vV;wcnPCwDaQu2jAwsk3Z|QmBiW-IKMVDR()*Z$`z4{5Tmbd!QY2 zfJCht>872u9|0Py<7ZGZbjqSRt0QW9<7ppY;ia}#=I=*d%5__0ZMd{?6a9wzvLo)Y zLdM1P;~905wn%RKvma3+qp>pd!x6!31N-AkT1B2(iQ@KAgeaIwnPZq@B=Pb&lC$~*kXLrR z-7s{N36MCMcCOsxXJq%t-tn$}?Tjv-_@apZ;VJ2hsr@f(V*!ea{Ybl$#Y($$nLfPB zDC8Vbzu@-sf~YzA%F6CGlq5i>9scW{fyLzGc#jJ;WKqpsP3I?(kPbgz#p|o6GD$%A zi0l6RjQOfaz`d{8y{G2)p8cGz<;M}FXLrEEe9<8FSWX(w?f#HjGmSHcy|^I#F(SBv zaLl&7!S+qLZCkR^-WlILx1DeJHl!($kd@h32hA{ZQz`(}9=Rb>1#usIvP9b3G-_S?}8S=vTdl0L;J^V{Ki;?i|s>g>dh}qxZ z;b{}$3IEJPVeT|Id2YVHKzPWT-h>o;?fts&`aQeMaIGbI2>RkVT;Be(PYjGc7pS|G>UvL>EH();N3Rj+HzzZL=kvY2Z5$ti%H_=9Fo{tB3=gj!x+ILl(nR)t`4rIlOgYT+hdEx6Njo&4;G zb!_lywuV2(5Q0qcVB2OaJ=B#fCo%lhY)`%C@VPx_1(SxL;%JvxJhG^#!V!TG0^FdJ zZzm~R9#T0cBx0#fZ=5dKoo9vkBH)yaFkSsbf@uR?ouN)`&ou9jM9=1OE}D5eR%!zL zHVn<6xl8%kY3YumGD8fNW`iJXzR zd9PfDuSCs8b&TBXD}C+hLxp}3uwn`bEDI`=W%>zAY!CZlm|NMo`X-Dt<#75rA2AhA z4B_|Tc1s&&k0eOlX{eA9jvkxp&EIr5qvT!zwFFszWNOU4CgrQKO{KLuj3_iW~LSSOE?Jgu9 z84VJ?4MHlS{Db1>kBpX&5x(Aqi}3ujSxCR$jZ&xVtvbikB8Y2Z;uawI;d5Mw7L}PW zV`7|BPI-EW{`BCPP+3(?2F5Zk&*O(5prl=~k&*MFMF*A4TQ=3BbICZ_?{%*a=Y6Yn zg!(y^R_sOCrId)TLyVtEllPEo&A(k|C|UDZdNVJ48d&&*;TE!(&@WB;8PoHcwAQg8 zs1ep=aJK}}xn?78MB_P2}QFT#n#cPMgk~m&rZL zJ_e3PbxJKXPyCL$9+{4`o6?Dx>$k_DPd7G4iR*F4tbotH!><;r0=9efdxC>75dl8z z?CakoAMS!#`41??0i3$=d&o{7TdVJWU}ir4jUpu99OpHJsLbFvD>rf z@4RX8&wORh3pl=%Lu|{pBUR2s)C|neV|T|-^6t9##Ti+cwiRRpPDolwA=lbp6q|w8 z_7v`&yElq;Wbmq0YzLoFioIDomRpAsDThSC--D-n#wQW5uKOyz&Vh|hR~e4{mY~Vs z>%0_=+=U3PJkdtwertfS~9@j&hLD-d;yWhaS|P=t%Md&O6?3ovC6uBLe<4EP1g~jNSl*%G z%+T7n4GVb$C%2H`@g`@?r&Ps9>b6u6^QgR~)Q(&vQ&7Lwti1Y4a-Uy(fG&};eUY?R zmdyM6D{oMVmQ2+zVMFu1Se6L~e(uDTlNH^&6?K z+WJPgZPLO%pd`C@5lJ$%Bij@i*BNc$p+giB&KF0j?Z%ysXU zyQ^d5_wo(lCutVK1V7C35PSae7dulj6r=rcDXa@3QB#bL`WYA>CGNrCwDNBg-O7E2 z@xhKL-RxfreS@@}lc8iUBlx}{V}+ZfOf_PXos`LR``o$(u#K)rvjJ0?Y@;9K*vs0u z=-n~3c|;=2>$@3W4>EWj6XU%i$vU8M`tdR8F6E97+MXl3Up}6!{V;y9_-GOPvr!zn zt%Z;YHC!Nqvh%)V#=$fJFOC#W*Vw8Ab&CQ%wbl#8OkAd9w?Q|q;4jLRlJLGAoD7`4 zk7HM4-jyFujD+5!m@I<x=BlPUz$;M;eGQuKYhTeuVmjR>#@y1>!QejkYK$iuwK{IJv~Ge-%If7aG&s-SU?GpB{xO>JBm8R=fX14i!Y{LuOE$eZU2>s=C=RlV4dXIqx#{{&>1yi6{)=78{l9|m=GGe zS@8xM1sG<7`br#wtaRIc?qr88t~g%yz`_8s?UO^8K1-CL6Zg_Qzu*8DXhzI^@44wQ z^hjFt1+@ngUVHpMgI43e#M~D_5lAccDFSl{-;6@q!2%+Xei?7+FDRW%GzeL>dMTW; z0JVCDaJAzbz`nSoB>1k*L``8z6M+T| z!DIZ9`&f(Clbk@Pz-3Jqa%CG<7@gr!`T0Xl@}Z%FOpPF?Bc&FKYOGL1Cg^#~?p}xg zx(rxWkbRab2@#_N+{fK$jHcT~6?65^!rSdsa5wdc(PAp19Pp@>WvU?~#5;*%ZQ)J7 zb4QnQk3|N5=E>@(-+8CZ}cd2dck(|k}!QQMqQ|xt^YCzO6Z@+TY@UvjfTnA$(D>RuLB;v zT-s_swY`h=3b#Rr8+%)!ruoxh6MOhthHsfo45iP4gYRAz(nEi`FuQq}}lnm_`>sLr%Mha^2*2Jft z&&f9{({sH*dK%6Gsuk67bE|X0W=&ADB^)(|xsV`B-h*zOFd67~pdL!NXsw-TmPC<5cVA`5w0KHJA0ojyB)OzS>Z1& zjDBkTmln!LvGz2wbA78ciDXu-K>~)GRZ@j2Lj8*SvbTTyOaU3$0grFCRQ?tqK2KZh z5gxRP?|yh|F8J#8?}4nI0+q!-41J=@W?2_-vMQFJl@E{P_!pV*&}Ctn$jJ9 z1&!_w*Bd=~HiY_YBmpp4=n<_Evq71DruRSr`b)kOhU!+tvmhpPfR*Rj~d&&IUUKyNpnf_ zg2Et#rOT#bhaVut7;BI`XX5SO+R2xfU+Vp5uOI&BlPW0@@erMJ!rw$6|FlG67B}<{ z8hnl4q4ge{i7d)LetIf1(+sn>KJ^gkI6QAH3c3*=`(DiPmfnMp2Za8DU@gi^DPm^Y zuZNClU#GCIuzaU)@C3R#-a|zAsPFAL23^8_o+2EqHT}_uSMO=3@6gj;{tlPQL@5ef zzDRhf*jt?1FPnPuHNs>?^mHpvon#eh6PVaDbT`g%F=F|BXldasRS?cyX z69KHN&lyvXvsDj_J0b#MV-&`$UTM%TiEH8`SI0K%;J!Az!KZeKy*2jblol!QBl|F& zb9G1IF!spz#|QmcwFhA!PcJ0tlA^Z!-8%v4mXL}FlaQBgfl#v$6-;vZVvjJA%V!-( z)dxba_N}co%v>Pg9pl0q%rA8g$@LG?0@j04sJxVSld;>Es^hUE6AWph6k&Fec344^a3Xd_@Rxpf~7*>Ldh1cgSKiaYk@)Wl2Ipy~# zzodNJklV*_epC3}h)Lx9p4vl(_x4pvl5WDU!l~u+h=W6eI9g4 z58RIjf5Mw$H?($uOF|8415c@=2J`%+b)246EogMv`~E{=(v;E)p+?iYXlx8~oc!2P z<&)?6H`$NkuPWWnSb2`^+WvqhDd_j&L5Ou~IPNMfN;<=9xcW=LT)pZ5egY<-S7fv^%(E!Gdn^#}c zH+nv&Z}klK^#^y{b_YxTk8iHp|5b2q!ys))e+Y`P#)+|II$sSU0aAeGFrG2NG}9by z^U=Q&PBF20d6>{K+^x^VF~Dt%-Z7ky7K$Z?ura;RdqbDzTCJv5u03wCPeD!nAF+DJ(I3?5iK@F?JkjF1q92!f!L3Z|J)4I-RvdaxLoe1G*T6ds%?4v`l&mo zH+iN1C*jMa35yr%!&iEw567Ef9X(VfVaPXJrz&@BL+hn_ul`U!*$z{vJtxjp{xAn@ zpw@UY1a%f29QJdve8?8mar32=NCg*wB`#kBTcj`uH~nWUSdQ5lT)y-vOept1=<|PX z-;+c6p})m=;`yf0MowruTJ@@beM@KkoWk!NqBQMoh6BHZ$ zbB76rmzwv+3m2eOw2Ir4k{4Ge=e*8C%n7NJXB0Ocl8Apacp*KD+OWy}OYbY&^Ue`S z{t}Ko2KV3p6-YW(Mf8O$LTQ-moPDL!Vzoyq?nsQp&I_9_b}ExzZ=A^K+==;WySa-z z!XQ5z&j!_+;z}@Vey!#>w1K7TR{5OMh%?8`qlUt8kIra56zA_QhrOaubKp$jJu7WE zU9cTr++5b&gi4b0=XG6?;$;$ zozz+?)m6fOxkvrJeL!g2AbHs5yv}g_yUi;*M?^aZJO}iX#c-ZnmfE*9v*LG&_aDWl zJ`+}oNlc%|E8B_t)57%G5Iv~cK%yXHo*=C_?nR4GtPH^0rWnZr~6-wBp?L)10?-L>O`j%i^yB+ zQPa!~Qbs#heI3@?J+F@0N%4kh?6j6tR7~EDo?9T>eJ0<%+tttG=v^lbyAWi5Am8>P zCS9PVYGjnWV~|Wu0rCvl_R>@aVq!nJkUvS09g@uBT6xRl4T*-`KezadnFe|cF2>)a z*?pdvuZczPiJ461Fa?O$RXRuyr40W(UK;ct-JxaRChG9wfCyzEN(e!kR;j`_FU@g&RqO%S=B^LGAAMWuV1e!+cn z=7srPO2A(28$$~-Wz1~zbdO%F;Po1Gu#?!yOBE$7rly-MZsFSRIt&4zd^M}*Bz>H&0RxUav{~29R>S@8aRUZ>-Z?pAa*_Sg3x;IX*Px^jf zhQIRAJzp9v%HK&o1RZKCrq|3}>rK-*?@{UX)2;sHeq-)-Ul01zQw1oCr*k3(alKai zWm{+vc*W<9#hO$?>GK_SXY<=BeZZb?|<7aPvPa@1Ny}$e^2og3TH9;**IvC+uWYCfD-2f7V?$ zN@PLqi3M{@#i_*w9 zVeo`o5uV~@h%hSv>iA*^Eb=nkcEa4Y2CEi4S6OaR;AxWEsc>= z)#MyvuJ{DL{ApCkm)bK%COGf|2T2@kHdDmrH}B;)zq2(l<=M*I*=;qQs5XC(W-a5s z@+Njy03=HflI@NO$EaII+}~HNH+jg&alJB4g1wGdx3y>W6Ue2@{{X z6#ccKG0N)=KbCKG?cUM|g#?ub@?iAqtrjBEEg;f1qSszKk_M((Sh1H7BWtUvqB&9g z+;W#2M(+L6g9J=&jMz=?YZxw*8^NV6!~JdNo|ya<;(*E?Fn-Cp%(`+Ww5&&gNpb!f zh_Q_#-)ql#OXD;c4H2uQG>SZj6F*qWX`v;oNM}mwT@cjsuLeL@!Wy;tROEY&GGt$*N4sHIi9$` zQ0ln+vnbb}zg0zxmFdneA=ly|c{YXx%==zN?WkwE>zLy=v8*?uV=el0(P3D9;}7ry zT{Id`c*Ayf^2sIaE|AS~$y@5%87s)S{Y^bh)yb^p!_5g@E6tJil#l)AE2I1B5SO|~ z)Mc4w-N5EE{SXOV0dT-{_;!vWmMfhU^LT{RvU8@#^1ev?sKbWK)`;2xq|e1@ewNYz z&*LH4B{%tL6%ICRH@Ni{21;fQe3(;?mxCY3T(+YsGLMJcg>U-Om2$z>t#*CcHLckT^79?IW zV0v7)1t@dUv))CGu+Tu6!B?-hT%wj(q&+S;TAZc!6njh(uno?C0BGvG8lKy@!Zo|~MhG77T@`3D!1Y`?ifbPJzEXbD zvR;S3-9kZ%JFnihKcgo-+iY(Im9U1^@<88dx0|{3eNnkula=s|wp}UB>$n5TDO_$7SE5mX|%>9b7lt!EnQ4qogIEgHzZk zR_WlpoKNL;>*8yfz68adA0TRrnTqAGZ4%?1bP_=>!#6fT1|~Cy<-%?Rp=~s#^;AID zu>eQC7A8(NkFD*|k-jj=`H)~S({IyP@Lgp}d^DM@sC2le)7HSJyX$;!+}Gmdie32I ztN|Au9yXnQ%a3-0+Z2I|mqzNIj4_zpyVAqK+a_EZF)arc!8kj?_&*pf!|^4;?@mCm zHNVI!KIpzw$sSF(e$+_;?V44FN9H&Et9v4JrsX$r7=2^@uSpyzKfe6F79Gy2 zh>1wn(boH(i6GAK=sP;z<>oQadF<-*Bg*hxqVSCy*)s%HY6i*hLil(872sbQmijM# z{4HyU#;H+;n1vw|WBmmXHX2%c53C&8zXf`f#zk8UYiaxqd63{}LTZ2HzkfF`v!W;+ zLnne91d_Z#xB(E&Ja)}-sa97jmmQD1%7TL${S*@MM`|y(NC*ZBOLK@4Ded&xa#D{X zIus}*r7m?-jH3^ZZ<}q_=8Yhcy#Q}b11^&z(`1HJH1KN*%3X#d*?fb=F z%_VJ5HnT~U_v>w8CCT-dH*>iNqB4<9`F-SqE>WcmpM0vBcMm5r=G>%a2S}681Rv4B z8GE5BkK`&QQ%}gtOcZ}r(2Q-PvreC9S>I4Yc;3E|%r#$S-yIN=ZM^P0;&E(n+?xIq zpgNz@%IPc+%v3MtT3WXHXy<{GCuZ9Driffm-KUEDcuDxi{ehE(eD5&lTb-hK)(P_q z#V{GJcx%COo5Y_b4XvH-PWh9*()~7Ct0il)bTe9XpNZ~`%l9<2XMSVevshMpd3yQ@ z9Vi9APy9WJg52M6Sz!59XTHU$p}%-Tc_6>+hn67}HeCX1-%O5uO12?>)~L9?;kIq4 z49yiPr0O69e_}W;lW*Kpb|oCH@`fj1683v^g}mH-UH0$TkS=OPjlt}T!XyPS03`a& z2!74y5XIY`asUJ#6EO=b1GbTdo8y2vH=dgV`o4ZuAPkNGVg9+lcGuH?-91u0HVvUBAg?kDsUP_KCmad1QXa7 zWgh?OeroSQXkrcyYs^_{i!rrfbLip;*Rdqjm`A?zJHGV85~(sdGZ8h78o3QaF*X*$ ztbi1*ZkI2Hhv*zEJ^MTvHf!ZCxmpkf*dz4S8I6vs;dma9xR$BkL zOoa+ohoLGc1gpczOP`6q4$U>M2U{s>CQ z;PCpl0L^cVvZxG9%~x_>orMkC3@<8KF0I~;>uu{DS5FVSKT#2|YUY^vI7tOs2OfcQ zds^hz+2j}JMX@!3ovUs~U7W;5$>v$iJ{?`!Lp($g;fP2%uBynniPcn{)l%i9c60?m zSLEr}0(19)HcYw18{1ywHCZZ_;#u~|XQRET!^Y6y!b#!N0`qUg%6vBScB;&Y)^nrv z=D+FEKle2*16*^z&tJ;VN6MEdPEfwfViQfd3s_#%!ljPt5@g@p7I_z@T!lYyTP1g@ zLzA0r4o!{AIyTA5+5;rFNU)wvYri6Wt5e^Ov9kVS!{KWW4|>lz;(V2NuLJAmni|-_ zLN9mKFi7unb>P4#z>r{nyH$IJMdfXp3dhf}a`#hgOAhLOpUgXv+QYX~HLX8}Gy88g zQkn;wLtc*cN9}uow2D9=zqcP{IbNW)4B(leyU*+*^l0mGYF)dXw-c7tz>KBP{kLL` z88~W|s=dGx=_M{BXIn*~Y(OXQ=7HUyyVcqX`~PVA%DAYWzim|Sh~Aex?x$Cj@@UyfB)y@&g?la=6q)6J6FvrWG-A%K%I^= zGDFgad}C9;uacT)=SDEbBhk=Epu?He@hl9ySUj98HU9&zCb4^eEIwf?c{}0=*g(Je zx!N`M{gqL1fze!jo_s0gbjd^NwM4I?Y&_Sy1%j_PN;fT?*r}c3K=u3_zL*b3m+>f#)LEI z`&P-RtvF1XVB?tw6rJ|_0r`3P{^Rof*8Fq%Du29N%`s&}O3W|hQTqdQ2gK%%0Ih9= zRK`8X#6dy6isz;$9}qZFv7OV85VEDxY>$Q^Ol-qiBaE{hNthgYeBHm#lShUR?jgC( zd~*xzQK!n3@Y(yG!sc$W=omy!pXS&GQBfLgB@iFxJ*n90o_#T~l{RYf+pXv@R$&i@ zFbxz4`kyc(tyQCkk377mknvrfQC5x|9aYlj1wKl~p-`}OUlY4fXuXanm=&0iF7Dw^PbzG@@r)&Fk158ZynDmGi+ekF6@h+wnl&ByA= z+bBKL4e`e0F`wA6^n#RJ?_VThM|7W=l_t6hF@1j3Rn8I~<=qWMLqdc&zh>5HwBHSJ zbbJnsO4=iZc(DA2+*p{?FR$nYpmEx!~!jrC0~tA=B*&y9+H zz_^s2@5?JVg08kKn`7d0_b(11ANuqk5M3EVeb5)bArTrzqJ9A_J^@2tjk9cJfoMhp z?C=e!mE~5+P3>cNcbG{)VLbl)FZ^F9?FEl0(QX&tVc5;%-jWqd^TZ*imyyqe(S%W? zyE)aRoPT>fQ_x7hN4(wT4{;tz9HXX5qnm4^*JmMMCgQTZ#<#D~d5%4Qj(-ziNS&uK z`Js?-p1anb#Kn+&l_svyX0KtVp&&L{&Hx}SXJ|R;0a{CQ?cMYF))8Gk8I1~jEQ}{p z)c5F~$Q+pNtJX5Ykkh>gDP>za?b+9snW1^1Q3pf4Wm||%kS#BhN>OUEp+f0z&;qm9 zsofT@S0)-dn@Le%f0WV|G&5)XxQ1CIXDjoqC;e`K`!>ygzK7BOzF1UG)MW6sR_tdS_D#lYXc3 zEnti(FugNqWj(DwrNg&0KRY|T101*yc;v(5Drg41J{jLLw%#M!lI$BY7a&vx4`k$jR-{q$nM5; zYOD6U?}F?H3L20^tH14);whs3coz2_FHdk5SarBg*IU4{{ij7NA}Evu4*>Wr6;NJ4HM>bWzhN zBBA+@1r0nhU;C5w46_l|+CbG2vth}QC55z8f@t9i?YSh4Sm8!B-H0XUbFS>_g~>@z z7{qCT&3>BqD2b$^Q#FbB5yU`I zQ0yndB_1gV+s=`*5dE#=)2lCm?;Z5=;f7uDO)8k1_U=~}X^wOW__@YV@$1xn)2Kkh z&+yKE$#}L$>m5!N~i{r82WoW90e#vl9SA~ka8+v-; zuo1tz5r56N*0j=1$GtMyO{YZVorx1c>3ubrxU{~K2nB1=f^4IVG>E10g* zoO-U7q?T~sMW@e4vLsZ~FWG^f?A9-^>vhl%#`T~t`Y6xJdV0g)s*sG(d6HdVEiekR zD0IAk>c{m1(I777^pzaXua69$RHV%)baH?1XEK+An&db0fURyxM@8D=%W2tuH~6Nv zK;7On4@{mGL|zaHVWzEAarb>DmRy9ck89MIx2j5cjq}1=d$`+U+R(PRv163HTbStg zhOVE_rJBwr&)@8LjTQC!Q+3xH=&0gd&;8eCNpGQc1c(GQi9~-g1BJR#5xT5=dH+y! zIUTswXr~V{p09s$6nzw&l5=YNw+wB7wdR=@X1p;g;itbZdrOYYwr7tu43Llt=x?my zzjr1fm-JT;=e)Dma+1=5Pj?_;_a0~WM2q4ZTf_|hPP5krm+e&@*JS@U&p-bkikX0dqdYK?qjYsMnCG;D$-P#o{oXq)M>8}1vDMwPXWGvPkN_(l@)g_6z}Yh`&j z!}!N~43+CZ4^;_1&jveMYT-Y`iWCn;Py<5Ca1j~X1%=vJ_prOaCbhKfpVnTc7Lv3J zH~I_$-9WOrMD~;v-)_#H!{Rt$=&TKvB1alMl-I$wg_xRl0-8pFMc?-XGVMJq9dOQ` zZ5Npz#fk$KSpZ?6i=?et|Fr#Z@U_8ahSnw(*$Sh~`oa3S-Y4o-wmXwG)hn9TZeGsY z4MKPq-23}28pEejb6wBr35Q=EZA+WCTrew3pKZz5^Pj9(;cHCNewthc?8%QHy7^i{ zp!OCu<#kBr=%xz0rpi|IGKio|LKse~x_Q9LQ?=Z*5PfvhcX|Gsl4|bYc|wtu4#ixG zKS4u}xnHh2fNEfSJY9M37AJ8kgR=WR#LBTjT73&2tZ38rVpu8K6vT&VHZ| zc=a2jlkaO*fb#*Q>BZVAbb|%;dlERQRcK zA|Ux0FbyAms%htTDHFMuHl4=+h7aSC|0b%!jk3=s&FjcCWkn4_p!fQRyC5tA2sAot zoc*+;vuhuDD2C&&5~Sq82w6RqzXneLchgU;YQQ zp=Q&}Tk>q<+ghrZt|?%Jf4k;6TQmzjEtpE3g;-x}%ltQ>)pNnQ*xokya(j{)w%vc0 zlX?4;J`S9)-b<7-R`=Ule7VY+#C!U}nynV30XfPLfj)}UwU;G@V52FbqYal6RDF8t z$MeWIrV=--<H&U$pwxmm$F%NTuk@fXnM#VX7#FWXWk08Rz~T|d&tQQ*LBGZt>^7FnUcT%EEkOr z^8)MAGol2oE}M<&DPK^6R&lgEx19yXh23~I{j@*P(*6Gvv}!!2yIA791|;8^YF*$V z-~_*mIp!f~wtMmnk-I(WbFA5cW}qY2>+KRijVHsCeC(T|?wxr|FX=L4#_o!Nd=?n3 z?ru-De(CZ%{?aN0Vb|@sCkwc(F;S^8DQwtW?ok!=p&#FD`TA(t%(m?e*C>;6!C-cL z8`nyodg_mQCaff+z>GxICt#VYNiQ8>zt_9FI-K#v^IZ*e?? zIJ*Y{ZsAP6`R|lwf;n(2j-LZOwIjM)#FR*y_YY!O zDWuaGhKB6YhQQCh9ipJBf>p)%l-CUIB&}k6ILSLnWjONf*SGLqH%YMJ2P1_{G$&Da zx>|{<=j~ORD`k5x+ksvTI%LbQ0xbt+XRvZj8J0(i^T27AmF^Do8W~4R6}i*;mI>UJ zKWCA#^Jla%TAxs6+weHSs}g~$2b0=J6K>pZKYuxCXRVf6uHo0ddGi}CTobj5QuwU* z0ghN%DiAw2v7FaC>4o*Pm+J9sZ&eYgGw;@~vXrkB$z`x8@$P9&@ezmtRZFt<3*)7O zHXa8Ef4O9Wr4x~=%k}B8MDpE_mH?cUu@0rTcUR9TZ|QGG8gT08ug&=Gf;yBGQSdWu z?VTSxrJ0BiW2tHBR+#q-UaL0ZoiN@^N{!QQlo6oqtV{`*+gmvU>vrqIf5EE&?2^$e zSq<*8(*x!%K*!^w+)Q(TJB~5*7o~uttWVG_Rl+ zcBavP{A%{xx8A36Z8x$^tU_O9+3BB(6u*7ON*ejKyHpKDubQ>CF8;>2oXJ<(8jL}p zBhWL&e1&05u#wf2wai8aYw^|Z1~E=U9miHzjc=f%%h$V)HnrZwa{O!IKC1A!al_6v@+#4;9h9{B~OhhCc=Z)hFy{cT&fRx!U94|E3u#+5%%iR;0z2l>aR2g z5mr7Jw?zaz1N!#0FY>+icyNQ!Tg5HTEReYA>xIE|r*mU}DSo9CEZcLckA4*V^vY6S zT=!`S7pdaP<@|m|nTi;_x!Z|Sy&JaU&l$A-jKN_c6^5!jl8o1C^}pZ9P|up?FnkKy zyUqT7k$if$W`g~wJL4n6qID8TwZ(n;AO%vazOPEY^8F58#!k%Eb=&GG!k!E?DlO2cTl@`atC}rrdwD5++ASL~J}xVqF={OTx?Y<(Orn%(>>% z(Ng0#Z_W5-J2pRZjtK#eadJ z@lPwF3sVWrn9=0R4QjnC)sLeB2D%TpJ&l1#u@ikQ4kOr9>Ej zeuNNRrDFMoBr~8>Vqc*{&Ygq6Vb!hs$K{6&$Pkf&OSJjZ;GglCN292!d{6vp?6Pt4 z8c~Q`yJiV%ha!N-8&?kugf!c$r>3HkOdIaEp-a}G5>YqrG zIP2zD7yYTArlXgbX6V0m)EI!@!NCmw;e$WBG?w2Ihg0Hde={IoUr;3s{Q8ljj+EpX zN7)cT)K}`J8Bs!gK2)feLUU)e5;zJ+HWP?R|23^-o$%Od{&Wc!_oKa&zQoiQINL9n zjOA^LCFN7bcMW|{6Wnr@LJ6;H7T6Z=Mn2_gn(!w@EZJrBtu=Ur-v0Rzn5%?H|88pW zN3MHf{R{Hy3-XcF)i{)aJGS**x#5Y9NNm+<$;@~o`r`=8oov8DUeRp1gflVVim}X_ zahB#p+eM*FWGwzh!)}Fpl}Ok#M)>G%40O(x4KjhJJ^lb+zvD-$*gJ0!Vm|yJMQAZ- z^;BbyR~Lu}ZQ*Zm+k5&y`ode9)54@Jk2pPQou@k~LBrYna~KIr5;X|>pHt93@tT;2 z3%Q7?qEFLrn7K7<$yF;HwB`H1TT4wy^qc1QYY(Ow*{;;+Hw`X{`Ro0rvVG($#`vlIRd{)QMR0dS28MHGelu$M)7u&Mgmz zZOoz5t0mLUDwAyd7S*cpoQ<4qGjqW@NWytjRJM2?`Ls6#w)?X0 zEh_NDf#uiCKhs_7Khs^9@A*KI&$*=!U#9v42CCfQ-N4bZZIQ4RFL$)(@3mo5D+2vQ zsbBowKpS1;ySip@`ki9_dEeYtg$pm$H!Y*1n9riaPLgef-RM=i%eh-C;t0U+P_;>? z<>mzULqn;1?B#tqQFWG0z{^aAXVnxH_8SjAk;dQXoJG?j_|Max1LFzsfde^3dko7- zF_W0&QYTBnQlxl5?1Mz_28fi;U(6L}OpbPI&gSxG60|@;AcQN1#JiV3ePMa z@$a|cG0`ALQ`Sr(i}WzdWP1K?s(XRx0NVMgE`c6qKpFrhjA0^pyae)WXiA8<`RbKb zj2%UThpQ=ga>D>*qH>9_q&AS+j(Wh}ivlgqdrP8YX59#{ywLQ=T7_dt)Gn2_1v?rl zDHcYN(I5O$(irx>Y|}YTqc~m0MV7aZ*ML-R9up}!8rLf!Z3K;HM3m&d{md6bS7&>u z8ptH1T#uwa>6An+#0%oN*rm0J9!wYg&%*tBo;Jj^C@(CNv=wFH&f5$!j*{t*nd-fu zoKJ&mrZP}uuZ?oAPE#fxHFz=9QM6Nk#yVML)+G#gzb~!r)jqS9jgE;V%kk11v%JD; zFk}Nn>A{Sx1Z}-h<~N;fA_`*#ZZwS!oV*8iPT0-@FJz=k-$6de31xos?}@JlpQFrg z_bBt5D$1!dEi1kpt?h3)<7DwM`Wworqxp0kI>W~hw$$7_2BZ-Km+GmgyIQU^M^XGh zy8E+!-xDmd53sh3*-~-cL{QAiYe7=-qv^ikhXux0K9LD3D5x)WJ?^X2I3o5L3e1yE zyx#hZGQdG#M&szBhSK0!hCORN$SfW7TZ<*{t@Od4mb{d^m&>n-i_G%XKDVNW%))P_ zqhj{bH;MWsky)y^3-~5>^C(eS*f=gPOWVW{K0dRlJ2U4r-{%uhjsP;A~h z%lZGU*ZTieMBmJG-}3QmlQA=Ku!Is3eTh}U;eSF(pb$N&pkv#(46tggUHq+kRH~E^ zngTPEB-PA{RYG7&QOEUVL@8b7u>D?4002rn7b&!+D1~c5zyH&mWi%Gzpt)ul|2}?y z$DKyVz!n-aOpgRky$h-858`Ris%rcb-Y)g6-Go8n^Q$NIkvt1gTa;-P=T7sL5huEj z4dQonBhw}fywyi|aGS2qnXCI=KOXo@x1tI7l`+}fUSu3QtK!#UywBqX2H3?(IU`n6 zf?nlJ749#zx8r3J7-RZopx$J9Pf^r(CuaJx-S-eX=SV5y?n z*8c8unzq~H_G$8U%kz;h-SxFt!l}ip(z}1-9eptmM32}$zIj}7YpYt?45Q!;1)7`L z09|cvpI)2^!{zQ6cETOF%sP;GUPd+v`hspof@tiYXXgkSc@oDo7N-_e!Br ziSBquZH*~j-!hQqUTS9RXKuQr&XY?ZYn*+go>f-*RJA>x8Vh^`31)T!>21cEnuW!L z)ugK_Fo2}2is=%KDr6BiKYhD)jGQO}P3>o2A%(J!Q!YdS*UI&@i|4-E z2WeBayoH*j8P1QB=#~9;;(~H9bv^+oKH^q;*}j!~=IY%*wp`z|E~>tLr&0{Bz03k#k6puzNt!-csGB>5 z)n}NDJFUW<3M}1SmD#JokJJtlvJ=blaF78IDtyysjs#Nm3+em6>F`AA8G^z`*8*)GbFQ z6hCaj<>o;hEJvo<(|6Z?uThyPgddg0!#ZTgf}3667Uh!<_B=XSkkY6X=Tk@RNxwR2 zuvhz<_#NlI`&91w)Vu!G!?LU91;}PoHu-ka$GBnT#xjwI(q=ZL{!#XM+dwl~s!Pzz z=}Lu7a#*0epWoXjDq?4su?$ZG|ClO(o~#z*9T!ybCeC_r3(%hu(SFGnL6oc@;ke3a zIQ9qcYY;2HX46ve`S#?-P;#SF!HCPZ7=`Wq8@^&izgV24xSr6r7W8L zA;v?yV>Hmb?k;PV(~M48Z5nABlq#E+jGyLZ9gm-%i7!UkZFF{xAIG`E3x>|uPb2_= zVovSo^jBQB`imIvm0uuq5pg>Y{%Xoo+&%VA}l4_Y-<PW4ylN3GY;gB~HKPdoTEtK}9oO9DYTzv2kH0Inr#+!yD{R?3r zOAh=sXK!FDA~OLIZ0lXdS}_}Sq^9t>g@24ws^^TZqDk9av?CcWASFuS)LmwDz{y~$ zupV4f8Z>E(YEQRv2^|xq7$_G?QX))@g8S`PnIZ;{=DCnHK?m#Y***HAJc}gUjvJ;1 zu!KSD@Zrqks+SjK&(Bi_{ z=_#T8>!KWf<;*Hi_guG483X~HhJTbRQ+JeaCKXn8`iD((0htJctuU#lnfo&!^PVUc zpV7xVH!)fbe~i^FEaTeq=B8k^HxYHHbOqM}2U;;`+n*!4V$Eu^HNG2o3Oq$yvtHkhApBdIa&>Z z4L@t1)SP?nl>zNikrM9_KigQG)LiTxyr8{@23I>hBj@i=(cLo}uH?(doS$(8UtOV) zHq7=dA6p=K+ZWTJm;thvx=Paho>;<1rnHOBlOBnm{QN?rg8y>SqB<&!biWfrZ@ z1M%nA$8T=KkvE(?m#c(J&YO6{^6O&oYFPe|zgoq|BVHeyJuFWEJ?iV5+zNTNS&DDc zkwEQcpizFyBcpQ3jIqCFp@C>_0oLaz=?iV!iYY3*EuZWX)8U)xhtN{wD2`9*ppwKJ7>d zAH+H4M6g$!!16k*>e`o<^2jS|#N({&U_!rq5?ZT6{buQMzy93fGN0 zIq*z8SGjDgRtZ{}OY}^9*`;N9@3ES>FSs4E@&dk%K@M$bR;j3Mjjj?mju$s1`~U)w ze)=LTG~R>PU#s$BJv?Jo#~nZPu`Qe%ZTiKx$;c{&#V3P*+-(oOJC7Z{9~r9pM%8h- zNtmtKNoil0BG8ey_2#e5axY6FeA2&S!*4zec1@yG&H;X*BLM1sP`miTAIL!7xZ`YfHM= z0_Qg`!SHa3U4rY$DkP3yT9|b(D761%d|tq2jUThdQoM;>WC~egOVtr2^lQr>l?5U7 zzQp!I{499>QfN9jY5y&0f`=5)y-MPxGx-B$AU!UfPfUf+gAxIf^A`-1{0UKM^MDg@ z0}}by587x8s>DJ5LG}DX^;id>l^kK-%~op~w2^2PVk#N4qCx8>(DTdF2tzLmG;!u? zp=esybcxWxl!)C54g@HvZ9bofk3wh*X<=|{I($P!4GYqwLpHb0p_)?#w~!yiZ)LDw zqY?v*8TcrMdp3(4u|6Jr{S@%kW)EHQ{WxY3Pbi^3!v~y>uIZyrfZ4qfT7eXsu@6_} z-@CD0oulCOpvJycPvgVxXL5MsIB|!dqj_k+sb2-5`1ya*Ow=7L)5_%84Y=7(x}h9h z=-N>gOBEb$BZ(n|BvSAxzd2#5&<@YRNIH zNmv|)*-DxIB4HZF0**3VdVQF(0;}C?N10^S#-Zx$z6yGkXneS6O(PZZ$Kp&%8uo(; zuPKZ3&u`OQGRIz|oHvV8M|XV02~c_-pp$%Et>Sn{sydkh=FupA`)T2Fd7d&VQQqIoRvUvu`gw}5&bM@waRw?962b9fZ8Gw6fR=XYL%K-N09eS zkmI52i1w9!zh=ZiA%yvg}9c$L`ZfEr5FgMpx{w0Hd!u zrp*H$XVJyXA;Ue7xAz6xrXc`Yv=gn)l1MJA^Oe#0Tx0opHJWmBYILlLEO_iW1t9Zj zVjUxn9S)9tS~L+O0l7v&!=;+nME;#ISd-(0iH9FeqCwR$ieb5?cTbo7-t=-C#jubE zn!KHD><$015U#tRcpy4$ziM0W)@!M4X>+gkrx({?YBRzZbe&6d z4~o6o>nBSF{keH{L6)P=Ms1~A-g_y(S>Z=0XsF3xVbBkV(&Q3LoC~fyQXlcnazN~~ z={;I6rdL8ZAhx&-k@QtgZnB)dBF-f$0vEVtUfpU0eK?G)oR%@s zYw2m}7Hz^};(JB%J7tR$rD86FMAMdS1kl{1A4nXsTY$ViWbo<8X2+wJ)rUXBM) zzVz!c2C|ojL}QJvm;%M`rTpS-+n0nK_n5YFULX7Vy7HXsxV{>TuPb8XemIDxb`*hG zvxzbu#xEiT7&Ro9F*ElKOh01c5E!lIF9>;xn$xa>b2b#ln0CdfXfvN8Kcv{hqo89f3bB1D!gigF>el`H9H5HqhMZx6>Ui~YYWe5c6mv!B{3l9E7l4$mQ-lczbL$_~kOVB_#)G;iEm_4D1%SPsJUIhyk-Et59rM*`qxMv}( zR>!?AEj~EtSaz z15xBr(=>`fQBIV16T1UM;sCDg{TJ^KUSRxTWS@b)^x186QW4aoGzDhC>U>D@L7u+m zmB>e9WrO`P^-k(tb_|TwOs0ZE^S%$@+1`&i8U7Zno(L7I93Q);d|OHR1k@2KFx+pM zp`e{6(XVPlXDI&;jo&=c;E&p*$#LEh|g!`dh^%n)}| zOU0_gm$NbWlsrOX@_l%)FYJYlSi7?P^dk5AZXnYkKlqkHtcydS$^+I7t152|tMJ^V z@nI#-v!#<_Z+>t7(&2EgC(Za4t@Jx1dk#GyQk+o_{JB`ad|0zj*X{%*Q*68swheYA ze}a4Ux=j)0Jb*b_r(7EvNK?FL5ZPF-rbLiPwsEi+zt;RI(ptLK;eK&3Yg{)`tEO4D zC-m+4W@cms+d(mumrSuWdBU^ZH=h;On&Z$uKbrHiEnupOc_UT<1h&oF%(nh}`X~w+ zZ#%zAz|GGF3sDLPKF9X|@~#|PJ^M#Klv_R<-1qD7!027ZD31xduk?rhT()d|4&>>t z%UON>7Q5zig9fS6tNMr>&|Xa7ZE4!$9q)+|%+Y-hsEg7|G4*ACB{%LJ;R(C_&X{dU z9vN2_FhN9B!ynra8r;Mt)#SB*%~H+Uy?UySEcQzVLiF*(xCIcniS(ux4C3jEO3NcK z_?(LVcT$s+FwF+?pojLGh!z*R+Q3f`Z|NHPvOQjRs9}`VYR35kzs-&OCZWsQjoJN0 zRO)>mfUX_NPcrVm$UHtEdU@|RqP_V;Qi3BqEBd^+a?Ij!JMHld++TL)&%Y7%H?5Pb zHJkU>kbH>u>A`~6whu;m$1X14XUXbgZ9lqagqr0ga4-}TOh&Mi+qD%HZ>$v0Rz52a zYHUM*YT@3IoFxm_F(Ee~_#@{9!!2Fn6$t$MTI4bRiVp$Zzk2-N!lUUzE<%3o49Klx z!E@5t$5qHxDT^$i#cNcnc^ZtxH2Nf-4rtpZ;cU}C7h7DF>3dAFqopgATh?g8ewZXr zr2P0)TSnHeEb+zz-LJ3q2*xFmGAj4UFw1Jur4Kp^hr`FmQ2|MvZYCK0?rO*8HcOG` z;c?spkwi8(tubx1n>$ka_+{@q3dm)Zw&85N*a0>p1AAYbUf*#9T+nG>jJ}r!Q^3+S zjoyv(0dU3d9&N1Vw@S18#gsaRxPSk62r%LCaBz0_#y)RfqWEYlePzG_aZ5T648ck_ z-+c8TUe{nKjVslvXmoo0E5vwNY4zGrOS{iL?t`8hiJlv-0M(*Szjtf)#N+h%c*NVK z@o&Xgeikp^?H&ZEo1CR$2H5d$<48$-a=%b3yif}so#15AQyJ7nllM+fTt*AolKVmC z<`$i{r`?t%6bM{c3s^wdUc&!K*jAkSJ1QiYN*m9f92D!(DgE>){J{Q((3mGT%V^w1 z&%H0m2p;51cb{AQcPqPdZ8N~&JP%;r=`2gREIq9S}4}43gQ|-+T?Zb=UkdmqmxF`us*en)ULA*S6lHctP*F-VSIFarl3I%L! z{Z$dkC(i`sd4KVxXr_;{z3;CM+>$PhGdvp}TEQBgpKqx6`!^$FPp{*l%#HAa!Bag| z_V!m*&!RV)cx;uMW&SNS{DY8>56L&URfOs|`eY7n0U0;T=wY9(51dA5kALRnt1x&HkxT_PPE9wSw+`j@x zoT{uB>Iv)9)q+OS?|zLw%OW3*8H<$M?{SHJO?P)0?Z)fty5R{2m`psu*}uwcGk0 zGdh?}UT8sS*me<+#0tP85txpD*;%GoPp1-molajR&} zgwlUCWL+%#^6Gt_^N`o}Z`f(e&xN_zh~zBy?Qb7vhk+P|zaE-s z*G#^=b>P#cYU`a+H{6g~{&RfmdiPf99u9w2v`xBAY*Z8~a^{5P`IGdLSz9ymF1bW^ z)ns~Ma-4Qm`Y);iI1~Nht-5X6u>I;vg72HOl6K~D^@lv$yc}B$BTZ#f_t|eo&s{IX z(%dt`SE5LpRkZgM0&bL3;io5l5;)g@KvbaQA)@)uePwIe?Ih$+gH-#)udR}&+oBrt zqK?hw+wRSfitn*Vf?*_Se{1z#&%||Js82f9LPVxwX-6eNzz_O6T6t6THdtNXIdyk> z5S~1(W7n12qV3qc2}0;3W9B5N^d{4*_!){E6_BvymUyMXS1cII%hL4IRYOH04;Qm% znSJuZTML^D!ZTbF?PI+m+MzfP*myzRYDpycd z3LI;0(cm&grK+nqO>LR`jCO82|3u)Hjgz@oe%5H*lSrxvGW$?UNKtGbSJ*C*7*X{? zduV!(-=h1a(5w)u5+Sz<{PIcxdxQ)fUm?el{z&Mw@voa|n^Gs=Z-5-VOC>NU{_Wry7O;P>~6(F zR8%yo!{^(n_tKUkW#$C30dHla_b5HuRZp;nkGje3d3mntHCX?`l%L_gYLyTid|JRY zrq6$A<-Us$u)OpLEpoVw3kSOdSKOX1%GLt!>#UXfUi=J<8ZT%B>BidHUS9HTaV*Q& zaEV3H&<#u&QJ*!pq~nK6H!48>q)JEq6%+bs^3L!tkI8|E%$@G;J5xEm!gmm3H)v*x zH|6SBus`3Qt9prbJ9td~`841CC4-^~%Ci)G%$o|VR{Lva-z;r5LLKm)i z^*rdI`L0&n<+mqvXt>MommY#$%Eh{HzPWUSK_^v)WekXkS6SqwnK6D>e^fHAVhx~^ z7(XtQg!d*&GH-c)&U#^M!d{zib5P12q{u-j@jg)OnPywQGkt}PWHpl9XLIoOohs1o z;yi1mqIwIr3igey(+&pqRep5h6PI+mR#G7b#S&`@{)kXaU~_Nni)XtM&bn>x-Hr0v zcNr#Q$2}A*nEVXu%YiWR=~7D7LXpnjQrna7vnC=!sJDC5>9$7%Ad%OG>#?+Z-a9NQ7I-d z$>hcug35Yqt$1}ThDO%fi6!I*?EUl+j<4}9rnbJCza=u9l*tY1BIE=xgcB^AN0_In zClokFUoja1rd~cp54p2Chr!zW6A~<*GkVf{y;qsD*4JbOU2co;EbDIHmw_h`bcK-b z;3S9UqA;o9XO<9_4t1^(yMY}k?d>0a1Dx#VWrLAqr1B>lkpb~i7A{-6+6UKBOfHg2 zApG-3Q>0w8jT#4F`bbiW*TEMf9yfm`#u;2d|3>lAMtSS)5N96Scg}r^dH7&+*MqCd zrb`OM>9CeAyXt9u%#++1+VN_tT*R-K$0CpA^GRXztQ4nL#-*u330UZ`*=uimg}2|& zzr1=Xd1iQiMPWmw(*9*TS6HsG-FGpF*7}4P(H1cjRY_75C-R z6?ZT49nd}*+bR}F&n{wl5@47PY@+`#1V$#2vEa!T6ff9{Bu$UG%InPM!fjf7(Q*{ZSWTCb6290@WlQmk&;kD^2?4F)`p@S0 zg)kenoGhuj#}%WXqwR0P44n(b2$PsT_TcSXG48U=y6hH^n#0NasDjb@ztrpA+Inpn zEz_QBSrZq^V$45?ZlZl2n#&)&jpuqsI1@l)4v%OqgH-$dyeX(rTckR4d5p8(j%8f3 z^Mol^K9=QOgrqm&0hUFZI$#Y>4;OitcfH<6;rG<^&O>)7h`B={f0Rwpx|r!6?(&`< z=6{FW)0JI?x4ee+zn0fb9?ZpJB*;u8VS6vky1AH(8A^d2|E_8QBf0{T{&{eWX3CTK z1&>T~&mQti`9jC_Gp{{1U-u7|=B(`{)$Pv$*!W5Qd>)sc6W`r>H*S70qcEV3Wxs1Cr`d&Pr1Rv>G|EYuxeDWa3HJ)i>GB}-I zHdyNJ7cO~C{R%|Bfvb%$Lj355G7Pi3_aTfx9( zN`LS7N8wn-At6A^jBKSqQ;J(~z2zVqp>cwjc@9}WS+q$pY6-#Cd~gRii&3n-X0q*R z9OS9C1g_Ar2R-wRSD7E;yB$o(bm@B*ycbug)G2W!cGVPGbA`5I0%37j7jc8UDG5~a zf>>_v126npPJtaS&a!ON+X`b`s`h62A!XRo?;hZ4Njg*8C6K`T+51dko^?MBW>2QZ z3GaDLZ(%(6Fwt91O_?{J-Z5FWZSQ6Osma=OyKJl(zw}7Zz3|Hl9y_g`@hg8MS+o4# z0qnD^3z-tR$ujYCye?(h6-;tjxk&OP^1Nt6VSa@i(zl^6c|70fC!7Rdj(h<$*!vDu zZ-%;W4g_a^C6);Wp=rN5ElI=EeNOsiZ&6~*rv_FrugyQe9M|pwSZj1y%YdG=)q}$m zxZ8E3=EbVUZt^>ooc%n1M~deXs(Jde9P$Zs+>SQVq&_ z`S(eig6gk`TP^UA-%3kf2D665bzY|vr)OucHx0RId4FMa8ybMmCEnXvd`TPo-bRGP zb8;7`8P=#eN;Ib&h!kjT{?|GYgb9t9c^;}= z9B=pTZr)RR-FW&eo*EFVuz<&~{o&|5p$*_7c?Y#MZdp_QW@0j3+bT)48{{BKWaUIu z=XUX!n$R`*=&B`sV8_w}iokFq0v5Pa&R#873>!aKEP1`AMxOE3)n1kC7S{oKPaug+ zv3O&W1Z*+J6Yu9{i;NM~YY)b;+uk+2?;Sq9CW+R(6RNZB!u@-2uBb$vT#e^-D~$j2 zOkogTfNe$;-@b4}vXA=*+svc;Z=dJ!%kW`Z=3q)=A!4TxfFUj)h$$s1c`pFM%=1l2 zIKo_Nc)PJdr6_1?v!DqVHI~xMEcgwlkgRK-}TZR*BF0*RA6Z6E0@dUycq_vqv6(rRfdzE#vy)lxt*VralfX zT>h;-qCCdFZM}T>^>}4%dB2k_v-oG(6=u&9ClyBMhxdsm&0z_yX|7aBm2cYz_hO{c z?1B=oNY?eeAp3idezo(2ELr<~(KoH~sp#8|r5#YyO@ND6AJMjboLSe!)Wa$b9DnS0 z%o~}9CII?v;HKY@k)F1Ry5S(SQB+D|YI)>(w|^_CE${Z-?cg28m_7+^@Vg$5)Owk{ za*w$^30neqAD_!bvPhut1HSt>Q2zIy53KR#YmwtLWS@}0p3}TWJ*oWOnmD-H^7t|>U@)!tS(}dE#-Kre|M#S!Q@G2Lp zYc-~d9?ZX|FG8W{ZV!VWyc?UOgwr9I!iEscPj9j)UurxC67d}c)pm#+-SUM#4qcw--~R(k+yA67XQ|BByKf_?Ssn>-v+MLP{_cpEN)8m~l% zE*!@7`hy(Y27->@FwjJ>PE|Uuz)oD?4P^6C<=ztBdU<1ZhMf8eLr&=pAx9aJI0uis zqP{mla3ppcq7j+px3Yb|*tL#4{t62MoZTY-zf^AA;on_+1qZx^Q)^|Em~n!^W`FFK z4IAQQsH^J)on(34Y8C}n+8?&E}fW3Agd^Z5jJxDBP7iug&;1oh1|CF*$8!A?(;%O+}e}{uvK_{8;WPvD; ziu(FYy4CrG`05O9ef#yMRGnmfWC!zRS8%Os<)>M< z&FLCPn|i*KY+T;O6JBzj{%!S_*?c*nf<#G(XsbyY5#&1&uktu)bBKcTd-s+Q6?;hY zZ6>UL>w1{xdiaR#Sh~}o!r1#HJ1=E+Cp{u}zDm8ZO7Xo3`fo+aynsKF9vztAC|ihr4Dv>+U*PL^3yZ0RGYsPmZ4HF=fL2Z6}ghPg@ z`BrJso44 zHKO&C+pos)nPdA1@+4YzjHS+>e@f@HM?I}DdFL(fzVExA&J2{5P}J-8g)|s*kc=A; zEIc<8r;jlo-=29fxiEhGY9S!Fg=^zODQ!2K1{^$yRNG*#X#3XWq~|YrbC+6FX=(8b zLt{O~#yzEg%^SXaaU-+PD_gl?Qw4VX z2`L{9;N`mH^$}MNPhm_2YU2adNe8iyKsWPL@$%ph=|z)d6Sl*4SBx?H|DgHG22>s zaDTz+{z7nA9`|n~e7`Ucg;WS@h<01(Z++0P$JoGpU)P~Lhqa8ql-B7JQs~$r=Q`0; zGm4kM%h;uK#LPUUwsYCzN-Cav@|eae!R@$v8Hu3Eo`_}edVAF<19<-7zWJJg=4cWv zWYqp0c*0wSoy&>t&T&+oDRd}N+t?l11>9p86n1{GBD>u&3T66mt**f5+%01DQpUuu zuPTq;tKNk>v7wJjwr~fMM)u=4sMX6S@|{!~A6!C|iX=p4M2GhJ%&E9yeB)RlGJgge zjz!-I2|Oo_^||dHRqq zN?*2Ey(+vO&>xKA`%=dC@gR>)B#L!!+22mb`Hs5ok(v)B&`t$KU0$3fU%z6|pG#;v zJUxFP8pk^Sx~nG9K?v<4I0GBnv(qON&ch|--rNa7xF5`~d{#lcUOKE92lr&v$u4|a zXmo%1yF5I8wc6OZ*xJQQ3EX1$kXdk*$9iL-U-A8&*jmf^gb2|QB3VaqoySyv9+PFkODaa{Ka-ixSTbN|Cn%gSQ%Q}M3|ug#{G z;sPgMS#ecb*QT4ZlEuw(ZH^w+f!gQZ0ntmHCtBi5n$_Lqzzd}xe6d@REq_=VZ7dfv zi}?CUCL7InM|Fa$f4NA=Lopt3Jp6>*>|7Z!D)zkDDs!-4rIh^=+N1PtA|!W(;J#BV6{HB{Zto{`Q)D z1a#lfz5sW9TnP9$=E381@#lVD5ClDHf?c;Va)Rlc%+b}^Kn2krW7Z0Z5+=GaTVX>Dqp67vc6 z(o|+@w&U;1EXDJ_vXv>0asqC?d8Vg4c8 zA=TmMezl-`hbfci^op{iQnM#CH6LyKD3w}}EhJ{C%#n8=vOOw7>FNBKdx^idP+TdK zvP^%p&`EqW9JgX@$c6hLJQ^3nccllSysSClojhyTT03=njexU}A9=QC$@zEe7vvyl zqpH;I`3;^3Artcz-s8ESuQqjtOX9QHf#aQG|vl0&&((L$`~e@q`` z7N}-;bQT~w#LTx&i;5q)Pm7gzy_KrYo?b3NfAxyVV9IUPmH6YCYbf=>{3wG(LF2dv z4j$3G)uffhS|a%2-6Xs2bms2}cRz)3U8`JU@${PMhj^VW%X6;w@(GfZ#E(=icNp8W z_KP_TO6s$}rTR^?AE!$>*QHMBa?)DZyZ^U))UU*Kui>wUrA+p_dkXx*RdlyZU1V;F zr67ksy$TMox|!o_MC<(fn4gJ{J~h?B?VOKsm4ow6ZOc!Unl^^qojwMuDjR3U$6134 zPd+^N`+ha*(baQ*eg|(hl@Gt;o=CkKdfaYLR1mX1cP?oDG;~0LAq`HoP1~y9dCxaK z{65Ml_qA-F+GR$U%=?W!&-Ee;BGzee`737e)g9OGE0k$NN;OA3mtJ}PFmf-r`k;W5 z+SQwNvg>!s$8lAMTjReq#LwYBU92+f4lbZAtcCdSupLaJysB5P2mG0pwz%^9-PIWw zm#}{7r)}@;9x1w=)5^U9!*kJ^>9*H0Z?(v|et7jRXzSq0z{TVbQ=gV1zy0-=HADT4 z32vh+{_}-&QDibQPbj0&#{9$CO4z;gS=u&@ZlayS z=O(K}PPC*OV>c{kOQ@@ZK*v58$Hv4WwJX_a=GCm%)Kulz`!heW!(=FI@4gh6`KTKG z7)>osmFmpSNYW*QcFM^ezq-uap+fIu^7WT!F~{tO-i@v{7K5v`_pa4ZbEO9vw>>AA zPl#k)RPlhZxUJp&Jp0gl_KWgE)?3Z*CNuxaTGU`VrJ7t;vCj?|ZhnHX7=`vmD6^UE z+_{)NMOicUen&JV{?}6|y0i={^sK+2$o?o=|0!qUmzm?o7VR7pyjw|+vK`+5WVO>I!PDAb|$_CF#97i7g@fb^zH*H`7DIb2C>|4eEhr76c`Ya$gStbawnTLIcre1@ zR@QNt8AjkEYT@;=x26+`lJ*HcJG8W0b5O{Lkau1_Aj`~qwDlmRloaik5qAR|`g z{+=>L0B*fKmOQlwsJN-qq&%5cpTQo)>(d@LZr~FJxYO*{(Q}~19XTPR;`+A-VdF!I z`2=*ky8h`YyGv4x0D>Vlna{7}h{o{oryMqY$S2*Z_{=8&7C+{bc)Feju~d9s&=y<8 zU(qJGS&1No!Am`{Rbdc#-bw_nCAL}!7Vm>Ckc!Xn2V$!%Y}$l>x>vxe&&K`#sL8DsSW4JxnE_J z_y^;H;^>s#b}s+;l>%0nJAk$vj|CSY1 zRlajBupQnX@_CfT_un${LR`kdx66?KmT6VZe#I1q*MH}PKl9>=LK)eH)qlU4O3hpI zO=u<5u)&rc&F1hJjuU+K*uYi9glnWOV&+>M#N>ycI6lqN`>)mYz zO|ZMasPBI@Jm86c2H2~z_CFyihD5v1urB2ai8Cm@9XI6X`}NHMY|xqnaY;c!gK-&0 z)*+fYXCE&^u=9H1^*&dTkfo*c(GF6*EF9wVbL-N$IVY zCU|A_&t!A3t*`M8{H?LxqQ14+zpH4_Hmz)FwHdwxt!vEOI~X#_7X<)+O36O3U5 zeeD||noQAP03^Y_YgWL()vQ4JTP@?(Pi}%FgETl)+Kf&+U(Nb!e!XAKMqx_&NkJkj zAOGTLqKOZjEjd7^T7>q$Yn3q&z6g;Y_0rbtPyQeY!MNW3wi82YH?-Vbi8DEl1tax4 z^8#2(i5GtRdqy?qdqQ2f?~~3Tf&K4>SbC+mzx~11a6oo>TUDHN?d<=Kvviz%9g}Rt z9*)84Qj2(cdwW;!?ZqmJKdsKMZ)$2vz8bm29%bq_+1RulltgHs#onB5=Wfi8BHbRBTC|-ozEY| zCKM+gHI+MMXQ9h~Ct6Qs2$CfjO*28&gzbFDj7(pUBk{>0za;lJ2u|h^wmfZUJo?ql zYj}iH0<^RC5lq85$-;4lzh$ac^Tc{ax39t}^~h?*d9%B`#hthFq|cX8F&;GQT6*6K z*@AtTtds^)`y%_v6}tj`6}#3A!nJ`n@Lj_rHY{s_67scy{9qCRQ!cR*Zy6I zVmq3b^C380&@jLEE5<&#M^+fE@h12h`(}5qlnwl9&TaX%Y@wDk@5Upm`SkJVqV@hD zF(qwxF(p&Kihby2cL#1o>1qyaT@tI>AiQRN8{gg>Er|XVoeyDvC0GnLJqFFcJsszp zsvTQo^bmH{LIfnM0m+Ul`EaEPP=m5$3$bQh5JdwzX=(#so4X}nFfZ6*>{E4gVWwn! z0DGa^2Ci{61a8VOQrxK$Wr`bVrjQy15B- zYVTk7dVZ3}{L^vacss@d$0zHO-9tY^Uiv?Kt5zH5 zh_`x0cs##g8nqUblA?U=g@${Km?)f9_yYurpzP@paKn-1xFY6K+ulkEl~Sr%hc>cQ2QgO%>Zia+(ZxCjzA}KV9dF`UV(E0k=R~k zN%yE(T7iXRXsECj%u6@LA|~s0%Qbn?B>cj}QUh}08$_{CJ9bD445NYp7)ESgV7W)m z4tjVx(HaL1(O(T<2RJZ73!py@_uL&Vz(LUX(67Ry0-S7jL4ULb(Q7QKHq)!qE zvIRjUU{_6*t(G_4;dLO+ITdQ)-3yviI7_SOJpdL^JLom#MC&aJ5F7}CX+i7Z3FN7O z{dm&<9kJk;LRHRV%TB|W+f(b5=k!;u$Z4iF^Kb1_samk$RA@IdlfE`TG?+OT8NXn zyvG><-c@nX{xpGIYKFZb2$q=*jcMEK+ zSyhoJ<5y%Z6)`h2)vm9vjRhM!zrpb-A4eKHx(|+R&_l=g-S=i6q`fFG`I`0(ZYB~@IT~PI!oqbv_SD)e5q&_nQbNj!FSsrbb;=0o1ufZAqSStJba2FO<~?|6hqXO6H*IJe%b zuP3lJ#1UbidF(6&&1M5CT-|W_9o<7l{eiQH^c^{(J7#H3G%Px^j1`2dY>u>eF5%u{ zmUbL$3OOdhU=TbHd9wmTn`!M9Zs6TcK2=VHWr8~kxLlPOZZ)izBkDH9RkzIXUW9ieICONcmJR5t&BybgQ6dNyH-f(w zf@MZXWg$^fj^Z@!Mp8WV_`;9vA32Xl!LaQINWqpu^CcV=W{JY`8cpT{%^N@;@@DK8 zHPhk|B4B9kDwioE;o7FHmnC#gAJx|bieP9_DLiq^b*Vv5G@@UZErKpph!G;8bB)tdKFKTNj^4Z)TMvDz#;3&W=P@bx(J)ESw>!Ff zqhSZ&cS;AE_7O~4hr|x@#0t?3u$i_WW+w!Wg%$m;3N*%UAaEA0<~0j9sF$`&akcM& z5`t#oMy-7K5%61~bRY8mt-R-zQU0X99+3e0&I(2{nNt{F9k}FC>Ir0jMR88P8Sd$meGQDZh&XIM zIBIUec~W~sUr@-)&~ON&%!B6e_e>lvn3tX1rh-#xUD$c4V<`W8Zo39O?5gAESp%i1 zHw}dk$}8OU`d+fVMm;Nc>(HjJSpvzQp>e<0_ zdKvTPNjyd_G9UldQ^D&LVaSFcJ%ONnD}3qg~_|por%V( zu!-+g-C*Svn7D#obM?j&7$o6iCCg^%{R^1tZPkWI4Rb;K=y&ZEvh>zdUpP~+dgjfl zal2^GPQZ?vwVJECe3DP-1+H3 zPtbCE{KwRSIhaL;*S%)x-7C|D`7HE>o-AOcvY182$#)<7ze$yPQhaQ>+q@8%j=w61 z5;+*JUbjKos)%R(Q5FDEKS303Dc>G8pfVJ2U#`SoA4J^*QAS~a0$_9@2fq6uFxJ44K{%; zc|B>aJ~BSrRNh7U@v_30l*F?B@Fe)ZnbQYH0#B;{8~Y4Wwi=b*htxmWAid&E3zO8F z0#&Igwrnt_!P{AX^6hL+#v5Z|2EhjN=4xs1J7|M;*qiHu{+faA`F3e*GxVx34T@&{ zS!IKj41fd22<)`_I|x(-fv-T|4G`E30=4^8n8YNq{v=<9m574F&&UJ>s`hLGD4K6M zue-Fl2j~k!R#$krj4k%QhH$L%a+!kuTHnM-msk4OzvMU=Z+p9xUr}R&lz9%(-F^#N z{TsBpSlq(I#PY=cB@YNJ1%b*SkY*`AM8^jC=RbDcZLW{0fBw4)6L-38!8P^t#NJ#A zQ(fBNV{guIFh2eq1n$}(X=<+yFQ_GDult{MI2>WU~TyoEvrM=R8?3XWrKuHj&2{Pt^KuwS_mIKC=^?9Sa?UzRu2=T#GyS<-P z^A`rki$^6mMG6O0oU(3Y$>?&xcC&>nGUU~otKDLECVJ94?3cw3#(Soh^7}lxwWT2a zAW%37wBi zgNEP`E$-G%nv6db8B0eXMAKhwkXZbV-BUZn&Y^MBgo0`Ei>Ua*#%MskZ^$zdDZ$0>M zMd>|wORLG$6}-y@e%?2A@vF|7H{$$?*XPOFl}1I6zGwVhYw{)QjbtMHuvP}Y5Y)@8 zpO&w{-$Sfqax^naUM40NHZ$l=_oWRKHw-bDvowMA7{*5oI4_auTH6|A=v1p49m~L8&!mt%E@Ws z7q^QB9YuOA!>4bw72h>wd{-=Kdf{EMlqtk>ON>$Chy7N_@_v-konC{hGsVcd$;BOe{e6jIUy3>Vbx~id<$~x&z z=eO;99J$jLvZlT6ps1^|Uy{Yscd57SyB#5mCF#2~jZSI1=Np~Ucc~h8(|9frW~63V zd}wWHgPk>PX+xZaZ6iaR?QGHaDH4OR=jM~A^}oz~nwI=BlRZuMWhQi*`#M6;R`@)& zdxw2=cW6g?G%$Ob^UF-+G<7@*R#g>@xAtP*II;8M-C%y{b!CIu#*1TxuWN^OF*Mzr zrco`;{CuNYx;a&2XWHBaLZnm^^XVm9+2Fm0wz466w`}V|_TJcHgGttDEp(^Gwl3$* zH(Ok&K!Lq5M>n|lo;04cKxO8KCEhdg!}5F)ZNXE4g3Q|sQzodj<>P}cz5@m0KXKt* zejVccp|&1{-F34C`HuB5_9O{CZ-{IsxCfR?&`=8LejygKQo=?poQH>_g z69xVWseeMT7uG_CwB-u};F|+@3e7)p9uz%v>Lak0>~pC(P*HYseAzsARHjK5mAOJ-tm~)%-fc;yA7KO#t#tPdi9Rl7IP0-)){FJ#eu3ytzNZwfxSz}jW8eF{adIU6)o>rBwSDw| zYp)GtBJCy#;l4_n`-Pt&81N+;bzh}CH%VT3X^G)w-%r}T^KZ-&(b2lYS^e6Ztq;vI zG$rhGomXG`tho7Dtgd>-36_34_V=KdcYBqc^ofCYb$^U24x=Btv-5e9Fzp*ey_&;k z@Z=Zv4=y1q^#S<0B{D(z(bE3643`UWHq3gZIFIiUXoK5`6wTY3qBV!>KH$p=C(0!~ zmDo+`lt8^Qx8ZAl5=39}Gz4z-E*ofq4<`rc@({8W=;b_{f66b(JB+MXX~5!S3xg{w zGc=dn0o7J|-PWixkD|N}NqOHX&3D5Cmk*Y>qU~n=zkM4{Md^GVHx9BC&vR40i~TK( zv!J?*{ZDYGMWd0HwN41Y1vigHm^l`qyk&C-ffUw`aZBwq8`Gk3pLdp5m;DB%X7$2N7Div;xC+|$5FNw|5_Bi%mw zKRJ!jo=xgl|EpN`DZBn7o2=)Ot<8FUL#L^no3^m?>Y$5`{(`&>HetbE{~1ak4*!RY z^YLE|>}_619VB-4Hp8<9i2`7jSdPzU@ta3JZf}N%Q^4_`Ons~ar(esYgat|km%Gp; z5^OK0yU-*NY%is|MD&!$j-B7WwrqelMk@5kd&YQgr7ixF94oR;T)VUd6yb}g2neop zpfHJmh#2-H!=nd*sy-4tauDzUv$#P3*GEDH4+0FEz$Ty`Mr@gl-jFbUyhgZblVhp9 zM(_kPy)^<;m@+D15Z81oZQVNwwXUd8u?|r6zdy4Tp~el}?Pz_WJ0&aH8&H)vC|e9> z8H2J8R>tUpU{A-BBI{^99@A`vT6s@L@2x4!uL=W?i^o6?@mB~5l?v`}(Mv*Et~XNP z57z)S8w&jK8Xy2>kJbQdFwVQ`~i2uE=H#q4TpKN#yeSn90rRvmrzxt%#eovi_?T$zSP4wQg z_;R);j(+h1i4(%1Ia3P3)@A*!m$j zec111cpGP5+HaGy{=;l-!rbs7ywfoMNXpz$3qD|2b5yk|b!fi2=P8H6zj((Zr`@8;a=t6Nx zmMP{3&)RN2a`83;PGE)f$cRl6DTp&H?XgnPT`M;C{2cVDSa+P;+x|w2XKKOtq+6=( zxLt#`M}RFux?PjD-R5@szDJU;P}8F9#_jd!xqR-R!o7NLr8C~cpz!It1J^zT>TM9r zGP{r?erb>af~VHh^qJs}quNro)8pnUosZtN@(06-pXJ?SBs9(0h7%k*#q}J~;L6*N{gDj=*fcZ5P ztX49}($Rsk5ST#NRU=v{vduHhWR?RwF?dwo0mVBKP+mmnow~3dpdch{*%2am9Jnts zxAX1Y#GR!A{jQ;5*D8kD9eUZOcAe$V@+Z&N-f;Dei6!RAyI0?f4UD(8T$zI9160Wr z(+-5_sSD3O;tq-L0ub2&yxK>|k?KN#+Wm#nlrtB;g9ZL2lmLm34ro~fZk@upC~+T8 z;a4fNB4n25XM73cI>Pyx!&hX@Z#Xx0=*ZS@GRrD27TEPe(IOs4u`3&FePa;$Gk#6P z%C%r9mBATb?h%}w64?&y2LlQFaC(YnCvfc)&P&k?1}gU9V4v`@Fu-ynJ`CUCbBa6% z*tG%a`-rO~B+mhYnPi!JgeV#Z3`OQ1KWj{9ck_7KHPq+oK|h;CFI(6?v?=0|RXivu zpSaxoFcz1vd|{>jvb=<9Y_!1{>hUJveu}z4DPufEaZ$=b0Fix!ILVS0nCt|Y_7T?N z$B3kHU}zt~Kw4k`@a+J3AGp^Agzf{M$AO7Q0PNd4kK*wmrz^5`nzOU#WxYFw%w0WX zXJ?b{qSgALESm00tbGT!+?67raRO+z-UFLQz{o8!oBlt&8Gm*&Hx6=dKcb3h}9 z_N>gh1rXaN+nHkFXg|QS1dnuR0hG4M>ob2hQEgi!hzSjxPAA(qw7BLcU{vgNOU z|NanN-gr{DUt|M4BIL;`1=((yor10iaKn6T!Jwb)>Yt{f@_8N502KIm8~_ZadAb^E zviI=0gj{HEQNK|AFytPi_WN$N7{Sr2_KcCLZd&o@YKoqEdm|hFx77KMa5H-#vZr-DnuaJwvy``Hrba8NNbZQLKJhBd7k_y=tlSw5WXCe_z?iGbd*4 z`}#JCJ>Bw)g5kTbTL-yp&-5;5fA`DX5d59=KzKPv!~`jJeB-x4?uo}`MeFYUXSq0r z{3rAa1_yJiqpzDvx0$T${vJbTe7RTqhThQ1T0>`JsAZSibhzrZXk|J118w}ydfiWZ zy-s^W;>=EaL*oKYZ(Zs`BnSiDi>QmFRFhK}6|lO9xkT!{heejN_aaRqav^GMZ$<&y$s^o_4#E&=L7X4~f$(T9x(C5o&%9+lIn8 z4rV@49+l_q=(nfFRD2E?YxCZ$BHUoQ-^!rI%Ak<;u;cw<>Faj2H|%Qp?P>+=nC}lm zqq5{3Wdld#W)rwIFi_2!Gaxg&v;&+I+a*Db} zvb4egclQzU;NnBFq@$Ew0E|Kbhc=)_XAq&s$z5*Ysen~Te^z$pIhOehaota9&1LK? z@~O)cGDjM~HHe^ELwVi-vVYb6pjaHq{6>73FKuifVAEgfzTV1GupSBbTTW$Q5;7Jx z)wSTOLB%=6Of8_DU01d~^^Ro5BfYJ~vF#@F(KXE@6)AWDIC6h*L|7SzYlv^~sIuFe zUFyv?tz^|_|P8xp69S(ZHYQL+hASxrak zfh_lfR2=$7))SDh>u}2lL9Jn=08Rpd{t#!lvhJXhg=}44VH)u`ELhHJUX>Ge0kcq# zLy6%&e>q`nq!O0T_v~~Ev&y5+fg~4PCZ> zz#Ty19Y-T`R4DGJr!$ykzS9qBZJJVSrynxfBF9=c&jQCf>WKv<@LK8nh}q7IwHhr*Z(kCi!4y@=s4|nNv)lCiZUM6vyHXQyrxb~mdLoA{R-iL9cn)CRGYf9{oS~OPp9R_=pc}mtTW0-yMdeL z!%N;rK;OKl$n{<%yOqwUC&AFtPy#XfZ4Qe?nGaVjQhARNv9&z zsVNj-6TSkUOahelkt`GjF%slGaAV(+k)qv(5IIHCQwG`)zTng|b>Rj$KJAYz4AqLI zMTn)vihX}@^%+0Ij|A%fz_R*Pv4g?)p-NRR!wHC>|2yDhFx}hrnIU@*+0aD`Z%`7{a2FpGig?P*69NXQZ_lS6u4hu{{f*v6`-ru?9IBSD1TQ;{w@#n z1#_&{VlRy*vz&W-LLpR(Ira*3Y@es=yG|hX7p}0EFlVU8F{kF)8Wfau^MxJtU2T2y zTMCB9(qr~Nq8}6%OI%fce*A81`Ps;2Wed-b8+2zp%LulwQeULLRy_l@Mc1ZB68H|`-UvNm- z@>fqS3VQZVezun6y=st5|Fy+{iFrSUfyA(ERk6X3X%1e5+aAHu^|3_JLBT=Tea62zZWsbFSGS%nA zuOx30=6ZA%zHuBqx(xv@?w46|C0d6IqaV?tIhbQb+ubvlE!NAd1U0r-!Cf98 z=EEq>@?YRC>WKLWN;41Hm-Y;&d$ex8G14@K#0%EL1F=a&C2W#mEO8|W9e8+dFNxL- zsT4+Bc{M8>7uLLBopWp2VTyhq)XzoQHHmHk8q=QTA@>C}IMmy0hGs`mA_v`RN_j~}0 zKh9%k2v#nO>Y69@SIDAz=1JWiE|jeXS%BWRWdYwj&nH)kkBr?WUn#|->*tY+eu$`T z@{5PDE=uyPo~{Awi>JI$c<{2OE9qh^Qf+T&K?%QxoytVKbfIvT%K{)Ft-loS=WPF~ zoC^P{)(U^Aw>$IFJ$plGS|n`j7mGJ9Nq(b6l`BwLL!^zu=m$t&GVs^u+z^+1%aMKKt*JcX*Km+k1lAs zxE|4^0~Am%n1l==u`u=mFINzk4&m$sz6cVFCPni)Admn^0fhwkfE17y4~+E!J}Za| zhwv+e5!V$s8v(hK4v6FsV2tURk~s}pUMoUi-_KTrm>RS+oqKM`E~~oR__{xKcePQJ zb8kyvh*fgUVv6-pT|@k^qu>$%j|AX-FiB615*-g%tsoQ*;Zy|JeTv-;po%pMVTl+} zCYJ=GsxU6EgHgZt>u4y$At(+1Ea>y6+y|IgosJf%$*Gs-}9D8-gn<%m>fGJ2y3#8%Ad=efTDN zuln-E{3GRSlA8AA8+(Zw_K&&FJ9O>s&3n&Vow#IG&DRgZCuKcsTdVe3@q;ee$AJzO zUN;hMEtb9LdvGJUm*_#cE!bF&;vyD*nUzhzRgnn=PxThShpLJ9WK%~Vg1EOg+0HyF zpTKS`aId0_*pICa2NNi_WBusl;R@;an7resPx+R&^ACRBeag4J{aQT^*O;|&V37(@ zZr`TQ74BI{vsp>|>H1h-uHd~jms~-pHI1Aty=F?sm?|bMiAB>hpe{cPxjiy@S$SkT zBX@lOHz8K?t#)+MB-&!dlY1<>#aYzvORjtglL&^5&@;h2O!lu%GN>BRTpY^jn>t}b?&(5r$=q$$%@>uRq z&`kE&A$s&xS4V2JjH@FpIyMce_zBv?9y>>m=5^hnMyt5)(4s@qptPT$k?gUZ^#9)q z60+>%+AIL&ARBUz6bT?v+wd~*l;w*T^P$v43 zGQQoPi#lwK+9+!&jav9AbnFtKYtf;<#xPQ%JXm~Oo zZuWgK*W+t0LxXEZ)oRD)a07E=WK`1|c(QA|-c9p;0}%-6*^+OV->B=00~gD10XK~O#&qNISPuFf`U-^E&(j>0oqPLZ4vm&d4j4z z$@fs!a#5Y53z#e9z;k4t5Q@qNib@zoC5EE%o}v;(QAxp23IHtEhajdzk2qpxd#;hM z^0On2GHfS-nBUsBu<{{@GyRPI?y;fGmcyfhy(8I%TyJ0H$4C5Sk|ha1_-!Am?U|H=tFe3pMv zJlLl&*ylIcM>E)mOG|=S4HInz&{xB)i#sZqpfl|iR8ZLa<@_{g(9qGLpN%4Cm}7vn>4wTigQnnXbQP8|8Z*v<~42J@=Kkdai|>4 z)ZKfON*t~Xsx$qizEwml_1Sx~;e3df_C5Gz@dld|>Q}1dQq(Q9Lfmo349yfTqS^7u&9d)69^ssAV+{WWVVw8+7p3NzH52i4% zc|Nx)oA(+4r+CTl&e7$KuL(ACJ28qr+BJOFxc;D=mBQFPxfv zw+)bZCaVI8`ZN;GC8Pp*%Y|f!OfNT+n+;p-(5LhG+7?DA8toz$^@1t)An1opGx9b! zw(xcjvFNR8tVsy8h9j1WJ(jB7?Xny*4Vr&Z?wLx!8;M^cp#l<+Es#y~8kl-kI>vg# z{d&W#;~9<<7|=H$v1$_1_avmn*3BLst4Kh&L>lhMM~#H{>;nh;K+!&6zYlDJH_D=b z%uc|L<_x9w1!xjF8lnqnmDfKQ(u#7?jd0Noami?t)xl)i(#e}#bgzCUXCeYEX&uxkhGIsx#`*m?)B4lXeZQltNFe9rF! zmroJ5NN`39U+F30A_<}O1wdas11iH>H`z8aTccdgL|Qjl78rwFXgXv=7c<-G38vaZE=*{yrdgiU^1SV3B}u8^DGEwDtj;Qv^K;yj_QU zK1^ZRb&>maZ+`t-2l3TdQ*&!5*P;hS}ibW*FB91a2Oqn+xChG)ZGlGM3K6^^d zt!D_Hi5C`rpiFHR8N+q9ko9LAxhVC5pvcE$-t@E3#3Fd(S#mDIz45`3SfRE$>`d>^ zU94$u1}itRDPKm++s=5QuwMS10jI|s=+^RU@{kbtcf)(aJJGd?z>QV%#wyjuYUm>v zUq^tSf~$%$n;g>OaoTnr_1f9)qtb=1D`(lg$4&9u-U5@@`=tw+@ynQdv6}3$njEp{ zwgWl2oO5XK1c}?206&>KaHLw0N*pPGUkGlg8q^v?3ZNzsZXe?QTUp=k9g&Skx}~ZE<<>&1RphP)FT1#keP$^e8tU$! z{S`E6ZncD%G>>X%VD#`%UR$FX9Qu@&nfbY)fz!i7Z*g{(TMqocApr7~*rMc$GP*@< zc{+_XoWlN|!u~gft(n4l(v9q<+>0%tN6Um;E6RBVTMNs1g;;xcG&I0moi+Z93`uXV z+csv=4i7Pcg@R*`31hfy$+3sjz*$4O6M1&9BFK5|?;$XMC6&QfMhtT36d=KFjARJ^ zv#wfk-0-CH%yk5z55{K z0`|^^4^yFff7>+~sSUYhsb{W}T%LI;)$t1dUf}uPCl%M>ya#m72@(S^I){nL6GWTr zqdHZM8{#G2f6q|Elw^!04@quQNZ1MwKZJ`=1(V0w(L0%5L-8IoRT(jl!diI9{qz>+61us&Vb(0_K}z z1xME^LwNIjT$+^Nzu=ZazG)+?iID?%;ikd(sw))7f|UTIofhvV&ap2qAV;8~ZM`9p zAuva{p?95-7#(PF9VJPqyX<@A&}!voViMLe3irBqAi-#nkSwQ1xruGPfHxEwNj_aL z49C6gD<&7S4Lht7#wY}ZKI?$eRHeT4fWD;vN7lQ*Gui+D<98&La2Hy_RFtGhsyWR% zp>&W`>P}Qb-POz?GKVXKLY7m~9Lhp{ItU%eVGc10GwR0O*oL;L#n{-`cD;X>>ihlt ze*ga-kGI*VYs~d}zh2MN6=i?o+{rI+Bj@ z%k+o>G#|2{fLab@C}m+<04#+5ke4O^We!*+#jSufW58}qIrLqD_N!qv1yU~&sF!@k zBnz42X_YJrf$BUQO=?h}lVw;9NwvA7Wa^r)_oeP3$<%zo_gj6v6)%yHP;YueUH((S z_wc^nkGEyS_(1Pcb!JgUN_9wi`Tmmi)gc=~N4E;PNBfGbUhel_Fm2818&)c!#k-J_ zyN1t+E9Ya)9Z4URBvURF@RSYymQvTXfU80XD`)*N*U=pmLRNB?5_ntu7<@^A0}_E9 z8|;)q3t__q;H-^kk3p~#pzA59%lO>!7DJBUa2+bE4DslNf{A-&v|$&L zNhaF0kmk;x*h;jIL(><`LdeCl9i`AB*gJIsAer(DKxq@u6M}VestO2b0(N@+&}7}P zoO($N&~mCK@U92hLZBmukVdwpAbT&o{FIO!s1}XEH{cdk7igwLI~5Db-q#VL>_#0w7WA}XwVwO&^TXxK{d!zt}*hi zH5%t%!D96b0@fN{xSBC`8UL>88fM^h4H<17)YIdLCswr{3_w-2Efl2r3(B5!`&bpx zxco8|;^kZDs4hyW{LE7@PmjNp2R%rZYX+r(hDk>;^)>Q&40tF+_PE3*uw95#f<^A1 zz+MV)6MFvvhB;Ji_#>O@If0u8KfMiKN`dv12DDcWXq)1bbTDfPRx9x>^&KZFby0mj zg=IA3BHH;Pnzr~}5?Y7vb_;zh2EKF~{?3M0%6nIY9(1q5x8 z<#l@bbt+2Q+B@YzLEhV`*@_yQoqx{1@?%@O*K@(PZL1e1s2=p5m|56n^yBjaky}vo zeJt*;$q+JaZ|AEj(#S?Kl6LT>s$fK)EE^8fxD);&kCf$kF4!)2-<`{XZJl1vzse?p z>OP_GtrAHkS`+^UjqIBg*-WZc&mWT+pBwb@!Ze}z*TbEw{3*4zX9rJqnylSAKnX`@ zgqP=qHP^mtvv2OK-hb$IRpQ82a)isFw^i9AOX%qE59paxv`Q*Ep6_-8-ORVt!XCPd zvt}@S$|=tM+lfowUqaB#por)@BPX|O-nBo4*B(zduBZyVyRoW~tKF8hy~HKoKluL0 z%=VJ~UT1<6M&h^oyLg=sKK`czwZGM-wW>9Ir___@<8|HhrsoY&^F11MXk2l)#=8SX znJJL#9B+_%YXCDgv{qgkB=uGYB^wk4#bW493Hk3L^2$W=Ux{Sf$|s5BB0|Ly{7Uaolz1~4Op=E=Pm0#pNN z-t-BqbphFp!1uqb>+(dP#|DRrKy@ZOE(r;)>h93dzQbF7bpjRLEP6V2nFb?5B+j}~CTrda+WdEHY(r4OhVl3)Ak_n=8 ze-b7WI~XFq_K`7sMSM*aJLpJ~bPY$j0z*>;wB#pOyA;MH0t+_SF9nNXY61vggHuxQ zB7PQljRI9ESPFw!K;-~KDd^?k;6Jv>Fit!igD(%;e$eVUxgZlC9a=fl%;9=e&Zy&~ z6UjI>*VPp~PkG^dNo&BzPHTX2dr`!zZD&cL>jY)Biz19$!S3%=#dhMJnej8bfWbjN zHG^3ISKsS`+Hb(s_q!mB*6cWb7r-9iQ%e>pBwIH101YP|mi6#8lEE z#rUN{#keYn%7SI43Pa8)gpl}o2Kdmx%6=VuXdHQfwH<|6~uvZMHPNGbNjWEw^MD3t*C2@ z!-8_V+a@$jOssR4#AG}qY*}(Bp{Z@5>o_F~dniP_Vwi8a9NY4cc1?WmI$8@Galm8x z9*3Vc!cR*h>WBo?%{YD=dMqe04s@NcgktTMMLD@kRYZOZ2*3hC4`;{(k zH~Sh{c56`2@89r6+@dWO4GwNeQRmPO5O-MQKhFVLZi}q51tENo^> z;2)fBY|1VjgFoz>go$S)@5k2K1w#S3{_uvGr*8zi;Qts&)Y}fGzq2kisV<-{U`IY+ z;y$sw|Kv@5jl72&j}z4eIWP+_cd(7)3FRiUr%z5BQ=hix3&M`|yUSlB^gc7^xhukr z`bBc{l!&C(Y1%%Y$OQ*S;2AikSekpEQ>7>)e;nQ)B1Bi#4^I!UMzU z4e*8-QF;(~%&d`E6TJTFbe4&>Tq`XPa%cgRTtQiMb~d(id~rEVcG_+FMr-QDmef%f z+L9ulb+&#FeYV?jANafou`Z&-cbBayNL_gizrPB4NTn7F9HV>FYflW~db(XY@6J~I zQ=UCD;4~dX{qn(!6K2P zen`$;aiF3uQq_>n3M(JK4)TOlH8{)+mehl23h+pQSt%hE4SYY!kYC1-pB3|R4EZ^s zLLL9cIaIJM)V?IdzBHufdMb)BvCP)XiB`84l&)0#?m0|hRxEhS0R~bC1+(ISgaeeN zVDo+jbY2WB<&Y9!HG(i9z{(csF$P z5<~|dfr1nRoS6Z2y#cjw7!x8-O~rLh_&)+r3Jl^wyBb>Py~8UP)(mQZcB14c?4rR-RcWG=f%#RJ|b7##&^0gbDvh)XyQ8)$twx&TKK;mLp}c%JboVX$<6j#Aq8z~ zzS}t}Wa~{atCdf+lw)E*u_;V$g4Cn|i-1Qx$Pz+2a%7w9J^ut8cLL8jRCRe+JirTC z25`iBIHD0uIROlU9qNx3KW7}YYd#p!d{DJ=bRi~>U2Me+xh3HH3i!`MJfDVmCZ;;@ z`N^r#e7@l*aH0S*8)>>V4@}Gnh!%sl4d90mQkAn7fv^VfVB-|@mho%5!Yu%#CZHt* zkA{G$)bOkr*Ug7KACYA#_%RQr{e#NzKk?{Taw3Pjv@(2axzEe8;fqDXx-*ZxLC9q#- zPU=(301GJKc^ckNccA?^v)zr^9#0M@SQ*ZZ8I7%}Ut3ajTxc#uK03C?DL(49{}lS1 zegtki&HZ>*@_>C4RCV}m6VQ+%KUg&z!pO&CK<)pwZaKbpjyh|{C;Emd_b6AlDy<%K ziQN;kV);T1OXjwnYyNCly~F^UTVunpVS_O9BZqONfbGkk9p+1>!}E+`x4dp zJg>t=8xEN=+aH4Ak9A@9phQnizSTa6*ez**>mHXt8>GiPLQ=h_&a>X1U*l#twV+T{ znsuAFyC2s!9$-u?@4f9vpFm*yDlZQmgq!%gkQZ^6iCbpJ!br(3^;mqUM-3w34R zeIGe=^nM&V`Sp>*K<~%oe9qMveok9s#s2Rny*#wBcI#-njA(1(eaafk=IifoC|jcc zv7v02!}%ke3q^!y=CPD@gJ1rdE}f8Fy5;r#>J`TKk?fL_|L(mKSNd9~mhnBb5EDM& zCH5<|yE!;?)tPascFdSa?#*)yki6T!hRFiSAZ$HsSa5S19FhVHDK2WWOyS+G0{pAk z$O-%}=r@;AGb?7OuaK2%_UvR-#YaAQASqyaeOadB*th|DKR+4Xf5yT6y&v3-wmcCf4sg(4LBL@pzt140jNqgSd1K?Pz^2} zi3OUW4It~Z5Ue&A!G>!}KZ^={@9~ShG@T8d_txf=lC+~#YNFQG3@jMLKfP9+S4vto zF!-HO7;z2j6atj(>C7ia5p^L97<}M^@vk*zYYRof!>GK(-HMerX3z9P_mVr?nohU2 z8F{w0X)!)#bbZWVe00zB%1_F*@41)ZuPZxh=648vu|1oT8ENxZTei;~3)&j*)ZKOZ zq)409>zs9rXcrgLMi)CDBOFzBzDoG?2Tj*9c=EE(q5Qa9dz8&dt2HKtAv_)sTiMGU_b$^cz|qiERql;3W2i_(1gH5IHz*-7XqFTpmgWB6mLD5 zOnp|iX;yZ64+QOiAmrmN2y%j;oe<;*LAxP{PJmvIuZ0g!Zc|{de3C4K-tn1vH<@`i zn0dFEd2!6VWM*E;$XMja*kYft7hAbw@9u?f>%ZsWo>_DMKO>*Fj(iRo`MhN0^MR4i z&+h4~rRb~aq&hC9og-|VM>|5;s7#x@S5^Jtp4!tiwM%!@E*S-##Ri>K4myi`q7`)3 zD(I|Q&{?yfv!@b*9|oZNRPozo%Va!qI)&2^_uUx0o7x z_O7bDv`Wd$I$6uOe&yJ^H_x8C=U^RYSU6@s=Fd*{L4RfFPt zfZLL9JN>M}1SLuc!dbnTN$C*T=lJ)BJ2*Vu!R;^mo~Bie4ipeqh+DHPGJcF&GJ1?k z@1moGgZqMTEUz)Ms(Nm8y4u&(Ps}rXkDvE3wTNKi^c02tJvz?oh zPX2-F2YpkhZT7xdvoPFp%%Z`5%0)4j$d+t7I`;Y%>(UBt z(^`wSCFWeCuhC`^Q0B-#+dcM;oeO?4@?v}TzA?Yxs*$nn9_*Z~Ef%jumg#R(6%gHr zaWR+4Y8f;n4Sv2hzIbHOq$oND|L^*NS5uW2d4WA>ylwqK=gQIfm^|eO@!@Iy=%^ca z)GhTFI#Jt233~vpWWjIafP;{QX@DT9;U5To2K_15OaMPP&_cQ9L3hxUIR}m`lp@&L zA|Y-mY!WUX{{!@7!T#$NboCIcBcpzqw2liTGNR#9#`tjj5ILo$po~&ZJCu*Miy#VO z(HRV%#l!=Sq>C}I{{{s;7W4~oCJn$|TA&Hk*wAXZMJ#9*Qs={A$nmO86&CTx%uGf0 zS>-uuG8zqJO<<`DaNeLWMDhKQnRzjZJb=YdUngTZeioG{7h#?%Md&{e1U@LC?aW83 zQfRCBf$NF-3Ft)CS)9u#xFE$XfJq44W-l-J13cwG>hjX~IV5h4ydbj}c0E3eQ-NLM zfrt$vrPM!Q3$c{C5H3AFOLZCrEjutJrUSWSfx!v1jvPYpa%QeNhF9NF6@xWDK3(~~ zXZVOK>0{S$khoF_`(h92sglC`sTeYldusxWv6Q+9Mo^zqY;atP^bx->zRs;vPplW*8wgI21jODEBIWkBC;zM?;xt2(Z|tG{$+pQ}5-Een)2u6S#al=21D-0~xN9kPnog?ncr z&;6@APL zmpJbiUx-IPXHe9Mud>kpMll}VMemapQUYa#8OW-LbdWfD2$J!AsDUyImof|D8E^6X zy7f(U>sgJmMhV#ExJkC=qQ%ih$U-`<36$B;D!JyQ)Nl!)WWi4};it+2Vz>bRTR+%? z)G?10i4*aKF}dtd@$b6UY)XIRbmP&Uy|K-C3lBd&gV4G^xd+MeZ%8@A`zK~s(Gz7` zqUa?9Id-CgjOqwUo4~>-ZEwg#?>+IJLho~*pH@?6KhB(h9Cma@$Sys|C5d=(=Sh-? zmx2S-#MaKqh{pnf_*g+&q!SV&k8-e6=S7V~X~|`?L-sS4rxmZ6-WojJASksv?P)st3AL;v*j3i+?*gLy;6X#7fc@lyPK zcCpP%N>d->Nl5zkk&)j(1>T(<*gu2kUW1I;F2Wcd^B%5c`gW(3Ktx5 z1N0TY{TJVbV1b;v2m~PWcLH!tfpObr!G^95krT#ZJ>Kgmvt~ZVqN&4-AlksJS>891 zS~h&TXc${G92F9IJynx2vDDT{Lp8(0hnez47^tCx zMG$E+<$8Q-b;VUNVZs1=I?~w!byXbd=6pZdcDC{{rPTh@H=K{UK_D!vYK0)wjNvMJ z3D{{qiR*KO6DwQ6VbqNG7e}}^Fb!NiJpy5~@58;w5%rKSC74fA*UAG_z$paUPnzSR zoGBnL1-4RF1e_14C>!$AYVO!v*{_Y?9!Kur_$Ak;{zx%s%1Zr_m1@vssbpZpuv~0F zQC5&FXARZBFnf-?-YBIfAOt!hy%0i=LXs@Y^nilcjOaP!a!aF!l8*c2+(YC12`tl?VRuV z&=UqIM+h{yg#5e7>ig}8Q&ak&BV`IZ7Ts(=`dhG0TT|qV4dIpa&&H&^s6iu9%8_fG^D4tMxV|Ir81TFDd)cC=mEJ1R zMV4XZP)fJYvu+=KVu~|q5#Mqtc3s=<;7qhZCfYp-ArgB-GZpR%ctLu}4D;}0NO*Md zev_OIVMS-U|18sSa$`ZYOa6~wOj~f|n0fdMI@Xvjswx>#Du`$cYmX!vNp_AUGhKtY zv+zC59q60(3uUT4`7`GSql{`wTgn6KfY-sz0UK=SrOWPNG8AfZn46B8WgeN_P;hCV z*N@;UZI>cn7==HlUk#)aw|Mh-&y552f2Y!)GoIWQPzT2Yk_Ueft~dlm%*<>`!!Oqz z*m#_|(T%w=p6pAg(8nLI@A%M){(c*~eLZ&j2JH5SG(T})EV}n0?Vr6rVU~pe(*Qb< zrXU`CVIw^0`2V17P2k7LZ$N_r>=1#*Z)`tG2wo1&!TbO4fei&@8x1h8gang@xL(a2 zQG^Or{B&c7f*{&)p5%NRi*_g4zYt$j!Xkm+C0)Z8#n;w#1CbN3s0YbHa3mIZu)#4Y zq&`OnVA$ZG6jFm(okzg<3I$aSj5qu~(GfYD=^VQ6jZ8vF$uR5gkU3!t*W(?I{?!nS zssLFPn|ebH-v3S@_WrQej>V!Up2;^8btA}JU<0%kCHDwzfOL?%t8MU8WWFc(i=Z0_ z9M_`L`3(QTnoKS??>}ghEm-#>R*x4;o;0s~!j2^;rC~L;PFwFCbvr#8xS6OQi%u-0 zo#ngjCZ13jp4>w+2F}QFi`8J#U0x3;L(slX6+ml3TH3iDa6Wj=1|tYyl~kcnl&XWP zY^sACa~&iIp*KT7UrI&bxEu!beJ|$fZTvS={Gnsa+y$7DrVd>~@H%F$PXDl{4@s1X z=9yv5caWU;j1}1X51f1Uf{xqpsd{L?G$4zOz;18jL8uVn!|m!JMB}#*wm^RQ*((&@ zi$Qk7T*ILbqS(~ZA*!LAw^G5=Rgi9m^tADdD~5`bhl4L_5BfGv;X3)hu(L}X zXn~x51Ds4kx^ZeBAG*Z=ANFFjZsXUP;$OHi4^s@%iVzGnqn7s z`8W_a?jXhU%hq>;Bb2#DT_5%^mLd|!|Mt~XG>oYSEubHoI$916I!X<1&8+XI_OC5a zJLNeE)ZPr$^d*SS*>xrxSX+c54~lY8)q!3D%Y0PCZCRQK2lwKtDYvuj63Rks0~6jd?CQ2Mr>%#U7T>S4r<-NQY*>iI*s2Z?;%1S{m(j zgzG3j=E5~n)VvyTbI4A!|Cd*uPLp~bn(Pxd^tLi7e~!7YD9wutN0e>3WwdKWwE0D} zJ>q*eeor}BXd4%jp9|??xcG4bZ+o_=M=|p)-Cydtd-6aPRJ>m;r(?3>Zo0pW=`yKb zaB6@4_h7v?Q6%0hypI0E*g{xUI}+~@c1LnAJY>(<4W@2Y@(AMKJ~yadWf!EGJANyi zn>NGheGi`A%{?{3^0?Ceeec+CsnWgPEK#yzhM1l$_4JhP0T}aiNBMiKx zEL9+@_yjDFzMv5V2n%NJ$j5O7YOtu94K`;BsMpotWE(OV>f};0Bkw)OM`Pa2><$!_ z3~?Z9stz3uw9n`lXdNI|JS4;Sb#)XRx{FD{a=6(@wUab+XX@X4uZ1Bp1G$ zF7`hUoImdcJUxZ?9{|+|92db)n;><>`1ZT=+ag8IiBjwL@W+yLMQ?i(glm_5ocYT< z+~U);$m^cu?o3u6>S~$A{d3-1o9Zs4Mg_huw|LP|ci|Ef^&>@A82qS$=;ZHV+WF0_ zb7lR>-PV`p``_j~+jpLH={EL-JJGXLd?5zCi9yjJzH%aMPm>ka26~6o*YR&gF-*^T zhcwjjlcE^vvO>FQM@>O;ejf^R#+!Msh=n5RQZ2*@$h?niJgj*jtPz|}0@WO_lL8V` zU{&XLqnAR0GlsZ+%^jNv!DdWx92q7ApE^&9NWqRBBQ7~iWG12|6q+*M@=xpn$62V4 z|C@Z?FT~A<4H0c08|;%BE(Wd*phpM}+@1Zobx9#K%(@OR9I#0Wotgj|a?<8m!;4}N z_=t>3`Pq#=stnh~d&Q7FINWWO;n;Fobqjjj6g%iajJ%FEETlQ}Etg;uoM#Pv#lNfB z{Qnw=HRk%WU!1_nZ%{e|Q5F^`feJR#pwnYORT2mnQki@xo&o;di*dh=uRF|)d{UXS z0Mo50f+bg~XKmDN^w3(h2@uJ)V&7BE~KDe_PyMdS1-uv&v zhT6rxb)B8b#-(qoPE0N!?>7#3RdsZ-7`Ze{hfC@vbn0_->J@gMMydh3Z&B*$$*(8T zscGm`>@h+}gTHgz%t%~VR_-~ZCwnp(v9~qrV$wyI(Z*GuxYOz1|7GqB!jkP=%qyz2>MA_BQ$HeKjx0|D z68rfFc7KihxR(c2?*JmBJdBE44aQA-{PwL}OnjQCczw{IwsR*reMjm7m(&DwsuMc3 zg?&LOwU~WjK`OWL;S}|ljy?ioB!DYy=*tQqiJ1eUriI8%NyW{W@rt&yX;Q^<;Blv02UNf`E6bL1MQc z@f1NUB8XLKXW1+MNR44z+joK0F24f_uB9ORHxfR8=x%Y#U_%u^N&v_P&OnZ7=>lkt zAW#U|$`OOReUiIbXFIP=zERxlB5rQxCm-V{@9#oo6K99Eh?}QA)K%{6N4;G@41LpG z5p18I_kBWOe=XF(zWR^+(+lb5i$^Lw+XCYghg~#j$JmuC^?R=m|3&abA%$v#Y-pXh zxr3j4>fG$mc5(9$ezIK`Dy-0AY?n9lc3q`vRA9h1Nqi_(Vk(KiP0Rk6mYr#jHf)SG zY>75(h&F7FHf)MEq(v9hM;AQfD%L^3>}zedpkiZ|d^>T%Ks;2viFl zFEQT7gKCC2*FHD>--bPvpvcD~($=PlvczF6LgeC9di{irb=|@dsY~0$>%?I_P1;+w zR70N?H>^sKuaH6l4_`W*kgqVnR@)Z)_ZIs1KJ@RU_+uXUV+#E-5Bx5ilsPQBEQ zl)(&YX1@H##E2ougv@DMeyv<5|8ktk7v(5c(TKFSsq9NrnW}!9a+bbnOW>oGG`Ej8 z0?+FjIKR2YYqgxvuWAV#i7_(NS7F~&vRRy^?}$!4r|G=N+NHq_r9V~gw$8io2g~Ug z;r&#A&+zQqTY-u%N5|;!6}%^Sv-t&dYGp6=Ir5_ZL0+F8^7ZG)*E>Ju!kaJ?iZA_@ z@Q+mZM-2Sq7W^X~Rv^~^LNX3MsmuxCS|;L`EpA{r{`=|lsyjE%?b~p}*!aEHqd+4-PrEf%Qa>8KG6p6W$d0KC8 zpDa=J5-#BSNX&E+E%Hu{|1*VRfsezU{I}g+yDbgZNl3|8v6KjhUEEut=%$L4cG?%t z-Zrhv=(RR&Tt<4v6||9!qr;vrKI!GO^UfsGRJ1$8XC?7bp)>L!V*1`gLE0!k?JGa+ zHrnc!RLAG8KPl3eq~uK6_TZa3M7e`9kpD7nK_+CHY}`5TcC zqi9S}@OYp+;=tQecZvCNE?;dP2j#~7O|yC2VDq@y=5dqFW17tcp@4zlsbhQwhi_?! z4c$#r;g|i1UEY@X-j0}QOB676laAKBJut@V87x>AZb9x@Ymvqai#E&dADm8H+$QVu zG!6GAKQ$ir4}LwOxbh+`@_NVXbj?>)hbDJ!?^Wf@T-kx&gWrYMXbc{R4L1wY3$hy< zudfk(d~Jc~jhY)$qso|N7RS$c>nBA8>Q6UM^r1}7cs~mfBx{vfbRHf{w#t$XdAj;1 zn&ugd5khY?^`{X+wQ~*B{b}|6W%<}cN2aa&8N=GnBzMN}RZW9xR=1Ztg>6BM)YA8Xb4ZRnUH1jqT4zGPzYVdBar#_%C= zr5bk3i4@T_?BxnHk$9AaK(hffErku^0gVj;rI6BZ#ok3JRGd8v9UlcY|4+m8WllT; zj*bGWB2bDQsCf_~Ds1Z5ukl~}ZULq=V)~j#|1j2>Br(7`>>z0}hKJk}07b!}8b^*l!KCW|*Y&>8WXiDh>1d0gv zA*ACKKHB5mOcRIenn;GTtK!ay73C5}?oQaCL37l>D&F{c+%hOLm_ zz{VnQSz53NfzuG-NRiN+E5zx+PqW}lnXn#qU}XKkh%K`{sIo1N99e04oxH2kbW&jH z-0$;(LbG=!on}z!17Z;JCm;@lN)fPU29$x{ z)9pQ9!g3Go1k|Sayz0GK8;tt_(rBjM<23X-&9lM#iZ82g&!4ZFh!JgV z@CMS9MmdzrV!2ITE3n&_KNM_)7yuB`^gjKdv8$xYG}_PVq^sn6-deh_YR&Y~bkBb8 z)AgT@P1D7)>X>Rf2Qm_YS%<^8)f~6#8qc^fwPCXAJgEB5iPCkFjbe|h&wB4DOm7WE z=$|NE`&~;;yuvhF{aq`HkZv;L={z~IXQJBd!xM+zjNIiJMoq10PYCBt_50ba^PJ7C zC+pKJ^!F`BtcgCy7wK;j_Is66>&F93!{5-K8`INds50^0*WuC6Nh323lB}9~Ui2JV z=RLWmKy|OVIQ+p#vx8=O&3j(M&TG+$t27)a`0IU<`SpF_F9F*IvSGqgBV+?8xc#N zT|=3gesx2cNipa}u(IVa5}_nP#P!N@>QWfNX%T+!Z9O=}0at`z8ax4E$Tw-hEERyr z_(}D^nFD;1<^)iv6qtHJ3|`+GWL^<-(aq!toq(}8jHHRI%I=60av$E)cU@tVf7Ckv zh;{w~nic!na(#Nt@XS4!ib&;r5!J06+SZ6@Yv+Xg2N4QS4(Y*EK*{(h)ZG)pvafZ5znG+K{t!6~e zPxlw{f~6uA`OFqSP5GG-sT)VSk0aI9r(PfSAjlV_vV5lNy<5;yJ*-fZ$Y$L{uODti zum6rL9)^1qOlBi*qdo2N$$-(`VB@z}9}fTU zh;@5wU}ar^FYWrDtXs?Uw4e=}&= z^-Dizm{h(r(R=sO#5Ge^VdCoKnjf2QuY(O=Ni1JVoD30<=vwS!=L4x;PO1BKQa@^^eryO-v3@asE_q<7#t*Pa;c}1cCMv^mhyQ4&rQIV@HXAzo zIHbC9hmYMOW!x57ezrC&p+%M|-yXkuXVOd6Z2aoN!S9D_de2@fZJO|Mem}C}(#VPu zLW+lVdPAC0>LT{Ng{k{2c|P|89S$`_<|fTpZ#w5t?Bn2f#=-BLgWp*PKOYC~83*n; z2X5A6{DGmBJ81Tp-nRP;tP?q+jv2jXxjwVFi~%$SOlLGAT}?Z<0!lmobpAlZVMsz8~-12{E!sUo{qyLAp12c zfAU4L1Xi?6s4I1cFJBdE;&ShL%#Bs*%hj`;7AXsy%9_XUYabzFa)W+D{aEOL&3N7v zc1s1iF`cqi634MbnQYh|9P9RO zHbzZ(1h!rIS{o}mGC7l$V{Cd`v}ID_Bz>yk@a52$;n(p}v+!5+DPvOG`SIuc(&?b> z{}f!kW8cY3O-J;|`zGfX*zM2f2cz0DBF8p_m(vG~T_>vSYI6Cy+sp;e0pTqOipo%xS z7E`>AwWS{);SATxKP#O+^+EAnp?EHgc-7*sYV< zMa7o>@%7fFt9TVw{r)f6)f?Jo^r8GT`(9O(@O*mKTDqhvX+$LrdsjDNqX+TXVdAqr zbLOg**nb|-{u(_y5U<{Hy6@)cz8k0ea?90Dm8pGssrIEz&F-a|U74EU8I;3&^T=1E zu!n!8*QptrRc~Iuj}`Bld0P6ZK(l^khYeT~QKl9#v1xk9PS7mrOE%1`l`f5#$PToC zw~slV&Bj*Pez_7dT{R?7Ywph`OzY(Sh^Z*$2*|Cq(zd=~|00@&3(1=?j1fx>u<#BN z&PXz3IP4`)u5AS+i>C|k*lRMA6`p;`Ys>|XZm8+PdukD7RJ8~PNP?5h%D4% z5|X{DUH?^FyZ1{x!ZBD3$AS-tx*QihzQsyuLHPsa)ER&@I`=Po9waT zn*Cw!4JsI&(**Z66^t&5S=owKT^XVONNjy#G;kqNKM9@qkjCK$-Vnc>#StyA-Eu?Z z|Mua4O6@s=>n$O)OpaWgAcKR*Q%mQ8ZNZPnE2G48Qyz9xmJ+u*k<_{`1%-3I{^bWl4U5l0lb7PJy^CLMsSQQC*Yy0 z@YWkG&R`t$Z$5}>KIl<7x&Sl4S*M97?wRKM3mD#`fmPkeMNwB=M=LXY{v<9*6+^EX zVA~wZmsl*NYQUvGtt|iB7qh`X`cn|X{QUSS0oDYX^>aajcZR@ODfBNN=u!X*VXrQR zSRDuq&K~08D|Iz6lKPHXLa_IF($W?*X+0KwjA);LCQ)cw{0U>Cz0N2&NdY`I2$w>u zoB#h&g7ZKC_wk%y58=1N*pR-QlsG3*a+^R@!Tx#*gq8JPG0HtnAxpF|MmiV@+ixo~ zC59~F_+36vYHLBeBYa~Px~I#>me{_7l*6|)>js__1S*_U5j^^>B3LB1_^C!hNRE2& zL4S(+fe&qym&PEx>~C3cGa^c5`HHDu_>k)(@@pr|cWumf9gH5^&xm4zubI@RuLs_OHOgar-c+;3|$ZK`4B*@qQZy2peU zF$=h39%sFrxjh3l=K055xmL`Yza|f4Tc!I~oiV0|_PgX~Jee_U^WXG7ILTPDM0~G0 z2fb-x&?^YauV%SSMrNPd@3o5V`c8bee;4MvQFz+NsI?ZMh+S;0xg@*h)7N?F*;V$3 zCxfz8_jz$9&&;H>U0OJKc;swr(^`{p!$EP-NTCU#h|(Yj0suBY)Dhe@)(71Nb2aCfvrd0^*gZr60egDIDRIT7nfk{ znmWwWu+vAUFRbJwl?eX33@>5=Lc#KbCc1$hqReA*y70SZ^p!3jyUp=)9a^I!8HaU66c~+w(nPX zmxzCvW#@rzY0bIcaK&O!*$u4H@c5(es!Z8j?sf7hHurdCl{y}uNVZ!O!7LF3 zLJw%lF=)*~+HU^DW}q5eQ$s`v-5un4m;e=KjXGw$zN4BTLNjX&`-k0q zNpvNwgQi%jgss~{D(xD+B$gr+yu=0I>H#7Nc25G{Y~UdU>M)du2_RmG(88!DkbWH*L8-?_p}cND#ntH7l5Jct(0ry`mtcj$a~nD$E0K^=$Z^)Y zSWsr)<>UB(<{~~3kABJ+4iKNv8ii`R!2&5V@Q{zld4G-L=tS`PnWP|~7ASpJ%%zdO znSzrqht68Ou?1`Yky*SRgkDdXq{60gMHVr)|-xO{IeDH|` z(XX?a4W&!k?LJ(sm0!)Mwjp~r$LBTF4H zbH4jX#CPwt%7(^^Pj{Bp?44XuK>lh~?3J9By~@JTYn{ziMNqrPs?t4P@rtLGuC+&4 zQKogJTl%xV<2-B-aItp=aoW1{7w{w=`#L4zcSp_@1RG~dbIroj>EY=nvRsm6ADndqJ@bP?Yz0sWQl7K64@QqZ@~7O2e8`*tlzu$~#cqK;k1BICF=}kT)y$2tWNtm$ECqXf z1NOKn_Be$W$}htbpY0^Qj)B7vqy8`O#7F)=h3`vs4tMOzFGaN$n z{9MCDJZIBR(zIw-8?9b$>Le;z*-?=7%C4WqANixXEhZ@=jy-b5+GhSCjrfcvrCP&F zg23EvAH+_6O>8|6duR_Sqic9%$9RcuZGpzPf4wZna*&=N31%xiui-QY>4_3Gwqn;c z>iUBP5|mznB%7^Ysm-guYOVT$W&BXI;OY2<8=%czkRyWaWwF0_iwZ94w4;X_{9z&S*bwiY)KPPMkIItui5se`fkfX z1LF96V^fm=M zc$`>65nn@L2X~VsjA3Q5baNLlaRLR6bB=*L5DIKWN{&@i;u9pKgt z=K&;kbhEdasDJ}dQrF5>$P6_T@M8@iS6%~GJV&S%6*J>Qm*I-jAKSliJt$j6JG^SV7FhL!2VnP*jW`d)k<(9rJ8?Z?2FcX3SQ`qF6B|l$#Va9 zt$?`?G}q=}jtA6*0Xp=QF&Cs`jI;RxhO!|Z%mX8T1%El8G2!qUJdHe#05Oax1l zkko6W$Ho1_r>^e;e^AIVN#qV~47sUeRi*9{%x<>dg)=0#mO0%7!-ZtYPfJFJ^V3LZ zl^B?YXkdQ!be1iUr98VH7|+S;+}TJE?HUJ0FMgwb;!~HvA34+o@Ffn?lz!Jif~{Fd zLw#P%(&ra9^8FHqijM@kt6;1+e#@ChWpayOm8i|m>KPTR8=iu@AOQ`;#+p%eTw@!LEZ7Cc5 z-09u%&8P4Q_5OZ5r*v!X+f0e?tmJiL_$6rDw8wMmzwDalOx(JYAf ztC^xexF%y{!XfOgeFM)ty(02ZcJ3x@cP5&GXi3z?{M!=04~i-nc1RaRj+xnb=X>|A z-QT%be)7%8t^yMm^U3h^pM}PC!p0-$7E);TBRGmDS9E^H;JcSfYkaF?YjZjVtIS*5 zTGZ-W32o^7?sXNC!O{rzzQ_VlyI?5t&WH=NtzqU&6?C5p-5eQp(9H7u5ggXG%|UX< zp2o{h=gl(JaKVsG0gs-z&ny2E!1+JuAyh%}RA@et^giP09p^S`!JqtMCck)Bp!<`` zC$VH?tJ1>zHFOB-(W2Yf{^kj%@)!e}&{MRfS14CPR?1rd&-&&wjxg!T(|FO~9cH-}e86gi5kZWve7xk;vF7p{z-glBpD}W6jtn zgtARY(pZvcAwp$0mKd^AA;S!YA!8j3W_kYisPFrI-{0|fc#OP(P2TUI=pq^~4P4=U(?HNnhuxdblt zbLm%{0Sip}29*N_p8cl@8q5fJO^C-e*>OnUn&hEenC zZ45EOS%u9AxqhR~Ikw69 z#&y-EtEx@l>owIT7u7>of!S$^cJk{2t^U+1&kqhV~o(CItdiwV(YiFMC`ndj4lj(B)$K3K}p4@7~~S_rA{T3hxR*Kx?FM0jIz`r<(>M^VBT ztx{a8(pCQ8>+l9qPW*3W`8h)8l6W3TgZC0)Xy~JL?@8cDUAA7)n6sdDBzi*w>0~)v zTDiMxP10IOs%5|ibJMov)N9KF6x)8p&6^oBl<^zR1jL?WGBcD^jv&r?@nWX(X=#eL zNy}K0c40yQ=73-3b-x*nHjCz95mvCAn(BCA82cruu;<0w*0nPN_!|)}0{_8kj;W2D zw&M`W)V)UDg$7=3T}x#LS+$e|709je`$M7@5~=MgC0`RMs|4#sr_4c%42m~j3oUq7 z!9TP!ozo*L0X;HQLg$MBACuWgf)v1v{9x&;%|#F-%7r@Uje5(cXKGYd>}@)ZtYqdH zOl&_WH1Dv#P2&5S96Lz1#ey^aNC!QzLQW5CyMaS;RX631U;Ce9L^8$d;GFdzA|?0g zokJA*Dy_Y4Xfu7sDWqbj%(f-h)Nbr}G+bHK{X#v~e%|$Xl_R(NuPt8pG`;TGYJF9b z9IP#plGLp&5|OOj%pwADnGBN%x*^~GVSRuu>g@=mJ`XvrLXu3h0fvQo;s+s`8=(^~ zgr3vP5*MoHUuV)As&H+HlZdL=8b86{1a{i z>$eg;I*>O{J?^)nqZi1XQN5>mp(bIBJ7UZ@VocT}Xj{BZ?Si6~fgm+TH7)ud)bfq!_XchX$C24JK>{a38D|w4l*|ZjvwxE>=dD?#%{QDT=-v?yr|@~5SMxe=uk}Gu@@JhVzm^Iw{wApmh;8Ng5=#u^6o5;*z;P_ zJa`3<8{sY*T1`AFjeaf&y+<{EyMq@_TOurt5SFJ9mM0OGrU=Uu2ul-$r7^;?bFAjm zEZuV~#O*3hy@=?j#t7cUNRMN6)P+#4<7l6VYyESZsi_ zYroUv=Ii>*rKH_UhV&8gNRABU|?%h9y_tq*?3Ahd-(P?4|$MNka0N*}#oM8cBK2yjp z&Q8Pd23#S}gxq+lEX!Vi#!b1J>$SsGk#beDqfRm{yj+Wq=CNZ!o?7&y-zBxjrM$<5 z_rKl#)0m(fGvyrodic`2C-kq+8Squc-7~|JzzcyTuT81kzwx!P^SAl%A8*~3!62ln ze`TlC!MXYJY;w8*DzU1S(vgT_5aa|XrOIA#@@%vIYmb7!>%)TOa4#7G5k_0Wd{tf9 zO>cAtDoDGP#t>>ub40LhTSRceTz!qgEI39+=_Y4jD<*PogRtcE`-nGABW-^Uw+^J; ztn_m;ajGhjgr$vFkPdh9xcr` zk1P@)IRPHk;~GNC-+!n@BBZ|n<|f#=0j>v720vLqz}VAu=-^fNO<+;M33HnC zaq2(NBH2*xJaHSl@DYH-aa;oSOkl~KHHGwJ*^EOzy59EoiuO?Z`+ zAGn5DY2p}Wq>`o6yRy{-d`@5rCcBShK^dl?7YLRW`jZ9Frv_UK770iefekKngF=;( z#RfYE92c9f4wBkv=GQ~%Kmtrczvu=k56DcUV$VGv@9fcuLyhh29^Qfkf&jd3- zkZ_;siRl@0&cO#ydKw1kJ>2N6@v{u?Edd`r280{^A5&Up80U>{&njBem}Tg;1RVCb zO^|y%ba@`qWa6?pFc?Gib%-ztVILu#H7fkic+!eTC&bG9#gNY7*uIg8xJUZK>MMST zsfEy zERzEY@N=4w|NHvXpY6cU_$3uQNo4Ptmgo~(z+mP7t9rN%#b-of3gUszmkQ= zO%@quLDXmM=!En0nMnd{?{PiJdFbB|0mw!G@zNBbunWaKTqm_zIN#{<>CF)*!`?(z zUU;=xO!D_R)&C)0x@)@^>!PeEv!5C4GsnE;iD_y0RvmhQJ1tQ(rtwmvOOYZwFcFs+ zoS~%MNV%P87o4G@-A>t)*c+UosNFzuOjHlfn8Cqgexln?WW?wR`PY!YO~bAR?+4I` z#(o^n^pnDqX!|pu;Jq`DGL9}xxF{p%4@zK{;Lp^~6$Ze~E%@h?H4RcuBd39#y{z+Q zVtVKJDqQ(Sbvi;uzPz&YNRhmwS2XTU?RjNJ;3{jZPM@prN~E4`i1V&OL~H!iTvGJ1 zhX0iU^c9_7>STR5Ls?|nvDi@68Ip$bDa`>jh|b2q@s@y4L}!ZAq<1L!wI8e60@TDY z2TS9dyN8>*PmD~y^YGbh=H}tUW#-`FBNBf;!X>f3yM!x#zu*0I>fAV8D48%wxt7Ri zX2@SW)OrcAN)%$J)I-Pq!Q#-XhOeHi8-lBOgDwfq_T+h-0NX*Cjd=up0d*{(cdNaI zUzVue^V(1S{DSN5s(~%T_XOR)hQk|Vy<(4f-7EBny`a_f(1p({U`x}~z-qshLAGx?CzPh#uuC>C2uMuVuJ0}4z6WX+j zzWVqdm~sodFanw;0qY@H8{F@K%&=#fS4Pk&KNH=T{I_>_e#|G5`})q*NFa&arE?L3 zbVVd_uCLD`q?WQhF>}d3o1DTP*9&}mZpG)p2pa|Vhk=#rUq&zb$w;%AaH>VH zD+%^mUiGAnb8JQxkG{WRz~Zqb@^~E3X;8@KW8PlLi)l_D_2m0V+U4S%Ef4&x3-I1v z#@{HcjZGUK5N+?1%A_Pw567%M2x19iCuH%)0(d~xmnHd$N@7CCK(L2!!kD5gzE=RR zE`To~`R$PG3?Jk5s8W#pO?jLm@dA5|wjkDqcTkfdHUtI9&=$Dc@IuLJtHKjweNAht zah?Y3-3v7}u2qGF%Jk*!<25x;80+G*(}QJ&bEKLYiG(p1S-iXe{;dGsjkGE$iFi0> z;SnU}X%KQZ4MV(U5Q14-HEs@K^3xXF+VF^@GU&!2=62cwsts>=R0g_7UVEW6cNBuw zGa>gK(_y%7UNxA{iD$rIgJ{*@^mCjMZxE*io&sw+{e0=hG#k^Y}8@1 zoflNV_)um3ZG<56_S9zdrSjU$8*5HC#+x;~IJzx?zacby@j)J6>fpd5cmJ8Mh0$rJlhZwZ;l`h_e}h%{(L&_ppoLig9mq> z$o|Ir*oZ$T^2?7`NB*-=z7_acnbb;vqUbjQW?{Z=vu*0~bCq)jx@+mG5;2X}(`Tmc z+wcXN%HgjEU%y|tT2+XB+wX4(pL4ZA!)?CMxK!Q_=yi>EYYKV!$F_%Gk;W2Mq!-+L z>bxsPtCNn-&CXhs(wA$i-s(%uIJ(%Vw!xR0cLrFB2HbdUCLUmU5_4~<*;7C9ku>i~ z48b?x4QcrO?7CiH@P}3ax-54hWys8(n{@4^<~NT|X~HV?8YXt7xczqevv?TW>ZJ17 z|7)v>W=f^gJ?{uc?1F=wmzdXaueeq~Tv97EE-*vZE_)xv;3E6grHOq!s4GucPE#-3 z$_V#tlqX^c%Q-9S)-T*D{8Q86*N4dymB5(b&=##b`#(vGH32J{HyrdTtQ zzFCETQaYt9=xi|)GTcL~6GgGE2L`LuywxKNhNaE1L;PNqnCFxz)j574M?@j!RS-I%u%k)aXTE}(9ZASeSnb9PxY)Q#_u_aQIC*z%lhvul6M_EuAuBVeQkbbWJS9LJP&9aKFJz373)K;|K!b=Xc#fN^Jg*#8+s zZr&I~;=0DTvhd-P3p)e!Vx=*!@Y$j4%(LsjxX;-mfz*Y+d5QDTW+rYcq*@2H&O_#5 z>uCEa4$VV~4YYhhBb@%<#d(OIiOySsz*O+J5!_v2s7kTS-@=2YNvPt6&(*gFdeB0y zVr-K24MYNhRQ~TAvg?1%A%Sn7Gc$n1*ywPGI06Z+0!8Dr2$)HkL+Cn)I8SW!gRpz& zaCr;t%G6uXnI@nF_F?nwPKVm91}WOA@*UbvdbOm6rBQfKd+tH{`p&#_@EO0D!z zT!EPoAbGy+%7z6jnPLnkyJ7n4<{j1APhbRnOT@SgVg zFl;){#w^{VM43R{0dCKL4d zINL{fJz9hbcfSGk%taiTS;eeZd(=D`78JBxnu`!DQoU59`ur;5aAVEI$lxMSu_%91 zy#OTff1q;Jf9dVLH$R`Z2h0&Ju92R&2c<&_SqHA|3M2Ez%xcuW7EU$|wLqZ;&V9XV z=L^xX9C&L~=O5dCfHmyS!&mpN_JMCx%|+IgkqPDE0P9aLk!mUnj8Qf$fL z+JFf&IfC|j(FqMXsinc_4k76A^*o*qi|;J%V%qQ+j@IL4(3P1|7nqz(JHf6>qtb+H>`$kD)M z{U>jwvM-!ETin}8ul2W~I`>z5qGi(FBBthQRB8$Xyoi!e`Jb_>P-+cZ=^^5IziN`oy_KAvD&+bHg~Qx zbR^*1qkYtgldhqou34j;G|)(_oJWZ$^0|p`zM5~oz0NO1sp)P{A)Q$hP!W|G_CUs_ z95x4-yT8}~2ZlmsB*=CZ4H6VKe332NmZ4|ez!r%U`!7#Wl(U%J&xTL{&;b~m?UNIG z8rw^vu@usTf0;iQ()kfK<$$iUrf=12pQ;Z&Rgv+1-3wcEhEL%yC$Ndf*U>_3BB1;3 zVxoB#VLpk+buGYk*uZ2?9AL@- z(cEUBrc=NHz!EU^M_idleB*^2!H@ogLD#{}Y#6jlMV*!6qY32zB5*Y zGe9NhR1DpNF*5;>bSmk5&z54nJ`@k z9ge@H?I;i6*ZeDN=W&29voVuP%3}8cFKjpm_r%49*8`k6F@Ke~8M++DE@jz3e1A7y zKW}~lN!*bmK&~sbQa*DEgmCkpSbPXbzE?}HqX5CT`=W+93Y7xTBNg$1+MNuS;6Nuv zpMiSdL~4pV%~RdUI7BH~iEN<0cn)GeLuFo{N>%z}(8y95F_3Goeg+Niq*wP$I5!0g zRCZpaE8d+QXVQ#mJ#(vb&UM77@<0<>fjQfNFr>`Tub)v0!T3~uAZ8N^Cg_ugb(>E4 z##&A8PU%t`_OU!FC1Qm?*sC^xdS*F!E4@oi&e%+fHl)d3dq2BY5n|(AnL+GjF$6FD zULUkX-KEeEmku)Y2WNJKbb3~16TOFK$#lI^U4}k!MkPemqcRUt7iapYS5^+_x6MwW z>ga)~f$k-Y7ejr3l0py+5n#_wV{wIB*yRzkoj5^MTh!O<@QT_ENGdXNYXRyp)z z?l{tc9{6$aIMbQpYlZ8pywb|d_`(VfuY}VWgH>d7XSp)$wkB-e7!lKL{o+l2gM$O~=*MQX(^b|>)@kK&Kyy5vpuyXw?vN)c~N zL5$Oo;cm!qFJ#EeoIA=!?S(31p`j+Ivk6jdf(n};ckMqA{WOH$4Wai!CQqT)&1f|; z8d1-Vk%hz_(+~+-(9hGv>qAVjDOZ~?Y&AcUt%*F>Y_*@9d(^AM=DC#I<7tI6W!a)5 z@jdUdW2Y4E>U>X)U#yY+h0fU~wI51OfRvii_E5+)+K`M!lc7yy$cPN>BZF)`XeZea zLs$~>WDA+Fg^bx4Gq#NpJ5Lsp-?f6?wTRa7WOwfCfE?er7a@1ZceD#X8j?KI-)`I7 z-rd};*4$py-0tb<`{Ob7U22!Da#r@&DXjsYwCg(7$EDt`#b1OT9P@d^>@#6c?}yyh z>6allS%|U^0@DY|erP!X+R}_RCgX(5r=XxwCft;b-3R!wkY+O!(F~b9Vj*Igs6!oS z*eH{JFgWIcHv%=mh{ zyM25XrHa^e0A&@j+Yka4PuM4>g@wl$pO+MEq?UB;+?%?LH; zKFiHynUf(UGUQ5z#L3VFGNf70=Gza^MJN#0DAUk7 zct{{TCJ>(8#Lpy1p$_^GQoB4;rpg9=2rfFa$EE0;S3-#Mm!QGt?ltr`9C01JZA~VY zX&BEm3}qTVVH!p-4da-G#>jQ_^D+p^G-hX-v57`(;wd)qB%64M3Q3XC3ZCpJkgcFG zbvYjkd+bd+a1E|1>`Oc5MHBF%DS6TMdeH)&OU;@3R;6?;gq+0l<&GKmE+kB?_WNvG z0Ix=r8~7V!LYbITY_m1+YGm$%G7mtR`=Lx(2(b@xc?uOZLt0+Fkl!d1oCfj-AoZtE zYBO}0jMlscc|V16zO5ll)1aT6)8UXX#r4=VIAWJCP0UN3w>&kPU}=oZbsJEF7rQv0 z#4{ho^X9r_O&dB?)h|t+K++~F-|swrVi|bTqNB(`rGrNHw@7?)%AiA#nv5)LTv7VwFIbMg zT|9D}ZK(R3c5|hQr_f%B(mLaxN*2>hv2eca9YMC&bTD^LkL`1bE5`pe!aN9-p6+(x z4!Cy;V>Mai7(m_C0N)J^=$ozz(ODFc;n^n}l!j}G18T+(kTcGAS;Ns6d z=r*8t$;+FQCh--t_aw3SGaX<2tH^p-`R2}x(2K`<{Qk!lMO&6TGoxv@n|l-7NbFRt zLiG88JlJsIuot3+RlZKDDkN*Kyo{o)d7(qA4Y?^Sa#dGGXZ_keZPj85OAf#_jl7cE z)8$IPmS6Icz}`Jr`lVc)Sb|L}EunDBxl2VrY`ziw-G}M!E^{(r^xFy|i6d$iq-$Wrp{+oWfb^%Fy-ZC^#5!0edp7S`9v!e8hy zu7nNdPL2%5%zT0kx~TfjQ%zu0KnpZEzVdoYplwX`WMp-}aA1+0?3@WJaBeUr-HsaJ z4)YC#K%>kZKu_3#b?CW=K(t_ZaSHtyXn56zsJTA9`lMX5S}U8f0jYn)%EA}=>q>!C ziOFu&u57~qYSh1&py(;|yB@%e6bgq%q&f8oXxZ;%%4~yVN$7)2&fC1z4`_D|R5Wk6 zgCiW>#<43#@i0MoM0>`jC<8iXZ@XU(7ASBt1+?)m zy@>heTi^+h+|vu$0<7jnenCDSWR0OWGc&gWBzci zEo3r}{?Y>-H;3R&KHe2Q?R&W3Zd(Xxyl}UMc5M%D6+#-U1mE~wI)x{|Y47C!k=j^7 zz#a+8&AtX`yYvPNYySVihYvKfjWc0{VE^w`k8dDq1 z;;LX-5X`{32v&1tbz^Hi_aFM*HqLh1L5Wp(ZXHt3#dbbJ8VHrG9Ux6ul&uLMYa+4k zq=~^7`XLuqR^>n@juA#~vPe|_c^2Ml>7sBibSDS+Z6VYu)G!8^)?iWtkW5lcP%Uns z2ev}^aa#xr=$erbnuII&WS7LzGF{Rjr!jh_TN-pMn}$I8u=6Y%Qh&9J=U^W#RGv`} zfloD+-*!#IZW|-q*h@L2?1~A>p0?dNX}f!}d$WFYSN3jw^RDdk0k>EVZze}*h}&t< z^QJX-xk8Y^5l167X+ihFO@|gV1D;Hy1AQY6?ea306R3g9_GIhsq2L5L==eLUh5W09 zUntP#zrvHh;|NvJ?bd=m@48W!^p5P*;Fp%$AKkcpYu5p>cghdK|9ToK89#;shi{-d zUUulG4p3|ofsU>^-P^mwcX<5}O(0w0&(*@%Q=$)^T&mF-%)^prS6<#Nj9;uc-Qo6| z)_BaOMy0O$?o*3#hPud+l9~iaTk!?`DI@YXBj7p+-74>Pu2!3qr9{bH%2*&)Wwu2P z`lI#k+NEMX(b^AUKKnl;+iD6u)B8PfBGHapyXTqYn7*Wlo}@^f8oy*xof@y?RDHte zhyu;S@_vM@6#aSY+U=E~Nb(fOm&w@QX;XZ@`QGz%d-II@-pL?7ClAajon*D~6PH@b zIiVgUAk?F#eS1P6q(Gp31%2gZzY7x!`H~s!;cm2%fz5tjk3P*dZLysmc}Mg35uVK@ z83)iN_|e*$TNhRu0iDBZsWJLRP5++YqFup70>MRlfg?V+NO1kS!%`#iJ^|J;gkNr) z{kUY}q?*4m6X2SMi~x_0Y1lso<^urU2e~A(f!MEI+T49*$*&{@kF6eQH<))t_?5_1 z4H!Nh+bM_7l8$fClZ*-<+v*|7AD><8=>y^e6mG~ z05YLXb(bN_98M%*$p|C|n02e53c(S^07Mfq&4J*GES!E9*8ACT+VsMN9tKWnzzUMu zBjzU#_<4Ko!zY`^=jlm01Zov<;lGf|c1ZSxk3||m?ibd<3ImF6qWBmX$pO0#8pZ^y zDk3*D7Xi`hAjTj-<0`N~oQ@$6lo<(if>gv2$Xgo9jDp<3&+Vq5z|dj6{G|zD3>*_s z<-cuMZ-;xvL%2;n_U&eE=d)f_lOujD4GYJ#oVoCMB){#Fg?#JK^Bzv@h3-5wv>O67 zx=bynjb}Cwxqx+p35l}Nzna(#1J%_kF=!0j91tc7A`Xojs;&wIFC1SVg)KD}PR0d z792YrQv>cd1oz`^57u&xcaMq5xkkb2O ztaY}G#fw#gj=0glzTJI=gM0c4-#0B!?*KdF7uT}!(+ zz&G<8ywe6vnvYGXhpK%4plf;{ZH|f#sOdn>zZsDG#z1eE_-YAfJB9Xs1&=Uyp9rW@ zT=cWs=59{1Qmj%8hmVI!ikZio3z;QHW$%?dPI|{{CZ+WUU_#er@VLJ_y50wzX+k8& z=wRgWKE>A^j1$D(jfe^zC+s>M#*0D;A@9Ej9#qbUGJL3k;HE>oHbKB~<_Nke?gPPx z7_ERmH_lRAe(SG9`%ZiN)^MEJV)ORgksGkpp>r!;J`)4K*-MF)C((VEeG`bmH(-n* zhZPSTqeXfIg&vS)N$(4MM&!PUSqXd^gfH&9O5NYT*3VlEF*3?zBCkBY@`w`SiCFnC zXLENzjCETUh8bC}h4bC)_>>Vob4iCR$2 zow81=2;$`jgubT~{9EaL;C;GL-s0 zL8>H9%KKS-xjA0Xr_Bt%+2`;n{DG-vTb;#c@j1Fvrx$^sJEZ}N=HaLzMA;4vzzc)` znk-H-jeGMsNFt66uLDp8@Sm*u2#O&=*Bil7f&SRdaW%lrDh96ml-PTEe;u8WEYpS| zzt*+;dw7T3z~?l@w?2z+O^#RY@|4plIEnu`Sq98G%ix#(`jEr^e|^XR(MaFTA_{WW z2>|H^JSKj~Mv)Cx35QrV0`%ViACqMY7g9hPAh1jAo$DA?k zoH76ZhT{M{=F4tqdIQc2@R;{k(R^&+-=~wH;Qu&|K#&O@H~?xnu>n#{w9tloC>qKH zFwJaE#0|a4TCV5;ES!l-UABH2{4bNZtc;^rm?t4;$%<4c_>o1#=GY*f2F3b}_zGO)^8gm+s-#sJ=LUF7;z4ZthQCM-0-d#xR$JAT* zskgFyKHKa3&dS!;(Rr0Et78qCc8!xDCmX1M3=q|M5cA#Xr#C zbp=vm7+a789Cl#)eXmrFweEy~V^Q0hGBP`bIj{~sj@M>ew2T~lO( zZW{>p7SD$6Cm<&zh7O-496ryn;xu}c@F1Vpw--0Z|7?msZjQf{<07T=E8B%zNAtCd z-5cm5G~K^rV;9!P!Tm}$Ex>plMdUP?E=Wt{95yn!J=OSHS8U7eyN9WpDtAsj1A@1& zz$K5=*QMjr=49qDsYHely(2Bvt)m7tXHdfMch%I5eqF_moqrqfEM$DOw^dBKvb14OI z;0LC&VFa;qESW$@;e&<98O_!6LGA=f&G&V?%U&VqKh54rtWJ9vefeM?U0!BZqM2sL zq-~e8SuRf?mm4@d)9a*|CsG(rj*FW!^GJagk{J=~nj*5j0jyS?R}QxLmS5+1GR1*G z!DgYnt4d|O1lQKLtOdg`V5O=LzUEKVfNBnub;j2dFWVAeNfe@Gj^Ws3Fn@VwhB@?6 zij{xP%dml%@?5W%axBp;rw3O_&>N(9B~lJji<a>;qj9T`~i|DFg7CVQ2iui zv5~zOzW^O!qWK_V10*yL$uc1x$glxY-SY=>$o^YZbOJMa6>zxM@j`1(RS=WYnZLJz z-Rw~bc6&gJ>Tb`B#^OZb=mrjLQ~HOZc}`@0N1a zOUxB&k5XxPyldfBJnEcY#*@dgS{<=#x+Ya8C$F4z5U4T#)_$!fDxhX1 z_1C#08CSOBac7wdca8U$Zn-PdpOfrp z3G}o!cU1Z&a(sT3Kx>p=oa1%!sDzbRp{X_BkoaN1BL`v~`;kmIvbPmq39`SNM zMTOZe&OY`Cr(KW8oliO5!DeI7fiLFnB^<(SBYSCp_W0u3OJ;x-ATpX86>K9boj?jT zOKmD|*yNVtkloUEdr|(&1+vpyVe(6(*;r#{{zOH`-T90^PQ2w3`}#I}ecZ7yXjDTU z)bO);@cTpoH@U*70Kb1&kZciR6iz?ywv|lS2jAvZW3b|Bh%I}oleM?%t&XQrdIBVK zLS+y6oK!}*V4Dqhx#iQ#o4jI9Ahnx6@{~J0ZRIXM`E+orSEF-3rr0@R!oPoefwy6^ z)aG*8eGY5hZYq+q5EK4yt?#c0q|~{^cEB_WMd5ywmyauO{HQo962}+VZ4b zoYP^3JL8$`y9QBqB%1zqul9YY9b}a-!p*0ZTfE>WX2qL_xXLwEseC2Yx_-DFQQlqr z6R5khr3RmnhRxf<2s@k0dFc|IjSKbH{?pvHlK6!of4FNIuUOhE(#}&mPw?1+FQ+ta zb-lW2629e#@?MQwj@_?Lv>v^93f$dTyzxPb-qQMg=c%(x)~acg?KtR~@Nk_A9hpfF z#D&9DL>OLR48ndP!6-ZP#Pp)T4gduq<)JFVY zJSy+)YCj2ArKUbCkLfyMT&hG(eN;Z(b^m1P5o&5!d1cp(F-n1&x?{eB=5k`k0L8L@ zdUMU3m``cf%~!1_Q^Hk*u5eWx@R6I8W|Q=^v~QLna=w=bg-s(KQD&qj_HOZB?lQ@` z`$%QW6$uY#BA0jNtLe}Jp$e|a$SjEnq-2HSr0XkeIFhU4(Y)T_I)d2buU8fVfyi3I zkxAcI7W{#;bp-Co_*WK!ff=;~yUC8MO3{@n{`pKImj`Z}kK?3Q*Laq)k;9_`o*{i7 zOjmMNo)LZ9kh0Iq7N^~1uO3{8n|^t<@cCZaVEY`+&&c`*E$}|(lm3AMluB><^sIXO zn7rQb;@YQ9U0Q$NOuC_kH*Jf)e}$?I?W3A;6UN{J?oZ)*9{c~ffuNbcNMq^+D~krB zokO3GUp(<1E-0$<>9)?(i@^p_5{# zPQ7`zDq>kt;#=}2#6EU(n+@l!_=glJ>a=|uRKYmZlC$M=~O-itabXQf1H)^knbB2 zPVtMs#t=cL*nM(7dc>@BSu7K`vIBi_lyUd|uWa3y_f0?6LWXHaI^j z_vGvn#icNFM3|&T+C$PN@si|7$4T2sM@Uj6{j0q5T=V?%Ybhg1Z%Pi#j9LGdC!&D- zjPF74FZ3)oJ%aHqc+9{HQQk?Qn{u<AXr zuy2O3+|GapZ#ueOvh7^P;bqyhe6>&Cbfj^Yx}0)lNpLd>%PHU6rucD8*Nl?_$+| zF8;pP>OHt7yfq}YqBDsaH=P-`Ql#C>CnZyd0^j(5*HLBz!#k&0K5 z3L*PndL~#Yx4wrz4)KFc9_UR@mvL^5ixDg&bDL%oD;GOUi~FN~kGS#>>RhG^Q11@4q3*WJ>Weg6*&@^VXMd*4`TPMqpb+5EAuU|sAWm$K)1P}4HuLq1Zv-JY@U*IXy%Nc{MvJ}fm22DMJDVaV_15eMcKQx zDW=6{+iS-yr}8fG>O8)8vEM1&wTdke7ho}bs-?l2D40ZuG7Hh`j4uoD{L|!Pe%c|a zJH>b@iYNF`;Uy270GwS?Acn7+VPSIY0N?W!4 z@41kDl}}j;Vd&I*4oKMeliwvh7CQOXw<|SbZ=NQ-xl%e%bp}g1m1W*~@x4yPxm=Tv zdXKgiz5jgl=j-Dp?$-$o*tFOo!&jkk>pOh!g;ZnNsi&${!(6K~Bc-N-+7*JKxd}24KcHdX#kZC_mUKK8{!k77UUH5W?!87kGY(p*$&WlgTAwZmcdiWiaTiY> zDLZmP`t}!TU1G|@Ds};xxaFa+=B|4OXHo}wXy%CGA1VlKkJ2IEmHZau7_zKGIraA91c5sAwMOaJm`Nr)h`ySX|Zn%V6GxuLT_b@s4$>oQ` zOA71q!7}krf~+O4c?#b5;P=S<7(Q0>OF_6i=-8^TOa>!Q>AfZLwCTla_ZO_0yr1-@ z3r~MS1=;WkW}XYt!Z>fZ^Kw*Fd}JEUI>VSwp?4&$hF(Uf^3*8&`uH}B{&mIkHmNVq9qnDYYarmuriFmx&V>OB@3=$SqA2X_V}~wM zlrPW?>gW0l$3NcYb#y3MVP@yd@h;>BRehaJ4Q^$)bkdClw{K6ubj*JLtfFkfu6rGMTk6#^ zD(@A;f3#JV9{1;qw#F6o#Q>$`+ZO_wq+NLJ^jtKy$Gv-Y{O6S7ih;wKhM<>n4+{PG zM9$TZ&%D1Uc=+<&<{;m#ZmtzmX4y4mWf(F0+q3VsS4u7a#ALst-}IPfX^lRnPZLI2 zr_Rs){G@{eTIvv~2enoYORd+Awmo<{xG<{Yy(rS>`0RnNko6ptJN6^^vT^B_5GZ8l z0y~&@loeQoh8P?Can5$s!RD^W3DL}h_wOZ}^9T!t@g{%W`Fk=;R5krl#MiGE8FM5# z>qINmj4Ns&{d4pKzVyyx_&UjX>(H_D0-BO)3dET1UPRZ+?_WPNm znlw8fuq6PR7+7^n9PKzoay>|Beb|dRLdtV7m&ZLPZS@?K}DrP~VZQorh4$^&i*5XUJAc`>Xj)NOa|+_c z!u)$`Z*t#_e622ge%f@;-CW!A3AWwIxqg562Oy=bO>)Wj+`|@q-ydJsb`i8wrrDvQ zElLI8c#G`j;+IU}NUQ)UxAx*=nZfRGC)J@;8P%iy_Va>tk=pGRTnFrr>uZ6;ioGMaDf6tEeles&wJiFWH6VtpG`aNMw-_z zcLt9?T+jZLUS-MMjk|4BGIelDsuA^NPz%>djaPP7zjqIh7)2SH9W1$||5Q4*t2Oj$ z#<^i1;)#$(i^W)md`pQI$fQ{HKNM0r=x?*_XllHU*Zkg|FW&_&@of__U7bEURwGw8 zh~I_s%ot-J%=@l7d44il-FB;>^ctm-CyZ`7?ijAuz3mOr{=>V1F_Xd1;!l5GsWvf{ zeI7EQ&{?NQt^WCO_>^F^==|LCY1@GhDW|c!Fb1(*LV>Epyjy-Aj_DU7ynRIIC8~u< zME61*TThVK=WF=GH!7?2k3)~U88u~Tu+E#+$yx!4Ip>jYi5E_*=-zRh$?siR(LTaj zIWSMtpDIlI&K>b2wCM~_EF86KcQ~tv8mV7f?zC7Db$fEZ_|8|V+ zNY2|Ab92<|1N+bKKd2=9<5cuZar>;&djfo6@7|r2Fxvb&ZcHOL{(hsxZ$iLHkG!4m z;Z08@Mw??q4?1)0*jo0m&k=qX|1tgBl#KMvFR9BNR4O%Otn9_(jay>8 z6Q`PQSy|q2y8m8j%An6=d+AZz%U7oa5=3oXm3|CH8y&QNukq$*ev zvV3ZW@|~B5`CqK}c(*qG3~bE#9xmZcTl;hP*XNp`vbDH=rs+OPqM4y@b8*a$=XgO& z#Mt8XasJb0BB3c22M75yfBuRrxOUCm$L_%PGw-{eh;2{W@~O;MZ-v&MfcP-IJngM8 zRE7vv5jdz^b2PpvlD}h8>PnLR$!`||O!Lot>ryWLbl9QjlUmXYHuH+R#phDJo5$`+ z?S(Bqo=%fh`QTz=uVeM)qj$&-9aRfI!{6OC?-+YssxyNc@2y3LUMj@g zD4o29+CtUJ(aC$Tzh-4|*QoO8ApJ1u8fQ;7bN(@ZZm)Bbj-rd>hmWHV9)?H0q;n;-^wfmJ_d^J;vKw+NgtUy^)i1r}d&lLCy6X zk!E`9wb_PU@Q~yA=`dvC4&4uTXFe=A?uxDMD{s8N;<@wr_nd2U{-p(1OwnzD`f=x6 zN3bV#Co*L+9;lGtpRcD+md&ORb=Egl{|s-FUFL~qJL3$U-8K(0uqW)y^1TfO_uFhIW{(A8cA#<0U$)!!+gxdm z`u89oPJYr`{%h$q=RafVwrR7$zOS3EYwnxabX|PQ)~gYVd$PP@&w6qx;0}Iy{q5Vf z*M^(U7)pq<4xe7v4!s!41^0OIW>ou3V;9$rg8z@Vw}7g0?b=4yVv*7yCEXxMOSg1~ z($XzRN=bvXbhk7p0)l|FgmiZ|NXMe{f57eD`_2Cw=bZ11;aI~Zj)%DCJ?Fe)PQYMi z)(_R8!Q?{dOC@Es-WS++}xntiM&|64eM#4y#Ur<>aGn z6G5i#Uua|dGznOSzajd&;>A1ZFO}|7x2Js|E3NDWGn$VrlsQ!P!yhN1Xmo4kz!K+bt>Ehf9f^kJf-Y3849!04vS0N;P-`GX-o zCYC9MHj>+KDA_wBgHDf4mJ83}RwD9iyrH?DT1sxoGVdNPduuKr^YKXBibtyn`2SB? zNqY7C$TLvduU>Qrr#L>*C&A3V`)k2Te!ld!-Q@-Tg!CIfm`LVOJVApfOdri=%iK;%JRI3((*%}uHqzZKs68eLOk9tM1&iG7OJtdy`eww z+?B8380u-}vV9)TwKvHXo~~U{??E#WQ?B@qtD@d(qa#BXv2NDSMU}{A6rG7PIOB}L zb;qkCyZ1tU1aPVzzm97(oq3hYU({)@T0OCTB8R1SE1H`6<7^6U^vtbqU%U|AO(#kB zg?Tie(u>0sTSD)%b(8WN-4g0ImispeA}aYbZ;D87!@uWq^KbE`H;8sX`|SI(51&{M zP{C8Ekn<`sw?A8bDuyCnWdGEe#3LnwutY&O9Rt@Q-L;<4J?H##OMdY?Ch=84=eS56 zK{!|U&o;f~ZB>RtIM8UlIj4e<*`wi%_q4iRH?G9t2*j#0x_PVufb3c7hKYr2~;pHo8-DXT#d63_WVW8xaJ!hV6QyoS3BWeR>5GYFge&;8#uf% zP@YLlN>1;U7k(KLtEVbB_b?Hq)aYUA0x&!_c~Hk-!|HUf4J#!s>23Wb>w>l`xy)!& zi8tv9Lr$iCl&A6tc^Nyx=qn*(fm7~FmC0CUMWpO^)87K6D3;B~r+)BL+4g)&tSQ3W zV!UE@AyFl&&88FJkaW!<(cL>Ea6R;3JAO^@L{661(8J{KE# zgK(`Y!QEdf_O^ep|KLb{hc@)1mMbJ!hD7A)W4-w0?y*H|lW+Lcji|QnkmEBs(%I|T@KbH*Mfz& zk?TY3EXZ;mas*y!U(UOm9>ilRtR6}!`Q+w5y4|7Oa$RcL3dC~u+->Rjz_P4P#6Kp% z$FiMs{B38CzchpJI}(^u)B6fF*5`2qt%>rZz-TV7cUBjopa*aZpBQwPqJA9D1yWZC zc86QK`XTJYWI9&jM(9h+AL?|G-te}ebDueGyL_#hJ@9~4%nl2S)p=oO|B6%jjjjjP zn}wZNWxW<8Q`r(^fwh_3^-;BVm#38IK0KG0w?d+ElZuz~7LCx$sW9v*^18qeUEAAi ztl97RTlwX>vVz{PKZwpmDWiiRBPU{G*oa0dzk9eQ=F=-e-kUA3zK6?&=OeI-7>+I* zjr%k5r^?cD3%hfG#yV)?Ewk-(zek`Kk{VmWWzyV?*dbVE5npQ{ zoE4Qd>@l49lK3Z_$+;k_6~UAjJWdY}-Ldl4D9Z#=6Hiim;w#M`y4319a&J@MKgd$* z2rV-FJg$;)-Em5r8M}Ae60U~F*Qe|RvYZ`KmlsH*KD>d;W=3OVCF~WnU8iT)nBhKl%{#b% zeO1yZ#&nL0&@WP+VRHg?^2|OhpM7$?VJ5_Jsi}7{IfJ=l))+h4{|flFPKNqJkfq|k zaTu0=DUjKI*-Ghwo;@{bI@lYF5p06V^f(xwRM-L{nZ@*E&nJWS{l49XpPsKuTESSj zy(jm^0%j`4&h-m=b3x_X@4Ex)ho=gHt@vjT%JcN_yb`V(^L0HMm~3>D zPTJnPGMV(qs`lPwqt&$pF_*a30c+1P^mZFu$9}Ne9&mY=N?Ng&8|4w;D8YlI_K-GyOe(0pH-SuyYROuDu5wPl zkGG&8{KysDQp@z44e|3_<4OemlZdtc!7J&VtI2-vj*RS$S1UQpZeJB?STN=V4NQbj zNd5O>V=_{Eg$)Fgb5=26`nYU%zMs>pPa0rFEhDv#$+Da(jr6Cn4uYEp0tb*fF>1(d zIYZ4WWZn0fSBttBK=a=`kdr1dQ&$%Tws2F}#>yinlSz(;x4M5&iLchXrsK zSb0gpo)XI$;1i>h5Tnz`3ss(c)b>=ie+*fL8k96`T-IOXDwR2FcN-jW_N+en3r} zOr1_xVUd)&P4HnsXsQoXN%N=%#*DgI<@`8ltvljJHI>J6qdO8_yu{d;sDRL}`o%ad z92xOioEo@BWv4N&qQiEr+t|Z8XTdR1228ixF1iF>EXR9(e&@BsblWQOqCf~OM0eWG zulH(vKF6cq>r-*b*jT^4q9jd%1dZ1!((Vg{U2g=g)dRk$KnrKe-81XS%9MpC-1|#{ zPP_+hrK6Bax#}GN0NK76mm(x1yIt4F$PGG^CUDQp#SzN^r`k*VIt@{Waf*^-HLckH@#Bl*O0 zkVw37|p5TVsRAi8(UsnuYJNdo!Iz? zg2lEz5sr1=R`=<)+@xur^6za1|nRK(!RB9qf(+L zF*gU@+S)sx@GY-=oxk*=-yB5Es*0XSOM6z?V^Bn{Dk1*zh5SV=xuuk3UJ)b)M^!~^ z68D3SI;^S+PD4m+G~?@!44!s^;9YKP9_;}RB6G3QuMvz1SI8 z7tr%~!m0RcV!uO#SFlxV|4Q}X=KG~*$}H`znnXXa*pz>m<0pSguI>oSdtaoq3P*+P zSiWo%`o&y+2@CDDcpU}ZMp=mY>kl~_2!_F38*QS+3QVe! z9pZq)0wfwyh#9o9y3WdiLhS*Tx|k^aX>?Z<$kKC`ki;^!BdogX z>z^dd8XyPN6tA*?8E?8tj6Wkpf2%WJ`|{x(Ul23cV9rD|S{wciS4SO^)EcXS9qkv_ zPr~X@(Q`6h+OldYMpjyOYAV(=uw^>LXMgD#5;I~WHzg0HAP*}ok6>8^RmRnR3mm^N zxVF_$c!>Dv^}(tTA|0O+12H3lp%Z)%UsP|)nh-1ehzsOE04k#rdWhwqqcV&o>mUOY za)|7XjU0r`Z2AzINPq=>{QZIvUrIKj!`a$dyU!*(-EUxS(;FCI}6RA!$WjK>%zjMLJ&(&$N}a~ z?NQd%5KPE6X>UgMdCb(g!&3-_S9o4YR7}IqQC-azZz;W;__rdtuEv*pwAGCTn@Vsb ziZ0eA@O@GgX!?t{^Q=FxOOv|8OqoW!g!jLbq~)ny!#f~|U$0|(py}6q2Z^$`K0Eix zK954X_!*_!*&DHiAE5X)OzBpVNSxF^!aM>eZmsREeACdzui(93<8t8!UM$zDjsbFl z6Vl0V8ODX4d=!Dqk@!BGFFQ976(xJQ5BO7XA^n~!VFV_myIykv4HN_UG~-ur!8*nC z!)VuBK*08xqiiE?#@>}3VzOfh)DA$cFx1zt?r!x40elF05UO_~Y7mciBHZJ?2dnI& zqimvWaNc!S6&xW)t{4Nf;aTX-%zaXQL5d1J(&38IPlEb;WIN>)7(1C^Qt*JvMu-d5 zi0oO0HH6b3Oa18p8b*c3NG2!gLU#luy%K5C!4F942BW{cqhxq6up8v)7F$~*GbDA~ z(QrLhTBrK~;$xGA0ceb7rsdEq(_^0V(*|=3Kff-ORMh*Y_@9Qki+=(j{y!uIl0^Lb z_@B#^zO5GaoAk~Rvb!L@p>RO2sMk-o|Qlq`I zu3+X{VGg_ITkB-tj}G4@ItKUTR|)BZCixTjI!4WWBuObD6t4{~gs*&ua#DMYFMgVd z52G*ft*+3Tu}5aiiR7k*tkYgT(H4PQu(*7(V6W5-rnm{!KSyxDws*txVNsq!U^xvN zE5Tq<*;K#hq&Cpt#ja)EAMr-+Xd=K|oGBlPoCRI*Bk53tt+8vI0WX$o=Dq+3 zDgN1RmMPD7Bg+;GSOy#!-wvb|b;vg=H9Oz4+UZ{DGj+AjF%n09Ws)Hc=1?Cd z{IqFz#6V8FK=Dr*o^Mc4xK6ueHgt1LSxOH`9xhLSMpjTXv&kep$4P12$_kJ{{79{T z@F4!7@)~0YfegHC5yivE=s5AbQ=)?UzI@?hUR6)VLJQ*$m}#=4De_FZ3c46;v`fn| z8_GErZ>x_x%=ciJsBdd)J$-jJ-M7$B= zj~q=g;Nu%$3%0GF8!KD?(9#$??(ocxTc zY*KxQ=h2qt&AxP@JpmS9DqRm$B!a_N#Ov6lM~KKw5r|KMMVkO>7YcOW;_-*9z zN4s(anDvt8lPl*h@>g_L#gz+sG4==#)C;=w$TQdM ztrzu)b)0efR-7#bDcWGqTu-=Gx^ENBY=o)%$E=`F?LU86ia%i+I(SMYJ1HKEkXZ(8 zNpG)5&Mhz+&qt%$t*cnRw2{gGpl&DJ|2a+Hxqf!*vQ&FkOlC6X?X2gNfpYnJyH>Sd z!}wcF^^&tQwPmm1p%}hMBwF=FBN=AW#H;n%o13rb)oNqb0oMB6`~10P^mM~JuZ)NU z4Us3-HD}!r9$(^pGMZObBHoMDqubJ8L{o@)64-go{q@R$dnuMU|013|bo}_Cke+-K zOz8M>dfUcZTbEsSflS_hI=$6Xnt=!hG~0WNexcY*^P*deMV3Hvb`nC;=_xC0rDdy-OfFrYs~RG$$sUUURkW!#DgkAAS! zzLNt=c1HPW3tbej>_Eu3x34488wQ{Vgb>r4NN<)sHuBDw-Zg~Ab0}2M#DSh?5t3?| zA6-AVW2D7s=wQVs#w1}yC-#A!+6?4)>12Ml5*{K2+8(%6l33z`I1(lpRzAr2!TP@k zzq;os|8v}%^CLyp65O^r#|WUdluoePuE_K2Cc4x6e&91KzoXDZ_OSmUYS|7-BA>*T z1tPx1A4U260VFG(WN>FGcEoqk>0qIYtA(}kr3rq{j-h3qmyUkLOB5Kojm1YT=Cv*r zFXfUw)i|!n8dMcL?KvUm8^q723SB(E%zwdo4oa__hhakaN<_BQC^20wwn18~XA##B z^hD8y4JG5`69nwxPIp1(?&6XDkNEV-Z+tpch6dXly0$@rybpp~zzQ8aVbJ2O?gdH* zv2~-$oadWvW*G&O%(@v>7)clYe0#KT5=#>n)vyWrv zoYZnF^vkBy9*`_qan=T##zgjLos5M7`5y5GLL!FoK;~dYexJ%WL9{qz0nZHsQ-ql} zMy^KsQSHWSt*T^6((*>>xf1rhde@jF1yB?0pjsB6hHUP;Mf^e2F%=8isb@z&KCm91 zKJ{q2I-tDHtgh405riqe$=Fah>?`oAYH6A7;f z$pXG0gnrK!M>pSVTC@NK{KR8Kea1SCplHVAmAAr!1~?3yo#lAB!V9|JkZ7fUceDe!^|}l~A{x3I1`} z*B!bs8BNWlma+`6SKr4peQVugEur4JFQ=>dVj0*kv(SSCO;1qOZ64HU4K?fKBUil6 z$e21gUUTR;UPBGqlz(nBbAnEM!WvP}?!0{v5EWPnfJQH8=#L+JVKL5EbGPG`u8!}f zo^V)OrM^UYmL=|Q5s5t`K}eQ8W%c#(#jeGL^H1u+=~+_4dyM(#a? zU2awW$UzP)bFpt>J_kJ`g*|q=+k+zuN|mG*TA6PM9S(jpc}I}?O^BG%{@_|`e~F^V zcV&2qwD5%nl)pkfIm`NSGXVwl;A4F`7B2O>Y-amM%@q2}ZYm~%Rs1)(6CI=q-*pch zPqLbp1sBoIE>Dk%5MB$fMy`hVx*Cq0I?g8zh6~Fd?xtS04gigcF zoGTpU1aW+5=ao7Qi}DB*uo-c`M!mbGcS*nWKIwZ8ku?FmK7|3sf`7;}?{o-hB!}=& zzpuCucC;s$j9Dnc$AE4FnG8da(R?u*)Oz2P3k2JOhGqGQ@(R2)B+v+|s#fRbXda+( z{gR4Jo*_H`R*FyIH(!gcl^L=s!gliG>jw6lLAefU6fXr=b(S)1+VwfGU=vX76N zMu%JT)a|=hO8`CEP^y-U`YTXw_zMnuZF_9y@!?<9CWdT~;^AB4`GI8I&iYuUm`JSg zV)8O@jamHb>Q1bypRj(Y@fnL;ncOHAFKFS&LLDDaZos zhB_kNgvU3Jrcr@vQADQo@9(h$70-Ixcn;4s)3i4}eRdRlF+Xg2%(fS1qgFUKO;T?J zu7}GT9+h21%CC(-(3v)dh7Tp64?0g}_vbRcTApCoDp$wNRC`57MC!x0(ZchEKJ-hb z`2*ZXkFoF&P7>rZ^bVXZvz97^^$$JLH`9U#w!ZGs5jy|ejy$8kAzKohHLHKsC~T8a zfAX^%_6Y7ek+z(~h|T(i`BJ;mi)7?d)I>qSX5F_Wr{s=-kM?JKd|F>dZ)wbDIr=C* zM)Slb0rNqvCocLxjq?Tk`39W>nQpR{BC>67ARAC6QpS1FVq{-eY6X6`)oa~ASzV7^ ze)zWDZQo_#{wk*Mu9{IL96PW5b5MF$c?SkHi~C%yDe!AZ`rg`Yft>|6zHJWNI(o;_did*dmq0=zwk~a*$Qk-#35wU*q5QOPeEON-%RJXhU^z-Z*F07q*CfY$&N+?u z?ZS5la9xQhc(5O?Y>RY^X7M&y#|wITLC<}=u!lnw`dN9#zOvCZoIQzl#z*5FDujGn zhl`r{5e6ls`bz+gyh;+HRy>U%oP{sS*Swl?5@aZpXW^7RF8@`H0ud_k`x)IDDs8Kr zp1Ih5wO@5Jda&vC$)o%H$X=hfH5}N$-O`zKv+WYn8Nu&lw*zadp5UFJ6|zaHA^Ib$ z@R{9PN9pfhvXG7>L;^M7t#nB#$Do}0dXH0zWpNs)=3nv0i1E`4(7v`3Md>yjA9>*~ z9ZioTJ?}7rgiih9%eZaKS>==75G}hePZq7I#n<5rH#*wv6?crMRm`=gj&JOF=DzVi z(m;><5K!?NL6e4%l%|9_iuQpHv*Nb6E?Ro~vRIKOKI*CabvExdbRF;VHU{%XsZsJ% zG6b?YKso;E-Y2~iF+&J4|4@&J5F$Yb=iU>LBD56OPZ~Yg zB5dgJi61yR_#sqKje#B`|DtzEv;ZObJ00uZr(+YlU)k8uLRxTS7A&<^YQP!@*GZ&6 zrsnM`m^t`w8u^63HS#)1_>nDv_no}UuTEb2ak}tP=gk_x>`dEF5?6W`OlzTG9O#|+ zAHtQLhhfua$p0--K8k-W;;3L~C#_+qU@9YJ$O{?aM}S!rhdM^Ux%j}?2Df?V@BxfY zH;~VrGSzq&V6e7P5?7ya-rmVrg#Ss#(sljS$$!R(A^D#uSleM3|3Sh6SW4cXl(jd! z1l#&3Few5=_QIp%oWHBiw>H1$UOX84q+Ae7H-rN}hEQ1*2ONH%7ib#p9BIwXX2vPW!M`$oxb!-qY$p71g&>F3MG%!yL(2G!pJLBNME9nE;S0GN!d4(_8Z!qTY;= zz6^J%a|aHO_o+wXB~A~7R4ypK&LBVTrJVK>`hG3;B9L;y&VT&Gav_Xr38Z`sF(Lw| zeCsh^6TL=&CEXshupG5vaSjWAE7By@8Ic2|d}#Ipi)94B?FCw=Lgq*q9`{1nRM=v$ zWe-Copws#tcNheTe6!XQ864Pxc z&x`Yau|I!=Cg(3RS`-VSt!Nv$aK8__)Fa_zpH|J%pZ`pVm%c+s);gmD9o(~lrR4vH z4Ma%V@-b#&PX1^c1nhU(K;o;pgw6vCM4OOPPsepoqkhKBP998&Ii66EbTRN z)Q)G%s|*CETOO+lr)zcxAJ^DLWzxj9JCvLFOr9p`u{Q=5bV>wSjPuW`7t{PSByampP=+293Ec zw$6mvueipwWze(#GxAG9QTZiI{ssJO zA%6nDNC5N!AWwQEqWCXr5n;FT@#G3`3B$_^MriC&NWMhO>*jwFle}6e%~|!laW7YRS{-HmoW;% zxc2*8C(Yc&{3Me<16UJw&s7V<5!&0>biYTlTY!A|i>>YlI#?K1>{xj4ua4CR>rZKA zs2!>G0ZR4v6o6YsISKqjND=AvPeT43InTXe`5>);wr&6g2#s5^|3C>ZHHQ+k@tXz! zyl|-?GL?s%#u52tD2_QBTgKdtH`o}eze}c`0Y~Byh7wf$ZUb_FEE8kT7E_p=p;X73 z_0!B)%9Knf%?w<=x?}wb?T*_nOm(ycDW}J{5RnymPGHNde*&0R9oXhNWLZ8IJB_pG z<-R-l9NsQL)34<*#sn8!bK~%aH_7fqkBJyNUKE-!-AD-++3J)Mog}@yUTb{zW*COE zDnmWnGYk8!!F%35O4TzqM=chgF#NX(aY(pJk63CAb69ZU-Qho_S;+Y@b?yc+vpEal z;m!y%;PbW&uT+(sE=0-ssyevbOWzZ-?dXa8yl1tc5+SOpn~34{ z49GXiTDi=I-O6c$PL{!C-_36xp`06YuQAVlpHRppt6zpe&D>{ae`KAX)z&z7=ax+C z64v62gA*4*e#Tb%K}M6ud74B{nvcg=q?< zvS|B`ntH%5!YLo9P4-xQ&;Ul`Dn{VLQD2vL(wsP1Pi-j&EOy{KcAi}nIG?Z9X!;`M z@PRMLN^Ktad*u&<1+D=0Dae$GLZCybK+i_FtLlSNx=QjLBh(8d%{(*!*(~ zi-#MO`9$>6#dNG}q`%FkCgHJ-ypcVWd1+1mVmyIA+>)0W=3`m_p((YH&+EQhA;u~C zs{TY``eXLa3y$lYJZP*`S2qvKQ)#n`G@1CDLAO}7jnE1E5x0soEkk3@E%$NY$l-+=;Lb(_O<2~q z$~TnW`)^0z0(fks9|xeh3s-_M%0+q&z8eDenr|?|x}GEu2=xU_fa1^073u0*X8cqC%{9k3O?t}x3C71m zmF$Wy4ejS*V6Tn@hXdw@NPy_I8$_i6_1$6Y5MUp7ebkI-$MtoHfjyQcpTAd8Hd~66 zXH`ntQat#>`R@c>qLlN8?;Z9ZeDD5LdF(8adNwM_b9P_^CEEuCVU_BGOF~u^^}JKM zxxP1v(I~claWh9~Olz-^MQY+`-xHIqrf0Rl+VY%PRMgAF-V9#c-}yrh`-*xkL-RlH zJcA`mrTYDy|9STKlPgp2ExA!vh^C2*Jb>XB9E{H@EIQE!SzP<%g(XFW1tAJEO>@$& zw5l4mGBY`?L@-(cT0>8GY~~*rik=vl%Y)gT5VI+IIoaIqArtUr^yEg$?pu$&-pjAh z7;gqjGPqKtCYJiX;iwOkvXZ2Y^Zjpv!yjh6wXUL=FcICpfUO1d{_vr7J^NNut2#^U z7dnkCJB`irld+0Kbj?|LpYP#*%A%k^qa3LN^QlU6Jzg}SbH3eY*7LKe_pch@gjmim z`bHZY?Ur^N<=-C6s=rTE>GLZ0p)24$z~zW042Ek2T)VM-9T zu72Ti5PFFhCUjO8R@?Hn=X0E(ZYrftpyP8))<~U}#OhP)QPHPjwx}*O(vGT6s~=R< z6k-skw6U?t2Dl-T8hAKE&Mw0@zWJIE)c7Vc^Hu3+cs#FGceke%;$rTn=(hZrL7kz8 zv?97W5l+0~gj~2hdcZb5?qB2b1}4X%Q23!d*A=pMwOZMeob8g=8#$j+#829@-boSc zSID zT?EQA2^kanwa9}WiI-;O>rQS{@6jb%xiEqvHac2O%R{y}^&+N#)tqyBb_=>uXtwk3 zxi6kA;o~fUnrqfemL24`2prckwsui6Y8*~p*z0n`)xP#XU;YV=w$%;F)*E(zov&-5 zS3d-LH5I(A??213zZ|>qo~ANLMJ+BQjL-q8uMb9-iK6d0*vtmbYbTWdeSBpRQ42V1$=&yzNJuuGfx{f4N$r#AKPii)G zi??cuZxSo+xy=W5G`d{;!95uK)n@q)k&*rKHtmBa?>tX0+C_aEKvW)98b@Vh8+X1C z_!)1AToJc-&#^FD0$#5UXF(E+!=F}Hv`Bq3?`rHxeybboX9s`@^WQ6Sf7wxy#>{+j zB9KA_jlIfX;VcbZ!1?P&2iTDiS95DYM;$RCJ0RB+!<7Ddf=c6z7Yx8Li+(&rq{k5I+# z=Y7olt5dW#;_lq1;rH&-2&Hp+f50|VQqaRpC++kAD%U3^->1-3!Xj4f#nE_Y>shaY z$+>s+7)~MoE2<>>d@WoBSbezh(WEX2dv+$82c5Rf`Qi;0rpweT0p2~ndk++~YTJQt z-5#C!+vq{`gg|6RLj>S*1glBV?bYf}9Vozk_LBG~Mj~yD)hA|5F%z zbWwnzfD2@pzQdHO&fXpN+{QURO|)-CH&Wxk>}jC@vtVF>K%)@M_dSyweyQOtVbI1+x!+wPbe& zd5EC|JR*koA;V*+iflByN=$joAp;7zAs9#vtwc(XU^PCtM|$E?IdB8Bh&~`&mOGo6 zw=okku0xX2Ogmr=L$E{tc2ThLUz+lozc=L&%Q~O4bXV#^ao1oTrb3J0Tpnt$_&Hod zFkI_9JoXUR9+Y6$IDHRXsf)zYpU+P47zT`u1?#WDkdC!G$wv^G{{o)?!wz{EVF@pm zX4RNRRZ{4KOUvqO`=Rq*U?j0>^`Xit`;=tPuEd`+WZo@$v&KCxqxXfToO* zoZSW%m?=vN-BwV5UvVUR_QA6rOg|nV$|GZOmo|1x{yA;jnbxzT7@11-d~B8C`nNm}DbIOcCI>w&dlK&jQX3)b?vMDssO4a6Y9hgjm=r}* zfs)kIy2Er2F*?LjUSVS%qM@b*0J6I`1CU)&><+S5AYccc#}GMxhJnZjU2+T&HTBh7 z!Yz{S+hsCd{Xy(3DbWSq6FV&qe*0^%Eux%b+~SR@rY+5RCgzu8ZyG<^B$Wq z4Z$$ABCsPod@p>BRL%nu)ezJx)E%IF8T{OXK6|;=kHTw!Qtua^d^dQb1X|MUXIK{~ zsWWSIBnh$`N(ZBG|M~%wMy>cD<8G7$=KkR3Xs z4%x1OVMjk@A8GXwFfAPgn3X1dv<@0zq)OR^XM(Lr06F5r8G7@72r}k5?BDijum7uk zTJ#{Gdv+zqLF2sgmp^u1ifLZs@3YXc)eboL=Dgl;Plt#^MHY&1{Jomm@6*mb_e1;# z_w)6GQusahBdJa~nlU1EKL~BlA@t;Z!v$SIi6nHiX^XJu+_IOU_7R zh#^E-%uzzeO3glxfjKwQlOY6*bI*BIq>3<@jYY(>XRo3JUrY`j`JMHhyHcO$isN5M zzq0Wx&1Y=nFO|&2Ar@^y-OTXIBSnQrWktg<3lK36q(kf-WSg4H_iONx0tnCc6#PI% zp=2eVW*?x*QVfWt49Gr5#%0Pr4^2LQ#jbL*38+escILpc0J8*!4xTV+UD*&=?}b-7 z6BMw|vt#VcST7t%PzP%32PEI8NQlLZ9Y7L?nXgf-!zBt8M3v|ph`m3$f=N{VMJ{ct z->;t_S&ujwP@(e25X~xrvCb)y=FTK}Tn2~sJj?Q(C^d#kh12$wv61#cK(sbGKWHxh2f37UzT`vVv=9|NpzAXpyZKRG4&70(2eGW`V%c`OIdu_2+s$S_ zuITdY-N^lPr9W~W`I_6QH z3_o^7e4$bc+eco`S7JM@^-o&UHV$rNn=jY-YpY*Rw<@tfS08eXGdPdgJm1rO5?9j6 zFi}~1IM`kCaGyb>Op;`IAu>=~{#uiy-{nMroY^zoyV4p*Y!C&DXres%P5Y0ol0gB# z%>YdkbTwG$W7#K~F{};&HfD1b5#9J8zcVOKjKGh)~yF#2XETbr0H0bY)4e z*~Lc!3vQeAnkM8>tD-Eq^z`jADy%i=^K+n!2zY^DGgG2E zP(Oc?JkNvpnXsHouIdFl>$hCXYVn^=!(X_{1SUK~dpZ42*#<2-{D-E$jE~TeZ1*h& z{0HJJG7ia5h+DN0JKkhkDoV$O@Gpw(GisWB?A6_d2DenqrPr3Z>VWL1z>|ExR^qpj zpI*9qrn;bZxU7w{B!=s_2F zIE@7Gxe;D?0xbPDR@!v&A8Ali(Po(Cq4U(&EwpFPL=khO$&@E(@~#)Xol+2p5?fpS zf50LZ+7B6{zS$|TBdFhLLJ;OVkfv!sz#@~tlnf6-2ep=!^JvP{a!&j2tEMHauUubT zU8V2jKLmktGYLfaXnFFH=u2*myMQ4-fuow8dBrbNjc?L7_#qpvC(51WTn}`G*8T119m1pf zIWe6+5}G4R@lUkq(UP3bN@ZyCv@I>f2v%)6Fm$ZV@Sb_@8@UefBPDbnnw+_olr@f5 zgT1cTI38&;&(l{+z^M1WGbhqqd9jksxOD#Z#^vNAG@(N1+)JFbh4^z-j8J+Swn~7= zE3$y7$(-2W^@g1fG=>#O6iF-z6B;2+7MP*mVxL-}s}7_m|E!EufbKZnz8$*kN-v~#g>{ZpT4@G} zBf@LvtF$QJecQqNbJj_-mm25BubYP;&V*vlO9KJ*$&ifJ;z(VEgWta;aB|DvxSqZGwABH zK$>Qzxu)69UCVpjy4*mx!JDSah}Q6^Mq&KT#iWNG*7E@0`B)tH$`qhG(t&+wNw z=Z|eXK8Z*&e%?S=nbF?VgkVevVkIO#h9lcBYRQU#lO_dx@+?i>ArSwufFU9@0t>SJ z&cBBL{z0=QVH2H^@8DNsTni>kLVy6%TZ#LI5=hLZ0e?JQ-os3L~odEOnC+lP{ zGd$;a&LM-pkglM z21cy-;ej;X+LnP2vAp_Ehq(Q>~~2N1Yh4*Xh{F%_yt-1>+$md!+PFX=)N&sY|jpnW&WgI=tD{Z@DW(9$xuZ3#6--)acz04 z$n=@)&$8CA@0~8?K7D4SQTL3{e;cFd_Yrm(ysIQ=0g&ijfS-{fQLzJjSZA;Rz-H;z z2IyNO;rCn^^Xw&5U+I`x+o_*EDdWhe%A{*-;wtm5JLF_7i3Zo}kkbfIKsR>K@r60j z*U;>bH5UfkJG_Im69q9E|AwxaoK;okJW6?PC)er#fCBJ+c{77Oo5w8U3b)e z9r@D#Q$O|Hp??A_aW*NMz*qDyht8TA@aM$uWj~t$7JXMB!f`$JUnls z4-sm&4SQsdktjR50Ewp0=e2(|hM3+E5B#Q~v-5<=T&3H5v^IP&I}FUom~QUa6!ibZ zrj%UC_k1)KX4VUmPWYeoXR)zwAE(E7cl-c1(>BadR=&KmGt~ojrea-cuDibE3k$$< zQcC{5p+9&Lr^}uz-rl(fZ~^WTG7a4R3gT`Ssi`tir~BLKRH558!i90?J&1LvAWp$! zoeC$8JvZfEK% zc1G%X({2~y?vAd~*yg)36La{keMMH~90hq}PP$$+&+VNsuDE)2GptUtKjlH%1V)aV z=4*zp3?H0SVm>ZbMe;Q% zbZ7E}dEO1QEmxwK@G7TaGHtqduKVHJ zq@}H+xBZ1oEdPhLw~VT)|GT~Ekd*E&MM^}vrKO~#8>G9tq`SLAy1N@Gk?!v9hO;!cy50_C*am)!?gbBI72vZ);b$HJ!J269XQR}&Tt}#FN4~TFq`vWB}889@onB6M0u=KHj@8`idgzr z6FD2>@sCxymkAnn>H`nj?GL1Q!?Y+`I4|_-lcvYJ&M^ar^Gi}jespg>NSP98Rg&AfrD zigmcb&kftQ(*JG3PxbG!`Fy$KmkUh5pnyDg8+kNG*5spjIbo-b^>p@F!^q~;JKe&) zj}ocr;%0SFiQqojC>3y3Wk&Q`m>pB)MSAnL_{|Fk&0sIjAsTgAxYZ*zZe6zDEjnom zxdq|dL9p|DMmqDqMk@?--A6rRNDYA&-=HF5hGWj(u&^tV1)LX zkxE2Ol;}nQEJpkhrDWB~>t&^jy%cwnGT&m;cG?4SaLFE~!UbqH`X&A=3@zvnJaEmc7rK)VX}u4Fm(lx;M&20He#5a9 zub(LGdrgr%u58RCbIpCqJp58vrDgn;*#lA|Ueba|t9D#%`6VEWcWrQDA3l&+X`IS8 z%G^4&IPE_!>G=}hwnFriiGmxmyqW1X#a2eBA-E*V=4`}mtOn87o~sxeQBlEKZaRFw zNi;@Zfmpp*I|ZGt%xvFbE|oGb;=CxFC9d~oqR`Bze^U0!MQ;!R$@QiVf-Kq!F$OK;u|QARCbCIUTALk5f*4dE$h&4#Jl8^2uGCg7mi{wu~t;s7*M2ozw_EP?^_YQlp zyRpT7oz&i;wQ{~pd2;V&IkWh2-@!X$)yEayu;u}`0WYc84 znBmRph1(LvF>H=E1q1R3QFy3Amu7guz&?|sCa3$>G$L6!`-8pI_o1TcI`p5cHHgiG&a+tWB-z$24_W-^Zi4Xn(LUk6@v;VX1haHxPoTT&!yAJyX(8jNxB2KyUQ1bKB3w3nh(ydLlA5y z%HVLGgB03)oR`KSiJwa;yxGuct3=W~M>Ar~v5Us&i%@PqCVyO+m-9Q3*vS?ja#_*x zUyrV4wj(rMDB@6~DVbx4W!Q8%X2on9yL<6syDwn#fHskE-;vle%JtSQN^o)=9x3m754Jy*-*(X7YT|IToD(NQdJ*U6 zi+)1TUh;9Z@sMJgQ&rR(x~9U((N@xT#-zeRTXE)bYR79XVNzvoBsBm?i>SH-EZAKNINI zIYy;azEr6G@7!Pmm)98h z9*_k9^Dm)YnLpiOGSE@H1fHWUTK%gwm({;C3az@8^FSw}n_DrW8f}?knB2{l|_mgsj`dvz>1EmCV>hAHTu(yU*5Cz$d zJ17cR5|Z}^)XT9C^du1BAG9q^ooEzHr{7O<9xd1(fn%lKkvU_*`iC}Otw2jP)D#&z z*;Ny84so-mW9v1vOixc=n`~NwguxNecF?1hQQmD@5omNy`t)*W8ZmIBwm|5g_Gq74 zm0goQI5sC)&V^To#JI0oNI<x4 z7epR@o}sUL3^KJ5%(itF8?UOmTQANwPr5Mkc6p4c#@r&~B?u~xw`nh8`CQyqk3JOh zoz2xY3Es;GYn}Y4H1{eUtY0nGuBo}j7^UbujDB~H^_XlKehZT=(=twNx{g_kmy~Sc zw^}{><35#odMR?KNO`Vl?Am&_J(16e^1-LZ8QQCH_mI8J1?TYYL?q-5N?!nDY!|g zUWJlYH#i)j8L#|ipqd&`(9iaNdQs~<^wqkT2*xZ zgEB$>sLIxqg76obY{QRNzCV@#^@}vnF(Yo$hOdZVIjpC zqB6VWMe-DrTB0?qC4E&ZKfnbiMY4}AOV{rZ#kME|R0xyiJt(yTKG@4IuB)9nsw>M7 zXjQ;}O5oF(xYqDE&wDqD#?6w!a9eSXwHr5ycrl@!ZI(F0(;*=n*qy~NaZ(FNrYd-l z?w;rllak=mm1|2it+#Bgw{Fh}I`SbZy}w8{K65HkW^RD?Km9gda>oeEez&1bB_wv_ zMY(k;TEar-USYvSOc2R={m06LO?XINcC z^%iqytMqu>4Btgt(nxfs+27DjP2ioasw;h;y##Y_Qw!kQ}+bF5eh$@cIOo>axk?6{0*5;--thT9mKQ6W7u8ta2$9yN+E&~)Cz0( zz!|LvW3E$1DA;pR*&ilEg#{^a`lUO>|>XtSk^gath||Z~E%&W<&AXNb zJ(gD+E|^c(-PM6*uMwU-u_0_AXW1v{Sh2g&7tL&rh}#GA5F>V#+H-$If+Q3!S;%fUNgMTFNMNxHl#YTQ1nO+`eC33Q*yO z{lvL>29!^hvWJy4i%QVL|MGxxpojfUfb`;l~Gw7eSY^BDc!m7fv0n0=r_I;!;Rtina2$ z08ob$rM~T^C~Y28U;Q{Tw37SK<#XC~p$$YZ^*stEcxFS@O6g*gXLqpPXcOeb@7aRzXx}ed}zGeCRpdiRk`{5t(ZmA%9pVx<_VcKNE*lu!O{2f=CurvhHYZ9&p@HT$B zln=-Om~?85em=lg+7*kvbj!35`?MhHsELa;_swh{bD~+w;-yVaFo`mb2L@3mPc|&m z4=qO~j&4%fnikArtw|W$qL2^|2CeVjqjKYwi@2VG)>`>&mNs2cXuP(vWEf}*QL^Nb zq@wZ|$or2}3A-)ne2>a;56bvWl-UO5ov1T0BUV&Q*7Q}(jJ2fUd+YW7Ig0xf`IWe@ zjhMY1(+YbK*=-xzTWUg#@Ll2*G3}DW6n{c=22k~_qwC9Zntkz3E#f4NXBFxDL8tdl zYa@)Ym|bpz)Nvwq=W8ve2fLL}tqho1w-1T2c1&DWKNU6rl*~!9>xS?#{~;&;wlE@6 zjw^LqNGG1unF}LTACHhmxY9atf2X|1w;;&ON8eeN65xS!k9jVSDax5Xld514i@zCA?odPbqZxM+B~`Pt*bHkV?9CYBZYxd6}c1D891t>AYh9AowzW|8hU$_I?O;#iCG7Hlmg8!pCDB z35sRe%*Kssb}?;<-__I<Tu|3BZa1N2Tg*c z1&ej3Ze?16GRLh&`Un>4-qR|xgnfi(584Q!2FloqyF_zDa0TxS*$nz}s}a%<%%oK? z4Sx!%)14&@!WPWQ9nBns1qL33wAI2Lgd`05od$XZomeuZg5!n%&Y5Kt0|aAa5^n6F zL%9`6Z)6IGBK(O?7$xV$IS{B5?HgMrH_aYGDCJ<;KcTLUFtjeFp)lO6*mGhHrhLnM zmp#mtd%5al_pR`pW;iO&%3(>pzo*4mWa+$tauP^V9Mf05>~tOI2~a7V+DLRuRu*(q z_m7#LuFomRtk=N8DSI?14SVpqf?pXuyy75Sdu-{JeCRpt@(~z#6m#J&W@@>0D7mAz zxtbqa_Rw|XegOS7OB{Z}<)zHOD|<1HQ7DUchFl^p3sa{{5&-)d=BMLJ9E$z!98=p^ z9jhavPD0sL5mCAYPV`2D<2ChV-l8U_LQlKR$rYg9W=>>)VniaSSTt>>t1w$gOoj%T z8U+Qxx%9=t>sS@pBj0=_{=FZLgVQ?~wvkL8DJ9ePSQgj%5en8-(H|DVZPu>ADGq7fq;g^no1z`t?2=PZ;UMI|4br~Lx4wS0rt83{ zy5Owpv3KCQ{BR&)#asiw`2M)7E~2v0nQU!c)3Fb^Y1A`CAC{~8`eFL~hKIu*;t=g< z61^?Nph3>AXtYo6}K1BY|j^YQ!=sQeOw?86`Q zm)PYr?+;^^;HxT*P@BR%Yz&#R_8Es|)$!XE92|bs7mZpu!scv)x+0p61im4onvaZ) z9q!31;R3z05uoR^t3s%8v^jDpxRE`7)xhNhJZn71HQ_Kh9a)mtO39-uv8i+O4|^3) z!fh6~=~0o-8IV`WJI$EZRqn-D;D?+#ouh%_L0kvQ87FCM~|P3eJ){261U7! zM)COf#Mct?Cdy4>In8hp4T&dBL6MYAJKlao-@Wg$__|6?OskgU z`s+l09+Z5_Lo+q-!Gb|yBKWul0(7);s2#zeoIgI0F!XluGd9d;i`6hj9>{J5dkM98 zCLH-tv&HrWm!>bGM2vb*JiW|<87K*V+819|a+s+8=P6&&nH*Ou6)d%+R*N~aW*}(zFRoRqLit~!@NvXY7(_LZjpwC)<9nodDpqdD7_RHbL)A{X^8@fWb zD<^@)4k5gn#6yW;={A0|_sCXZ3uNBc!>W-P6k1uZWTElF;zFgZhMHc}5DJDc3QgUN zdyjdw4d9*@J=fRdqD`#=DlzOW^_36y26ZQAYTF0kE{M_zR4G=Vb*%J+nmuGJROWC> zcD9WaSNZ{}S;;&Tx$1dbE_A!26%WMZDlJ1D?^f>a-Ntg&A=^0C?OO9kPfMY$FrdXOy$06ZdkSs=!T_B{d@R8*b&z2Cz|53;B7g~#_5TtScpiV0s71J zg!Fb2yiY~#oz?V@cKkm=yg?n$+TT3I(kDmOf95G7O}k9Bi@}gLK6y*-JR_d$B~P@% z);9BJ#3E>)*z2c|feLrL{}H+S4}69H6?YeaTA`WM&WVfEK{FwU0xCXa#e=ecb#DR6 z5dLa4p9H9Ef5|66f>rpAoMF~K%JlfwbD!4cgesw%*)eHytAF#mOcwsdCw2Wt_fe(Y z*0n%JUVeKB?1_=Fe$y|6FoC5soG86-CSbGr?X{X+X#EN@f4uRp+O5Q(g4VB+99=&e{aHr_tz!jTFW z-Fa9T(!Ehp`CSRfIKBn|9suz!D-`5ctUTgge`%38U5+#2`+#}!i(bmmssTCNi3rFBo=Y}3=52akujeG#GwCsfY{dhm;Wsw`1E(I>r{oDqQzW)1f1y6eG-}}exlBQ z6O)SszU!lg4P*-5j{lLu{1#R2{w=C}xIqHDLqt|Y^aa)l)Ube~PUe@RE|@fL{=4rl zS0Lcc!*RkH)Gs~49@HNj&`*Raofic-M}M@R#sq(BKU4HRT^n$-EwCx2{>;Gp^|DQI z(`>2#>yZKf$0HMDe+CGHdVc+3>wmB!e)WSSitqT^h4;&f1^QhNhROzH6seuan*W_Q z#up2~mi33;%^3S^FGuY3rbZRLqGwp!WI#qI^b#OsJ>Fmyf%J2o(Vt(4adN^f@WPB6 z-VTF;O5Nk#a0Fz)fqJyK07mx;1$jf2f~;=;BeI>>z*8OuDh7}w*Ym=fi7pB$!wMx( ztR2PbtqdQ^D0bQgD>4k-lMCtjh614KLHqchZYa>~PdAkR9jX4zlJWmtZFK+Fdxu8S z&n^!&U`-3Ax!{wHAICy|0O2)qW8FKEyOslxPDbX1&tEY;nd@`1?nMf0skxt+xEbX@ zBpjTyN9f=DZcgwi)9j~J$Zti`#nW10wuo%!7e0J*a}ARLz=!j<@$`Z6aaSRMk47LO z-)sW0A5Z*~-?1Manq#iyxp*Q_(cs;22VEGF@Id??#OdajW`Kh-HWUjTexeH<;V|~) z@Kb_h-og;42G`nbUHH;N=-cs`I$y!ry3BnQsGXqU2z4aqQcC930Y|`N;IPhl3u9i_ zy8}2$i5$5Ci}$rPTwveJ5DyYVtj!h3BVQ66VHf#sr9#>(1*y28*4(e0dGhk=V#AX0YbP4t|z?Mt$a7=o}JG--!LhnTEle^46dcsKMKV@K%p2f z7VpXlt<~=356a3Bhjnu57g*Dl5t?M5c;0BaaQfZp;$_;^3tgKhH|H;N-nDx$C?lap zzd}#=iQF&q&wpb$5z(njrwmzuJjogL$IgV-egVcBQ$Z}Bgl#hacVDtvBjtwN+q78H z&MfZ#(N@Uxb6lFj&oSVq8_&02(k$Ez;!2+WFD?SmE^D#MgnJ4e?lD#1acW(grC_2m z)Go<<`6V#dp&p=4T)5(~q?D?jiIVA(`^11r3t0&!ffh0^hE@_O^T8jmd#b?aUBBoY z7N#Dg7X8>az??HTp9zq|+&;0prSN|Lop=M2=F+gX2T~=bu?iu6$`cg%!}-G<3uxK- z%K^^JRVjc^e}a?^D5mbLT(PQBg~wyxvNf|)o%EOwC}2X3T+yy?<3VHLF9K^b`xX}9 zS8UCJIc`KV*~(UcpSI~9L9IDEv|0=>qgw7r0!QXaDf3zUX*QKYW|HtC`UMFA1Zjpz z`dNo323@=o61tL77LA`Ty$CSVuVL&zC?u~T;IKcVBDe!xpdoNN-VvbYD;o2X3_D`xNqRt{dlEK={vo@)%&hNwdW5W%i zFh*X0&`ik9I;c^n;G5qGpS%%eKe$`7d?|>2$qawyKI5u1+{`Fj&p`;1WgT51rxi4f6S_0mxJbBf1|SPam*fgKor0|0TP8#p*48{E zZ*!f=--X0Jw9-=4mBMUdMoG1MSJ6-LsDGQN@w9B zps0SBb>m2MEMRfKS?>H8X{;VN+#q^)xpHdiydZam+eI_b%x*I@f3m==xBNP_nwJ03 z04gT?GGv&1!MmM$l21bj%?AC7D!}<6%Fy)D@^0+Dpe6Q#v=PVx5@)IzcJ&~}-Stbz z(?I3B-we?s#+BCc0?{_q7(_$fqNV-hwd9Pw9Pw@Ztk2QGjzD%3zb8{BrV9nrf>z(! z)X>6qNATeyy6m{X=cSHf`U$IaS0YHJ%^j8?(u<}(9e~hJeiX45+bZcU{|2Eq16S|7 z9ja^+4-Va}#1yO2c!}dtYk{v4zO$KtsZ>beuD>i(9mmUS{klD0KC5Gf6Qdg?<4f;1 zmKYH#qXaK-96`tn8S;+f4Ns8(qiX}51V~vGT&!Yg0yPT+F6c^r{^fQwI@HsQ)kO$zhK;b6q}ILW-|| zaA8-#lN|5zJDrVd2|@ndjY z2GB66S0^F=#0e;47up>qR!HRoxqcFwo?(A-0a87_!)L!TaQm4*|2-6_`Jg8kiTz&u zLoLZk*lJ4+gn|80AOQOGX9WSEPcHz1;fOw&yB`5{Lgx9aoL{EL%o5;Ra{urr4MNnD z2EmCDYqn@i^zt)EEkJ0m@dOcNvuFQX#*hj+tm#Fd3k~B2Jh4)$)()=UlV$0~qx+A1 zS?ga+3eU#@Fe$`z|28RL-{8S)tqKAB#9XrM7&1XJ{VWQ7%5?=SuR&Ozx4sC0tZ#%j z%)!dQq6U$rcAm`zTVKDx(ERvqE}(~Jj0M-D^#THZ&hh+U6)2*Po~*OlM6bD^0=ddp zgL(Tj|9Y9J9mJ#v5M0w}CQ$pP2&M`26Cc%lQScxE67h2jlh}IpO4yOpK;AE_~PDY$>%Yii2*1&m_H681&)A+@KvV&a(5a5S-3Df3M$gzo^32G zz8=N=w<%m`ZujFgN@7>cry1TccphW2B3lDmgGmjaj(QxtS@q#0vzhDRej^4b$Rw{! zh*cW717~Pp8JVDT&`XA|XO6tPF%N~=la$_qoF#PZQ*EXkTDjJ<>sv)K7RmYI+#K>o ziBJ+{2t#2WjIXWp0&bSkb$^H%5;+{F>2gO zO0HUTMBOOI(*a9L8fD^mkyE^Y=Wv%cBvQ#uyOTT!bqQeuOooF{2=l_A2#0QPDQN1I>bq^@z_+H&9sG|K&iyAe`_2u9Yl+vlGB}r$a2<~oWDPx{{zuC*?gwRV zzsla<+xqYPpWT^wSBx~_jXXyn+4YzCFeu)@jMSEKsAHt`MSdL_PC_a!2*w~bV-XZoyZ^0^>{F0X6zL?o zdt}a%7Dy~vyynMaeb7Ui+J*j=e1@$vcmeMHyzf$kV~#mC#h>3S79N_zZ&>YI(G)sz$_Q(ha9d{kEKYFEL?qj2eywMj;)wV2SR zhpZ2|aig-uBm^Qsrfd6z2#oAbT}oeSk8yUt!C;e5Du}G5xtVdF#;7D$Ht%3)xR)Tf@Cg*JdxqoME3*`d)YbvoJuB(sQ3>FtlldKu?^q= z(^7M!$1^Jw)en6sJ#CF%q{}MeyNC=>ymSx~KYhw(_D}*OtqbS%||5TMhmd*F*5;$uQh@^1|{a;+K)TkAZ&1$1cYW%R;F)L_2O10J#RwC6g3TIz79r zo9B065Au}%?cu?iW2WS?t}ikGV$KuYgfEQRoa`@rQ;z>Hd{gkn?o;YqD~w^!Z)!16 zTs?_=HNdrgCHf{|FoJ`#hi!msA?2|>&2x9O0l$@DSJ(im`^kUyyAy3-Bh!ceFY&`t ztU7-&qkoS?5&vn#;_DgV^;B7wTeu&w;-UQH0njv#&L_ZV7ogJ&Jp*Mc!BKOkl0mbP zFF65*5yA+vQrf>UjDRW3N-!{m0S>~`6y~rk;;}K|nDlH2026m;-DbePK4|~XMo#F+XN(qxI5+t^W*%m7 z`}Wq86;w!QSLnCc7imyP%1IXMiFOqe6Q2-?;wep<*#NHG$UvXgjr(!&3m5)i?$}T+ z2KZD6In!d0_wVujo`SmMs1zEva*sDO{0D7k`j-e$!Z7gS@DvZ*?pPvZv{3%tz814p zg_e^Gg*B~zRJ@%+fDX!gc!~08;T*%Xe}he4li^Zlf4gq}ux8ZBZS&#{Gzg^a8c`*K z?MGfaT$9w?^WD9>0DJ+4_p}G0ezjCAq-q3VzV1#C(w@0zEr<^*SuiM{XN}R+GTd*;#PnzIkeRwc@ds2 zlyv{YD)^=%Z2O%=HJ{rR!x?Jo`C6mhO7tlnxFWP2R43h*!2}J`N&R}8)o9UW=~6MD zy20g0u2P(xyyLicOE1^X^aW3?+U;gA7H!a_aZh^{5<$A&{98MO!=({}hx`TECS6st z;Vj2nisS5U%x-}JPC>4DzNv2}8Tjtj_Z`{WEs5J=3K=bLQb~8YF6wr)v9sqwfISmM*X!WVzzU zs{e%g!^s`xspNwigG#z~2>Xwlek;CCHg+68EuD9qp{@ zQfLuto@t5&TWKIM8sRLr#`>7TtndhoKNxZK|WHac)ugPK@ho#Z$U-u#?GM0 zkiJRL;M;?Zg0h3_IRp+que$zQ#~G%uK=C|1rtZuV`X8sqzoB#vR9M1nJYP(xX!c6A z&|#d*bLIasMvJ=qqRX8FC`fs(r&teBJquo8OF=_R+fS}O$AER5nB76lJ z%1Y}c=HIgel?L>mlCjqAKO7MsAG|;s_yuub03->p$1)584^IUE;zHm+y9oI-iQs*9 zL%`v9@5|={w&_+)03GNagXsCEOEs(UY}k}RSXx(Y2dH#ULFTUjqWkZm@UPCYT51X8 zn?H{D$1`^i3Iw!wUva%0OZ`7+frv=$K6RGKLm%s9N|_N|LA142fYuTN)?X;J6De(| zw1WOmYsnVhJnhora{92}I0y#v$x!%vfJOhUQ`|&xkv>S+oj2C-m`kQs5Otkq7g9}I zL-F!;lypTWwV^#fabr~dWKTbA$c(MJWvSQP2cDr->X82T1NpiW@HY=0HPso*I|KwyU?02e;Z)XQc)vpOC<107?;>VJ<`aZDc@_(ZRQC(bbPl8e2lT zCo4aKA!T3c)dWRwX|g4pU}15xb~V5Y;UzTbl5vwsO-mxt7IR-LObrgi za&Am;LR`r^DrLdvP7}_1S2W6g?AomfDb<=oJydNS{Z^2o&IQG!^w+PXPT3RQ5c4FBeYnHHp^sLxfaS{zqfhx zIY;8A+jY2-`o6DQKgyVEPbG*C^deB%a}5Vd@Jz_L2ur8l?49iakhYO=bLm+s0$H9# zj5g(}bMugGwUKvwDB2|E;hmQHv9a>0beyy;NpwS;Z}pJ1!&g|*Tg5%5-`fU}Ku6E< z)w8p!$=oIAVJ=Fz*Tg|um*eB9Ol1cr^oKc=*Y6(X^M60-e#_tZB1%o2ZLbG$TH&PF zr3EIpfG)_Se+|+|sJ6_L<$D87tmb!tk))Jzn75sooz!>s@9CM0)+u4M!Q-pGwPP>0 z%a4XvASDh9u`>txoJDewL{;uoZs$KWnRpH@@vMWlyjw4;4v%;Be{$Pf%iZ`=9d@v+ z+?}KE0DusBNpiYd^deP}lf6zZk(91@eKXopNkaR%R3ZB9QC=#<1qv6(pSfQ4H)pQR zVy=<8B@d;$hY@{sa-UAP@MWC^iZZtXQk8@8^_f^})QX+22~P)Vbv7qHuRd^y4i!a! zS!m>2?GpaFRuq0=cM|V+HAi{edH9|Tl?F3x$Wjtk9^lb&aX;dC*wHA(X9|l=aO^T` z@UKApPzfQ#oiTDm@#=_(xj;0SVObQ#D&EiM(@0h&>2F@%>|Htyox+1G`F}yp5chu% zrGkBV7WGA;QSEzSE+!1~F2r(Ajt@?p+1M*(A$WIehS+^gNw}#|5R$?7w7E+^@y%aB zGSj{(xEX*g>A)OMITUKCopUpPWhT)jlFVdnjC;J~)K!$Yi2K4c1Kjjuo9>5(S4ztr zNmr^~>WGHE(2Iw_C6WEHeKIC0)o9sX!gnvki->T|DR! z(5&Hpj~#2_Qo>e_n~`U|?Hu&DpI&tCCr_|4juZ;bLZ&A>g6nl%#>sB}?UX3BRm{c> zKBhWT$>Anmb_^3T;zg@Cw0Uvy;Y>+TfPt*d%>|#%&tc_h z?X@Es@BNUSSFV@e&7WKLZi2NiI@XUo=-KlJ;^=w=aDQ2 zhO?KE^;LAvC!F{gEg319<5{LI@nc1q(RBI@!$(`=MaRd@iDWhfQ6NZ$BJ&AjMMNp} zRgZ^lp;fM@I-62zM|AuSh8VP5?gx9aOO1DhQ{p~*`E^Srq#=zbmsE&cZlfWaEjTTu zkIRpV=A?5GwJ!Viu0xJ&XhmOH1Raw<9SpHk@Y{46;9s#Vzh@}R1uNi%H;1hQP8Vzj4FBP8?(=A$w@X8%&3|;P z|LmFVflGPdo5plY1u=Vznx{3*!cq!AQhbS554TbVso%f)ju{Al{Nm{DW=fk={)=1o z!RMNC^YoLCiwp?OItKytF~~xJ5~G@NmKK2ZG7(~Xr9`xP^uXq0u;KB`_Rm6sHm=(+ z_TT18bq^C&Rf6Q1b@-mgI|)oP=8ea^L-Q;rDF%-xu2`;Qm)5WP?lr>zGBt-A!Aqh6$(0}s`auB+B}xPpa7=BOM7BI>rq2frPzoIF?b%|S4n z{76!REbQ-$OdIwjl?FVP2d3AZlajAD25L}1$d3HLs^VVy9{FLVe8v&75%54uF*as%5SYV(6U$a*S@o&;)p$e08f#mh70XYwBr4wu_nsUE-^P&chbm#0!=#%tMv_`Z zT$T4&rk=~~UwiIo)^t=ma?WA-Rl$XB8R#5LFZLZ-YVi@}r6?wc*J3V^T@raPUzF95 zdOEc)Q&5^```b_+<0OZ)&o$_IPlz9>u{0h9 zDl9eDysczJUAVr+KZDl|Q|I`iNzmyr(YGpo+blVAMN!eW+=v0>tpW&c%Q*8$?u~zbN&SeKcGTeUgZIHZQGU_~1JJXk{ zXVU$iX(2aK1!m_JXw^L-l*GtAJUtI@WAyZz)0O?>?SG)x%WcWWHJRc+=3XLso7zOv z9gL=3tyhL}!OZ6;!_KoQY_4;sRP?Zp6*V6(eD^jb*IQ|e{87YL)1I_7kT9^feLXRlqz^=wN`ZJi_HQ zLRoe3vJU%F&=(d|V->kXb+guqJ8hYP2FcDOCrDP)X1HRU7j}&%DsAm#i92i zp=kX#dPYemLl*;50ow`6+G5vf%~EPhQumTf;^?7Vh?8VTGW@b0zwPFoz_Ar~k*ZVp zOGm3lNgOpcZ_JBTs!_*JC(hlyxrs3B>j;&QWCVL!CFwo)(hv#~WCtsAzP;(#SPFQJ zIu`U$-YINqx%c8;Pr^>Jv3ykTL#6kI8ue;+O-yU&3T7`2Jk3@8Q9{|==5D33R$p=6 zME5@m(Ly3R7p$=yGQsb~9rxOuDx)aLQ z9DB2Mwnsn~&LxgnhnW_xaywF=<%t1D3(&(Y1%ayB+MT8@7H zkb?OtMFw;Z?emUC50$0V_w~`H>Eom|LIYcATd>M)MIOr8wl*L98ntsyooWR;JS7WZ z|HaQI$VDLECSz%D%lI$W8_m>}zgk5@cQf{9!A-ok(#Dp4cgXC5)DVR}Sf?0BHJx;`Z$6-HSTgP6D$yqTL>i+J7O(h#%8K^*_v^T|foFf$ItBaN)LgXSCtvmm7GgW>RLh~q(wV*%_E9tMX&?G!K2EK(4z&#zGN&Gwju#y*(oMiDNZh7OqI8|lG!eZlf0gDU8tn? zCqr!zckZh9K{ash`j$dZm6tQ_ioet@!>FirpxZa}&7K@Uv=p};Eakqvd*JVdaW;j! zu0~cHE(@C{Mqcx>KZt1Ll$w)Xy}z1{78Sd>b`ZZv)-NY?gYB>gEibrL1YtuezVuJ^ zu$Z8MJG1Er6J05~Oj{cAQh%*r?W!7G1FdLcN=bPy5m3U~5{g=K#3gFdK!?Wx%1qGO zSFOvAQOwD-8#7J6707Oo^6e_iAx0;q>F0^DPz7eL1lFm|i1u0;lXvpWYbEGrPJ6z_ zp`=S8*d%Vu1@deBx4sk_pE#!0Ij}(8nis@&Co(M_P3C75KkiPX9Bn%|%HIVvgf>g; z%DcL9i|oqNvs|ChZA>S66e^>x+)GDH6!C#^*e6aD8O*y&uw z6su{sSV+Um%8oNd$8BiKNZjB^n|CNoQX(4^v2+?cxBUcl*mJvb>9F)cf+&t;Pfj%? z^ldaD`5Hcw71if3Y$=V(Fasec^+y!$+ST(F-u9^RQn_TKi2{m3Mtk%hDcSmC}B z4<>LmdYH@@+ta>v3pQmhJP6CTFWn)Lhi+Csl(-^bM^jICx+r30k#qZE{F#DUN!c0O z$S>WXWWO%%ZL@)dxDo{Rog7oo?gdniUS_>Fa5YZHy&(X@oKz0kik{xywzuIYUQ7M) zGCiwFL^*|fVYoT*!$QmOJ+QqyBE6TyjCkNavm&5qJ4JH4cDs2}Dgi>J_-7kV52d2A zOg58N^oszJ@M@_WRKqqenW`TdT_h$*=pvMTrWO0Pc73M#=UPYtQb>lc@}yq61(NuE zd5N^s*1}ih__8yQ`)EbLnX$o$a&{_fTPgaW)weHk@OEQAkvVdjEC?b?1m!h9jAj}Z z3@CNjcmTjPD=c%GX|Lua>C1@lqwKnp`p7=hXlzb&1Rf^d?9j!i?9C!v;5qno`q;fX&L+(#To zlX)$D5r85>t)~ElMfs!ACRvz3^q%ANn9O33JfC)q>D|@5YI1;f*l1!p!&svBsf# zSY>@^z3u=heQ&qDq<>u|R=(qEncl^`uvO&Z?z8XoQJkHPLvR6*NE=YT6>a4xfx6cm zcF4VX8O?WZj@aTbtQs5`I;)=gaHG>fP&~XlcXPIDbUiltDOt?a-kkQ8^8@$c>v!BQ z*?EzsZm4@E#*t0+JJjP2v?Z9Aey&?B&G}+pTU)MmS=4lLB@6aw7FcTE{tGl--H^O zH2C%hMpEj8?2xP^l2ONl3ssJVrAJo~nBg#{wdUf%oGllOUY4UY&q%`J&R~3|D#H#-&_2Uyjqa2r{S`Pzdu2<5yJ} z!(t2$d*u~2|4(mk8C7N1?`_i{jUb(pij*kbjkJiQba!`$gwowg3QBi(NQZQHce9B1 zTwq++weS1h&wj>!-Y*UZL;c{I>pbWD&)@Gj&RmoOX?ct>734+z%SyFE8CK8W7)Gz@ zwCrbY1KAF_Jvc#YX?-u1n!Y*QXt>TAoRHn#wt1Y?hV`F)#<6pE!Q*C#v2y2yyx&O5 zfT>=oGf?zQ=oGDvjN#D04F4Hn&n)f$G{wU}epGdqVe{_MWKlIB^ibI6a>4c=5Y zfsYT?*TTXakH5G>adOJX#k{JKP`nwBO|GrqsMnaQb=tF27lnXmnH@L6==zvz^uxBe zgmiVZj%hyFdpYScGwDbqbvX&Hj)}eivbC_c!2=9+wyv03ENf8@+j)E z#OyjPZ4T#is^YOIS0Gz6365|^jLVOm01(1@!kV<8pjI+PK8?c{!KD4NVb~=qn!2*B#XOLu;AI?jDCjkqVJkR zg$vvTB66SyEe+LEW1nC`Wug zY4G$Z!tu?DM;&VF8?Lz!^OIN90O4S8_R?7`ONwYpgyYf*6w|uf2jm=ZYI-AQ?2`$3 ziqzfZEN#ftUgBKY0nnlP(4l}e5*35fuOOUq-m6;3q850yz4+1iWb)VVXTOlY51%FV z4Fu(j%Rw^@LDX+EPB9f>d5zd2>tklC2}{E!c5LdtnVx}as$4ppewe8~{}{OI&7(7$ z)=;76Rio*f8#KVk3|wT#Y3%i?Lg1wu^m$znwbv6mmT@I^@L`X-QRN5BQ)L!ZY12rN z-po$6q?vN%5&N#IP`x0fM`AVVZQnW&FJim%?P?IRbJ32evzqjKvS(S|q6-2`BQuV% zz))H$0d=TORKc{O*G}@I$^||6=xb)Z8h6<9c6fE#KRHF(-W(TsqC;;PJzIfVO0h3B zYd0(W%%Uv4cF&LK8pHnM6MG1~*^cf@|J!U2u|pn7^1itz*Mj&5x#F|ERpCJ6>sa&S ztO9zEJpEp2ls>GklRfd_%5#7yz`Q*Sh{Q3XPBsRu_Q`-&6Aw|waJB>H+T5w*=S1H{ zkZ$TX8=nE=;k|L^*ko09y}e=eHpL;1%Z-Q0;D(YRpG@Z>C+Kk1c>iU}%GBr7Vpj>~ zIs0f=`3BxhD|c?zgIiW_fa1V{g_c@kW4g?7bNBLmdS}r92LAsgYN+Lj@d}C0=+!Zp z^obBHIQkdQ3Xem}v6hVk*bemUQYq}%3W$@T`+Iv;L;J4Yxq0r=++kJ3Vyob*O2n6# z`t)MIE)O(!$;Og3=fj}yF0I{2|Bb6jvX+U7w1WWLauFgS9-B#X3(s+$8p(A3!ku+j^$YE$sXsZJ-2+8BWf{-x6cX&*`Pfu!sPYEF{JUANYXR3xt3K3Sfb&-?PAH0L(2NjTPb%@MF|^ zS7ySasrrA^kxs$n+xt3F9c-F4#`PJ{Re1*Ps{FJ+36g&yq6HhQ;K!E0;v&OG7k~%K z@7@E&2}oj;sxv(RNemGZAc#e7$rKzh4p@aVC+DG3j2;5w<(-zx={q%1v zy8%vcj)1=TmrWP)tmN}wRJtUoHCmU2Rh+-UxqvwcGC%?N4+sx{_SFXrNODh;P>nPJ zZZbEI(_oLD9~drwmuu+uMbNKw>9nK9Wm~>CdR_8i`K}sT@u4}Gu0F1bjD%#rlVkwl zRYx6dz7SS$dUbKprEnd{OTu>3c5X;OHP?3gQaB{x{bIfUO)>o|BB}U>iqp@D>Q_WE zc$L}l9MB;fua;om=NtaLMEZ}$=Z>iS^AZUlDibBa{7g9%MkfN;WZWHk?V%+g%dlRd zdhd*kox2OwKA$wFdXUmz3nq+fhYxY!>0WK!{(=?_yr7T&1l z(cMGfXXJ(Im-$;L3D&P4zLgkoKPmKk3pe0KI78C>Yd|oBb_yi%ktW0hR~%>Ohyj1& zwW;AH-<9`JMpBRN=6c7Pc^r@F?%y&E5R2e;W9zb|3Ao%?^|N;M0{vV!lsL84aJBgP zr!4p|j=zfC*p~UG&j1oKNr3kNAsyh)4Cz(Vb+CR;nhkvi!A8flkVNi0XurEIbVb7k zi)l2SVA17HZjf~ z>VMF9V)fkcO!m6j;Wk|X=Tb##fM93PhPz6I>Vu8HG>BvqW}^w;dNq-QfIw&%aI^WD z7f^HyZTwbrTL30-T0sB#{0ku?{x9FF9sCmyJHR~_Y`^81>7X|6c@bt&AaVl_sR!76 z0b7cq=+sx_A9x0o4aDb~GUhz-zq&TxH04;}1D^Q{PLdL2`$bJHqMsRM@OK>mogsJc zJwt9u_&c8uoj(a`x;=f)WdwI8Nh*G?B6NWTm6uopJfusT?6%*(@kWrY zE*!xllP1F3z*k*9+h5o5?IPRyW9lYhzj7QrZaHoSoHRdcYVbYiC!|ME035kxkrigoW2yF~vB$&|FY|KDG4nrEpM;z$Kl_Mgn zPY4R-0qk-f{{UI^d52GLFP*!9R}RySjwT?55E)+S6puyUZzN7aE>L0TI~R~u2{Ya} z#Cu)cYVdcn{pYdl-|)Tqrpd@U(-mL5AM|#6e@4 zMYKGuuspt^SBkyzpj>G!rU&b51M$7DWR^pLr*Vs^E-24O1aHo%{& zo{+SXd-g?3W>ttwL%f=|I1l9(SuSN2G5$%sjB@JtOG*Fp8<>=dBN+LIj&|oFC-i$` ze9uVsK7dxbUrDLsq>e2sgwNF>TwGOX)7Bq*19-rNSWY<u4vuTTnR(cSY_nOFj!1XfL2) zz-t&<9>WRLkfHD}sy!oCu49ed*_r^EYu`5L@6`amftoX(n+yaM&e~M4sK4hWw@l8- z`x-XaE7+}jShRZPx2!0B9$kf=M~F7pW$sII8^fN)^PAg0X zA^l*)c@QYIsNjmT;bFjPW;{{ZO8l%UK!vaMX_l~n z&VGzTshQ z#C%qKaab63u9sZ$?2d#*F0ICl&Ac`>G^d7PPFB(C#KP2O-NbMej`@(QA zo>l&84&GjZsI6{5G5OdFYyw;KB;FnG5w@qMhPLJavky|BnSd9zCn50WzHn-7JJTEl zkncz_iebaC_eq|RaM=I2ce|^%y#HNq`LlOprn;9e{`>v?zb~D{dBv36!%jtePl?OH zedLGfGs3@+rT}>~^II*nd?XeCas{F^f20I*$FWYNAy(h>;-1 z3Vs&O3BiBEo)(Z%sGb4nB$jnK`+pKktAG#=pdk9)7h1ymxbxQdkKDl1A)s9K{*9}x z3na7Pu;D~Vdl6QSAdBG9OCXtmUm8dF&;R!~?%dQl5aAgu(RX>>SDZ9HurP$r{}M<2 z%Ng$hMvvuL*p@V-WvA6$HU0l~1xS1T`xPJv6r8Ame$!tUKuJ>=xMPJWbl3R5S0wQ7 z{8vf(zyJ7sJ%NvZprOt`Z(0&CN*X#~L=pp^h+xBvb0_c$<`4C5X}BeA;=gz9 zPXUOm)JL$-A{Xqlh#x04t$0m0qXS98*JKDVYW4Ue;1~aV^a_p0K)RV0{PMhq49MjG zOGg`=c9y+cIT`R;HPOc4v@?+fm~%_Y+&TG6<)n07i;YeXavm*jvP#1RmVy6>2%T<-M_ zJMNvT0d~=rlrC!_q&J9U)uFp_&%vAFEzL^E2j6Gel^QwRxzk^HCunzO2kp@_!>`y^ zA`_w7&^bk#_;D1aL-ji-V?A=m+e$Dsxs4&BC6PezA>!F9vKhC;+~rEc#ar51$&W{2 z^40hJT|@B-3+9Pz@?cmKL(6d9_mv07x)Klse5T7@la<7kNk}AkAN=Ab_x;MT3kqhP zLPIFyXxQxJ_zhC6+mAA#y}+5th|4Cj%U;-HOs?X<8I#ETr4X42hou0}%64jH>U&~l zGG{fpV~DOwYKx@WN$LQthFfbIP-wqyss}W6_ZcgIhi#-eh=J zox-wk4lP&1BW@8?PN8w*9|IT=gMCvuplf9qhyJ#`#Vb@iL0H^al5dBx{oWoP4Jh4- zox5$;1>(CKYc?_@9sPPKs(z``lc_S36`zxOMf)7YXP(lq%Ve);$Q`XuQs%1quk=%r zNFQEBNSpXRKS4e_mRY0=tf*Wvdl$%ha+}SzIfk@!YasW!1M%>pMdWn{mEAM8TaI!M zw}M?h_C){wNDg}#SL=M~?uNA0LDksOkZag~z5;#kUV+)V*f>I~I8ndf4g4z?o@@{S z6Q3?809h!YWV!Fg{^MxyAMiY~&4ECB0_`EOAef$!waESecpp-E;W^(iLwv!9*MEuT zF)HDkMtN=l2WU){z?xCofsudV1NPtMFa0Y&O?M#)=%r`HA=35U*JlUUV-w9(u@Er$KSN>-q!Fp5=DM`jT=pWw{2;KejvXBYl8l;zUknVe~vT$(^2%kC(HRq zxY*u-u4BLsM0{5P`-@B$I_;z5JDgpmX4_28p=I3R-m)vyTu!j3vo@JTcS~b@(D~6X@z*DeA0dxK zfSq4#re4-+hOg$2Wq<*O4NN(M6E5f+A*PCKC4QTw1UrAP2_;51Bfuo5QZSVD(@OQT zD6QBlJ;jHf5*OC&g*}Yaz;sJhV9h$7w zX5=Sg5HdG5*#WYf_ij7Ow`5t)z$XY?UB+BBDc>De6DMZSoFHH!c8`jBM7=_Jc;Fh- z)itoW*3kCnT(-GWo?7yA^WdCjQMz0N)Fs`TYg&X!lxx{$RuHD2(PXTB2ffdUJdBZw ze>+&lJ;Ia3edZxmtZ1mkz%a43ro)B+_4rFuKMU8*QF;fc{;`$=PkTP$n!Cqry1~0m znKX(61p%wqjpY$5M_KE35f$OlPp>N@0wRi>gg zcWQKH0>?kB7R9=7&v$!cZWp3R_8fA|LK^1JnY7*N`ReDxdKkI;D@u^l&~cd_@HW7I zKRknJzQ8;TYCBHw`yOGg8CzJEAf?E(^X*pqE9&4)1Wau4RYL4f^cXtwjw?Lc>v zusJk0nY0 zno^~coeja(&QUN|N7l#NZW_)GM8t&!3Hy-VzM_Fyb{3MM{ucZqjp8=ZWTc*4S$08x7ubz8j6>)nLA+3s?AqU3z!3wjvHP!7@ z$8IU@&-ERrb2y`7=`5Ue(igp|rG@SAmhjwyAIKGzvvLe(uoNvNc*DbWbogn|v=`h2 zXb7~&n2mfb-#R~P= zI5N*IHy-^@}haR9jD1d=j}Lrq?~&LO|_Ov~9RS`tP2d|1ajecW;L3|@v1q6afJaoulO2Y>yK%&cvDaLTs>DS8$3yy) zKPQV#_{{h3o=K>HU9Vt`@4vZllrZqBOjOy3#(RZ{sSc3t?sh@odnE8l6ujf~{k`1` zUj2Cz?dH2XiIQg}HzKY0tS7ZDMijOt^+biW+QNNtLWODmunHXWEEx&IY(=F!_zuH@ zpv#8%sRpe7Qj(pv|C(~AI|phyue@&tFQeXqfh8{tN@rBi|G*-q`2l2^${%Fe;h(px zH)u@)`JeNO!Disl$^Ylj83cEK=tMf-CqdW-&b-Km8=vA@e*)`%n$*<+le+91iZ@=q zF#c)fuYY97DV(&!-76l5=g~()W-2GfXf~#@`4pGz z#ehQ3>*C%Z<{lk3CrOjf=&>qrh9huh1A2e%f`6JRwB60tqPRDf^0v!_VDsr?3hdNqPYu|p$EQrFsLqwWJ(?iL-jY;t z(BdBEr*~=4%E*}T47R4(8xJ$C>nE9vT1t(t+VS~IA!{pnPMnCzOB<%`gKP9ErybLX z*YW8#{kL(q0@5B;Y&|rUfBPaf))pzpG^cvwv^2;pPuazj@oo61+S3$BoU zJh(oo8eraAFg&>#4LDc8r3R`VvvbJv%68$FOU@)fP)}OAH5p5zB!xK3q7+4kf^gd> z5gGurve4QKnXIeGmxVqh?JY6tjO~sy5PhBE7IxLPLF+ne9ULxkhR(88V@TrZxHnaF zbi?Ikg1PW6qMyv#5QD1ChhFsx@%(JALe7r)TDoC;Zlh)Y$}_fRDbdnuiyV|E$VAXE zn+XU_j@>xu-P`ig3vQ0;6}VqG4A~&OTFJ!63RAsNP$)l z&e`?h)s;*CDQPE!G0<6q(2S@cv~Zd&=6jV|knPxgUKhsSi&|bpfG{pTqvSvwr`P=r z_xRw&7;Im}`$!Y-$Pvp+rr-X z38<~qC^V4aqf3?JcE#o{SR{VxrxVYSHl3s{>Ox)Je`%4&EN)I+?<1WtV<@>lF$=)%ta<)`HSLm)FjnV#rmrcPN$paKt^WC zjaIzxE_s`rq#9{M8?ZJ#c>&nA^M|=E)E>dwbT+JM_*lPCVrVd|%t6mjK{6%=igZD8 zguwTnJ?{4M((fA0gMnJnQFWZVm$0XwU&Fsv0i&h!i(J=or9st~_qchGnV75SNT8>M zTdlgNlx@!+Q=0C4jqG)FcmU%>eH`cnPTfLvCn_ar)N^~(IXXC78@J<%<`V#g9td+p z$rph-Se)xqy;*439VPYdG9Nw!VQQj`K~;~VqSlXpDhpbBY;(5rzNHKGNf0mgyVkD8 zvn~0=i}BCrh%+SxlFfsML^{3CC*sQbVvBrnpE{!Sw?!SKv2$o+=SeAaL7fz81L4lB=@NFjQ-m#e`W1JYd=K(~u_ zr&)$Sw(QWSFXm*&3mf*jXJ7@gQo$_)Ig`$Qa{7As4`8xaVXb#kJ;goc3R9VMH|wpl z-ut0eUmWIFj!ewU*_m<~{a&6tcU4{y6(jZERo=m0Ro)WuzXnXc{7*IrO}d{}wvmr5 z_Oxih$9ks8cdZ#6fF*6fqC&us06t(Fm?W3-{8H%JP8!y{WUvNCCtnV`Eqe@xe@~b1 zSsHQRlRDU<7GeK2J{elb{%_vE9W-Hpkg%Tsnp*Q@5dkZK%OeXF>!n6Cz9hE8Fo;0rN22b~ ztY4m5EqnW(!#bAOD-%Sr1xk53XN>5Nf`X|_=6XVKAR!)^=za??6M1MEUvlEhcFg!OsMSE~rFlRgc)!7`v^pX)xn^YC7cF*1(?KOwzC zH_fwTP1c2?#N+dom40snkM@$(4TFn*!Gb(r88xbfqu3vgHy_s4PUb-M$h-@J?_I+1 z`}>pf1Wjzw+r&2U;a2*k{65jAiQuqROTT>ARF3!~glt}zvV!?Lc~(rK}Oyj#^Pe@ zg8?2nPnz8KGe|BX6=n}9Nb+`#N;5Z5%8U5X%^;@=sL5|aHv<`lrB1Bz=qt>{IfEoW zbmiN9loFC_+D?Qa`0+HMTOufgVoN~^c&0sMS+-xoZ&nhpcF8$Ms;rzD9^a0m!>aVK z^z}F*zKsj972I?9m||2QBk$1C3Ci9`bt3U2vEgw~dUyrVT&-gfQO$uKu%LNU+qQP* zaFOH&w0qBRvRVroNiX7Iv|S@T^+pgd3P45++Cls%d9=xhrjD~ujEA8h) zZi&>GoGoclBrx-OxmNiKq3Javc7OJ@j`n@g}+I3HJd3Cp@As_2+xAnm%yg~Z&i z-dku9oOIR@S!toSxY)E+X%P&1%LuA}so|1T;1&QHJ?9BtUn;^H%uzWU}9kZo~XPuGMT=T70n%@s^uW$>s#^=gPeaKe5X0M{4py6y%A40R!0x#@2Rw><7k=R9* za#2rilX|cENypo((Y*?R0i+EiTdmYFOSmh0)^j)^*^=8LDv$+(u7;xz%&r=|+6b08 z|3dQ)@eXz3>2QKuy`LKkR_ZfGM9c8)>WPZr>zUr`8C64FBLm$H7mV){P|ik37u*b% zB*v9K7}Gam(|+#q?!>xfRcB5c6^$-m7xYxmbCymn)Y0Io*B_jo<5NjHJt`3N^yg^Z z`r$MuJo_Fo$ zwT>$Sj_i%4kb~6^{X?s73dTMQb;!Hhny{YX)F2b?1Hd__{){3 z#o&Y|p^SBNqp)H&jo9$#kq6ekW_sn_&uc?{q%qg<<#zCPE0)uhbX$E*dNn(Dsna4c z4%74p?vnLviJDqV(g@#16z7k}UWoR|3Da7oZ<XqG>BpLH$RQ1+Iz+!w6e zxLX`9bB^kh!GD^Jcsq0NIA-e{8a!Coj=8V#7#yV=m#Jg~cn1ieyFAG%W5U@Wg+-xx zGmz$JIA%{iXjV)?AX|IM|hV`MIW=UahJ{sCAPZ-fOp3~(rbe4vpf(xzXxvG)3S)-?H?x~cogpZle(lE& z8#N2daT2@SKu=)PWNkYP?>m$$AsF7oM)k!ZRJCmLONDRTUwRpYtd$*R3iQXi?Dla# zD2!Ppy%;MYLP|?%md zk#~W^Ln}?cAV0u{!5ORL)|tqDD}!sp-uzW^oj@PPEk|nVMM%HBbD&+IR<%-HQD}^I zj`gz>n^vhcx#HJrZdb+HCLQ$_dj+XZDOx)lQYv-vahW#X=%!beGN*o2?FC;wMQwOV zw2f-WTS)J;U%F@)|q1CaPl=iUD({H`$xM+yB%l#%VUdVCs>_N(!(py?y$xe=u*gDtH{OJ1H z)xoo3>6c6Xx~^q{Nw(UqZiXEkFFj`yUn*y_@Z5$LO9OwqC8c`Y!fL$az%Wa5eKU$B zT~Eq|$lX?>*P&>RoNJEKX*}z6SUd)G&7-q=B(l!6;O-wD=`S{axg^-Mv~^GI)z*Z7 zDuMG?AT6{Af)41m%pUea6H|s@B0#s{GeXz&JH!iTM6eWSBjbB7aP6#l4JUS~T)1u^ zFvI|{yt2jwzB_`1Y4(SubH(x;2L@W`*QE_*bZ4jKYDn;mWAeRZ3oK&udEA|9XcRW! zytE*a1G>h~n6oz!ln8So5?f``vZ5|_`o^bt1f;h)sEaBoo-t7~Q&KP`LmCrXS2tp- zn<95Ez%ImQyp6)ek0dd#Y=n|!oE;?&I~D;?phAEN)Z#4#cmnkY*?$go@UK~C0Z0t` zSVwVq4}o3i5DL=47vJ|QKAKUe0L z^}*==4l=(XSmbC-vy-}o$s?KQSR*anG31PX22gQm04h$=%6i$Ly>Z}Y$dwCVJ_=4`{Vy(q z^LuNw9}#IOUDR9KxKE4h;%!Hf|9TB1|KF{FFklUMwou46;-QK;-(5Y6wt1->ctC@1 zj#`sDSGA5(aiNV}z0OmdD076J0@>+vi~=*+DItX~VCw^6Tm5jDgPeMh!AbXx_i?rX zcddt?fpAgj`X@9}UEd|MLfl_3^*-r|+_tTUee-R`T|X5zt!Ep^*FJ#{$VG$cX8)VG z;hF2tHQ-ZeQc6tp{DcM!x3@lKdCh%)oAmvA=r2}XA-L|re^O4_Vt9j(e4)#>TEGcC zE}bdt+<^v1Rfn=_zd18#zX^P3h(Fiilf76U=Y_}^wnoqjQowd>Xt^T4W+~5I6NAf* zaZ;VGNE7#0-ulE6y+Q_2k@ zfE}5w9eT@}zVlYGcwOrl(6Fx&B1=(3=N3R z?tUFj+*g-S2)<}YD(5tfEuyVjcU_Ai0G-x|EbI>pNa^2j@%{zd{g>Nj4Pc%D7eDsj z+%}VCBbhF=1wB+pcNaGn4txNex$yqMLn<$*K0qf$0Jgty0``}nTMNGK2|QAO{*9J+ z+lni@gw%T0Ln}_#CDCIgE+z4-_sIjAy9yd9J<#In(a{$JVs~P!tr>!UyM`9Hc#k6W zH)3iqhA=O=AO-Zw3Sp&EjgT`tJgs2ZaMe#h-Cf5l{bapy>nA`RGlw`+1U#czj`|6? zte9od|MMj`K`)mFf5{sSIUl)P-4dH+17Bx68k1}hMp^YfuN=5BV9|ghdvf=AcMo70 zJtTiWc=ZzZ@VjM?#x1-SXLQ7I2;c&eFY4eGYcb@s1708B=Da-JiC7rGSmfwbsXGU$T?n7c>F zc6_hJv=CNfvMCFNUyQK8i|bDxa|IrT_Y(xDm*={?2?qc>)1ZNMCJ0B z8m0o#YTklxQN>E&ipY1i>dj&oWYb4pdjo2M?Gt)BVLZJTZqjprC)TxgEf#~^C^8Lt zkfigpC075+a;5W1y*#yEYFVR!g&|-eW_>A5CL`T+5xCj4`+(&orbo-&lAe^Z~W!W%oz*cP?(-dR}Z zCEQvMHN2dNSG+b`?K#V0NsZ#wpI3*zMEJ%^IwR_L+AW4-&>F`uzveO2T>|pfuZXe` zRWrqkEp6m!y;{E5ZL7+)%BT&2P9(Jqh5r_~+IZOf&@)AbF_bXs;$^6d@{&5w_jemv z*qkKt_=;Tw<95jqydv{`pM@S5wy^2HImBnLO~jY!N*riu4(x#~FJybn2%%+agP?{D zF^hnnKpn@z@94>m2CLO^({H_6li%x5XHvg^gaC&ixhLWkjPN}xd3XQl>L$NE_VAr# zI6QkfznGT1sfisCqV?QxIa(@sx+|bYBO9n|Y+>{Bmx2Vur+`66Jj$I?LNs=yR6#l z{Py&OFhe0R441iq?P%*xt;Rfv32hB5w>=wt(XIdvL_PG|36!y1gOO~3q=fdIGIo2l z|m^b-dpCU{hc?O>4Hx!Z|KDipo{HR2_q$I|_$-t!2#`RV}BryRnru z`C+G0+qSDZ*-f;T!})e)FJLTsFMt}+0@vgAh0T@13+dCPhI@(P&qff55_TJD+9z)& zD>PhEem<$Nb+0rLVG4X~Zli>W-Ke~&WR_uNOBv_q2OI5 zB|C*JrbRR62eh2PkfaRc?xw+fG+T-W5eDs2p%@)%K}%9#2)*qbbD}Qz)emQj zvo+JyIYpXIh|I_7dPY${i(XG0Sim3<>T@zzR83q#G2Mb_ZsGaFlAU`|!+kd<<%Ib? zbYrZ1JJRr8EB&>r^8KktCaP-=sd~=&je#O z=JNavpQnV8KbgB?IIrewsqhXRHZRju72&wbOo8)=ZRUmGi>xaPI3s#H+p)n_9L{fZ zksvBZ`M&N=16uJ{8`6{pnWuYe$I#u(Nx8Az7Ak;+Db@z3e*&AHwReoMRu0zUP4f}V zEPfHGdWBq~eYJVKez+0=jRVTVf!Y+`g{0S(Y;|uRBaA5Y(5d1okd}Q^BW`(a+!+f~ zA->1;n7%ng!E~PL#6;yZs2T5#rDKCQY5rtb0K|k$&F${F)Mm$Z0?wiHqjKJ^gF*P^ zlcOntp=&!6QzI8sBNfn%Pg!WN06QJaQTJL9#XDGvn4a)ZU99rhjp!k=ANCx zY^2}2q47C>#;l?O_wS`t4P1K)7b9mUml!AUN8G>S zJwGw&9Sxw0X}&Gur-R?34EXTu=~C+jULj{6J9o)?wJEe8VRxdkvRX}vqk={qqlV`Wz1ld!|sW;?y%MG#><<$jL!ADKs z7#vg%5+1Yz079Jvvje+BZ)x>`??`D!-l9Qn>@&vdeCQeL@4c3&;BF<PO*5P(7m3$}& zkvz6myraKWK4)!YR36QyJTzsOffbo%7o~Dw3K^ zlJE;GY5Y(G9Lj<$lM0$^5v-(e^qM^QHEE9_G@}lyukKPV>b9Gq(%0ek*H)6byvwze z(ma%Xc^8I)p*)`D3Ti%E5E(W7Sr;=*9lh0VIY-xT0)0OBoeeiEf;N8geB$~g9?4;K z6!gypJdUE$r=l?P-WSajS`Pl^D)b}{L+OXx-b{Ank^cL5r!=z&?AM&(H(n~j1N3Ub z==_N+W|O)PeG^%*%N{)5bTQbiZC~4C)rqNxCeiPkW?!2jSxe$PQ@~Wr<)fy7)cYjH z!w}=_Wl9^?|25M*Lnrs)90%xYAZ|sx$=q5AgK~R)r-24)LI5?2E!9iTNPN>wnKrxf zaOsz#*@@{IHNJDisdHV=8rp`k*A#0jrs|SEgz+w(P>;EzA~-!4PxkMiTGt`#->bO< zxx8?>i8)dYTdC+_z0o}NCjwy?UtS6acw9dg8k@d2*Vrz9Twfb^)}ff}!ijTGHiBJq zjY_MIv|`77q)=&Cj~JLD30K^mi8}7uW4_h1Hr5bEJ;l^;dVaW-->*T@t#QhMojw-* z8b>i&`BX3KX`qB@K-lzI-KT^4hyf!et31_*7Fr=Ky~+CcqnBe%pQ4`S6?6v|#5_}H z_$>M|F%e(B#wj9Gp{D;wFj7xvUj1`3SMlj@)Tq~&bHx7C?jGvA)@4(hdm~poCBvt9 z0yEuDIJQjLY78Z6!h!}id(`K6N=DBSlzA8qt*UGmhk{#3-lgLB%5J*e^!ym$G2o{a z{Lua0%(niM$#`^Rn-k@6sWxNq*E}M!V@_b4c!kW#dv8Tkb1u>8HLz&xaif;Zt7tI6`sf>>B6a6b<>lfm zht&w#)TAD-wD+*KJ3j+1gwH(O{5;iw7fO2*OdJealLRA!I{_-1x8NsOLf8&|oOL)k zON?V5+If6jK?8Fi@qGxdQ)J8os9LCkCW3wJT4<6+u5%ddM%I0zD;SJ$l23>~Je_69 z#&WWsRa7gZ^`QvW^dIAwru&jZ%04=Yz$dxdp^fK0h#^ZKO`IB>m$#rmJ!W;sBxJ5mhDy@?s`5IBJX5ly zEG)5Oyc1tD*^--ORL0oDarZ2dGr9E`g}cNgX}cj{qDxF^qkb%X`OE@i^+8+TvFepY zlAL6W>~W7vyw&nevIvy>8f;ksl0L5<%++qGPN?bl4eQ-0WGAK{9D(VWG2a;t zB;h1OC1fKHFC{}P}=RY}HbhmX{euPv&51$z}a&AuzsX#UW$7TrHnmQ4SN zoknCosD5p&(gFfv9KOx*MJ+XNYWLUF+u8oTW9ypqcgD!CYR4ix1|#4<5#8$M-AXPw z(4M~w=8eME!-}s~n062B-iCPi+`p;A-b#b$cFy(fnan5mYtc`&H(mA&Y_BR4!w?Xg zzHsXEE|r^Gu^S33}53n3A`o2mwgLw=+cQT;GbU7c%ENeEAes$52Ap=+LBMjunKhSAjEsGNfdh@0WbAL*E#~>V72%)UcAqV}@t$;9? z4&F&i;mUfJbwgC^Y1|?(MEcaK$D$|x&3{^C4*ujisV~QU_kiK7Ys8AFB2aW~_l@Oh z)en~2^6UL_TYu~ssU3onTOF-)87mKC4~y$tP>e;J$KW|X?5(;>ed5%oB`HMpy@teN WnY!t>N4m%QZ_nkHI1?R&xBfrD$r7Ca diff --git a/ProgramFiles/sysplotter_gui_fcns/get_box_values.m b/ProgramFiles/sysplotter_gui_fcns/get_box_values.m index d17389a..5f9aeaf 100644 --- a/ProgramFiles/sysplotter_gui_fcns/get_box_values.m +++ b/ProgramFiles/sysplotter_gui_fcns/get_box_values.m @@ -7,7 +7,7 @@ %build the list of plot boxes for the column %classes of plot - plot_types = {'vfield','hfun','bvi','disp','beta','dbeta','xy','xyopt'}; + plot_types = {'vfield','CCF','bvi','disp','beta','dbeta','xy','xyopt'}; %plot or subplot for each coordinate plot_style = {'plot','plot','subplot','subplot','plot','plot','single','single'}; diff --git a/ProgramFiles/sysplotter_gui_fcns/initialize_plot_windows.m b/ProgramFiles/sysplotter_gui_fcns/initialize_plot_windows.m index f676d37..38e0e04 100644 --- a/ProgramFiles/sysplotter_gui_fcns/initialize_plot_windows.m +++ b/ProgramFiles/sysplotter_gui_fcns/initialize_plot_windows.m @@ -1,5 +1,5 @@ function plots_to_make = initialize_plot_windows(box_active,plot_types,merged_plot_subtypes... - ,plot_style,hfuntype,stretchstate,handles,source_number_text) + ,plot_style,CCFtype,stretchstate,handles,source_number_text) %%%%% %Determine how many windows to create @@ -50,7 +50,7 @@ end %Decide which kind of height function to show - plots_to_make(end,1).hfuntype = hfuntype; + plots_to_make(end,1).CCFtype = CCFtype; % set the stretch on each component. Menu item 1 is no stretch, % 2 is stretch (and if we offer multiple stretches in the diff --git a/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback.m b/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback.m index 7ced56b..90c9584 100644 --- a/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback.m +++ b/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback.m @@ -23,8 +23,8 @@ get_box_values(source_number_text,handles); %#ok %get the height function type to plot -hfuntype = get(findobj(handles.(['hfunradio' source_number_text]),'Value',1),'Tag'); -hfuntype(3) = []; +CCFtype = get(findobj(handles.(['CCFradio' source_number_text]),'Value',1),'Tag'); +CCFtype(3) = []; % Get the state of the Stretch menu (coordinate conversion to flatten % metric) @@ -33,7 +33,7 @@ % Initialize the plot windows plots_to_make = initialize_plot_windows(box_active,plot_types,merged_plot_subtypes... - ,plot_style,hfuntype,stretchstate,handles,source_number_text); + ,plot_style,CCFtype,stretchstate,handles,source_number_text); %%%%%%%%%%% From 6d79f752e3bd8c0860013d1085ed48c4b5a956d1 Mon Sep 17 00:00:00 2001 From: remaleyj Date: Tue, 10 Jan 2017 13:36:51 -0800 Subject: [PATCH 002/286] test file to learn git --- test.txt.txt | 1 + 1 file changed, 1 insertion(+) create mode 100644 test.txt.txt diff --git a/test.txt.txt b/test.txt.txt new file mode 100644 index 0000000..33fc59f --- /dev/null +++ b/test.txt.txt @@ -0,0 +1 @@ +A \ No newline at end of file From c718a7a56483399edb421e4b189e459881e43e53 Mon Sep 17 00:00:00 2001 From: remaleyj Date: Tue, 10 Jan 2017 13:38:27 -0800 Subject: [PATCH 003/286] removed test file --- test.txt.txt | 1 - 1 file changed, 1 deletion(-) delete mode 100644 test.txt.txt diff --git a/test.txt.txt b/test.txt.txt deleted file mode 100644 index 33fc59f..0000000 --- a/test.txt.txt +++ /dev/null @@ -1 +0,0 @@ -A \ No newline at end of file From 80b0f579784d2d2936ed2e566204b33c4825bda6 Mon Sep 17 00:00:00 2001 From: rlhatton Date: Thu, 20 Apr 2017 15:25:34 -0700 Subject: [PATCH 004/286] Improved numerical stability of metric flattening --- ..._dissipation_metric_from_curvature_bases.m | 32 ++ ...issipation_metric_from_general_curvature.m | 42 +++ ProgramFiles/Utilities/metricellipsefield.m | 138 +++++++++ ProgramFiles/sys_calcsystem.m | 2 +- .../fast_flatten_metric/dualize_grid.m | 36 +++ .../fast_flatten_metric/fast_flatten_metric.m | 31 +- .../get_spring_neutral_lengths.m | 36 +-- .../sys_calcsystem_fcns/test_function_type.m | 8 +- ProgramFiles/sys_draw_fcns/CCF_draw.m | 5 +- ProgramFiles/sys_draw_fcns/vfield_draw.m~ | 287 ------------------ 10 files changed, 296 insertions(+), 321 deletions(-) create mode 100644 ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_curvature_bases.m create mode 100644 ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_general_curvature.m create mode 100644 ProgramFiles/Utilities/metricellipsefield.m create mode 100644 ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/dualize_grid.m mode change 100644 => 100755 ProgramFiles/sys_calcsystem_fcns/test_function_type.m delete mode 100644 ProgramFiles/sys_draw_fcns/vfield_draw.m~ diff --git a/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_curvature_bases.m b/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_curvature_bases.m new file mode 100644 index 0000000..cb04e17 --- /dev/null +++ b/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_curvature_bases.m @@ -0,0 +1,32 @@ +function Mp = Internal_dissipation_metric_from_curvature_bases(kappa_basis,L,internal_damping_constant) +% Calculate the internal dissipation power metric for a set of curvature bases + + % Specified integration limits + int_limit = L*[-0.5 0.5]; + + % Integrate along the body for the internal dissipation metric + Mp_sol = ode_multistart(@ode45,@(s,Mp) dMetric(s,Mp,kappa_basis,internal_damping_constant),int_limit,int_limit(1),zeros(length(kappa_basis)^2,1)); + + Mp = reshape(Mp_sol(int_limit(end)),length(kappa_basis),[]); + +end + +function dMp = dMetric(s,Mp,kappa_basis,internal_damping_constant) %#ok +% Calculate the local contribution to the internal dissipation power metric + + dMp = zeros(numel(kappa_basis)); + + for idx1 = 1:size(dMp,1) + for idx2 = 1:idx1 + + dMp(idx1,idx2) = kappa_basis{idx1}(s)*kappa_basis{idx2}(s); + dMp(idx2,idx1) = dMp(idx1,idx2); + + end + + end + + + dMp = (internal_damping_constant^2) * dMp(:); + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_general_curvature.m b/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_general_curvature.m new file mode 100644 index 0000000..130edd3 --- /dev/null +++ b/ProgramFiles/Utilities/LowRe_toolbox/Internal_dissipation_metric_from_general_curvature.m @@ -0,0 +1,42 @@ +function Mp = LowRE_dissipation_metric_from_general_curvature(curvdef,cparams,L,c,drag_ratio) +% Calculate the dissipation power metric for a set of curvature bases + + % Specified integration limits + int_limit = L*[-0.5 0.5]; + + % Define the tangential, lateral drag matrix for unit/double drag + drag = [1 0; 0 drag_ratio]*c; + + % Get the backbone locus, Jacobian, and Local Connection functions + [A, h, J,Omega] = LowRE_local_connection_from_general_curvature(curvdef,cparams,L,c,drag_ratio); + + % Integrate along the body for the power metric + Mp_sol = ode_multistart(@ode45,@(s,Mp) dMetric(s,Mp,A,h,J,drag),int_limit,int_limit(1),zeros(length(cparams)^2,1)); + + Mp = reshape(Mp_sol(int_limit(end)),length(cparams),[]); + +end + + +function localJ = local_body_velocity_J(A,h,J) +% Calculate the Jacobian from shape parameter velocity to local tangential +% and normal velocity + + R = [cos(h(3)) sin(h(3)); + -sin(h(3)) cos(h(3))]; + + %Velocity is sum of body velocity and velocity within body frame + localJ = R*(-A(1:2,:) + J(1:2,:) + [-h(2)*(-A(3,:)); h(1)*(-A(3,:))]); + +end + +function dMp = dMetric(s,Mp,A,h,J,drag) %#ok +% Calculate the local contribution to the power metric + + localJ = local_body_velocity_J(A,h(s),J(s)); + + dMp = localJ.'*drag*localJ; + + dMp = dMp(:); + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/metricellipsefield.m b/ProgramFiles/Utilities/metricellipsefield.m new file mode 100644 index 0000000..6436c82 --- /dev/null +++ b/ProgramFiles/Utilities/metricellipsefield.m @@ -0,0 +1,138 @@ +function h = metricellipsefield(x,y,M,style,varargin) +%Plot an ellipse field based on the singular values of a metric +%tensor M. M should be specified as a cell array with with the same +%dimensions as x and y, and each cell containing a 2x2 matrix containing +%its value at the corresponding x,y location + + +%%%%%%%%%%%%% +% Construct the ellipses for each location + +% Make the circle primitive +th = linspace(0,2*pi,50); +xc = cos(th); +yc = sin(th); + +% Replicate the circle primitive into a cell array at each x,y location +circles = repmat({[xc;yc]},size(x)); + + +switch style + + % The tissot indicatrix, showing linear stretch + case 'tissot' + + % Calculate the svd of the metric tensor + [u,s,v] = cellfun(@(m) svd(inv(m)),M,'UniformOutput',false); + + % Apply the transform corresponding to M to the circles + circles = cellfun(@(u,s,v,c)(u*sqrt(s)*v')*c,u,s,v,circles,'UniformOutput',false); + %circles = cellfun(@(u,s,v,c)(sqrt(s)*v')*c,u,s,v,circles,'UniformOutput',false); + + plot_options = varargin{1}; + + % the tissot indicatrix, with major and minor axis crosses added + case 'tissot-cross' + + % Calculate the svd of the metric tensor + [u,s,v] = cellfun(@(m) svd(inv(m)),M,'UniformOutput',false); + + % Apply the transform corresponding to M to the circles + circles = cellfun(@(u,s,v,c)(u*sqrt(s)*v')*c,u,s,v,circles,'UniformOutput',false); + + % Create the crosses + crosses = cellfun(@(u,s)... + [u(1,1)*s(1,1) -u(1,1)*s(1,1);...% NaN u(1,2)*s(2,2) u(1,2)*s(2,2);... + u(2,1)*s(1,1) -u(2,1)*s(1,1);... NaN u(2,2)*s(2,2) -u(2,2)*s(2,2) + ],u,s,'UniformOutput',false); + + plot_options = varargin{1}; + plot_options_crosses = varargin{2}; + + + +end + + + +% Find the greatest x or y range in the circles +xrange = cellfun(@(u)range(u(1,:)),circles); +yrange = cellfun(@(u)range(u(2,:)),circles); + +xrange = max(xrange(:)); +yrange = max(yrange(:)); + +% Find the smallest spacing in each direction +xspacing = min(diff(x(:,1))); +yspacing = min(diff(y(1,:))); + +% Set the percentage of the spacing that the largest element should occupy +max_fill = 0.6; + +% Determine if x or y fitting is the limiting factor for the plot and set +% the scaling accordingly +scale_factor = min(xspacing/xrange, yspacing/yrange)*max_fill; + +% Multiply all the circles by the scale factor +circles = cellfun(@(u)u*scale_factor,circles,'UniformOutput',false); + +if exist('crosses','var') + crosses = cellfun(@(u)u*scale_factor,crosses,'UniformOutput',false); +end + +% Recenter the circles +circles = cellfun(@(u,v,w) [u(1,:)+v;u(2,:)+w],circles,num2cell(x),num2cell(y),'UniformOutput',false); + +if exist('crosses','var') + crosses = cellfun(@(u,v,w) [u(1,:)+v;u(2,:)+w],crosses,num2cell(x),num2cell(y),'UniformOutput',false); +end + +%%%%%%%%%%%%%%%%% +% Fill in default values for plot options + +% Ensure plot options exists +if ~exist('plot_options','var') + + plot_options = {}; + +end + + +% Color +if ~any(strcmpi('edgecolor',plot_options(1:2:end))) + + plot_options = [plot_options,{'EdgeColor','k'}]; + +end +if ~any(strcmpi('facecolor',plot_options(1:2:end))) + + plot_options = [plot_options,{'FaceColor','none'}]; + +end + +% Parent +if isempty(plot_options) || ~any(strmatch('parent',lower(plot_options(1:2:end)))) + + f = figure; + ax = axes('Parent',f); + plot_options = [plot_options,{'Parent',ax}]; + +end + +%%%%%%%%%%%%%%%%%% +% Make the ellipses + +switch style + + case 'tissot' + + h = cellfun(@(u)patch('XData',u(1,:),'YData',u(2,:),plot_options{:}),circles,'UniformOutput',false); + + case 'tissot-cross' + + h_cross = cellfun(@(u)patch('XData',u(1,:),'YData',u(2,:),plot_options_crosses{:}),crosses,'UniformOutput',false); + + h_ellipse = cellfun(@(u)patch('XData',u(1,:),'YData',u(2,:),plot_options{:}),circles,'UniformOutput',false); + + +end \ No newline at end of file diff --git a/ProgramFiles/sys_calcsystem.m b/ProgramFiles/sys_calcsystem.m index b896422..f94b3c7 100644 --- a/ProgramFiles/sys_calcsystem.m +++ b/ProgramFiles/sys_calcsystem.m @@ -48,7 +48,7 @@ %Calculate optimal coordinate choice s = optimize_coordinate_choice(s); - %Calculate the height functions from the connection + %Calculate the constraint curvature functions from the connection s = calc_constraint_curvature(s); %Build a stretch function corresponding to the metric diff --git a/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/dualize_grid.m b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/dualize_grid.m new file mode 100644 index 0000000..df569a2 --- /dev/null +++ b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/dualize_grid.m @@ -0,0 +1,36 @@ +function [xc,yc] = dualize_grid(x,y,padding) +% Make an ndgrid whose points are at the center of the cells in a provided +% ndgrid. If padding is "true", also make a set of points that are outside +% the grid. + +%%%%Get a set of x,y points at the mean position of each cell +n_x = size(x,1); +n_y = size(x,2); + +% Center-point in x direction, with robustness against non-square +% blocks (e.g., different sampling densities in different directions +xc = ((x(2:n_x,1:(n_y-1)) - x(1:(n_x-1),1:(n_y-1)))/2 + x(1:(n_x-1),1:(n_y-1)) + ... + (x(2:n_x,2:n_y) - x(1:(n_x-1),2:n_y))/2 + x(1:(n_x-1),2:n_y))/2; + +% Center-point in y direction +yc = ((y(1:(n_x-1), 2:n_y) - y(1:(n_x-1),1:(n_y-1)))/2 + y(1:(n_x-1),1:(n_y-1)) + ... + (y(2:n_x,2:n_y) - y(2:n_x,1:(n_y-1)))/2 + y(2:n_x,1:(n_y-1)))/2; + +if padding + deltax1 = (x(2,1)-x(1,1)); + deltax2 = (x(end,1)-x(end-1,1)); + + deltay1 = (y(1,2)-y(1,1)); + deltay2 = (y(1,end)-y(1,end-1)); + + xc = [ xc(1,1)-deltax1 xc(1,:)-deltax1 xc(1,end)-deltax1; + xc(:,1) xc xc(:,end); + xc(end,1)+deltax2 xc(end,:)+deltax2 xc(end,end)+deltax2]; + + yc = [ yc(1,1)-deltay1 yc(1,:) yc(1,end)+deltay2; + yc(:,1)-deltay1 yc yc(:,end)+deltay2; + yc(end,1)-deltay1 yc(end,:) yc(end,end)+deltay2]; + +end + +end diff --git a/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/fast_flatten_metric.m b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/fast_flatten_metric.m index d0b46a5..0f160ca 100644 --- a/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/fast_flatten_metric.m +++ b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/fast_flatten_metric.m @@ -26,16 +26,20 @@ % during the relaxation period, to say how far along the evolution this % point conversion should be made - + %Dualize the grid, so that the metric values calculated on the grid are + %at the center of a cell made from the new gridpoints + [xc,yc] = dualize_grid(grid{:},1); + griddual = {xc;yc}; + %Build springs from grid - [springs, blocks] = generate_springs(grid{1}); + [springs, blocks] = generate_springs(griddual{1}); % Find the initial lengths of the springs (the initial grid separations - [start_lengths,~,start_deltas] = get_spring_lengths_and_azimuths(springs,grid{:}); + [start_lengths,~,start_deltas] = get_spring_lengths_and_azimuths(springs,griddual{:}); % Calculate the lengths the springs would be if the metric could be % flattened entirely - [neutral_lengths,mean_neutral_length] = get_spring_neutral_lengths(springs,blocks,start_deltas,grid{:},metric); + [neutral_lengths,mean_neutral_length] = get_spring_neutral_lengths(springs,blocks,start_deltas,metric); % % Scale the initial positions by the ratio between the mean neutral % % length and the mean initial length (this puts roughly half the @@ -46,8 +50,8 @@ % Scale the initial positions by the geometric mean of the starting % lengths (this puts roughly half the springs initially in tension and % half in compression) - x_scaled = (grid{1}/geomean(start_lengths)); - y_scaled = (grid{2}/geomean(start_lengths)); + x_scaled = (griddual{1}/geomean(start_lengths)); + y_scaled = (griddual{2}/geomean(start_lengths)); %%%%% % Masking functions for non-rectangular regions of the shape space @@ -58,7 +62,7 @@ end % Apply the mask to the points - masked_points = mask(grid{1}(:),grid{2}(:)); + masked_points = mask(griddual{1}(:),griddual{2}(:)); % Generate a mask for the springs, that returns zero if either end of % the spring is outside the target region. @@ -89,17 +93,18 @@ %Build the output functions % Convert points - convert.old_to_new_points = @(x_old,y_old) convert_points(grid{:},final_x,final_y,x_old,y_old); - Fx = TriScatteredInterp([final_x(:) final_y(:)],grid{1}(:)); - Fy = TriScatteredInterp([final_x(:) final_y(:)],grid{2}(:)); + convert.old_to_new_points = @(x_old,y_old) convert_points(griddual{:},final_x,final_y,x_old,y_old); + Fx = TriScatteredInterp([final_x(:) final_y(:)],griddual{1}(:)); + Fy = TriScatteredInterp([final_x(:) final_y(:)],griddual{2}(:)); convert.new_to_old_points = @(x_new,y_new) multiTriInterp(Fx,Fy,x_new,y_new); % Jacobian from old to new tangent vectors - final_jacobian = find_jacobian(grid{:},final_x,final_y); - convert.jacobian = @(x_p,y_p) interpolate_cellwise_tensor(grid{:},x_p,y_p,final_jacobian); + final_jacobian = find_jacobian(griddual{:},final_x,final_y); + convert.jacobian = @(x_p,y_p) interpolate_cellwise_tensor(griddual{:},x_p,y_p,final_jacobian); % Metric in new space - final_new_metric = cellfun(@(j,m) j'\m/j,celltensorconvert(final_jacobian),(metric),'UniformOutput',false); + final_jacobian_metric = arrayfun(convert.jacobian,grid{:},'UniformOutput',false); + final_new_metric = cellfun(@(j,m) j'\m/j,final_jacobian_metric,(metric),'UniformOutput',false); convert.new_metric = @(x_p,y_p) interpolate_cellwise_tensor(grid{:},x_p,y_p,celltensorconvert(final_new_metric)); convert.old_metric = @(x_p,y_p) interpolate_cellwise_tensor(grid{:},x_p,y_p,celltensorconvert(metric)); diff --git a/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/get_spring_neutral_lengths.m b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/get_spring_neutral_lengths.m index 277492e..5c2eae9 100644 --- a/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/get_spring_neutral_lengths.m +++ b/ProgramFiles/sys_calcsystem_fcns/fast_flatten_metric/get_spring_neutral_lengths.m @@ -2,24 +2,26 @@ % box it's part of is premultiplied by sqrt(M)^-1. For springs that are part of % two boxes, the neutral length is taken as the average across the two % boxes -function [metric_lengths,mean_length] = get_spring_neutral_lengths(springs,blocks,start_deltas,x,y,M) +function [metric_lengths,mean_length] = get_spring_neutral_lengths(springs,blocks,start_deltas,M) - %%%%Get a set of x,y points at the mean position of each cell - n_x = size(x,1); - n_y = size(x,2); - - % Center-point in x direction, with robustness against non-square - % blocks (e.g., different sampling densities in different directions - xc = ((x(2:n_x,1:(n_y-1)) - x(1:(n_x-1),1:(n_y-1)))/2 + x(1:(n_x-1),1:(n_y-1)) + ... - (x(2:n_x,2:n_y) - x(1:(n_x-1),2:n_y))/2 + x(1:(n_x-1),2:n_y))/2; - - % Center-point in y direction - yc = ((y(1:(n_x-1), 2:n_y) - y(1:(n_x-1),1:(n_y-1)))/2 + y(1:(n_x-1),1:(n_y-1)) + ... - (y(2:n_x,2:n_y) - y(2:n_x,1:(n_y-1)))/2 + y(2:n_x,1:(n_y-1)))/2; - - % Evaluate the metric at the center of each cell, - metric = celltensorconvert(... - cellfun(@(m) interpn(x,y,m,xc,yc,'cubic'),M,'UniformOutput',false)); +% %%%%Get a set of x,y points at the mean position of each cell +% n_x = size(x,1); +% n_y = size(x,2); +% +% % Center-point in x direction, with robustness against non-square +% % blocks (e.g., different sampling densities in different directions +% xc = ((x(2:n_x,1:(n_y-1)) - x(1:(n_x-1),1:(n_y-1)))/2 + x(1:(n_x-1),1:(n_y-1)) + ... +% (x(2:n_x,2:n_y) - x(1:(n_x-1),2:n_y))/2 + x(1:(n_x-1),2:n_y))/2; +% +% % Center-point in y direction +% yc = ((y(1:(n_x-1), 2:n_y) - y(1:(n_x-1),1:(n_y-1)))/2 + y(1:(n_x-1),1:(n_y-1)) + ... +% (y(2:n_x,2:n_y) - y(2:n_x,1:(n_y-1)))/2 + y(2:n_x,1:(n_y-1)))/2; +% +% % Evaluate the metric at the center of each cell, +% metric = celltensorconvert(... +% cellfun(@(m) interpn(x,y,m,xc,yc,'cubic'),M,'UniformOutput',false)); + + metric = celltensorconvert(M); %%%%%%%%%% % Make a cell array of the coordinates of the four nodes associated diff --git a/ProgramFiles/sys_calcsystem_fcns/test_function_type.m b/ProgramFiles/sys_calcsystem_fcns/test_function_type.m old mode 100644 new mode 100755 index cfaa36a..092a5fa --- a/ProgramFiles/sys_calcsystem_fcns/test_function_type.m +++ b/ProgramFiles/sys_calcsystem_fcns/test_function_type.m @@ -25,7 +25,7 @@ % supply the point twice as if it were two grid points double_midpoint = mat2tiles([range_mid{:} range_mid{:}],size(range_mid)); vector_input = 1; -A_test = tensorfunction(range_mid{:}); % This is to make the system throw an error if tensorfunction is bad, because the try line on double_midpoint will treat an error as indicating a non-vector function +A_test_single = tensorfunction(range_mid{:}); % This is to make the system throw an error if tensorfunction is bad, because the try line on double_midpoint will treat an error as indicating a non-vector function try A_test = tensorfunction(double_midpoint{:}); %#ok @@ -63,6 +63,12 @@ end +% If the output is not a cell array, and A_test does not have twice as many +% entries as A_test_single, then this function doesn't handle vector inputs +% properly, and should be marked as single +elseif numel(A_test) ~= 2*numel(A_test_single) + + tensorfunctiontype = 'single point'; % If the function appears able to take vector input and return non-cell output, test to see if the % output is block or woven diff --git a/ProgramFiles/sys_draw_fcns/CCF_draw.m b/ProgramFiles/sys_draw_fcns/CCF_draw.m index 0e40d0f..191f3e9 100644 --- a/ProgramFiles/sys_draw_fcns/CCF_draw.m +++ b/ProgramFiles/sys_draw_fcns/CCF_draw.m @@ -2,7 +2,8 @@ %Draw the constraint curvature function %Get the configuration file, and extract the Colorpath - configfile = './sysplotter_config'; + configfile = 'sysplotter_config'; + configfile = fullfile(fileparts(mfilename('fullpath')),'..',configfile); load(configfile,'Colorset'); %constraint curvature function list @@ -300,7 +301,7 @@ %Label the axes - label_shapespace_axes(ax,[],~isempty(s.convert)); + label_shapespace_axes(ax,[],plot_info.stretch); %Set the tic marks set_tics_shapespace(ax,s,s.convert); diff --git a/ProgramFiles/sys_draw_fcns/vfield_draw.m~ b/ProgramFiles/sys_draw_fcns/vfield_draw.m~ deleted file mode 100644 index d888b62..0000000 --- a/ProgramFiles/sys_draw_fcns/vfield_draw.m~ +++ /dev/null @@ -1,287 +0,0 @@ -function plot_info = vfield_draw(s,p,plot_info,sys,shch,resolution) - - %Vector field list - vfield_list = {'X','Y','T','Xopt','Yopt','Topt'}; - - % Get the number of dimensions - n_dim = numel(s.grid.eval); - - %Ensure that there are figure axes to plot into, and create new windows - %for those axes if necessary - plot_info = ensure_figure_axes(plot_info); - - %%%%%%% - % Get the vector field and interpolate into the specified grid - - % Extract the display vector field - V = cat(1,s.vecfield.display.content.Avec,s.vecfield.display.content.Avec_optimized); - % Extract the plotting grid - grid = s.grid.vector; - - - %% - % Convert the vector field to the plotting grid specified in the gui - [V,grid] = plotting_interp(V,grid,resolution,'vector'); - - % Create a set of vector fields along coordinate directions - V_coord = repmat({zeros(size(V{1}))},numel(grid)); - for i = 1:numel(grid) - - V_coord{i,i} = ones(size(V{1})); - - end - - %%%%% - % If the shape coordinates should be transformed, make the conversion - % (multiply the vectors by the inverse jacobian) - - if plot_info.stretch - - % Calculate the jacobians at the plotting points - Jac = arrayfun(s.convert.jacobian,grid{:},'UniformOutput',false); - - % Use the jacobians to convert the vectors - - % Iterate over all connection vector fields present - for i = 1:size(V,1) - - % Iterate over all vectors present - for j = 1:numel(V{i,1}) - - % Extract all components of the relevant vector - tempVin = cellfun(@(x) x(j),V(i,:)); - - % Multiply by the inverse Jacobian (because V is a - % gradient, not a flow) - tempVout = Jac{j}\tempVin(:); - - % Replace vector components - for k = 1:size(V,2) - - V{i,k}(j) = tempVout(k); - - end - - end - - - end - - - - % Use the jacobians to convert the coordinate vectors in accordance - % with the stretch transformation - - % Iterate over all coordinate vector fields present - for i = 1:size(V_coord,1) - - % Iterate over all vectors present - for j = 1:numel(V_coord{i,1}) - - % Extract all components of the relevant vector - tempVin = cellfun(@(x) x(j),V_coord(i,:)); - - % Multiply by the Jacobian (because V_coord is a flow) - tempVout = Jac{j}*tempVin(:); - - % Replace vector components - for k = 1:size(V_coord,2) - - V_coord{i,k}(j) = tempVout(k); - - end - - end - - - end - - % Rotate the coordinate vectors to get normals - V_norm = repmat({zeros(size(V{1}))},numel(grid)); - if numel(grid) == 2; - - V_norm = {V_coord{2,2} -V_coord{2,1}; - -V_coord{1,2} V_coord{1,1}}; - - elseif numel(grid) == 3; - - V_norm = {V_coord{3,3} V_coord{3,2} -V_coord{3,1}; % z coord field around y - -V_coord{1,2} V_coord{1,1} -V_coord{1,3}; % x around z - V_coord{2,1} V_coord{2,3} -V_coord{2,2}}; % y around x - - else - warning('Rotations for >3 dimensions undefined in vfield_draw clipping of stretched vector field (add them if you need them) ') - - end - - % Convert the grid points to their new locations - [grid{:}] = s.convert.old_to_new_points(grid{:}); - - - - %%%% - % Trim any vectors that go outside the boundary - - % Take the dot product of the connection vector fields and the - % normal vector fields - dprods = repmat({zeros(size(V_norm{1}))},size(V,1),size(V_norm,1)); - for i = 1:size(dprods,1) - - for j = 1:size(dprods,2) - - elementprods = cellfun(@(x,y) x.*y,V(i,:),V_norm(j,:),'UniformOutput',false); - - for k = 1:numel(elementprods) - - dprods{i,j} = dprods{i,j}+elementprods{k}; - - end - - end - - end - - % Create a cell array to hold the masking term - edgemask = repmat({zeros(size(V{1}))},size(V)); - - % Iterate along the rows of V (each row is one field) - for idxA = 1:size(V,1) - - % Iterate along the elements of dotprods in the corresponding row - % (each colum corresponds to the dot product of the current row of - % V with the then nth coordinate field - for idxB = 1:size(dprods,2) - - % Identify the index sets that correspond to the first and last - % elements along this direction of the grid - indices_start = [repmat({':'},1,idxB-1), {1}, repmat({':'},1,size(V,2)-idxB)]; - indices_end = [repmat({':'},1,idxB-1), {size(V{1},idxB)}, repmat({':'},1,size(V,2)-idxB)]; - - % Find all vectors that point out - V_test_start = dprods{idxA,idxB} < 0; - V_test_end = dprods{idxA,idxB} > 0; - - % Take the start and end indices values from the test boolean - edgemask{idxA,idxB}(indices_start{:}) = V_test_start(indices_start{:}); - edgemask{idxA,idxB}(indices_end{:}) = V_test_end(indices_end{:}); - - end - - % Combine all the edgemasks for a field into a single mask - - edgemask_merged = zeros(size(edgemask{1})); - for idxB = 1:size(V,2) - - edgemask_merged = edgemask_merged | edgemask{idxA,idxB}; - - end - - % Apply edgemask_merged to all the fields in this row of V - for idxB = 1:size(V,2) - - V{idxA,idxB}(edgemask_merged) = 0; - - end - end - end - - %%% - %If there's a singularity, use arctan scaling on the magnitude of the - %vector field - if s.singularity - - V = arctan_scale_vector_fields(V); - - end - - - - - for i = 1:length(plot_info.axes) - - %call up the relevant axis - ax = plot_info.axes(i); - - %get which vector field to use - field_number = find(strcmp(plot_info.components{i}, vfield_list)); - - %plot the vector field arrows - if n_dim == 2 - quiver(ax,grid{:},V{field_number,1},V{field_number,2},'k','LineWidth',2) - else - quiver3(ax,grid{1:3},V{field_number,:},'k','LineWidth',2) - end - - % Make edges if coordinates have changed - if plot_info.stretch - - edgeres = 30; - - oldx_edge = [s.grid_range(1)*ones(edgeres,1);linspace(s.grid_range(1),s.grid_range(2),edgeres)';... - s.grid_range(2)*ones(edgeres,1);linspace(s.grid_range(2),s.grid_range(1),edgeres)']; - oldy_edge = [linspace(s.grid_range(3),s.grid_range(4),edgeres)';s.grid_range(4)*ones(edgeres,1);... - linspace(s.grid_range(4),s.grid_range(3),edgeres)';s.grid_range(3)*ones(edgeres,1)]; - - [x_edge,y_edge] = s.convert.old_to_new_points(oldx_edge,oldy_edge); - - l_edge = line('Parent',ax,'Xdata',x_edge,'YData',y_edge,'Color','k','LineWidth',1); %#ok - - end - - - if plot_info.stretch - axis(ax,'equal'); - axis(ax,[min(grid{1}(:)) max(grid{1}(:)) min(grid{2}(:)) max(grid{2}(:))]); - else - axis(ax,'equal'); - end - %set the display range - if ~plot_info.stretch - axis(ax,s.grid_range); - end - - %Label the axes (two-dimensional) - label_shapespace_axes(ax,[],plot_info.stretch); - - %Set the tic marks - set_tics_shapespace(ax,s,s.convert); - - %If there's a shape change involved, plot it - if ~strcmp(shch,'null') - - overlay_shape_change_2d(ax,p,plot_info.stretch,s.convert); - - end - - - %%%% - %Make clicking on the thumbnail open it larger in a new window - - if ~plot_info.own_figure - - %build a plot_info structure for just the current plot - plot_info_specific.axes = 'new'; - plot_info_specific.components = plot_info.components(i); - plot_info_specific.category = 'vfield'; - plot_info_specific.stretch = plot_info.stretch; - - %set the button down callback on the plot to be sys_draw with - %the argument list for the current plot - set(plot_info.axes(i),'ButtonDownFcn',{@sys_draw_dummy_callback,plot_info_specific,sys,shch}); - - else - - set(get(ax(1),'Parent'),'Name',[vfield_list{field_number} ' Vector Field']) - - %Mark this figure as a vector field - udata = get(plot_info.figure(i),'UserData'); - udata.plottype = 'vfield'; - set(plot_info.figure(i),'UserData',udata); - - - end - - - end - -end \ No newline at end of file From 865a9ec555cf8b365c58977054c25f3865817985 Mon Sep 17 00:00:00 2001 From: Suresh Ramasamy Date: Fri, 21 Apr 2017 14:38:04 -0700 Subject: [PATCH 005/286] Optimize gait button --- .../Utilities/gait_gui_draw/gait_gui_draw.m | 20 +- .../gait_gui_draw/gait_gui_optimize.m | 105 +++ .../gait_gui_draw/optimalgaitgenerator.m | 641 ++++++++++++++++++ ProgramFiles/sysplotter.fig | Bin 150328 -> 129051 bytes ProgramFiles/sysplotter.m | 15 +- .../gait_gui_draw_Callback.m | 5 +- .../plotpushbutton_Callback_optimize.m | 71 ++ 7 files changed, 852 insertions(+), 5 deletions(-) create mode 100644 ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m create mode 100644 ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m create mode 100644 ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback_optimize.m diff --git a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m index 4e4c015..da03297 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m +++ b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m @@ -1,4 +1,4 @@ -function gait_gui_draw(hAx) +function gait_gui_draw(hAx,hObject, eventdata, handles) % Load the sysplotter configuration information load sysplotter_config @@ -64,6 +64,10 @@ function gait_gui_draw(hAx) alpha1_plot = ppval(spline_alpha1,t_plot); alpha2_plot = ppval(spline_alpha2,t_plot); +% y=optimalgaitgenerator(s,2,100); +% alpha1_optimalplot = y(:,1)'; +% alpha2_optimalplot = y(:,2)'; + % Provide zdata to line if necessary maxZ = 0; hAxChildren = get(hAx,'Children'); @@ -130,7 +134,17 @@ function gait_gui_draw(hAx) refresh_handle.Callback(refresh_handle,0) % Push the refresh button end - - + +shch_index = get(handles.shapechangemenu,'Value'); +shch_names = get(handles.shapechangemenu,'UserData'); + +current_shch = shch_names{shch_index}; + +[rn,cn]=find(strcmp(shch_names,['shchf_' paramfilenamebare])); +set(handles.shapechangemenu,'Value',rn(1)); +active=0; +% shapechangemenu_Callback(hObject, eventdata, handles,active) +enable_disable_shch_plots(hObject,eventdata,handles) + plot_info = plotpushbutton_Callback(findall(0,'tag','plotpushbutton3'), eventdata, handles); end \ No newline at end of file diff --git a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m new file mode 100644 index 0000000..54f327c --- /dev/null +++ b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m @@ -0,0 +1,105 @@ +function gait_gui_optimize(hAx,hObject,eventdata,handles) + +% Load the sysplotter configuration information +load sysplotter_config + +% Upsample and plot to show gait to user + +system_index = get(handles.systemmenu,'Value'); +system_names = get(handles.systemmenu,'UserData'); + +current_system = system_names{system_index}; + +shch_index = get(handles.shapechangemenu,'Value'); +shch_names = get(handles.shapechangemenu,'UserData'); + +current_shch = shch_names{shch_index}; + +g=fullfile(shchpath,strcat(current_shch(7:end),'.mat')); +load(g); + +endslope1 = (alpha1(2)-alpha1(end-1))/(t(end)-t(end-2)); +endslope2 = (alpha2(2)-alpha2(end-1))/(t(end)-t(end-2)); +spline_alpha1 = spline(t,[endslope1;alpha1(:);endslope1]); +spline_alpha2 = spline(t,[endslope2;alpha2(:);endslope2]); +period = 2*pi; + + +n_plot = 100; +t_plot = linspace(0,period,n_plot+1); + +alpha1_plot = ppval(spline_alpha1,t_plot); +alpha2_plot = ppval(spline_alpha2,t_plot); + +f=fullfile(datapath,strcat(current_system,'_calc.mat')); +load(f); +lb=0.9*[s.grid_range(1)*ones(n_plot,1);s.grid_range(3)*ones(n_plot,1)]; +ub=0.9*[s.grid_range(2)*ones(n_plot,1);s.grid_range(4)*ones(n_plot,1)]; +y=optimalgaitgenerator(s,2,n_plot,alpha1_plot,alpha2_plot,lb,ub); +alpha1 = [y(1:100)',y(1)]'; +alpha2 = [y(101:200)',y(101)]'; +t=t_plot; + +% Provide zdata to line if necessary +maxZ = 0; +hAxChildren = get(hAx,'Children'); +if ~isempty(hAxChildren) + for idx = 1:numel(hAxChildren) + if ~isempty(hAxChildren(idx).ZData) + maxZ = max(maxZ,max(hAxChildren(idx).ZData(:))); + end + end +end + +gaitline = line('Parent',hAx,'XData',alpha1,'YData',alpha2,'ZData',maxZ*ones(size(alpha1)),'Color',Colorset.spot,'LineWidth',5); + +%%%% Ask the user for a filename +current_dir = pwd; % Remember where we started +cd(shchpath) % Move to shape change directory + + +paramfilename=[current_shch(7:end) '.mat']; +[~,paramfilenamebare,ext] = fileparts(paramfilename); + +cd(current_dir) % Go back to original directory +%%%% + +% If the user didn't hit cancel, save the data and create a shchf file that +% reads the data and interprets it as a gait. +% if ~usercancel + + % Save the data to a parameters file +% save(fullfile(shchpath,paramfilename),'alpha1','alpha2','t') + save(fullfile(shchpath,strcat(paramfilenamebare,'_optimal.mat')),'alpha1','alpha2','t') + + % Create the file if it doesn't already exist; future work could be + % more fine-grained about this (making sure that any patches are + % applied vs not overwriting any hand-edits the user made) and allowing + % user to enter a prettier string for the display name here. + + + if ~exist(fullfile(shchpath,['shchf_' paramfilenamebare '_optimal.m']),'file') + + gait_gui_draw_make_shchf([paramfilenamebare '_optimal'], [paramfilenamebare '_optimal'] ) + + end + + refresh_handle = findall(0,'tag','refresh_gui'); % Get the handle for the button + refresh_handle.Callback(refresh_handle,0) % Push the refresh button + +% end + + shch_index = get(handles.shapechangemenu,'Value'); +shch_names = get(handles.shapechangemenu,'UserData'); + +current_shch = shch_names{shch_index}; + +[rn,cn]=find(strcmp(shch_names,['shchf_' paramfilenamebare '_optimal'])); +set(handles.shapechangemenu,'Value',rn(1)); +active=0; +% shapechangemenu_Callback(hObject, eventdata, handles,active) +enable_disable_shch_plots(hObject,eventdata,handles) + plot_info = plotpushbutton_Callback(findall(0,'tag','plotpushbutton3'), eventdata, handles); + + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m new file mode 100644 index 0000000..214fcc7 --- /dev/null +++ b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m @@ -0,0 +1,641 @@ +function y=optimalgaitgenerator(s,dimension,npoints,a1,a2,lb,ub) + +% load('sysf_honey_swimmer_calc.mat'); +% npoints=100; +% dimension=2; +% y=optimalgaitgenerator(s,2,100) + + +n=npoints; + +% for i=1:1:n +% P1(i,1)=1*cos((i-1)*2*pi/n); +% P1(i,2)=1*sin((i-1)*2*pi/n); +% for j=3:1:dimension +% P1(i,j)=0; +% end +% end +P1(:,1)=a1(1,1:n)'; +P1(:,2)=a2(1,1:n)'; + +% for i=1:1:n/2 +% P1(i,1)=-0.5+0.5*cos((i-1)*4*pi/n); +% P1(i,2)=+0.5*sin((i-1)*4*pi/n); +% for j=3:1:dimension +% P1(i,j)=0.0; +% end +% end +% +% for i=n/2+1:1:n +% P1(i,1)=0.5-0.5*cos(-(i-1)*4*pi/n); +% P1(i,2)=-0.5*sin(-(i-1)*4*pi/n); +% for j=3:1:dimension +% P1(i,j)=0.0; +% end +%end + +P0=P1(:); +A=[]; +b=[]; +Aeq=[]; +beq=[]; +% lb=-2.2*ones(200,1); +% ub=2.2*ones(200,1); +nonlcon=[]; +options = optimoptions('fmincon','SpecifyObjectiveGradient',true,'Display','iter','Algorithm','active-set','GradObj','on','TolX',10^-4,'TolFun',10^-6,'MaxIter',4000,'MaxFunEvals',20000); + [y fval exitflag output]=fmincon(@(y) solvedifffmincon(y,s,n,dimension),P0,A,b,Aeq,beq,lb,ub,nonlcon,options); +% [y fval exitflag output]=fmincon(@(y) solvedifffmincon1(y,s,n),P0,A,b,Aeq,beq,lb,ub,nonlcon,options); + +for i=1:n + xf(i)=y(i); + yf(i)=y(n+i); +end + +% for i=1:n +% xf(i)=P1(i,1); +% yf(i)=P1(i,2); +% end + +% figure(10) +% hold on +% plot(xf,yf,'r') +end + +function [f,g]=solvedifffmincon(y,s,n,dimension) +afactor=0.001; +y1=y; +clear y +y=zeros(n,dimension); +for j=1:1:dimension + y(:,j)=y1((j-1)*n+1:n*j); +end + +% pointvalues=[y1(1:n)*abar,y1(n+1:2*n)*bbar,y1(2*n+1:3*n)*cbar]; +pointvalues=y; + +%% Calculating cost and displacement per gait +g=10; +p.phi = @(t) interp1( linspace(0,g,n+1), [pointvalues; pointvalues(1,:)], t); +for i=1:1:n-1 + velocityvalues(i,:)=n*(pointvalues(i+1,:)-pointvalues(i,:))/g; +end +velocityvalues(n,:)=n*(pointvalues(1,:)-pointvalues(n,:))/g; +p.dphi = @(t) interp1( linspace(0,g,n), [velocityvalues], t); + + +[net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,[0, g],'interpolated','fixed_step',100); +lineint=net_disp_opt(1); +totalstroke=cost; + +if lineint<0 + lineint=-lineint; + ytemp=y; + for i=1:n + y(i,:)=ytemp(n+1-i,:); + end + invert=1; +else + lineint=lineint; + invert=0; +end + + +%% Preliminaries for calculation + +for i=1:1:n + for j=1:1:dimension + yvalues{j}=y(i,j); + end + + for j=1:1:dimension + interpstateheight{j}=s.grid.eval{j,1}; + interpmetricgrid{j}=s.grid.metric_eval{j,1}; + end + + for j=1:dimension*(dimension-1)/2 + height(i,j)=interpn(interpstateheight{:},s.DA_optimized{1,j},yvalues{:},'cubic'); + end + + metricsize=dimension*dimension; + + for j=1:1:dimension + for k=1:1:dimension + metric{i}(j,k)=interpn(interpmetricgrid{:},s.metricfield.metric_eval.content.metric{j,k},yvalues{:},'cubic'); + end + end +% metric{i}=eye(2); + + for l=1:1:dimension + for m=1:1:dimension + if m==l + yvalues2{m}=y(i,m)+afactor; + yvalues1{m}=y(i,m)-afactor; + else + yvalues2{m}=y(i,m); + yvalues1{m}=y(i,m); + end + end + for j=1:1:dimension + for k=1:1:dimension + metricgrad{i,l}(j,k)=(interpn(interpmetricgrid{:}, s.metricfield.metric_eval.content.metric{j,k}, yvalues2{:},'cubic')-interpn(interpmetricgrid{:}, s.metricfield.metric_eval.content.metric{j,k}, yvalues1{:},'cubic'))/(2*afactor); + end + end + + end +end + +% for i=2:1:n-1 +% lengthjacdisp(i)= sqrt((y(i-1,1)-y(i+1,1))^2+(y(i-1,2)-y(i+1,2))^2+(y(i-1,3)-y(i+1,3))^2); +% end +% lengthjacdisp(1)=sqrt((y(n,1)-y(2,1))^2+(y(n,2)-y(2,2))^2+(y(n,3)-y(2,3))^2); +% lengthjacdisp(n)=sqrt((y(n-1,1)-y(1,1))^2+(y(n-1,2)-y(1,2))^2+(y(n-1,3)-y(1,3))^2); + +pointvalues=y; + +for i=1:1:n-1 + l(i)=sqrt((y(i+1,:)-y(i,:))*((metric{i}+metric{i+1})/2)*(y(i+1,:)-y(i,:))'); +end +l(n)=sqrt((y(1,:)-y(n,:))*((metric{n}+metric{1})/2)*(y(1,:)-y(n,:))'); + +%% Jacobianstroke + +jacobianstroke = zeros(n,dimension); +contrigrad=zeros(n,dimension); + +for i=1:n-1 + delp{i}=y(i+1,:)-y(i,:); +end +delp{n}=y(1,:)-y(n,:); + +for i=2:n-1 + for j=1:dimension + contrigrad(i,j)=0.5*delp{i}*metricgrad{i,j}*delp{i}'/(2*l(i))+0.5*delp{i-1}*metricgrad{i,j}*delp{i-1}'/(2*l(i-1)); + end + jacobianstroke(i,:)=(-(((metric{i}+metric{i+1})/2)*delp{i}')'-(delp{i}*((metric{i}+metric{i+1})/2)))/(2*l(i))+((((metric{i-1}+metric{i})/2)*delp{i-1}')'+(delp{i-1}*((metric{i}+metric{i-1})/2)))/(2*l(i-1))+contrigrad(i,:);%+0.5*[delp{i}*metricgradx{i}*delp{i}',delp{i}*metricgrady{i}*delp{i}',delp{i}*metricgradz{i}*delp{i}']/(2*l(i))+0.5*[delp{i-1}*metricgradx{i}*delp{i-1}',delp{i-1}*metricgrady{i}*delp{i-1}',delp{i-1}*metricgradz{i}*delp{i-1}']/(2*l(i-1)); +end + +for j=1:dimension + contrigrad(1,j)=0.5*delp{1}*metricgrad{1,j}*delp{1}'/(2*l(1))+0.5*delp{n}*metricgrad{1,j}*delp{n}'/(2*l(n)); +end +jacobianstroke(1,:)=(-(((metric{1}+metric{2})/2)*delp{1}')'-(delp{1}*((metric{1}+metric{2})/2)))/(2*l(1))+((((metric{n}+metric{1})/2)*delp{n}')'+(delp{n}*((metric{n}+metric{1})/2)))/(2*l(n))+contrigrad(1,:);%+0.5*[delp{1}*metricgradx{1}*delp{1}',delp{1}*metricgrady{1}*delp{1}',delp{1}*metricgradz{1}*delp{1}']/(2*l(1))+0.5*[delp{n}*metricgradx{1}*delp{n}',delp{n}*metricgrady{1}*delp{n}',delp{n}*metricgradz{1}*delp{n}']/(2*l(n)); + +for j=1:dimension + contrigrad(n,j)=0.5*delp{n}*metricgrad{n,j}*delp{n}'/(2*l(n))+0.5*delp{n-1}*metricgrad{n,j}*delp{n-1}'/(2*l(n-1)); +end +jacobianstroke(n,:)=(-(((metric{n}+metric{1})/2)*delp{n}')'-(delp{n}*((metric{n}+metric{1})/2)))/(2*l(n))+((((metric{n}+metric{n-1})/2)*delp{n-1}')'+(delp{n-1}*((metric{n}+metric{n-1})/2)))/(2*l(n-1))+contrigrad(n,:);%+0.5*[delp{n}*metricgradx{n}*delp{n}',delp{n}*metricgrady{n}*delp{n}',delp{n}*metricgradz{n}*delp{n}']/(2*l(n))+0.5*[delp{n-1}*metricgradx{n}*delp{n-1}',delp{n-1}*metricgrady{n}*delp{n-1}',delp{n-1}*metricgradz{n}*delp{n-1}']/(2*l(n-1)); + + +% for i=1:n-1 +% delp{i}=[y(i+1,1)-y(i,1),y(i+1,2)-y(i,2),y(i+1,3)-y(i,3)]; +% end +% delp{n}=[y(1,1)-y(n,1),y(1,2)-y(n,2),y(1,3)-y(n,3)]; +% +% for i=2:n-1 +% jacobianstroke(i,:)=(-(((metric{i}+metric{i+1})/2)*delp{i}')'-(delp{i}*((metric{i}+metric{i+1})/2)))/(2*l(i))+((((metric{i-1}+metric{i})/2)*delp{i-1}')'+(delp{i-1}*((metric{i}+metric{i-1})/2)))/(2*l(i-1))+0.5*[delp{i}*metricgradx{i}*delp{i}',delp{i}*metricgrady{i}*delp{i}',delp{i}*metricgradz{i}*delp{i}']/(2*l(i))+0.5*[delp{i-1}*metricgradx{i}*delp{i-1}',delp{i-1}*metricgrady{i}*delp{i-1}',delp{i-1}*metricgradz{i}*delp{i-1}']/(2*l(i-1)); +% end +% jacobianstroke(1,:)=(-(((metric{1}+metric{2})/2)*delp{1}')'-(delp{1}*((metric{1}+metric{2})/2)))/(2*l(1))+((((metric{n}+metric{1})/2)*delp{n}')'+(delp{n}*((metric{n}+metric{1})/2)))/(2*l(n))+0.5*[delp{1}*metricgradx{1}*delp{1}',delp{1}*metricgrady{1}*delp{1}',delp{1}*metricgradz{1}*delp{1}']/(2*l(1))+0.5*[delp{n}*metricgradx{1}*delp{n}',delp{n}*metricgrady{1}*delp{n}',delp{n}*metricgradz{1}*delp{n}']/(2*l(n)); +% jacobianstroke(n,:)=(-(((metric{n}+metric{1})/2)*delp{n}')'-(delp{n}*((metric{n}+metric{1})/2)))/(2*l(n))+((((metric{n}+metric{n-1})/2)*delp{n-1}')'+(delp{n-1}*((metric{n}+metric{n-1})/2)))/(2*l(n-1))+0.5*[delp{n}*metricgradx{n}*delp{n}',delp{n}*metricgrady{n}*delp{n}',delp{n}*metricgradz{n}*delp{n}']/(2*l(n))+0.5*[delp{n-1}*metricgradx{n}*delp{n-1}',delp{n-1}*metricgrady{n}*delp{n-1}',delp{n-1}*metricgradz{n}*delp{n-1}']/(2*l(n-1)); + + +%% Jacobiandisp-jacobian for displacement produced by gait + +for i=2:1:n-1 + jacobiandisp(i,:)=jacobiandispcalculator3(y(i-1,:),y(i,:),y(i+1,:),height(i,:),dimension); +end +jacobiandisp(1,:)=jacobiandispcalculator3(y(n,:),y(1,:),y(2,:),height(1,:),dimension); +jacobiandisp(n,:)=jacobiandispcalculator3(y(n-1,:),y(n,:),y(1,:),height(n,:),dimension); + +%% Jacobianeqi-term that keeps points eqi distant from each other + + +for i=2:n-1; + len=sqrt((y(i+1,:)-y(i-1,:))*((metric{i-1}+metric{i+1})/2)*(y(i+1,:)-y(i-1,:))'); + midpoint=y(i-1,:)+((y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2))/2; + betacos=(y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2)*((y(i,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i})/2))'/(l(i-1)*len); + xhat=y(i-1,:)+(y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2)*l(i-1)*betacos/len; + jacobianeqi(i,:)=midpoint-xhat; +end + + len=sqrt((y(2,:)-y(n,:))*((metric{2}+metric{n})/2)*(y(2,:)-y(n,:))'); + midpoint=y(n,:)+((y(2,:)-y(n,:))*sqrtm((metric{n}+metric{2})/2))/2; + betacos=(y(2,:)-y(n,:))*sqrtm((metric{n}+metric{2})/2)*((y(1,:)-y(n,:))*sqrtm((metric{n}+metric{1})/2))'/(l(n)*len); + xhat=y(n,:)+(y(2,:)-y(n,:))*sqrtm((metric{n}+metric{2})/2)*l(n)*betacos/len; + jacobianeqi(1,:)=midpoint-xhat; + + len=sqrt((y(1,:)-y(n-1,:))*((metric{1}+metric{n-1})/2)*(y(1,:)-y(n-1,:))'); + midpoint=y(n-1,:)+((y(1,:)-y(n-1,:))*sqrtm((metric{1}+metric{n-1})/2))/2; + betacos=(y(1,:)-y(n-1,:))*sqrtm((metric{n-1}+metric{1})/2)*((y(n,:)-y(n-1,:))*sqrtm((metric{n-1}+metric{n})/2))'/(l(n-1)*len); + xhat=y(n-1,:)+(y(1,:)-y(n-1,:))*sqrtm((metric{n-1}+metric{1})/2)*l(n-1)*betacos/len; + jacobianeqi(n,:)=midpoint-xhat; + + + +% for i=2:n-1; +% len=sqrt((y(i+1,:)-y(i-1,:))*(y(i+1,:)-y(i-1,:))'); +% l1=sqrt((y(i,:)-y(i-1,:))*(y(i,:)-y(i-1,:))'); +% midpoint=y(i-1,:)+(y(i+1,:)-y(i-1,:))/2; +% betacos=(y(i+1,:)-y(i-1,:))*(y(i,:)-y(i-1,:))'/(l1*len); +% xhat=y(i-1,:)+(y(i+1,:)-y(i-1,:))*l1*betacos/len; +% jacobianeqi(i,:)=midpoint-xhat; +% end +% +% len=sqrt((y(2,:)-y(n,:))*(y(2,:)-y(n,:))'); +% l1=sqrt((y(1,:)-y(n,:))*(y(1,:)-y(n,:))'); +% midpoint=y(n,:)+(y(2,:)-y(n,:))/2; +% betacos=(y(2,:)-y(n,:))*(y(1,:)-y(n,:))'/(l1*len); +% xhat=y(n,:)+(y(2,:)-y(n,:))*l1*betacos/len; +% jacobianeqi(1,:)=midpoint-xhat; +% +% len=sqrt((y(1,:)-y(n-1,:))*(y(1,:)-y(n-1,:))'); +% l1=sqrt((y(2,:)-y(1,:))*(y(2,:)-y(1,:))'); +% midpoint=y(n-1,:)+(y(1,:)-y(n-1,:))/2; +% betacos=(y(1,:)-y(n-1,:))*(y(n,:)-y(n-1,:))'/(l1*len); +% xhat=y(n-1,:)+(y(1,:)-y(n-1,:))*l1*betacos/len; +% jacobianeqi(n,:)=midpoint-xhat; + + + +%% Final gradient calculation +if invert == 0 + %totaljacobian=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; + totaljacobian=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; + dsdw=jacobiandisp; + dy=dsdw(:); +else + %totaljacobiantemp=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; + totaljacobiantemp=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; + for i=1:n + totaljacobian(i,:)=totaljacobiantemp(n+1-i,:); + end +end + +%% minimizing negative of efficiency +f=-lineint/(totalstroke); +if nargout>1 + %g=-(jacobiandisp)-1*jacobianeqi; + g=-totaljacobian(:); +end + +%% Debugging and plotting + +% for i=1:n +% G(i)=y(i,1); +% H(i)=y(i,2); +% % P(i)=y(i,3); +% I(i)=1*jacobianstroke(i,1); +% J(i)=1*jacobianstroke(i,2); +% % N(i)=1*jacobianstroke(i,3); +% K(i)=jacobiandisp(i,1); +% L(i)=jacobiandisp(i,2); +% % Q(i)=jacobiandisp(i,3); +% B(i)=totaljacobian(i,1); +% C(i)=totaljacobian(i,2); +% % D(i)=totaljacobian(i,3); +% O(i)=jacobianeqi(i,1); +% S(i)=jacobianeqi(i,2); +% % R(i)=jacobianeqi(i,3); +% % heightx(i)=height(i,1); +% % heighty(i)=height(i,2); +% % heightz(i)=height(i,3); +% % heightcrosscheck(i)=height(i,:)*jacobiandisp(i,:)'; +% end +% +% +% clf(figure(6)) %%jacobiandisp +% figure(6) +% scale=0; +% scale1=1; +% quiver(G,H,K,L,scale1) +% hold on +% % quiver(G,H,P,heightx,heighty,heightz,scale1) +% plot(G,H) +% axis equal +% hold off +% % +% clf(figure(7)) %%jacobianstroke +% figure(7) +% scale=0; +% % quiver(G,H,K,L,scale) +% quiver(G,H,I,J,scale1) +% hold on +% plot(G,H) +% axis equal +% hold off +% % % % +% clf(figure(8)) %%% totaljacobian +% figure(8) +% scale=0; +% quiver(G,H,B,C,scale1) +% hold on +% plot(G,H) +% axis equal +% hold off +% +% clf(figure(3)) %%%jacobianeqi +% figure(3) +% scale1=1; +% quiver3(G,H,P,O,S,R,scale1) +% hold on +% plot3(G,H,P) +% axis equal +% hold off +% +% +% % figure(5) +% % scale=0; +% % quiver(G,H,B1,C1,scale1) +% % hold on +% % plot(G,H) +% % axis equal +% % hold off +% pause(0.1) +end + +function a=jacobiandispcalculator3(p1,p2,p3,height,dimension) + + + +% l=sqrt((p1(1)-p3(1))^2+(p1(2)-p3(2))^2+(p1(3)-p3(3))^2); +l1=0; +for i=1:1:dimension + l1=l1+(p1(i)-p3(i))^2; + base(1,i)=p3(i)-p1(i); +end +l=sqrt(l1); + +for i=1:1:dimension + jacobian(1,i)=0; + perp1=zeros(1,dimension); + perp1(i)=1; + %parcomp=base*perp1'/norm(base); + perp=perp1;%perp1-parcomp*base/norm(base); %%recheck again + for j=1:dimension-1 + for k=1:dimension-j + veca=zeros(1,dimension); + vecb=zeros(1,dimension); + veca(j)=1; + vecb(j+k)=1; + f=(j-1)*dimension-(j*(j-1))/2+k; + jacobian(1,i)=jacobian(1,i)+0.5*height(f)*((veca*perp')*(vecb*base')-(vecb*perp')*(veca*base')); + end + end +end + +a=jacobian; + +% %% local coordinates +% xparallel1=[p3(1)-p1(1),p3(2)-p1(2),p3(3)-p1(3)]; +% xparallel=xparallel1/norm(xparallel1); +% +% xneeded1=[p2(1)-p1(1),p2(2)-p1(2),p2(3)-p1(3)]; +% xneeded=xneeded1/norm(xneeded1); +% +% xper21=cross(xparallel,xneeded); +% xper2=xper21/norm(xper21); +% +% xper11=cross(xper2,xparallel); +% xper1=xper11/norm(xper11); +% +% %% jacobian calculation +% per1flux=-xper2; +% per2flux=xper1; +% +% heightper1=height*per1flux'; +% heightper2=height*per2flux'; +% +% jacobian=0.5*l*heightper1*xper1+0.5*l*heightper2*xper2; +% a=jacobian; + +end + +function [net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,tspan,ConnectionEval,IntegrationMethod,resolution) +% Evaluate the displacement and cost for the gait specified in the +% structure GAIT when executed by the system described in the structure +% S. +% +% S should be a sysplotter 's' structure loaded from a file +% sysf_FILENAME_calc.mat (note the _calc suffix) +% +% P should be a structure with fields "phi" and "dphi", returning a +% vector of shapes and shape velocities respectively. If it is not +% convenient to analytically describe the shape velocity function, +% gait.dphi should be defined as +% +% p.dphi = @(t) jacobianest(@(T) p.phi (T),t) +% +% as is done automatically by sysplotter, but note that this will be slower +% than specifying a function directly +% +% ConnectionEval can specify whether the local connection should be generated from +% its original function definiton, or by interpolation into the evaluated +% matrix, but is optional. Valid options are 'functional' or +% 'interpolated'. Defaults to "interpolated", which significantly faster +% when calculating the local connection or metric from scratch takes +% appreciable computational time +% +% IntegrationMethod can specify whether ODE45 or a fixed point +% (euler-exponential) integration method should be employed. Defaults to +% ODE, fixed point code is experimental. +% +% RESOLUTION specifies the number of points for fixed-point resolution +% evaluation. A future option may support autoconvergence, but ODE +% performance with interpolated evaluation appears to be fast enough that +% refinement of fixed-point performance is on hold. + + + % if no ConnectionEval method is specified, default to interpolated + if ~exist('ConnectionEval','var') + ConnectionEval = 'interpolated'; + end + + % if no IntegrationMethod is specified, default to ODE + if ~exist('IntegrationMethod','var') + IntegrationMethod = 'ODE'; + end + + % if no resolution is specified, default to 100 (this only affects + % fixed_step integration) + if ~exist('resolution','var') + resolution = 100; + end + + + + switch IntegrationMethod + + case 'fixed_step' + + [net_disp_orig, cost] = fixed_step_integrator(s,p,tspan,ConnectionEval,resolution); + + case 'ODE' + + % Calculate the system motion over the gait + sol = ode45(@(t,y) helper_function(t,y,s,p,ConnectionEval),tspan,[0 0 0 0]'); + + % Extract the final motion + disp_and_cost = deval(sol,tspan(end)); + + net_disp_orig = disp_and_cost(1:3); + cost = disp_and_cost(end); + + % Convert the final motion into its representation in optimal + % coordinates + startshape = p.phi(0); + startshapelist = num2cell(startshape); + beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); + net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... + -sin(beta_theta) cos(beta_theta) 0;... + 0 0 1]*net_disp_orig; + + otherwise + error('Unknown method for integrating motion'); + end + + + % Convert the final motion into its representation in optimal + % coordinates + startshape = p.phi(0); + startshapelist = num2cell(startshape); + beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); + net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... + -sin(beta_theta) cos(beta_theta) 0;... + 0 0 1]*net_disp_orig; + + +end + +% Evaluate the body velocity and cost velocity (according to system metric) +% at a given time +function [xi, dcost] = get_velocities(t,s,gait,ConnectionEval) + + % Get the shape and shape derivative at the current time + shape = gait.phi(t); + shapelist = num2cell(shape); + dshape = gait.dphi(t); + + + % Get the local connection and metric at the current time, in the new coordinates + switch ConnectionEval + case 'functional' + + A = s.A_num(shapelist{:})./s.A_den(shapelist{:}); + + M = s.metric(shapelist{:}); + + case 'interpolated' + + A = -cellfun(@(C) interpn(s.grid.eval{:},C,shapelist{:}),s.vecfield.eval.content.Avec); + + M = cellfun(@(C) interpn(s.grid.metric_eval{:},C,shapelist{:}),s.metricfield.metric_eval.content.metric); + + otherwise + error('Unknown method for evaluating local connection'); + end + + % Get the body velocity at the current time + xi = - A * dshape(:); + + % get the cost velocity + dcost = sqrt(dshape(:)' * M * dshape(:)); + +end + + +% Function to integrate up system velocities using a fixed-step method +function [net_disp_orig, cost] = fixed_step_integrator(s,gait,tspan,ConnectionEval,resolution) + + % Duplicate 'resolution' to 'res' if it is a number, or place res at a + % starting resolution if an automatic convergence method is selected + % (automatic convergence not yet enabled) + default_res = 100; + if isnumeric(resolution) + res = resolution; + elseif isstr(resolution) && strcmp(resolution,'autoconverge') + res = default_res; + else + error('Unexpected value for resolution'); + end + + % Generate the fixed points from the time span and resolution + tpoints = linspace(tspan(1),tspan(2),res); + tsteps = gradient(tpoints); + + % Evaluate the velocity function at each time + [xi, dcost] = arrayfun(@(t) get_velocities(t,s,gait,ConnectionEval),tpoints,'UniformOutput',false); + + + %%%%%%% + % Integrate cost and displacement into final values + + %% + % Exponential integration for body velocity + + % Exponentiate each velocity over the corresponding time step + expXi = cellfun(@(xi,timestep) se2exp(xi*timestep),xi,num2cell(tsteps),'UniformOutput',false); + + % Start off with zero position and displacement + net_disp_matrix = eye(size(expXi{1})); + + % Loop over all the time steps from 1 to n-1, multiplying the + % transformation into the current displacement + for i = 1:(length(expXi)-1) + + net_disp_matrix = net_disp_matrix * expXi{i}; + + end + + % De-matrixafy the result + g_theta = atan2(net_disp_matrix(2,1),net_disp_matrix(1,1)); + g_xy = net_disp_matrix(1:2,3); + + net_disp_orig = [g_xy;g_theta]; + + %% + % Trapezoidal integration for cost + dcost = [dcost{:}]; + cost = trapz(tpoints,dcost); + +end + + +% Function to evaluate velocity and differential cost at each time for ODE +% solver +function dX = helper_function(t,X,s,gait,ConnectionEval) + + % X is the accrued displacement and cost + + [xi, dcost] = get_velocities(t,s,gait,ConnectionEval); + + % Rotate body velocity into world frame + theta = X(3); + v = [cos(theta) -sin(theta) 0; sin(theta) cos(theta) 0; 0 0 1]*xi; + + % Combine the output + dX = [v;dcost]; + + +end + +function expXi = se2exp(xi) + + % Make sure xi is a column + xi = xi(:); + + % Special case non-rotating motion + if xi(3) == 0 + + expXi = [eye(2) xi(1:2); 0 0 1]; + + else + + z_theta = xi(3); + + z_xy = 1/z_theta * [sin(z_theta), 1-cos(z_theta); cos(z_theta)-1, sin(z_theta)] * xi(1:2); + + expXi = [ [cos(z_theta), -sin(z_theta); sin(z_theta), cos(z_theta)], z_xy; + 0 0 1]; + + end + + +end diff --git a/ProgramFiles/sysplotter.fig b/ProgramFiles/sysplotter.fig index 8f0e04569bb341b5c4779173f3f14ffa70522622..f4e98f976e6de1393765c783c7bc9ee4fadc03d4 100644 GIT binary patch literal 129051 zcma&MWl$Z_+BAv=2(obq?iOGpL4vzGB)Ge~%SM8`y99S9xVyW%ySwg>bIyDJ-!(N= zQ}fiUA2X|0cRxL{f+{kCLL_XAOeC^`Dhwv(R>t%s3Re0~CbkaNTqFv@s*-Z-Kj=w> z9gOvzjEzWaZMaCp9Lz}s?Hov0m`Rv_a4|D+v9Xb`FfntG{Qn%qu@L_okdm^1&#RCa z2ne@~Gj&}v0#V%THSOCfiXbYBVxXw^RkxG|IKQ}hQD=;p?f!@ol2qZ)TadYgWW0(X&@1+&<$fPZ~0S5j!CZ_d7gWs~i;NorR377mQBP>ez;coeJ z86&!KLXP3`-z}vbvJ=BS$htq);bg)09*iu^^#N!B<(USuE3skKd75@|!a|H&27$RI z?-$x{TXWPe&{DcAO&>?_X5Ud}E)_|2^+5-OXP!B!wSB#OR8cFPzPuTYinC8hH3*R@ zrs%6j^zcblMLe|rr8(`DtlGS_n+}(dq&q^Yuo8_S)%xP2ps=hxrlgc#J%+KOdH0)lk%}+;(9w!I z-0j~D_j0ukdW;b1-08;hrPH6yc|o|WN?g)Ts;6jwFvXK|w=Mif_*NrKC;8K*zb(9v z>XmFa7~4zw>Krb@me$3F&c}+zN2+soruT_sW#0VFn7~NOD8p#Yh`?COIKz1DKZW2o zpMLO%BKKzc%jF|#Ji!i$_M5`%Rzv59+-B=`_u3zUg`!OgRW=t(|SoCJ{L5 zK#E&nBFZy!x47XpMW#m{Qs!5n`pWd>ue)X|q16dt$Iw&Vi{tVQT+|!Ig~9_|H|!U=wwJzF(HTpVEDZNXIuAbg1yl{tyYOs;SAtcVU)Try%)WmrrsykC8AW^SaHB6PL3!3`8u-yiq%6zMbf;=#=EZet^Rm~Rqq z!Q>~&zug&V>8ctrJT489=T4@kydLQGzQ8fsf450Z)b^XDG-BKzmb%LK*FGZA{F8#I z4snB(J=j&@MtO|^VWi(_(HQ;P0xA%jYTo`AzsC8g2S56mszLUB3)`KNOkI_15< z!|LhzeY=oW+mDz2iO2k1DXqs_ogX7M&(@)iK#%L?^R17=R3p>Peo|6hBkMR$pZE1* z5Bbs!`chTD6JEoCflAGOsPRWnuXZg$sA*nXEq_9rV#W#Ar}MILq#6sC`koSjRPmGJ zEt8wY$0}WIP1cL{+rI2ze(?CycA#+MW#)UIn!C|Xwr>2X7`M+o?Sq~A-hAja*Q?WM z@}r=sJLNU@A>H1(G|1^;G!x9pi#12?kmcr*N*_;KW4O{!`;H5LMrVFu_>rY?zMCO` z>Oz^U>bky|x?+zL(=rK|=~$>SoE{$9}`rGUYBC&$vhKyq}UogP1KI25fWk|=`j6et7&Z;&xD9=`Yw7jA>6 za@_Hf`d+d2E`tz7I_?``qgZqs^{^`o5#`MNTRLSin# zI)7a)ZoHs*`Q`XDp>{*#f%V!kcufSwHiWn%qrqv>(N7wQu(zTxXr4{IO~9s;e|-`X z9Kv!|;Bc^=)o3?qx@}{RWFAj(g2R;^k6oE7j6I<5Yi6~T;=`WhXZW%l;#F#Nl-SQ< za#hmqm+{E|Y7KtBS}m9cq44QEe@qr!7P{~D0Qni-uNs=X@8^NZVMDB3B$LI;B`Pg9 zZ@g(YvIj?h7rnBhdk?HC!modcu*6q8czh zZr)t_)4|xgF@|LY!AL}6<1jOsh$`yfwP%alvZ72P|9)k>B}zJJlig}})&41haKg2k9j^>bvp1hss*@vlvo`{u=H;WN%+2fc};4rP@A#oMtLbI{ZtN{@PF! z{>w9s$1mdUq6L1#Yg#VeQOv_iG#onY30i65hL8IU@9f%#U-iLWxEP8O7qi%%x#W<| zW_Ej0rn3%v^V74~6HfA=PEwWF4TXEhfa-VIy@V=P>$ZQ4FUX$z$LY>;As#{h`t7Lb zGY}ZEi-3~-XY7XCV@5~IG8fW==8c2i9qw+**c%B0;dkrB09E+Qj6l~)psoY8)HYGb zrsz#r2cS$BirgL%{mi<%aG>m9Nc9I_%BJTA@2SyE2TrR_r5q=%oMLnBjbMbf7_4bu z7cF@*-qxIvYNc)A$h>gpXfsv8a-rJMn-O1`VzQ}BI@S6&iPM{MgZK?SH1<<}EcFbI zpW!8{h9bY!Tl5yeiyA3z1ow-N7>+{JHdDl_Gr_9H4hwe4aScRGeuE=7c#8S zTdu_t=F};(d~NMG%Z2R(x@>uqbp`aT0YijT>>p3A?-eG-)Bv0 z?W&M-lP1N@H!sJzzoPp&7iOq$H#l5Xs=0;f1VAQ<8S&W_^sUS3%_aVX;@cI-w{Fj` z!z#GxOs?A$wd@RseibF|k0EDjMRUYK%Wce*y}mv3>F!Z=TJefdxkW?D5EfiZrq>eP z)O*##@PpWZ9D4MlkMj%8Q;^nPA);kO+0hf!M^|?q6`?>s+j$sj5!ZN9a)~HjJvIby zzQz?bKKkgqzeU#rpBGPf9|ly#Po%lT));1Vn>fyZJV_rt)beJa?ly7LV`zp~x)ueH zAf--Yy6Y$#b*6syw!Zh5cWW@t`>_5S?m%>JU$pioUKp|XQC9PvqJTbci2vO)Q>4u> z1aSwc*=ZO4F$+nrs{A!mjP@2Y?61gY;9Y_%1R(abT*#&UO2TE{cPrLfh zA23%z-kxy0IOpM{Kc4@+xP<^7h2DwUYZ>0DDeX8@NLyvZ!=Tmf)^Zin5&#f%IJ&I6x_L=J3hPfldOtwbZH-ISto1N(+y*1c}m_zsh_<;yCl*$>s8^5B0 zcM_C$hYOPlG+&x^NGL_8LpNBYfKhCj%Fe$7c@mt8b~i-r?T{$_a;!`~p4=jMv*(

Kp($-| z$-1U|^JG5sV26=egKLS2{SVrFo$zKuh@S;NJwH zCjz0nDu{%!tU*R?JNSSr1{o~ zMreA^`6DQ?j?1pV)qLCKF5vr#0HU2Lp;^uFWHeWG=M^u+-i4>YG@cw3mgY~E{dSnnW8kcGIvElYyOYUv+>)Jl}clz7g70A0A+{N1o?QqTC zbvIU{JHG8+xbJ)?z5M7ZlZQ9~Mzu=@3$s5zZ-WEC?O+h}e*lWE_c@?<{NKjf;talg z;Uigvq#JrLu7wEge>h{XQC{RewfaaLh5vUBa+?BQ$b=+4BLcLT zgp`BMH%vx{g0TF8F57wXjRrxghaN?X8r;Mm6 zU8RsNs$W>mx9K7Fax8^zSp?PLkYbieP_>j2Qj?>`s>UQm;{Zdz3Hsr&$$;xj zRu)I4Fr{rTv%79TLqS0~69+PhaA^ZcvZW6_y?+727#NdQNX6SyWpDCP+y+uCN`4!7 z)eZumd~wsXxhtrMqQ-<&>Cgog{;{oyV&=D=$fSXSB*E?bt)IZ;OA(WN%OUtrlqwGK z`dHm&mZOk_{7bC&X+1k1RiNkt!h;UL=3X8z=FN7Psp+PZ68pWE9DEva01E1!1%!|& z5i^{C)-tAPdJkz&`C}^h7lZJ_8#1A^WG`kXHZ)=wTEf!Etz=T)1?@PL*4V$+Q zAv*#oba0iE3cb^6gpIRDK~;26c#zmN_Se+iPXDE1$Z`|^jL`7wC``}gl6R9V0HVo{!E|Il&tm1p;P>$c*xFtJVIF=A)g|9wrmI zulDwrCissyKT*!*xNhB=eg%2&P&MU7B3zv8_M5@;?mS?mYB8JLbYo&#de}LuZSF+A zY?3%edajF0KlUB61$Xn;LlOD4(X+Md9_=t(Gh>j`S4w57OE!hDuVOqm5RJt-T2*U} z(FH=@5qMwbzsI)+br%N-?jzINxpxYx>s-7SA2wq;M|rtuwbR_ctfvB63nz6HqJ}I8 zJ09w4Ej!$5$-x0PE3nqHn&9#8in}bhIN!oUWaQ87DND~NP$&0CJc_1w7S0X&m2KbU z`VGMNs`3I_mIUt6M$Gz6lQxj2>P75G@%Vk132GAG6_VHxFhh({BMp9EbJKsY>%NgB z7gK#7*h8Af;aBjWQ;h=sW5d(Q5Z`uVrje1q58zP@B)&uVKSs!5c__U=ae)Y z%`pkx@#nd7qzJC|H_1xz$YAfr>&I=>Xc=x;lx5&!-L>u)umaUQp)lOSTiIGVk&owY zlJrPy9_anydU$fQ=}TDU`U6C(4oL4kG32r_e~%0ssf_Bdr^6NvI$g~Uqq&xmrY(eU zB+&_(s4zl#{euT)A5;eflRTc|e`9jr=T%M9&-Z@>aMdsZnlGCK= z%uI8mfogdwUH3@kb=G*?{icQqjOQ^7*9aPr%72**7Sky3LL;(%!G_&?a%QK<$^dqf zXf`Le#uEnio_LC2Xz!))43w9HLuf7v7!{B~FQwkXER*kyI8k+YTv zRK(S;%gmg%$3NA|rn!j=kJLXrP*QmJysg`4WTaxae!;(#1WR||9ZP@U-N-=T>Hn3AU8ylZ zAZO3iEg_549U%+jU8oU`58W?)tuyw!>K~o;I_B%QdLF-1*TMH|^0$q2Zmjc9pyqrq zkQnNJo5z18XI4I&b$`;`9`rPslxFeLLr!k6Y$PUtq2fXCd!SS8GKC>~-RVWX^+|sK zYs{8ycNIK;15#5o1`B)sl4WF01P>qf41`Q}RINZd?gUh&W1=ZEa) z&NDd-h^-cU2!QpedBM8V@?ZVrza|5gf^|XSX2{e`@-ct>bR?9peQW;2nh~WWC8W>^ z^Ko-UN?>k7q~perhSt_lX&eehsa7CYRr@8Y_F6ni6jd>Bp|(+6-$ZbeA@pgiTYGv2W!pmgAY=O=3Da*I zX-O5YaNf?UcSY+&_?+#`TBRQ5X1%;a3nN{!ohg%iwGZK|cg9HRbo>H}#3mxrQJ^E_s_)vaHqC zj%V^ZC%qh@CvxY-@}T~W>}wAixm?F@nBWTZ;Fxd5tNqv{VLBt2$}It|ATCfh+b_nI7yBPT2dR zZ~PFDbLCzPdvH4?bQ-DYU2sg=lkgGjhw#acK`$!ol-< zcE>Gz<}i`zI-d$OaQ~Ib_(Y&>=R}%^7+!=Sek#{?sH5%vbJ5v4@wMbw$ilpzf8`%T z3zN>@mYBh^6DR$dX;^Wbu}j1({zpyXtwbp|UEE3q?V;UY&MkIqd5E^BQnP`gG{ZK^+uiHIy({RA9bVVVC#S|2t&tl{!s}Iw z168qr^iH)Ma7y$7Cj}W2U7QF@XPG||mIMXt5iZ6bSl;&XM}Bwv>Tocm^xL@-}J z{1B*JhIR?exzLZS?T#!~44fA3)~Mc{iGb0)MOZ2Ua~HnxiRMnH3t;2PN3EPCIQeyS z3$t|SRhnDp*W*U4Lx*_jb$f34W$e&p+Wqt7>IbjTZ57!i@Z9b5Pt%8)HK$QFGlLC_HSLeh@Vi)4g{P?`ai@F5Oxe69Mvi^; zZ0UTWg}Y`UV2`XA4y!FhM+B9JZf89J?mib=@tPQfDuo6E5Cu+9aNDzJr#X?c{UOA4 z=}gT8+HSNx8b8iMLoiP32zxS|{~}q%Zsnx7J9A?zc4ThFn<5p@@k3WkF}l644~Ffq z0CaHqRdx4YW0)z-vpN5Wl6Pt1X@$v3gK}YT9<*dNGi=%*#Hk8A)1X`KxBFVMM8VDu zL&Wb=!~VpaT64OW`~2M6-G7$RQo{C5MHa>VsUjA{t&FHddGyVCykNLPNUR*z3dqUz zEq|U78CE)LB>AZfC7lJpnD}%8GDj3gKCW&ok%u0?_hO4tv9_f+s#8^%F7-X&BDX4Q z>{Jn+!@BwQDVM)D%y0#{m)G8-F}d=n1iZPK6~3?aLoW^%>3o0eBz&tr81~#>O!X7C zT;NvGQZbXlb;veqYs|bCF?!SG<&`vQ{?LUT^Vs&ZP*pbJv37B#A%lc&@ zm+2dX7JOoc0@tEgYcrO(dE>4+-5T@S>T_rE^4#8FTck^e|GQpHL#|WNgy$}ZVXqCD zs4bWG?74^!JlInoEojiy6v;e1!JP(cEm4ik$&SFnmZhUdVO&a|V!-tSH-k8%BbH~bL3$8VOm_o>XGAkIkg@2V9l*(e~mh_i|j|bWvjiU?fTEc$H&Ua zzH_v-D=H*v4A+y%L@*b6vGP0Y11s5cvc7440dJf7 zWhC*e%1mKq&R|N;^X7>RXObVn^x1g&4~&6hdCHjh<^kmLsDY*~D~t4oCWcg@vk`Mm z&G%FGA2mOjgOs)K5i{{^b)JDQMT#DbBB>rN95aL(kuI z65G91DaWqclWVI2y)JVE^%8eIgOjzf9yg}T;Wo*0ZZ^J4JrkwMfGl2k-Yo<>#ZL;} znZ|Bx1thw_e-Zmve%ZI6qBxOG1$t@Y{^WYrAI-xt{)-r3T#8t$ja7u$>&FPw5>thE zT((+-H_5MR;qp;9a-~-Dk;f=9s)A$GN+*XiqprQQU*~fyj^qE5@9M*@fXU2soxbR5 zXsWvLb}jSG2h?G1`RKZTc*D){@A5fcq(hAS*tC(wotOLw#O&M?ESPzfJ%=!BtU-U3D zVXAIwd>93BjBbW{TxvGlF1M-CK|W?d&-0YoALv1U|BSIckr?dczBrNU_wLkRcI4B& z(3(xP%sD~dLv&-ZQ{fyqnXh{S3yJ$CM}Z@-RIR0Rn18sD;8S|Le0jlW4*YOwe5m|C z$=QB#({@7T^ZP=AJoNMhWC34EJ~p;aMPZ}QJ+rklEq<~w*N zPx4l8&y&znlfk+F^jr7tt;}#^(vXWt!YJMsnK`68D7w`_iE|(`ib=*;`p?4%K{C~? zbYi2S(+*G?az~(-R!y&N*3u-5KRwF6kn{W`XJ=?w zDI$^(^Y)=EnyV*8ANE$v0dQ?v5_F>k3GeV$7kDoFLcM0q5Z^yJ;J+-8Drou10)x~w zk&#m~JEDjdFa->l<)SL}F>^_uG_X=XBSi5@14e1%pEO{O57-fz0l+04Rm$U}Itdvclj!?5LJQ<7HR!&Fh)Zx~g9{*B=kY)4e+h(UHj$aUp&{KzP-+ znpNesf63RZC?TxBWQs0lOVjB0AfP*{C6LoK_2K&Z1c}YRcHsuu$`wvHtE7@-K*}?I z1_$e@O7x1?y&>Bgd`$hZ*z(Zr`T9c2Ayw%H(#GdqY_r|)yq+06Y_!?9)i^Y~AH{z> z#XL}^$&O5Vt|m$oF;pY>(#RZ}EZ-VT9gG&fQkE7kcvt#6J+^Jn&mOB0G)@qm#4y1;AUK@jH$j zPKtcIF`rCu?BB>RSemC+=#kN2he1{647Hk{`i^Aj7@JuS7pb5o6|@Z8GCR3)EZuo~ zD4C@U2zF|oEdX`p2JcP7@jw|8bv?sgpIxA%LB&&P6h_t$>ZHcxflzV1+l(B`B(-FG z1w|o+Fys31SXoD-c8|u&#`vtCWA@V9lYuys*p+9xH&m+onPu77?VGn(!QUJ@Bi-M^ zuB#7mq~9u^&7y^KyJDi4B{w;YkWXUt2<4gH0;ozb(iF9gl_gz3sSCr6U_#3&jm zkVoE^f~_X%7(-&XgDLPn<*y*Eqx08T8l`};bjM1pfe^?|9)sVZcF8tegP`E$_@YM z{^biqX}P^T%4=i}`VS4ahzFwbSRZ7xSr3~|(~4+ZiSU){kkX~B*XmIC9=ySI=6o?E z%7FJN6B*6q$})+du{{_Hru$d#Be4O>@IxB4sG=FtEILh|NbCjX8C-jl%W?fq$!b%z zUNNZB1PP;5@z0*3z*RgDjMp8d|FdxDnyF*r%$xm{4(?Sdrkyx#xsANj7LWy|aQ;$6 z{K2LF>kWf-fZ z`!NimofFdV_k$Yv>hW`bwd7;w=W2W@{{*$JP6HG$C|;s4QBQCFpa@l`9M-0}W$Q%f zALE*r!;$#xx}-UX4L?O)Rr@Nrm@%YnL=J~aOWV$wv;wgTe^qYsGAlXBY=t?b zP~a#Ug#XU}G^&Loz|((f=&avzg^pQ;=u{C`b^@a^&y=wH?d(Ksx}`?LJN)$guj`v; zD{6apl~A5$_M{{~@!Jd2R;v9RzRA!#JJ(agt^REhqF1!Lxx7GbPqiPjBtHihAzq9g zv|Tw`KJ6zs6_nzaO}_T$VE^S-9SczYaQ*sh+VrY6Wx7=ii80PA@oQ{rnGu{?x!aAH zNeBn%eR~iVP1^j53KO{O&d{nj*|}dc-1Gjg?TQDIC3p2SWkSH>p^J%qrx0a-?1+hs zIX`fzF9t;tNv)0OFvL`12-tftwSjWkp=SFOMi%d~kEcBVUjhE@*f;k}CdA;(Qt=0F zAwQO&$qC-?8Uld5pSiiN{u+@inajS7rY7Q|b+NuRgQ&E{5`l< z*H;IxT&fMgL4BfnA9BlY^N2i6pZG+wmEN52u$nw6w`8`j*as(d`$4wk-WOH|Tf!ACH z!9rXLjdl(u*I9SfF4t=Xu8uQ#Cop2tlVL9t!-sG8|20?!M!pb`BnJ>Xdv9%VZ!=`% zd?c;VACG78S+3Vh_~K_PWaS3=JuT+}s96!gs0tdtbYgcJalNvL5SZ2ALxlGNaF z-l3Oe_@>W3I?*#ROakFk&dyLh9OPq2ZZljTaGZX4a*}r8`?w4p1MTpnG;jpS(6z&F zunq?mi?XcuX#PJ<<^zq|3fW8h16Y@jOBX%%#V=+oE<=UFN5IG4MAF2ENQ($v)@~~! zUR@z36%NOVo@QuRMh?c@UXorCW)&wx9hM_5<;hqWQT|gy^0NZ=6k>efpkA7%?gF0N zpGBLyjD9Dk`P&6ULOSA3jrkoT>U9x==#h%Aiy-<&7kRy7{(<~>7ZFd(ZFl6)ER|9o zzUX!u*-kZ_eFV;AKJ-0>e=aeSj=DNcMFT054z##e_~-EdwBdu^>VH&sARx_+56;~H z`kzyA8aq?IF}?RA@25lCOBzGcpPNt|6bRgk2`c&sS}01ISTGAah?&SqDbmpdVB+Lc znNl5et;~JWpD(wWP85%C z0y%ZzOaSeCsEt^H+1~l^7bw_H>JBJU7 zRVIpAiPAI5X(MQE-0_}ByfKB=h-yNLbLa~c+lP;EA=x5IOQuGMv5yFwet?l30SH~_ ziL%1=xlT+D0}V(f2zkt21mEJ`?(Q;FLJXM+rj}Tzqpmj|ln{r%eC858*{mO2|&gjZ~2|5-b68 z&hOQptKSQk@sTfGts240cxW_~pc%frtKryT?>bsKIQT$n{xp!lTi8fkZXbP0Rm2yg zwgffT*my9Bejy9zXy9j}@jqQl;CA7vd-BHR>2kZ-6}O$>jY2pA%l8B9J8M*+oI*|Z ziY(DAP~IA(-E5~UC^&&@j;D9qZQma`s%7B(adK)54 z>DflEV@_Gzpuz&UQw733dzskg$Mqp!T(ZRN2UHdRmW;jw7AonoLRtkVl|7m+5fF=Bi8 zQ{%SJ;ru&i))lsU?hpn-R!YlbnUzQ?PQfT(a+6T~>0Mvjo$Owjzr?ops*mgei$GqB z=0+rz8l6Y~3`qX1@2zDIBmCfA=_RoJZwEJaP1Tm$j*>q$U()^nhWwwzTNw4ap}00k zOiGA+JM>S$^z+otx&KEP^ZXohcibj+1xGFpK8%OCz6^kPIB%5RtPf}}j*qv-#T$3u zgke)REb!agc%9y?q8`(d=k$HCP^Zv(LLY<5Aqn;J5s}JpOIf&edIUrgk4$cYeeo!` z7xCa)pDt_rvUeVOJ8TG%PxO}7A+eUPoc}#!Sy|s^nm_y?gjqg^6A#k~-okK*zfE(% znAq=+-T&pSrKOeuLooZ~C?h67*-iBb}FpxN2=Zvc>}LLK=KoeEH*ZU`KP9QadDUqKBmNfDx?t-R#KmzJf&se$M!%s zd_IHn>QoH3Ei_h1jXtLST8jC)S`9bY%gcg(mq0|>)KeAE&mCC*e%i?Bf1g!eztr6n zb6n&mzH?m{@7XwSrMk0d@eZu*XCdyNRy%?1Bm#&3XI1PIKC&JXg8yeqRdppW1#z=^ z&!YoPZ0Cia74k`pR=~Nutogx0vK27fX{)QZREI7}>&-X*U8sV&!9-+XUp;7%{Qcp{ z{Eq-i^3Mu!fP3`V-&4{GsEVu`6Kst-7w)QN4ba4Oote)apT}*wEhdET4m{9NfSJbi z3YjXhFX#MA?!Q?^(Cv&AgOSrPXQ*?DH*p`rHx3MZMG+)Fe3AkEV&@`zr0tM`qSe(L zql`q4**=MYwLUqC?LVN3BQuW>7OM1=F=Li&NqeqJ%-xPuzUb&w*2^Mvoy18 z70ZY?@Es3r;e3Mk-n#YF)#;+5LcJC8;2&`UQtQ_vnCD|y!gjx|y94{0fYkzbv|AXn znS@E^Q$M?dX!5?3f3n2|U?RaEK@q5zxGbcRkb_lqMAstPx1%+L+P^T$BiI4~$9NSB zfI8!d>RVl7YHJJ(Dd#eW2AeJ>d^-QLP_Bs31wwR~x)zT(2WM5NYmJnO(vkDG zT)aMs0ZAddyv3H#xbwHs+q$KBdHtk^A3qu#+Aw8SI!PbN>^xg3JPR24VQ{{_5&$K= zJCG!-3*@vVw3M&oG=U_?utm7?PZZIE_VRHlDlrDuC!4fP?YATb2W&y?#;)JOIB{k! z@1zerfgOzYA4LaN#?>-u)UM~w(PNI!gZ5CVF|&ppKG!##)jmB{BRuYHIBti8)*(A3 zH(y;hrhH?~rBX-0G2(lU+5FL<)#wL6S@xkCFp99VEX(JW>EHV)!~MwMV(4|1p+$$i zeH_X%7xMf*k*Z=)CYeC)^tYdb%>&9uKQDeI=nni!r>qP_*??!MG^LK;?ynCi(ZoDv zmqwipZLmJU^XEKoRDD~%XoZ9<|jS`lLHH8V!7N4Fk(v?=+kS5Kfi? zB8xTWJ2tv6iRb=Ot_(K_NB?4Sxt>Vvxc%Vn2NgYCCeXWxJZo;y8Y}UxZqSBn?b>^B zhB*^tNF4+!ILkoc=;IID)J`Q5nI*nU5n zt7td2KRlI{UCzU)-vsdYBkq&15;2zCx{`Q9nEK;5+@EIe2I^$vcPkoPL*m>S9d12Qb=^aB{-#wCDL{xX=?!>Ba*WHjS52X z598-`n`>nqwqaSOmrcuw)Q2Ogvo+aB=dj&)y%LNL z2o9uf+a(IL1!#75?ef27jSgf?%)ubdfF|enxWf>P-E!3erJB$ly1TC=U-04))g2bS zHE#{8`sE#cYTjWabPjJ*Dg`X|yP()vK27Az5fqtue*bb$6N)6Bn#+2LeO7*NX9P!l zaF8(cF@m{V>~IW=d=<0cEof>iy(J7mF~ZMBGyr{_&TmWzSfV!3XYG4TT#8O4wU2sg z-4GBExywFRoiw?V5gFNVF>Yh?Jo#F*SRF@ z&u8Efi=Y3csk#04=2$a(FJ)0ibUdPUEwN_jU=8tZ@3zEoL)rOB zlze}SVT~Yx>EoQ$y5cWWH)qjVXHoL|?y~#2fukxwZhb~nxz;mdhf@jQ1Dnw)VC0r5 z>tNHE53&&&=RY&pK?(qHe1j1M6$S!TNUmOe&NRPo^~i+p2qkJ;f8GY*@MsnH1?B;w zHwk`%8?fw1S8|&aj8#{+h2T9dlNk@KUDuwHFO#E*#@fE6d49j(f4jYnKh*8}b@@Ky z*;x?+3b31+`1Te-&L~81KnbDvd=tk>%4G-D}^&oHQgp1@d3J< z&DXxvE$!S#Gh)t}V_sgA2eTHbfSSM`ZDNOWwkK;QP8p(31QBxNK1$#7fY9qrP)4{2 zzDu1^;T5ViUUl{jDT{SKxeqK2Z&Ylw7?PSoGX2SvkdTKXqB5H#5Ov@*?PZCVv^%s5 zWlw%Y5EL+>CZI6UbNaq(Rvaq1v~qi)dyqE@i=lv~Pw$ zs=j}-=Zuf1H`Qgce|D$*7nUOg1uS9=rvK>s9h1~IY9khAH8`y)6kK0flpQoN=^hGYB0g*3y4Shg46QX#w5PS5nlS?Z~5l%}0 zCk0dW+0PBz2Uk;q`-r$OZY*gE{qj9=N8*U^2$8h#c!*oPN*gbK(Ae^F-Z&9zh14A$ zvcB8=bWI*~na$F>5xVXB_APOJ&yk%SI9s%0~s}L{nT)%z#V=a`v3T z?qNVFhM=T;&@g*dKv0S*R4E~{;6zNb=6&*@Xq{!kFHtObU?6mT7^{4w&&< zze8Nh^NM%IqN`WaaHTc#l4=?RV+^j~M?Co76Q76;pWkNyl43XxW^_@8NNX}|sAHqL@yhix z#@6_M(*amOG9N-IEKy96YE}7}cz-kAukCIMDk^UfwqYc>+~ZcgPGfHR7`12sv*?S6 z$T$5?_~@_Dm@)b^lrZncU=JZDqqchKHgz`G+yXa#9!=KoOz1Sl*G*7rD+&RYj0ja*m0*C? zXc+jfVcR;>kG%uv?r*5b%~2|ED76{v!%#%~awD3tvJj@5P(DCi2Y<|JVRgOm0M+>5 z^t(%*JZDpP?8CD9sE0klh&DO44$s^*4VX7&kJM?Iu<0SqA5B!kF~{M1E}NsbPE|fU zc#WcTjmN-+g#GQhW<3MseO%CCO)|M35&lr;(0_7R@CGIQMs(3RapSqfUgekNfB$=o z&y0fICrm+j(5b6%$WK8|`_5f|P*Xz{+I;fR$}%T(M7gHrY{B-o-hI4Gq9~mlZHwJE z0;!2pE>*J5Yo2XKHY$XnCHXsUMraAF{2$hbGPq$wX#$R?Ag)Eo>P?W`%PE7;l8Jj1 zq2$PJ!3HALE8zK3uEY4>X^=v2g|5$G>2*7#D-o{FKn8n%kHw-H^4vf zU|2aB!elI?h;ma>qVaWytG{b6p9vKPBej-X%FmkD?(nF=Lw;3w>M!3jFdqI>Y6Qbl zCk+Os43yjokQlSs8&E!SbH2Q)(?6C7J$TN!@G}(jjwot~@7wkGX#E-t4R)7{XnjO@ z5mD! zeEFV$2-{K`h3MmaBy-uc=KS;--H~ei)uNedz-zvO`)^>Aaw+|3Um8C~8MJG>$nhqX*+qSf48oSE1>%fXW35^J_yg+tH7UN8> zp2!L&06j>}w$pn&u-*{`f9#%Tw0f4gX5r8eq9E06W_o9NXPKJtd1k;tY)x}pvem1e zE^dpFs)-K{YeT3UKeoSU6;$$Kze*`UdbMQzZO0!qQWF!IJ&ar|M@GXMHWbTD66t+| zSoq8-4_dxQ<)_e@IK$&bn4cL~is9e{3dKf*ZY^KGQ)RZDe z>X!wBCH;lJzpr0|^T?rl-#--*4x8%|sH^4(h0}wwFC?dBJQ!%nh@-`r(mZwha9blh zyP4S)7$f|j*mc={+aw54`9IYottGIJ&Hi-JJUxyVsDHcS42G)e9sVbBU5Ue2h|5)wFlrc$C3G|@yS34_1-9QDT`~mm z13iI20__j}CVWxugUI?k{GlRCigGoUaJK zAs1N$Ylot7aAk*~R%K#26AYaWHBR+Z!2wAxtn1DuMgskYbTaHNlTN}1H|dK^jjF`1af{%W&N}Rr%|Ry>imA`c^$a`# z`X4_g|2H=sq-L{L{>#?h06!yK5Q%vVz@!~2{D+MuEu0?am%zEa{`r?Fx4!EPJ1?z& zNXVT+xe6v)n;UvGFKq%|zYrSWK@Bj&-zAOKmukeZE@K#9I2BY4-FxBcvN5{KVavB% z0teA#=BmbJdEbSQhCE*Rb#7R;m}D4`cjk_GuCs!V zh0pY+Rr_R4vonaN8qa(&QYvQ~&TP}36jl}*9)668UL*CRT;*kA6(%v#G%C>DArICJyr?(UY5?rx-G=x&sd z?k?%>kS=M4?ijjZzVY_C-|v0a+P3v){l3mgxX#(ny^iW@B?siH@l3b<;ntdE8o@K2 z(KlzOxC}}lA>8}B&6gkJ*EaJiJP)>;z%Z*uu>BWKGD00F#PZob=iJq1>sSLaRqmp z&+}{9nA%~(_F?qO=Q=a|Be6n_`K#^hiGC11ojUk+93NzQ&Q}F<#U)o)b;a5u0hrr; z&vzyzr>~IMKfSa@-8T&O?KynD7uqWnfR2FaBN(K*(@jZI4uZ4ko}(8jv$bc&kSV2L zC{ji(!>ZI3L?5^WgpLZ$_63P#hvpN=e~qS)m=7`$dnFXp48(rv@WnOqyxE{TKZX)f zPRm@V@z!#$;cq1H8cD=uSMo1Nn)j8rAS-k(PuAnxi>U5r zy}ElF&OtErpWi@Zvwz%aoMh&~#t3ujftQkYUC*VPuxgu z?3X-}jC^rp+sE@@l-4%x+^u*PHKz?RWLo33frve(|CKfRMdZ8+50ikd+I_~`EwAl? zBK&~jzxejx$5i`RqHzg78zEevTqN7oOv1x=o>J+{?q+(4J;WVci)7Qi{hs>?{4|~q z5~YrUpR_l-YjenG*?BMv2B>SPFi)~J#^{?94mN`rGmJb@;NWteAvrDnc&YFRTBc7B zZBgG(g^2}Uqp%1Agy#0iMcBt82XHAD74D3P{=*NWi%Lj9fR+Pd%7eoy3clp>@?nSm zQp1lWEKG_5Yt5?$wZ(bZPK>^yv9j{cuT}Y`V!dkhUui3%lt|LsdtGXuuPwZ_mAN`W}buyS!K_QIBSI-?d5k z!mnRl6~>rIF%_dHnr1p@&86UeKiT+{y_pXwCk$-10X!aI0xdVG|LVD{|69+khqhwI zI3|_7x~G^Rv=#w+K+E!n3i|@rgS$YDxX!$02cD)Fgve_oZg1PLc3436FL2Vsj;J6YYbIu?P!zW zLD+b(8iLHL5`NW#kkKb_+#cYK@FZBCvEwXzNfX`j^$wrvVLeRpfmD(Y!x8=T3A+?l za6-nK2SYnU8;%Jo$B^zjO7Ln=q&ZqRC?h+`pkFwHFPs>{Ao_UJ9o7TSxZ*apzZ2B4 zy>~5J%NzBeZoHR42#I2KdZE(2bz@O(^2wbe?W@Y%g!*7WFS&vrRF)|+@4^3dByRO` z`#IzqchJCXxvTT1`rbtP>21yuTAvB+3B3N;8b_rkr^GH|?)i??734oa<%{aK)R5F+ zqVNmVKX$`CO>8>m|M&r&M<*Hnac`RYLz!~EflI+L+bg8JVsKGS*nz!_VwYpPx-#_H zj~>hTmiL)khze7N9fSKl&WiM8ab*?<_(t z@pGM{m7SpJ{(1-;|Jy?l!6O`2K(=Zm+)ae=$tB$N|LNz1k`W?&|MF4#k>^itane8< zVDxNO?5p*ZPtvwM?BzGgVhasd z5M~QQisFfu-m8JJ+X}f9`KoB_B!kBisG5Tm`QuD9mf3bQ=7dSHgqv#YGtqr~Z-kb+ zQ(g-S#BCvuuos;7Ohn}}?1cM9oURGq;3b|F|HfynAwU~AalTk;Up=b5_s&utjw3#3_&63?-;d1Wt2&CfLXpT}TT zm@tn2m^g|2zo8IAee*al$C{4&nizhjX z1WzWonVi=yb57kZ;1n2pij?ty(NK=gPcCj-cCmv zHV$5vQ+%jnAfFHh3_5wEXR)u3enIcvm*Jn+xD{vmfy4w5CNSDVHe|(J5+J+59j;g) z^5^ENrJ`jmr4#CcqcF(Oj@SC8m1xipwY~q{bg!`YC$5;bl|CCC>wpEs5(1^h z0^lJ-_>X{KV2LAzm)-WPVv{r&)_B{qAvOSa8NZlkWwj(ni6wq)l*i%dn6{GMM$F#C zzLqBE>}h3yED;Ex2yYbpCQ6E&oGc1_oIZ$(Tyq%ki z%&#;cV&6$q+j>)%gSp?j4zZfvy@VJTJ7WJON6ct2tb%-4=tnMMkJ z3b9QHfw{fJvIs^F$jIs#4#j^c{kXR)C|1IgMiLrqn#0r51j66$^ua6#x~#0|^rXD$ zX&MhxI-DwUD;17f?I7iJ$U5)~9JB}nb);T@{d&JxGGj2i_rXqtk0Iz*De#gj@8S4- z(-N`aSon~SA?0psxh`eRkJ0JS?UdZjX`HFH_ipZK#dlrpQT|tbJWpCKyTj*~48-zn zv9R*;EMX=^(ZD(rmM&m3f+ilWP?g=;%SdWR*1_E12l}d<8=Zcdh7hrcyZ#U36n`y>RPFaPQx_kljp=PGxv(VxzU91AIQKbACjrn7 zKKxc|0^02`Kr2(!p^C+Jhr_x&2uHG;8cUZo_icfzC+|8DO~$V}{5=Q-y7-m$z2{qE zQMz2$Il3ne#@0Qbi=A$M>Aq&J16XMUeH>r5mL}8py&>!O9`yZ5l>+bA!}q{Nx%z6bS0gv+yC4M?Bi2S2KC<%%dHziCpNa7^KXZ=A_ zlMH~5%({<{kGD78eotN}?d^{Gez9c{#pqfKeb%gC8abq9!cOJNs-mk9&mmkQgPO-) za;4Fi!U58^TPSL8k5JUcPf_GznYlX+Z{QE_bVrwiK#(h&2sa^)E>AGwIA48Nb<&wX z20r=*oT=N(WkU{lVX8&J#Ooz1T#X|RPkwEO-$#Ay8U0+`ZhR+uN0nZONPz-?%cFEa zZuELhM8<+UE*iHm+F&>hSDWLhMiAr!tu>$~3JKw5T?A37(b=1yuUZ^sG2kyTvpSh?MC2SmU_aXKaT@ltfz-;qTo_pHy zHsd<`g|V+nmszC>L;kb}LB+Gc03@fyIA8y(2-(NdfK=*;$C>jQD6oejE7^*n}ndLc3 zm~CeumuhzIMe`qf|1|@Q|M9|S_j5KH%X-%Z7DCJbw^Q`t;qm>_$~E;$HOLRK!q_O^A=2kNWi5PB%slI$y zeph=PY3rTDq)<6Q^PI|br@FV&j0|hK8meW9vD<}AkNhI#ab0&j2Td}Mnf14`kAe+H zfS(Q6&AhyK_U>nz8w1&4zoLYM;P%d5z1nUMto%1)PXZVsyKgR&58d~1H`=F8JA1aNop44Qw_V6H9Izx8s-&XCkE?xmXS@`L_n zR?E!H6GjJOB|zapj3l7zsZ#6la)>Net%dRv~Y93&#z>^RR{} z`!Zn)OPR@7@uQiz_K^L{ka?*6s2Rt_WNZR5cXy~-<;!;uljGX z$41!nmZ!-k{g*fVE*peJbdGJrj%MDA_mg4PE7c;}?D3W?_QvwaFUi)z*jTnO;tOGN>iCOcR@+uC)-yG=X=qwz5O!S=8u%pYLy3CmPgtLs@IQc3DYh$ ztuGrNdT#vbN)(ufZ%91u_J>HAl;r#{{a~mphWArrg|!c(By5WqVd)2&qQVQ}Nlai( z5U4(MpK4dvWO=3o(rm}G36Ri=2DjZmhoF|De2PZ$dJU_{Ftbd>_)SEl?21>cMjij% zVVgi>hE;?Gw$E&&@7G7;N`GR4vdpI3*c)903wSP#$aFfzeS=%2IJ=B6ikOfg+O$=a zkz0o`61Y%ziQcP~6AWFt^E97|^ZVZnH#e7!S*|bD?b{`Gf;2<8@z0(P(m<6;J;oGw zI26wz)foPXt~!=Icdz)atG)wm^61EB+337$G!C1xxHrVGH?{7 zu-$R%ZZsTp+ho2GlCCgLB#BAHzzHuq~f!Sx7+uO#=w|E#ua@!;K1Bf~E#F|GR zs_yKiu+K{;lZ(I!@IX^PQ|s-u($V!5#Ju)2O20)DIs4!+_%yoRZa4TOR}A7?gOg<6 zBUW^4&;?><2-JWRy8Z*Am85Z0@UnmZ{xnt3dmYv7pN-vrTb7@^n1W=*~L`I*U7K>L6drxtc6E@Zj_o4OcNyl2+T9X5!2JWa` zCSqLLditI3mG}A`5JV`sk5#D?D!s2-iDIRUHp5LHG3OGOCkFR!so##A4*nBsM2A1y zV5NjQH64_(GZtBQ0|VPp;I>T4_hznb{YY>8Gewj3{%*AGv_8CQwwf~GGz{9?vyZnc z_}+nL5-6}p*hmE)pUf}%SpDWlx}s|-wcbSZ))?SZ-ja-T&h-LimQuF$qn>OJ%m+>v zVY)o_#&-fzvhQhysu7hwPFw`xc6D}oZ$nR3h27Y2&N^T=WZ7O+n9hqiLLFIWx0Dq1 zFEWlOC4`V7?iRy!mG*Y;&_feLSXB7vw+#vH2R>g0()ZNuqiK!Zru1Y6tSZ|_@b%%O za{QG7i=@A0>v|+`3QQC3b7-`8dT8RO?nGqBX`|TcNnhM&e>LK`e4cq8fdQKw)m4|> zQG%zY;9ap@bA^;#19sINTUktw11nJu*HKcc$66la{5H00_D+kA0=fQkz58aslf&W3 zy)`};Rygrl7*BDFu>fV_laS&BX~{x~u0wb3~rf2^buMh?Ts zlrh8YKvfah5>;$z_U#00G;YI^C?Hvr>8_wrtB@X8US!!=5px3yY7g0hhqq)#a`cta_8@1R=b#` zwgh5IR~7YzhU&Uv4o4EbWx!PP{<%A9tKs?}Xr?(n=3=NsY?rAA2ij%3t&Dpsc;Wuz zQnTlrrD6D5={&3d)Ccp%Rw$)Ry`}2d;r9*k*wY)uby$UT)rEzT@{OZbK9z;)<@G0> zSMM&sneF6tCbi$C&WZle)At>Kf6Tp*^zo11UT&<% zx%7~O{a5v%AD5q)WcV;LY2*(jNY)661C#Cf&yf9TilQ*W*a(gc>ZS>mMvQ+&HV^ir zfqDFbuZ0I8Es=yz5WXr{>YK~3ekMtK3)4d_k>+_g{5%4Qiahu~Z;d66J@ezO^H8$W z7Sg?&K$j7pL4}Kjhv!NA6+yXo`U(wAZ%A_armHa2fHC;UaG!!|h{@`LL*fN0d;?fc$ zMOO~o9-~-14>q2(T=D-f#;}sg$e%=1X7zSJOP=lZY&>F6t}foc!Q4PdFc-oL-H3gg$ZzMKAb$Yd9|EZuQUI0nX)$3e zy+?TMGGO@+DbpYDFJtoqIMLZk_PCrwM@wO)r3l&4|1>y#`I{^3Z)_B`@m9_KM)Hj_ zUhG&zB6w|CRa~3ERy!J@*VH{ddg-L14SU7oNCr8w(M#n-5286uCJG}VE|)44#tPn;@!EYOz6c`pd3cJ)oOK$y$Q-#voM z-WdrE_K4-foRo`HvZ`vTPVFowW9+_~x{u4U2UjiEuH1JkE(h(ayEA=KErGtofxf5~ z@qurRjXD(Dv~*zIUECNm7nANZ;~ff<-S|AxZk?>hqXWWE$J(mDq|>}-!?Mr#&9UI~ zW(Csx;K=_&yw%zY{)EUPHzu_x7H3#|kSw6(rg*w9P_@@1qZBB2MhdQVpo z=@ON2QC2LIAn$C6^|J^%#`R|#KpWW*OPnSRDa`J6E>IEt4q7S^OCOsFQYGxh zMqFC>%1^%UX?$mD$A5t~H;H{c#%AUTdj!ctm%`k76xfq|NC9nmJ{^9a{L=LPRYvew z_hIo)1}0%`YGmF`=G7=r*TEgB!`^%GYK5b7!E|{x{(!~aNdEGw(OeV-%N9EJZ6In) zF>dN89x_Ui78U`0jP5jg;qyA}efH*b`E+~;_IvreI7+>`{3OcFh=k*59o(=`=ANUi z9?gOU#Jn6%o}~nxOVWwB3}y>mzfB0#vT40a6%4rEBD`9ZU84Dn?7ojFLqR!65}g)L z1-%F+p=-$I>FGjUalsAU>Dl@GoK+N`bL&r%FMB0qXkn)|6l^)a;cwo}trw~4V;_C2 zB{RU?g9>+tgousbFImNjQ38Ql0Wr1&7TjDKyj(!p-L4fOfnFEEGArk=);~5~3=N(K z`^7NUlQIK|Gf-OmLMQi_g`V_WIwrIxJFP3lcG!+D9=kh8`kZ2f@A$F~zaWH-hRNPY z<)2u$wwkaSxPSCmr&UnboKq#W-9Zj!o>^QUcHCG&JXC<~QlfvTlUqdZ`v|sg!#bz) z$klH95sM4-Zr`{NWo4Fs_H(t^pBSv&2pMMGg`ch}+J?ut@qqSdpF+R&Fygoe9p?jG zKY*Wl=MyeP?^7=WEj4E^0#7aihfqBAH^46Epm538NtIvO#UU>&70B>UD(9jNZXCqS zAHCYAY}?OC|K5~;YvJ2$k}|AjaXw$?7D~urc}Z7^;=H>}EEnmYGOYTZl;mRX?%TyGelvy%Vj%1i`c_ONm{;X`&kZ4tU~e#|lHFmsxw7hAW2*=>Ptu>dkIrNGw0 zvH8iZ)>HhmF}p4!+tfcBZr_5|ch(-aPCtZ(2U?x#UCxZXeq308`u=yfE_dTw$Evs} zwet2EL48ym>3#y%nvsWy-lztYDC+cu(z(a2HIOl<()PD;CrJ3XV-jF)7l|jW=D}Y+ zvic%pOA%PJx9Rh?G?AREhA$?Dv+S52i=3SY8L56-`B8DVGG&ZJ`-MJb24~{d|jfzxz5cnvQ~0)4_e=HRE*Ep?pm2FwtF(tfgkQqZUj2UanKPhZQyhC$o4Wh;18}IOqpR8$l&G z$ONUg<(gSZaotak`)g{ZkNund)?>W22kvirUH zu-L4s;HL_uS)Q)ST+f@;{NUrX0ElCN*N7`$7>ElfGV%8|Hdf%OVIqY4MI#W-$*G~1 zA_4as0Yta$V4w zGH#yO;2#=-s(TZpzO<2)lYFW6BPMqBo6LYc{aszczpMw?5%pMgB~Ekyy0d!<*5Os< z+S&nwx;k86pGX0VbI&P_(ywxvKfqC^qhP>4NQ2EMhU9(agn!x`UL)i^F$mrinWHIb7fN&MmXTpk_i@n%O#2LyL!(g(U zlkPAaw1awB=sQQYoI$QXRXC{f4-yYN(tGjSf*6Zm$=;uIBAd_jet{avhU(Ap3D3Bb z8in3k`)|?L<4<;)`r+`9r!*WUVD(a%@3KI1u}JE6mfJwf!q=v0y>W(%i{ZZU<V3K}4z%>>GHH8hj}tiLj8j_1#S!FTYjJ=G!%+Vv48vc&EAY$ehG0m4?K28m zut=}GnPc+*?VPdo`J2ssiuMCW;O;7}>`&+FZiro>b1P`@hImr^T!%=P{jGm`YX0J7 zs1LXrz|9QI`m0O-dfb}*uJ*Y^kuOY!|13e29EGTg&<(o&4Y)H0i~8L_eI?1#R752q zn16&)!*Im5a+7*pyo=r5$vawmzg92?P(M{{;5HBu8vG{r0kOZjWQ>_k1pK9@D?^qW*gA!dx#^ zbdDTjly}Z1lxIG<*N1rR6f4DpiqrBmbj*{7CA>( z5fK+xu@r$vM+RPRjG5D}$%`e~KT?_@hW={e`wN4weu_W|r(PS+;Kq|cm1>xpkRDRs zO6#P>U`K|3vL*ZNM?&S>A*ST?UO+G`3+su;t|?Bk?{lX+FtuGM%m=f!er(V}W?izv z>Nk$})m64SxNc8*!Hy6uA<>L44ctYv>!g z=9h=z>l)UKzD}$C2q_XJ5B`K-*kT6m0R2~M<@m{OS>9@|qEqJnw8@T7xr-xWPFFx; zU5W_=CHeWzmO<>NZs^gfyQ{T}enw?(rFeEZ`C&q3brat#@CM zg1n43A%uJsTFH)CcPeCJf>1ScA#3wUcam8|q?}K|ZPj;o6)!J}CBRQL4!akGz4_>j zh9$SgBI{CX_W@^xMf07sJ#&|$xwm5tU~;7wLIDz}x*=GJ43bDn)+hw?48%?c%eS0p z_5hC)x!KIA$EM!#E7~$ICIej2Vgi6YaSPe=KTX?PkWMw0|3#VfK~a7)51jE4whbtV zgI6G>{ESwl1mQJgD(P51g&lx|XC{LsgeVjJ{&x-bzrM6&@A#YiFxXb_e~f9We~f9k zc&EbM0vVQP&=+#-Nmp00k(Vxx!R)n=8Z~VBc|&(=<{!JM>HrSAuUPu8}hzbJ~|o^3bHd>61Ir8E|wft&n=>bMo$bCR~E`8 z`;{;nEscKj{}guY{NKV3l`$jJKaJHWk%I3X3E=;fcVwf*-vrDAz+iOMqwZcA?AIFD zwMyN}{Fb{#m}j8;zLLB`+WfA!X4S5jdZ>cq@Oo5>G4gly7 zJDYC9j2ipwzys-y-i5SSG#a{_L0YnZ>;RlsG1U?ikgwa7ui z%8C42EbhOe6 zb;vBUyPr+&<3PKKYwo86vs-sQh%e>Ae6NW;Nf4?VuS?^?ra>L~xY5zyfV>=MzOUNP zue8gr@g)iNbL-E&V^>;i+yd8`1c($4l6^vS4|VYNR6N>t&6DeI7>^~am)*Pz?_>TP zHc205u-J<#FiH}h{DRK&9OU{8iw3rT4b?}9QVrns#-i8C@_*2{aC%%Atxi&kyLrk6 zziDHi-ye?B8|1&gZoYqGyYW#4pL#_7a+QwR=<>=bNi(;+g+Gjuf3zBN!d!JgzA1|j z6jF#cU=56rLw4pTrQ|hFE#XvrUqhkxxkuwp{bQ9C@`UK-Pk1)VPN5JBdh(asI>{RP zaIP6<8{Jo!^5FLmj_D%K+x)G1PH@0?q>(~q4^jfpV(PEtE)~c^LcBFK$MT!yv&_rx3K0W>e>uE{?p^vOg{;FictKfH2k0Pwpkvr`{0a4&pWs)SAxs^;5mdu6 zl=ZH^j%v>jjY3uq3Zo0>qhPz!0^I2-;|#}4?uqvFZQ31(CuE(%6geX=xaQJ@*eYIB zlCGw9q$cuY5_K5AY{>{8Xv7AhYnqs|xjU_LL&;eEMv_mZWK;`)V~|z?g)8xsC>0EW z;?RWP2xmKl)mNdUVF7-uqag8`7XGTH^8!j{w=5_ItKUH%!}PYjm~&@a5$e7h+!N=)!EaS2w#XR1&}GW{3ZboSWO zyU;#|j&gl}spSMB1tcGa5_}N8dvS|v+rmKKJStyjchffq04i_Rjn1y~@;jYgr8$G+ zOKfiS8GQO%hwZ)`tf9$PqdVruy>;NT$fFyr@8SKb+2Krnl5aj~M!cdgxfD3u?;}TV z_2huk#u4lC;`3QqBUuM=ZTiobH~Ne=@CN1>Cd5_z8u-2 zj}o{=DtY81EHff*PUKZKbWuhRYEx)W$tJ~v4=lg z-Y2fkOFao%pgwe_ma}gH18vFaya1X$aWQu7G4HfJZ-TP48$o@X;*Kz*v2?T z`R~|sZoHctznyq%g4M$9*?;oZuYtE>cm)WShZ7b$6V8@z>A`&4rRZmFa6HIxFj-GDD@TVT8gaMlCnH_m-yaw# zW7da_qr>}5?^<*it_y!Z^NLu!!vFU+H#0bM9ass_r;?!Nd9#aiu^!~z!q5}Raj3Ty zBp&ASnM+vUr!#!c`1D{R3D-VO^z2?-v-_ z0)V3c{0vOCF<8cU`U{Gh=4#4h%eRuC%ChJbd8)N+8m6LDE%FI5-`pdNNjBtuDm1#e z8Y}J+KLCR4V528^;Tw?}J;-#0aPtA_ zd6Tsg84{LkQqjY4w$YiL2z6}~JLmV#4>SFX613NR}=0*pot zCTf$j$FI}=$d@&sh^kLnk>TS_+p~P+TipF@DVicUN-&QR;=%BobljlsX9h+XxLJSQ zbFN;`7VDZb$;kG`5#qUJq3-{B=jj2=|EAUMu$}x+PuRkXC)ZuDrI8;Eg`Z)U zdJH>9&dnr2y+(B*ETV2>S-ILkAlmA!j@hf>QfNIwumP^|mZ#<~<{|stS6llEP7W~4 zvElZC#C$ZuF%15oO`{B*#KdBW&a4geuZId1`?Hw*ZFTWu4ap$Hc+8Dyc~kfHBO^Z| zotp>wqDnuulKwu{`tXK&>GpWxtz{mZCB+ijIOe_)7bNpTL!+|(i?y6m;HY(eX?us- z1?5ikl;Ds%d~r(BOh?C7b5`@#V4RUe+_vi5WlJi{^90z6_f+1QV@eYwe7vrYTamYG zE)#^=Sk%H}A&7|&rrk&GS?Z5B|Z$I(4;!FxbCHeGFJcJV zEL7W9Cv82q?()|WosS(8U!pn`+XLd3c;fMB$qP?V<#uWyg2cH4D1ZKtfSwR*hcODd% zHnSJvRn42n$(1je=>X=%xaFsbsqvT0?EcpYgGr&QU9Plur#k>cz`i2nwvl>S5N@mw z_=)+%XLI8)doh;4n008Dm2j8vH^1`lc-D>`<9w>3)JH@sqy}mpq`$jX3PVo`hZWO> z2*r@8`k=pfe1Z<8^Gds|+yCHp z<8kUmaqYFl(O-p9{d}=z(8c>c70lc1^5!$7EKiP|#z)qTOX{xGI8j-_)Lq*r+lp;{2qw%Ujy}=^T z{K^tk8roY~6dvN4-_20%9+Ws+V`M0BFKB~D0OBfY!&QC5-*tIUhSf0O!!ZItf3u%$ z5@eVuHE_d@`PhW~NOas^QM2iVQR*r*v*yYN`}PFx>MT0@Z12&kyKi+Jxqu*p3n}*u z^qwu}F#0R$G0w5{)z#;E*Wy0pioVbDDim=Xk=|h#Tth98{YGAu&B)A>$Y%J*N=l|D z4Id}hi{WEH7`fJfRLqGic^g(L?8P-(7BE8G#dGy&b4ghLnIBr4qc^A`JjBV@KNTez z`up+EDrgaWgT2UlK-tb9>Fp2o{}Ef=M|Pu}*$v2RYrJ%z3wI`hkzwAC9uNQ<%`1M%RbCfB=w==FY%mw#UKq z@jm67RKP<}dK77g~u%&z`e3v!csr`C?+t)ScvGoEGZ*AsrCAdWFH1FV^kGQkAJ(Fmc zV`v9I<$d(O-Ha$SdtJNrcslQIPtR%Gj_@}i9>O*R7lCxdv+#mOVAd0ltYaB$ zn!H`95<1mVto#zTHy7@P+uV`Dc@3pWBxPhaKlvKNY|S<5>b{XVNi%onzH#y=5vDJu z5DurHLf(SfnxZHmk^MkhAghoYrW?ua7?k$%>r7F8!3mXBBb#3v&~^pv^mN!uZ)zhr zHF4LDQ;;n)J&6Tv@%HL*J-(u zET1uz8Aue^T}|(YU%G7Ft~~%ClpZuNPB*5IqQ0S3y#^^?Q`3B76qVyPmGr~;nUIz!fE>Y8J%S_m5c#0b%EI{U+?IKOd|wEQO+)kPOSE9jnxhOYUxAACGo;RaFVVqr#`VZMEhFAg?W%UZu>E| z4>~JmfI1p`L(a`P@pmm-b(~7$#^RI~pEv3i4GqUqt+^NwF2G=4ZSX1<%OE22@wK;K ztBxNWsPzZTBuJ`#3~1lrSjo$v&Ll zSj!)~Ru2$dpXXhwik32#ru(8@U@uK(<%vdZPdmqlKTD|bXw^H@quN4$(P6meQ(Y>f z=ILF$B{htn>l*>O0KX6AmaAjT|RsF!tk<>2=d-;^*b6LNvR@TGB7J70#6tPQQrt4E$zJU`%+98izMJN^_x+QQb7W=) zuF~Fbzth!Y-kC(n-BH$Xb>}uxrB4*Cu){@vfkX`a z6d%8ntJ&QGh(u`Z4=94Hf`FoOkcV+g`|czoy^_4BiHKkVR-HKG$YUfI=VPZKa>HGg zh%a#SfExHgNSE%c_5F4GY@|5ft6p6o87D-nLcCj~iQ zd*s4*)dd}ztvV51{nL*e3B*tSd7Xe`gs!hEU4GkXlft|2C;frDX?;vfY*{=`3iIUq zkNy^kq}JYX7V}RFck2laA0{W0z(JtlzY`AsMO$)bk3)&hx#;TgjX9gn9#eG*mhfwG z)%`d>Xs)qD!u9v<_s<4TPAlr_thS?0g8(GrW#~sH*FCpAVd2U+BHGB*h4*BlQI@$4 zZ{UyRFfL@)S~5G**D{ty_nb+{Nk6uAEj@I;bV4#(Pp4>5Ri+%acv{Rsq0xAup;7Th zd88qzmypAM9g!a~boNPOoW+Sry6;I%T#02I5)tMdMV<&>CoaO(@+UBBbc;@hq?d^Ly^05{N3RuBs!$csP`o7aY*M$17U<_r9>Cy>=a zSOdDZy3pT4@On4Jr0!Gv1gZuNa&;bsTrQ6{p1L;@)wt*E)Ekp zB5!k?+$0*ek9_ zS2{nG{m@qgRMxWr+kE|;PBPOgE06W#GWCUJ3x5DTYZ_hGXjz18rc9Za;VKn-ex~oc z4N%5u*7=P3o#LFLziwV?g&s5Cg57mhYS^muV1(ZCUsI)KM2SQM(De<&4Is~dj^xfw zL!dW4Xou;oGC;vS#4`VEk<~qi1&mKNHa{X!?#cFr;5Hy3LHq4 zE(AY_Top*^hU~Im_bqL9jtEdcjzlnUCAxo`lLG+Gk9$bJhcIUWj`mi#zLNoTt?p-s zO_T*6{kceq7Cd2>W!|~*j$2edzB3m9lV7AAE0z1%aZhHrcwD?f%o;W{I%A;D$ZDQuC8%A3q{)z z!}sr%{Li)`C<#7H1cI|^(cU_>6h~h;Z;iQ9zaF?~cCKH!NF7C}FPQYmC@)+D|MMUh zG^N$`NBhG!4#Bl9@|qV!8jKe$D;lp_$L`T>8uMz|s2My&d>)&zKkJ`Wj$)3x>I((& zQHF;|3$(a58d=4;^JxF)$XP`q)(L2La_0tW7 zej${^%<#$BXHb)RSJPA0=!MMZyy1%AN1?~w>)NU3#E3Xhm+MWk^QnuQ^+Ck?cQp|D zx?cNp+E0&raqHU-W}D~BlM6JKht&XUkWlsHE zW1sN17fJ+guvV01G0zgqRSIfzWg@>Hxc%gF=Nbo&vGG~RlSaOyzfp*PPpad4mHYWH zXe-DUOM=vPot};&Pt_OmaziJxWu+xOeZ?HasXgfkX&vF>TX*P!^w;`c(ZWJ4GSQ2{ zhXy9#hmzj@V{tr#>0oO$HeGjXs0fC@`f)a=bf=CyI(1L)96a__T(xfUy zLT>?t2#A!>yMPLU4^2QRQUlUUq)0Cby|>Uql6Uxh-@hO3de50NGk0evliAJg?3Zu% z3dY#m6LjrXea&occH}_l{9xWg#_t{kCH8F`Uf(FQ^Gs%5kWvM^L|g^n%UroKLUOZZ}d$5nl``6?~SN7IK{Un1;I z{ZyRPnR+~oVE;M@N%6WZymVNln4i8;WL4*vT;sbs1s~ReoA3TDNFC1e=cXngU1UZh z6&Cq@dh1K_|5NbK=JZZZa%!cTev93Feptg)2}!(?UA?Pt4`~_2_)stzr5U9zl&Q@V z$rofC_~%miT?+f9I#nf?qpUQ=pLbebN8`3On0B>)+>!f*vb6PH9I6EmuhkEDJ|r4G zuDGm!s%_i(^91Mj?xPB!IQF}BHx*CT&MhBkY}cE(G~Tij3Sjx)?G34;kYcKXog@$<~HQXG~!C_0fDAnnO6U!{Fhper%j zb1HwDSGjofH!Y%J+=8$c+N7Z0PTR6t-V-7;>H%X$OuVQ-Xf4)U%UjHV(CoQ~@)cf2(grlKG(z39 z|8E8X=3G4MY(&?F|IBXtCsX9nHFAGr(2irb8v||6;|guh@hLT9b+ayYz`vXD-KUEd zJMTETzc`S*(qi+(sM6fOhwCU~F4&@A-4>(uct~GzWj03UgSC5qHAeaTj|1s=h{)XxLx^&9}A3{#T1l%1}|)C zx8`aNf+INjUJ9;W`pNh+F(ehZ;)>{=NdeZSKpbn$gw`3P*jXhN9!eB|gABA74#0#_ak%UY+; z7y*B>|IakWG|f&E9lh(m)WyJjp%L9ZSvv68H7m#qrf0QQ3FidQuNe>)UgqA!sjZ z`rogIUvGi8Dap_?Xja#8Mr7UmROrIS8zGb4@jJhGSTg^Wf^wh3eW=KOPh3zAUqsI7 zpF8ezmh(?aT?Cxth7WKVq<7^OUWCsz{!5LqgLu`Z`qZ!N){c|xljX)mc~y5rCQ_GA zN~em2y8EwG>y~;J92q>Txy!CkkuK^zWS9N8!=hVAU3C-gVK%E=_Mh4U%XYc&zM!q2 z`%K-ttWQ}t&fZZ>&!_p$cIeT6e&dSPpW$hSgu3*E?{CwlVzczOn!OE+vJj`sjD*0SnjC=`fYk z7cW5+h(35w6zE-FA zUU~Ew&e3pqh4)-`|HAp}=XwL}&Bf1!p3P>M^p1aeels8Z=Et)dP5y|8JE9vUh&OOAqz~|s!o~K)wBImW1 zt?s6`lvK437nF9f-qcB4*OzYO#C@q|9>L)EWf8TvQsDy=mYb5*JYM96CWSodB8>xM zn)+ae!@9*#XTYVN9eXOG2QOBqKl&``x2Wr7H?I7&LL0-$tU@7V5LrQ^XJ_XtX~Lxl zdC9FNcUfa#Cl`8ovP!y#_4K4oNnuQAPkfTAg1LW`;cl| z=O>i9e{{Evh?8X^8^hs-@aP0K+&<)c4!GhOoId^j3^g>oE7hm1-hbAI#1 zJehYPBsm8*{FP+<6}kGYbVftPQ^oeg{>^!&3f z;jxrD?=|&>GMNJL(y}V<+snl(PO%ZU`mf)+=5!O1)o{l9vo`ek0~wx^s^>2XKw;nk z*@}DEc*7^+{)4ff+%(+>hZ7v)qaW_V@%~iOJbsVdo#{O);QeI#WY6A*33$Z%N6W|C z#D$Mvd=_jRVkIZb=^m;)Nn%8>UrN(F75R;@a?$bXN6U(5u#GdCp>F3As~iSP&voBp ztlE7zT}Pu^HG7*emE*oT!dc2V6P46Ci~M@-$j(E#m@;OVZ>3Apq8wb88?vlAIu@~4c4|LZuH*YJsC!1b)RcZc`S+1AB zrm0z+q3{O6oVIxxL3xazw3g9Bz^h!{#&W&SOB?iHE9W++un#DNkTpHY3~IL64An1{ z=47nsFSIx3i1+={vZ~gws)LeL?!8k`7CGw6Tthsqa2NWDy63w%b@|8ymo^oH=O|KS zv1cLc!@T&c5?KcmT9`gD7_$bpqkhJ;vCPL0> zDLb@ns*QI#1Ut36t7F&jPy0f4U&jOQdC5-)PX2rux<}V3?>+zN;LDSgUX$uClGy23 zQaQhByqEiP*X#@N)mmn&=#Cs%30Kd8dPW98+V@AKO~YM%BMK6&d-hYjnu!?XL#qWX_kXiT1Z5`>V1RRZ!?+gC> z>SjZ|U{IO{-myqjCWjqqQn5>le?g(Fzb)(=tm{vNr~R%O(8I&!cAB2}_Ne*3`g6qS zEVuK(0LG~D92$HBs%A6$V2R{eH^^?0>#-ch(|?4FN;N;>5LsUJ)byvFULNi4f5umw zq?0lSyZr@V&I4gbjg{K-@F(h2C)K5Bhb^p6s3~95Vp@yZgZf92oBpJ*X_hzZ1#_lU zDUY>e)r@cOg^VuKbhI7nMTVa+`AC($sDHl+13zhx5R5B)Q6rsUPoC9EFv{;lDTu_*URwTaDpozSR%Ls1Bi zR1Xkm?~W-7&dtCA?nH_L=9xBq{5nxHOEWXNo_n2tPMrL|cT~-tnhJNF^rUm4yY}w8 z#jEr0+A**9zWfOc@0>BGW##wJ#F(E&W)7V@`~DzMn{M#C*<@W9WTd+q> zjLSCM#M(s7_Nj?^q=})mx1sfu|F~1mTq7w&b(33=2W74?KV>(Zr zxULTWaU7SO^+^y{oW2GMW^;k67c-e~h(Y%ka#qHN=&q1C#7 zm&ITB@1Q5QUH7)PXfe7QdgK+Dl{b!j-m=gL5CTt?cxMw@&gI{VIP*v6ho85b zD=i7-U+L_3y-HUQec3jw;CA=ji#Dc2(<>vPo$Q-@`7+C?LdB8SS&Q=7_A;*RVYg=Y zcdnE}w`oMq>2lvSZlkYMi!&j+FMm+!rH|YNP(JappBjG4rW=c~aOLOyQzB$bG3k2C zF6>*+{u8f_zCR*qD;iFgRd_l0UAIfTc;VN1_wc1g*au6RM zyyY!BU}8IUUnKcorT*UIInz_9H(tdOxEM8Me{s!vwT-;^&xJ!zMmnmEJ|1>*j;>}G z>U0O_=^8!usd>u9oSDD7YWFR6JnGDhCHK3M9cxU()+T8v=`6=<-KAxBH?usccehWy zHtH#CI!Sni7ajdmMyXc(^_OM(sFQ`Y)Y9Zi65l6M=7j?LT+xJ2!YAeR=o&nTGNpq_ z#;zPIEWxYGujA-WY%ub3qz!sCOu>e(F@;~{zZGKy+aBdNDSHzgXjU=8RBB_t<7#P( zkk%KwG2i&}QjlQp1JmC>6ubvCg2%s`+)Og$NVSH62ek{-{u5!fi5U2sr4eCBzh)<> zo7c{ng4A>n+m_>>>!GdNcf8vEQu*fScHW|JSrMn$i}?uV-)_^XY!mw>Yu3gm!oF$> zX=q({w^zh3G>zd1S@}p?yscZx2|kGt{yt! zIJMYarr%FH6z^D$7F-{`cPB7)NvSxA?@pP=iNEGdsxahC z?@4^RY*5FVdP0gju2+PQQERgxdwI67uXb`^f*C@{g|6doTy#Hc51Y6xd>u-$?JDPg zWcNxjkiwevZ>mjQ<~7rUcWemG2emtQ+$A|vuFA`8UBfBK#te_TbBrfwp1@@My7FrH zFTKa)x3AYjuSNW5EBK;IWv4~lPFc5J7;k?2-=TLVd7z^|=QKi01!X{{ySI?J#J_3I zY2|DvElyv%sJ#}bW}|@TW4Kc%pO;F{$)5Fh`sly#_WL}qXH4ADlU0;dWqI4~1z17{R*Xrc&AEyaaYPGp ze6vtOnbB7{A?Rhl7M+^DcH$#X_44cUJ5Mi`7Frg1`QIa3eAS`Lh(iC?ct1UU>TZYM zsrqGx-`{j(8PIFUt7BtUHzSMJhJGkK(s^C>Qz2DW-0#TU)W6m;9T8NHKw@J#$he01=5q2ot^3iFXhhy0S>7gWJ6#}3IvFY{w+xZ%& zO+&00{5S_*cG8U9DGGs(xWjj5M+JwUM?5zsXX76aa5PRcX^B?{5et|cEs|)Teqe~7 znAXibr5j_Jv?QuSh&4>>7M_ZY5DsMP22U`HB>Fw^E0dNaI-EGogcnCc8a-~K*&78o zYEy|m9JPr=G6%A4gTjd6cPD>`%-9B;* zwrMsxvI`z;F-E^_XrftqI;V!gU+u4t8Xu){iTYV5hWWQ`d>8y`sq`{OrM zeTdf~|nY7@R>+4Zr{(eJE0@&aCs!Z@C_f3&tp%$Z~ z#A#6~q;b^72z^?5+adBJ%H-7%M{yinAYqI3&oe*9;Sv1%O9{dq>cRvf2zUwD=UKwbcE7RP1qCv3HR$Ubs17gSUc zo?X9|u;p=415%uv8z{`-5Zi|@9A=(McIQS1$3bkHzuIQ;fW*zDt8bLOGOgv? zmc;yR6h&v6$oT)F=YXP()iz6HHo$NzE{grvjE?Ynazi@n)|X~^k(nkWl6R)5R#9l? zL4=pd2kcc++Ijfhxjtode-fU4^QnbxyKkW?BRLS{w9#!18*woK8y)toFT0(k)!0kB zrOGD#Su#9gw!LS-=9x-sSjx}(Eu_g1p26#B9#U-PL4o(v)-Xf2Tj?SzU!wL- z=YNZ0zq`T+GXF?8_DVpl_6DGSceUfq1F+e(;z8ODu?OwvzB0Wy^)tPdgOJly6vE(8XY{2V;wZ|=mhK3S9d?157?Bw+Vk*VtDK-04p7um6k z0+fpqzFDTXzZGq3G;JsPEhZ`Tim^)GJG8Pmt6pc+X(nTewEmD*bY4=J->#kfQG#UA zOWhOo*^)8ZEn<^Y-z|bkD(`;3DEVyn`&CIp*?;EEt>h&M3#*K)609@mt|X@tt%9V@ z60Oyw(B2|e$p?pS7W`^;CY_dxgV^L-l(Q0&S(D<{DchV)nu&hXNy)vA7bR5>A6r5L_bSX}12O`9-mTG6yTs+oO+WN)VySR}Mk9n3GcAss9(cOX~I z6V!8jJ8yeU@>o}{^hsF9r>(PTeuPaY$n}0hDm)mQjs#xr{ zB9ngW?c%yAy|`AoEpA?xcBH<~{cekSo?(a_O9yhu>-iyvmohNTLwz5k!y&I{ha3mL zwk5XWwu^U#7A@wbds|x9v#`-Q+1Ou`>TtQbL=wjVCatA4!xElPc>&7K$i{xEdz9h0 z<=AU_o|Lm)O!8Q?n1O?Qby?V7G?0gufOMzw`mW5tjcwt)_(vUMEv-L)c2ZpJ`fl$P zlQb7|I0b#fDJrQZ3nV~hU6_uL=H^wfviekPrm~7oM(o} ztncq%2FLYZu4LzRj8~A@>i!u%`OBzn-k}#q7`5`(tWnu*>8_eFS*aGAofvDIA9og$ zn&jOxU#)Q#8<-H=+hX>AbjWe^4m6e0qQz=sZ_7$c78Zwn1h<37BL|S8zMX#RK=2+2 z)PSH52-14zS>lZk^;1=VX&fef(mUixdkK71U|NSsl<;i{MBR3A*>R}`ix#_#y)A@! z(2#fyxSeSn(z@=tFO#3zp+30;2wngIClCw*K@kv4YIYpa+L9>QV_~@U)*5|s!dTcZ z$BvpLN};RxzJeF_*LnvMEESv9vch5sXQFEF;zqEboijkMQjA7^^SkA%NipiS*kuPd zOfa@1lML_g;`)_)TlyP7>|a3p#t5d*t0BYMYV=8YbQZHtjPa4E$Oj?+1O~#d zO52vG_yYWDV1WR~0Q?{DLBwSr0Zsw<8}NSv3kEm=;6mV+0gD7U9pKNvuLTwWa5TUM z?dwvGTf_QmO$2^tv9r?gKE>6QV_{tdput6sEgL&qkd5tH1ufxlY}wf1)od*86G-Da zHn5kUfQ@Hihm8R?KK6mt0IUG80?^iEPhXb4s{Ayq^00#p61^6YvQULx4@PEMn4b1(c z&p{0SinCZVKF&wN2OO|2ml+fLbTQxX3?bjnbOB#`lWV|)fq~v{%IDi@avk`hz;5}5 zoALw91N_)6kG2eS;c*%9V_}rMSrcJXp*{26v!IK}E?UsM7cCAR0{=2Fet@k3)&)Kk zm=wV706zi#L|mOlz>G`cSlDdUtVu0{&x}dKVhoA*CA@TjT1Qj&Pk!$Dwmf^7MJUwb)i~3_bayl@MD7ZJU2uDR;Zf!r9}wear0H z>xR&6JeFvEokFs(z=tbnwId@_L$~*?z{zh)v_2^0jeX+qk*bsnrAaw^IInnR(WLA2 zhI9U;YpgwqP$(b!blJzGQtp!?zBl874|3S1IbAWDO6mSsqdnEXUT(2va8I^$8k5sO z#)sBqR@26Y7(2$jirF3N40Sy6_gb;auDiaw)oXgi=f+~u$C|)xy%v+Fhj!*g!jxadda=~s zLwS$|rBn zAw=O}iL9Dxt?Ok^w!G{YudQQvxMqFDvr4xmX6zR&p0h7nXy`3kJd!?;4|Yw&TRhV8 zf``khPC#CItHD*gHQ*}U@km{xq^&)#`5BUYWf;$VhcQ#-y*2ax2hQv-MdOjdM#8>K zmG=)hoRhaDmedz5I%a!YqJ*-rJbG&Iu)=s`nUM$(JOqMI+r&BXLL$a_kERWzX zx#N&!^1{C1-kOI=BrrJ4J_RLA_qOEb0D%?|q#p}JfZz!bfFW`QjO?wX-j*+kSy&M< zATR-fY7m3h<3o-uFgz@Pk-cLX#83`maC`(0n>ZGT_}Y7E9S%{!AUSUg1mxb91Z)=e zDf|)K1qlRbFi0F|9u94VZWk}>ELwEW13?j}!t@dRYb`iTXi&nz6Cj8H4fPTT_JANm zhdQyGf~H>ckeFAk3^P`2GZsF40QPmgw7?-XjY}KTFLPHa(^zYnXGw;!^40H2uGY-FcoGuEC$5)f{hHv;) zA>fMu;{{m2H$3Gg@Wp(EQ?B`Hrt$%tvQ^`%ffVR44nG8K-p>Zg>6;OC?*cP}$BD>? zU0^2A6@zr|iU)oIuxNl|k?tZOy$hs^fOHX%F7o)m2pIVMtPnm?McMP5xtuSG)#R^#_te*11w zle|EeB}B(n)x_X2&fuDLn=zBTut)KB?pRYZYi~=v1u)QQdc!-nky6&}dw~H4xBJK( zNv)de7KAswEki54EzS8rWDg7mgku1w0pAFiJitc)R|6jn>=eM@d%L+W8yj#2SP(Fq zM{tX6qN2f!KtcL3aB^^GQX>+C>mmA>KAHFFEE z%CLY-Gooj8W1wes6Syq$TFGV>ZU^#bb>sJN^|o6`eM6PQA^n$!9Qr!Iz+BEy6^V^- znO$_T>3W{oCTI zfwi>>lk(%Q6}-F0Ug7v&5c$&;q=~DH4Nbp0nZ#VwC@DGVD2mT~G%!fL86DYkJ&2Dy zc(P09t{6ug$z4n)hdIR=QqF&DmtU;^CUX-Z!&z_s8*JqC; z>J8doAP)YuKS>;;K~efBcM!9n{=MCrfwXNc1M z_BV*qz4mvB(gXHfMCl%TW}@^zdl8~^pS=Q6deEMgSpL_Zj#%Dr&r2-twU;E857_%G z>`k2TdCNm8>#-L~E-$biZLMCtGpaP_P&E9uVLfyBNkfQ+#|1xuuHExUm=8CxG24d$ zE~=2YL7X8mz$0ruY!G`H>EWU^QGf|MW`wsZnSRdSurxuq!;{$~YvMW?^-Q141^E}iu zF+&d+t@p@8+%Eb!Dn(FKEL?!p(54mRMclQahZp*N1iO*L0Dt0_utD5qKV~8UGk?rP z14i$d2?b2zF%u6MX_btQ^FFnps76yz)IY~4FXB>pt0#iyaGM+IACk{n=$DZXDf9zP zcC<$ihtl3{5SOqF@IoqRvLoy<^ByqxVilL z>Ii1(cs)33o*e`h((FdUl&P;pq0~P2LrQ1d#mE*;1i`_xZJDoN?y$ zWOk2$`wcChu7_?osXiKz7mb@1jZ)sPV0?aEW{oYrtr{qKNK>NP@iTzKR;+JQzpPdw zo@NDGCYa9Y`8i0K)V+(a`&LlBGisMdh)~-;RFnFKDf?)WZttb)5MNzgGW+T0i_I;z z4xL{wcD8H>ibM^Tp<5|ZwWVc-CMKg>q9aTCb$MmK2ekTh@rUC-@BZ}jaEQpCRC#HE z9R}CEMp6vx5^KJiX}T0mHZ*Vl8|Xe<+>H#B;HvQx;FQ!bUEvp-w5NzjnW9X*NB4(i zYq7KYwMmvVVGJpfbYXcm$U%NWB`uL%LN~a~Q%uZudU+J4WHPpOcI0AprMiBk$IISB z&+_bitjEg{;8^8P_H%fRtCHl`zCI8ozfSHz8hVjmudaTLD94sfAV;q7Hox@gFdE?4 zz(^E`EIXjL$w!cCKklMBirjA8l7#GN-88M_w`V1->Pz0BR_W&c%i7c(2qSGpTSvj6 zlf&sQLf44d`a>Shslg6ay?Rx>(A1kzuv7F1_EF5is(^C`A%s=JMiGu4c&BGt9~ zp6WWvdMIhHwSfPrU`2gW3O2PR3ZE5KOS(@Uy4+ZXoz8d@JP4oPY4M>jOd*#;O^|KN zTDylj)tfpus(f7XFkUg`vPoiv(95mE%VyaXvidg)p}Jvtn7a+jW(6Cv`T{mZn0g`F zH|S;ci6ygWzz7#Y6F%f&vZt2Jl7U_n=sCoS+}=eAC>e3tv*|$sVkxrkVllEq zw+f+Up?R29pbn{!9TF^rx&t`AMa#!1#MD5o_2F)7gZELpd+oz`D$>b@cISWJkOOW% zUc6vCyWz-t4H+fM%E);`_#V@`X&H!P8Va^ki> zBeSzvNP@h+6QaH%n{lyP$8$O2YP= z8>Qco1=(7pH@v>TwO%etqDRy+7W+&Ng)^YNHe}a0WJ?a~HpN?ahhVexWU$_xbI>wH0fThPMN_IqTBSm)YJ#`RR&CMrKgvy1^c^h=cdkT zOAF0-=}Ir_q$$i;)Ae^f%uRh<(($(J-nf0x@8Pphk$fd7y8tHdcKuHC2JWYM9ZDbhW>0 zSzFri-gq^G8!15^zcfc-vtg+`II%RRlADUPOdLm_awCC&Y_z2_RL0RK-AFh3yY#fB zO{ZyYv7{%;Z)58AlZGWm)t(r5`iTbqxcz0RUX2fe9v{noQi22!x>zJOg7FD zAb_BE+hFa-;k6-k_qdMExoxC^N(mXDQkm9+=;eADwsAR6}SI~Cs!&p0wWaG{#8f7O%xiUMN;GC}Ci9HU>*Q~k zfrk)>R;8EDe?mkI01GarfcHxo}ic6*<9k$I6k&eP3XEGgApl>B)E8<~e520^a5EZeou?NsK ze#l-F#-|PEJ45hu-nbVm>-l%V%;kNpFnk^F!3{HFM?(D9bA9#2Ve?j%s6F+oCsON!;|??soqA4$YWUp&oy(BH(dXs6W&Lr;1m9;kz_8)+C?xFNGh&>tmfQWOA+v| zh3xuVUk|F5?%u=sZRN$}|6b5jP>|MB_Fb8OgM2h#w!+dwBJpKe)G2PA^tP^je|E?* zm(0j_rx*SC{dI(nCaJk3Wg+>+#ani@hRT<^1|Q}AcVNh%vMJl>>i_Az?NCu6dHF{F zUo__Zw*?)^@yVN?WxR(^74@-rX;7$A3^JiAv~Ip|V z+^FbA8E5tCNk<>tXe}Elp_-N5k<2pP($sbm6@%{Kb$T|Y|KxVWY}WhYG|MZ}EW^!R z_aYfAGV^Qi!JxgG9FXP;nGfN!*T(gsx5H;MKNQ2*?j~T&4IOVnZZPJKHz^5P$lP=g zhFERy#bTVBowX3eykxhrUoAA7xC96e&+9^F0lmk z&pBp3IEG~5R`+=Y+gCmNN;4`44RyvT387HgA(%W%|LQqC4HH$8hdjEPv$aLFdAD&k zXgZwi>-oHaf<#x#Y_E6kH8Dt_o%qpCmk(W~4qYR2wBi*g2@kX4DlAnmlq8plep5IbiB*zuf7cVR%FP~cb?nY4fwK=Bqa!f~V zOvh(T2QsFkI;NAO?ETFq)5aSoSwl=lLh;){Hd}<`Wn!}5Mkn)zroX5433*BJru0oG z@taW?oCJb{4%!@uaUz&ihhP}Ep>LUH2xTXr!KaTmi(Cz0fN zQB(d5fBIQgyl0Z{C@-|z0#)KhD*RKIsrzlDYMmW6eJ zh4q|;b(@9t`Gs}%h4sXRbv?ngqIIwO!Db{&lH&^L-E1>O-YlpXPbZbctH?4$-(nwV zA>{)rZ5o(Wfm4Mhe7yP?c&`TyA%@3t%UiIb8t5fUd75g3)`z+gwTHA|a zS{eM_M)HDxoBB>6GtlsbX}CO+dI3pgKvJ(Dsb`SXOGs)#6fzyQ5GJ_MG`Z3AJVfkU zBfBIaEP10zc;8$KEdi-bVl?g4C>ERQY*Y*&{iv5@VU%DA6K4sNV9^j~(U4&2I5p>C zWmc0Xzf<_I#!h?Pu%9fpWE|o>Xjg-z*^~Bd%%)mtw9&Wu{_cM^@F({LE*Q|V9t5S`XRgGOkDOX!W!n z<|OTgQQN}v{nhUeC>j9H-I5Z^YCwxSra+CK%GWD&Z+%xCkF6JLOpJ$%#UKQ~f8CH;q868a%s>F18#mJ4MVQD${2IPi! zB=(b=+r4e7kWj@vPjuNSufQW8?CXDqeXR-ej~~3{^O0PgXx4YUKAEG5G_9G?+_f2| zbQMo150tKY|DH*ZvU&8@%H`Y4K+k_ZY#k2v-3ep5-KkeM@gC-c6=Pe34-ZmKZP()$ zIgHPvv{K*Md`Nz(tsW}?m#a_WPep2|jvB^1u z3m*O**J(xAA%)F@R_1;EOT)dYzcAGZ7#mJW0%p$wkvk1r;XwU}?NthGP^#@!QmV(D zKyc7QFa$F>1P2o&h(UJ9V9|^o#uS8k#SLjBnw^G)zsDF8%-CSz!59gYcv++@M~#iiC=+!tH<@f!@M~O>5GT9UxM=AQ5C$VQoOL2ORxIF&v?)KX4e6d7|-4`m-gi{p` z4@M$kF0!XwWN(Y-d_Coh{#k<6(%#;bwSpJ1Y;OiEOk@7GK)zz7GqEg6aCnLt9R77B z%%X?A<+E7i-gZ;yLRjoyc7d;APn1m4KGq_beVt?vr^5O69?0Vx4ch04EA=E4G(E&+ zQ$8(Zo`{xbVJCQ1Xm1{we34(z4j`EXlT0E>Ccp_LnFNtcMCO@y@Q(wiq4SjbuBU^F z<$rn<_rCbAsnEu-RIh7)6{LBG=+5Ya9%=-CLcicx=10h9nQbm#!D__*z_pkKl`T_(bX00qrr0N=xTbn zSQByDVc!#ioCw11okC8q?C;-OoYo1#CdMO881_9cAx$vYLE<#?z9%bkLj7+`h&mjO zYiZfo3~gz7xIc6no`Gwb-`G5ZMl--uiPL#}WcnKE{olcproMGKeykxFQzAhcvCjpi z(j)dI2?Vih44VvE9$NcCc3+f0@ImaKg!;Y5WDp28i2WN%5Pu=ABRWVir_pL=dS@8) zOS6o4vrMjI8s==X%uq7|!W`l9qreIJ?D4qk-_`}#9jRY(t#`VW5}cqV5iWmw_ql$a zJEDvj9_-mcf-w9K=QF==%DuKu!^}0yyndC2xibyR;+(&x(w*n__gio&8TRvTw~`#< z^}5sF3s6~{k_}?v6vUXA$q91}!Emd&XMS>YoJEt(YJDXpVR$szqP8;0k$Wx`dvMvT zmQH*!AZb054==qy)tg))47yVHDI^FgLf0>>UTzqew~ zhLes`sy3{cYUkyztFN+tIFWJbia(sarKjb_!Zb0dkG^x!^nd5%LvCQK zQx$yLy4R5F;?g{@a}f*jeIR5 z@yJv@83ShHSt4uVjW~*eXgpq{A zCw2v5$Wh;`Sq#$2Q4!=Q3^^){92G*2!jiQ!E9xG!?_Bm7cp12pU|wUT?r?EAr<6W)^843L%G*qve3mwOJIz$2y9he3hb7s4DDl_5Nw&FhXmjb% z#_b+0{{an#p~_sQxWEqQJ-6`;3mL3EiUMvI0Z{>FQ|~cV1j1V^#z!8y_CnV4 z5s`2<8^fspeH(~LB@!+pDlS3af?3#CS5!tXj)K}a0h8w-5MCiXPeZwbFf9av6Tum-+PDglumk3GOO_L2?#4SYA;atuF&;lF8Az#C zXaTZH*i22=H=AY?+x2AM@a1IRh~;F8CJMje=>IxizIRT)ZCMjV%a{I59X1>DJH4}3 z#I^nQZnK>w)saX*QWXM`Yj4Jo4gtRBEHc7vGQ7QZEi`8Rw&N)uvamGm-OY@2B$d(k zNcwOezP(wuFkQw{zURbZP*f)7&1r0EZ)Ifqhhvc4cV@3t?C{DUJ0)T{>}2y!)4l0K z^C%}@iJ^*G4s#<@rn}=baw(B(<;`DTj#q)}jRVc&Ar9eHETdOF;AN6)NP8^#2WE=8 zmT$B!n!dC4ac3=fXDxDPEnsIYbZ70K8VzRlh2}>9#oELzR{J-9_HX{`&!6ef?|o4e{^7|S;FWv0oXW`@rAs#`S54ZwJa%}S+`f(J=2g8awJ&MH(85QrS$-z_^ z7{%rEp}#Qr!QSlQeIqJi&-l#l(nj=U-1DqU{r3PH~>(l5tekb&tk_wcMO)=iwI*oU4sr%#NX| zz6X12wNX~pL%bi$C^o!hT3Wm@Sdv$kmi&71<_)iyE-OB*vda7!L8-*XNkOrl@9sJf zk0PO+H)SR)G*e%68M`x`m%lsORzzcFip+n_Ca#osm7jGfc~+)v>ws}5-`Ov2+)_oM zs$X^V@sl=-DIK5mn3j>Wms^Nb(j#t17n3&DnOcTu0##~z%=hrdn#qL>2flfmA(hY= zn~^j=uLOC;5aX_Fsg?o5N9lGh8f_%|w>P|My9#cI{iuwX36d(0uWp@lk6|AjLr&FB zTFyXQY4LOp{)vL*Dj3B$fLh43uzqXX@M|6C-^qx?%DP&a(l$vO zZ`Hv0&bjk0b26RD^Aa{D^=V!`k~St=oym#uE^{xM(uTjJNxoEYvF4oXbni^&N|Kb5 zuyKFYEzdcdHeBHP0|MP`zzLm%?&5HM2v26HNeD)oKzNMsWQ0Qhm>c3+uD_|c0S<%X=+7h36!q9Y($p#z)Vjl{vt?Pt7s|~pZQM}1@#L<9zgV?8ocGu$!uo%VFZ-Fy)^88fY zln;_b`J=4ujnbAzv5gHO`Ly>TIvX3D@<-g+Auj4H^F*FmC3g9&=#X9&!)f^}$!?Wu zC+=`3?n3cy74K`@0W+773FiYufCFnG4225x~E3*c0{}L;FqA+&hE>UpkxzmUWD6}vH z!$}}KMBJo@1Q9aDVQisKArIoAAA?ZZP-uIj(iud>@HF8v7V|P5`c@Bdv(Qz$VLFo! z76(RsLgpP3o`P) z$DBp|JrBK#Q?kHf__-l_H@SX3N92BYMU}TGi6C;BA#Q|BQCL3)bNE#D^?$B^nV>0+ zN?|7;1%%AIu%7{#GSpuvbfi(~Hq7yB4%#fl zrTGpMiV_#B$FU)j&O!PJX0ou(cbH_9I3v`$B^M*34slUI=%0mj5Y5iO^0yJ5pxF3c zoHsa;QHPKe{&yy$e;N`-G-H4XNA%)svoUv3KQ2QD&LD*hhHd_%i2Oocgw@bliwb8cB@mX5DOR)7he#>*v9 zfyP(6smWEu^gXSZ^ETrctNP!BsYJ!9Z@hduU%-d=MXsHx6wWr=d>{UfV97gL(MB&w&)fdp(TX+V%81S0S$yUgSStPR zkmvAEYU8t~+FtZQ7_QDK;8~ z*JS>_ZgF!oNh8kW8uO(pHn3H2LC_0-UJ@1J^bUp zwvHu7ktNPZo3)};b1-P?MieQP6qa+qyJKlrmeANrs9T{_#_n)S%1)sMXCh14 zYDBXAztp|=_xt_-f3L>L%ks*rInVcbKA-pJnYT%C%e$twY&utxnw>J(W_I-*yzrs# zl$gBn-lzUgYG_=aZc@;SwKpUw-a37v-K%AY{{`bNIg)pyAxrIxAb8wc$LpG_GApM5?#>Gzjb+oY14`_0DM0Wofp7}a?# z=B~^=QE6epxhIRc2bR~0m{2_yGyhWTI3U5f2UBe^YawP`1lyhL6JIQii%C%ce zeR`bR63+I;tXD7<%Pn?r3WS-8ghjWYr_7I;&NVBju4P?pRSXkB?8Kmlyflk)`ukwq z(*#PEgl{gVY?eY#3P9_5X|jl&I22D1A2sw(y097qVEqbumI9=QHHg546?7`v4?~7z zni?{uc?b4YqS(ci6W=hM-{3_RgropOU4(E?uykIM3ESe>a74Phv23>@=-8e zB?PDF=zG5fZFM^CCkPLR<5MIFPOjfzy3l90zn9WUcKJW>f&5QEZ5#%APl2>uAu$-btq;KI^b8S<-wRT4?Tc!2=K zzYNPMA$vCKCoKD=-W)&^7D3HChRH>^SBbJN7!SvC)n5?O=wWf_HTgdqEcyM=nal87 zRV-KXpSuUk)gl@Bjf4Y^dze6)A0W=Z=M zztEy*U~;_+Sc-)*C#mUubiT?hysg*ayzZ=yZ$GA6#2cPbtFBqz*`D;e!{0g8i>Y$) z_Fb-BWo_JvY{!9pE%smCV*GYF{NXluzua#1iE|mYN*X?K)#+<;w)#Bj*`gYCz4&d< zqv+N|n&nsDn5x~KjIY9cXSa{U%TcU^vI*yUE=`Sj~Z ziIT(7k19KCp~P4EFQciqam10*qxo57uPrqBN?+aTE&bMG_+qSw)q_u&xU_6<+JPZ1 zT^BtGL+i=3j4HZT6#g~@))z+A@AK9bAT2gbNHW%=!O9l80xk;h&2oCPFy)CDt3eKa zN6`Hu=XF1D{)$3H1Tl;?h{5`m^mzSGY4@v$rk6vEC=?llps7ki0K?L%=zF7ZhYZb0YBfDKY_wth_nrnYZS34(g zt-rojhH`}Uy{%Ku4AvA($NNp!Q(KV-^>I^?T3*@+VybiTV1a!i!(OG% zWfHkv;cX+U2E8_p7YR=p+Kzvons#-Poaz3QnD?PS@lvC1e46uyo%MFT1BtH<4c&J# zfI%~wR0sQ8_Ial?7kFFt@${0T`d9)f&Eejb@@w04Z5EB!9PCfL->BP)`u6IN)qLwu zRBF(r-gahgujgJ)DG)JqKSTLG&2z(!rs40q7p8boNQxjTm7yqagr?X}-un&m64vK5 zcZ2qhqXZ9!;C^82MLEWFC`v@%8-Y`TaWx8@5`jCDq%G*j1(n|_$7=?C5%7`Bau&O$GZAvqG*OPQvqGyeCCeV z_s#76(4XqkXxw!xsMK_BnjA=7VK~FLX3R}1HyEcb8n1UwnVm#t_#!|0c8}HD^rz;4 zuU*q-Yz+PQE@BiI9@T{y%?3vq^SZUae^)Y^4T%ckbsK*_eCV~&t5x|?AC*@;3X=Dn zJiM>g^jJ@zTfMns$AgQNwN9LNLF!SS6T7O`Gm5<{vcT+3+?g*NTS~vvm8#k!99xL` zndc3e#}Gg$no zht-{j_@Cz}u_r&L9T->olxCKOXJYd$vH|iW3_pZ5D8lc`=||C%5H!R~+pz^Q_}L=9 z@xTt)EDQbuiM(>)-rJx4Bz&9j?og8pYFkub;Zq@sR$iZmw~HM4G~9WwXq)6;RulWZ zN)nOYz?x#E&i0@mp1rmH?rxpK9ksJgO1R2Nr6;t^TUqJOyYe5|$n@$q<~8I!GKToQ zrY?RTcjf2XWDiPO3e%N)-81^y?^Ali9~=KY>{VWz&bnT5(a|}q!|b~9DT9N)u|t~& z8lN?Pp)KE3|Aa4{RC1u#*3%(k!se=9U%FP$NVm-Tylf((Z%e=BWA>k32FE*hI%Mq| zK4v_kI<;dc(5uGprGG;5M6{*F6aU`YWT&DiR^d=-)ADCiW>WF|n<~@53P>_6ipz8U z(5czJ;`l_~ovL?rH#6)#N?*5svW znnBjFaApO43(^8Ii#YC!o(#rKejSsGkj>9qh&>s&E%=EN&=f(;Vpwn$AsB^+gV|Ia zsX3&d(CwNlj|@se?mUJvQWJ>>M6+^t4UpSVR1}6`R}6?7i=fC#Vkw5LK@bthw367k z(F1$XM0^m1Epfb=M=nNDaC@$c!t>(b4OS>>IY4?x;W8xoJBo_ImJzr$Nw%z^Bmu2% z1Cj(meUT_<3A`Z`Uzk7a1flo}!V$xK_E6Rx)ITgofK~_-Lb#$3)d%4Yx?-1_h-7id zMxA0e;F^oT*`fG-9;t|OR#!m!|SB>sE{P^)`w!Q*d@4uUCZQ)7ag+Hi{h|$8@mf`0N?zb&X=Hk-cUd zA8}?%1lyVHZC}&zz^c$zjG9wkdw(UnIfg7Q|cyoiFg#;N%L7|Sz?hPF%WC$+J zC{zM2?@=gV4~;UmMIV}}c|kcV1ih~yJh9x8Dgsu9gyLY&eQ1BzD=&>2!bz1&08gT= z0)>t$_A#{3Hbr>RngNDs22RIvWspJS149Q{9D*;K?@cR76}r?FebbRf-&#|Ud8c17X)FdapB6Hi3~e#~R+iH6N_dqVM5 zsCoo0jjD&^n^5&g{9=Os-2?h}FOq4B@M$tl4*o=gKN-S`vGC2UAIM)r>l=@22M;3U zU!ce5{rXKrgqH5y_eyYQM$z$jEfKD- z#++6BKu-sY!m^=HO+sf|uPL7_%4FRfI?^<7@A<^;S@lbP@iD_|N8)OB*QL0g&r8M6 z_`ROpQ&g70x-oR9sojnLSGDe|byamucihiq?e1$=UX$$NmpiuW{f;}P?aG?=48H`{ zts$P?nQewwGP2$=R~goNS`Q37WAlt^9gQmMiarc>oG@yxE9xHk9CGGT zgW<;+pRWa~smD{O{kDqfEStQ<7a>5@y{2L^} zV=P71Mc`|(+-2|$P=MSraM_i}gGgKw%Uud@_=2|exaQgpkmBKZoH=x#_Dc?xfaD3{ zIhMQOHoo5cpOO%aYw<`;l%oh|18NGx)+2Th)LPX-Y|X%jRw7(5_AK1{piU+$LtYvb zZVr~aV}OxWMMz@UYJ>~iU6OP{Icsm@MRC8nhtl65sd56xMwcM8#ZXi^k&cZjAT(ub zXs7;~z0gEtDMP6Q(T9zS zApT;|F@k7aN}0aH8r4On1);J<^X?;%7*}AUYRI$*6jVtVW4XqeFbqUMr3$)UH-Z3X z@IW`BATyX&EaquN^dkqhJkQgCqi?xdy%IK1KbM48UUs(v_M^rNJ@qr-qmRW$AXzEb zaTO>Ie4-tN4)#nm)3iuONXHSFM#b{ROI1|O*; zCNWF^u@i;Pk!k0ChwNj2P1DK?vverli8Vm*j|#dm+AjqO{rQQJ_H{~SeHgw6eHn_M zMHP6i*ScM=-Dg>)Vb?%9_+|Ic8g=XE+)Ow59RdQ`B&H(`n~0$5VW8S5NJ7U+#yaFO zj(@>)R%XJgnv^}_JjPa}CIm0Qbn3eqrQk%(z%#_>kLgTrWKTGL3e%y$PUZ6$fovnO zJp{OeTp!oK) ztN}*)j((Nj59EeW21A>Q#yanK6|EF7@O%^^I~e|F+0Wjo$j5nRb&;-DFFU5F$jgh* z28)YDL;v*r_E>AJy7!pL1brf|uB%ImKW)0R=+o}_-1{MeN)(CEhy*E6p=?}h*e_={ zdIp)*>^7r5y`MOkczWVMOo~%c;TY@v@}|A**&(g>H2BLsI}vA>mHb4{PU+Mf*%bB_ z=K7#id98#v_$tjsQ(x7u>YYwPR`t}0YQ9wc>zA{xoe@e(1?L>+&K8wrk0I|9o7_Lnyng@2(uqIx zpkz$&J>`!4yJ7W`m!4_^&z~9W)_&Bn)A!y`cGK&#UJ~39cKGns;gI3woUWNU{kzg( z28Wfa2u4lh%URh+s{=M~r`|BsI$l@%mnd^138@*mdYye_EI4-r2;#;iI%qrq2I1~SqMYQQqsyfAAeBriV36Gc0 ziz90he-Y?dB|*hT*CT@#`=O~=xbzZ9dZBGn5JZw`Rm4i5^T)!o2hr~i10)oMui%kt z==bGtV8}eCkS|P`zQ-DsN2VpAxiIu)5U&!xxV%s0ISQFB?@Qyj!seiNxZ?_l!s>yv z*hW3{#j@eFVpjkg_NCnhmqZMTv*6$?aHEG#yZ`Qb?KBJiQX}pfe7Q*w^$pqU&nftg z`B$ZdNhou}p~8DYR1co2?%%Z;nEP_B9Za<;w=m?~lcGwJnSVq(7%OVzthlloJt;X~ z8Nea&(G`1IMQkyLD9hlR3yos~_zOXI|0U2J4281~>H|XpXa`eEAPO%{24O|u8?Xjh zxR9XBA*{XoA;VbM*96m90vZu=5vtJRiltW(7NFhKM8@{(_Yb-Lk7CnWNdya1xDQx5 z3UEX@v3})(JIy2EpY0E6iEIiKS6y=9p9zzu}SUQKmSet=Q z8O{rMqW_3;B*_z|(7$!p>U3^5cLet3H&ONY)LF{DRV1P+q%Hq1d)iysExf>{_y8c)y&0Y*E|3@<$<8Hc-xvImqUQTr`*Q8xg-KKK^K8 z1H~gY+G_hq$wX(dfu6yH7N7aGZZ@yFhCNwZ-BD9rGU2{SJMsFiJIB_{X*CX)${KWoBJZ^kdHl_UtQ#kMF?^$vxVVP$z()V4Lt`EMuRr67wh2H6JO-HKHr$5C)hUCLJe5EovYvXOw+o!- z8)XJnDun@Oqz~DumdU*!!1HWIdA_EoAV?@)xnM!64y18FNvK1iwU^zo;z4;zEa(BA zxx(O{2NaXKV-ns3E?}H^tojtzGzq2reYuMs)B?Ty;nq86^l4>l{FaYb+^vaa!@Vqy z9uU{V*m*Q&-8kpo1D1P8g~fBhVTWsM8H-$Y3@8DQU74E8`+ApkbCXUdv77H4d&qW= zW!8nW`DE|(Z&dk;+MSrS2y;UOdpDV>$vuFxKWTWTcXYjuo$}KgpAa7$i4&MQDl~Oe zX3B5N_=Mu%$kVp2&$(r-$Aivfcn5XMMZBI+YiXc?MTq6;L*)JTC7&C?3^8J~E(<2Un$x zwrM?A?(T~j^^PBMTr$qgZ5fGZhIXI;6jW@v!8WoksTGdX692Edl7+S@I=Mp24D*75CVfRtrdWU~~_(m1R+irlOw zH@KOa>3&mQ!fWK1Rp*qv;l%7(?o_<%$T6ZMNOod&3wNqj*3wjSDxkS}RwvL69T zGo^T7*Uqx^jALDXyeg9khwm3Orb|YxyE`R}b;HZ#16{Zs(*j<6Q*Lc4&5Q3`-*xd= zY>?Iq&AM;y9}5C`dac^7*~fTxWiJW>arYUyz906{{0WW`(e%VL?cFt2w7XObGmZpU;X=2y}wyQ-EJ#hx^$ z?q0^s)a=;9=On^ZT~ZYSM>QByYs{N!1vA*;Se__T4&vB~Q(u!#dfW%W>^Lk>oO!6S z_U5vpFEhr0=LDFcvn$FrgyBP2t`O{5F@J`4fB_&DhBcA-+m3Vv~)POL=H#gHjUsw00>wRkG)KOuKalkq_wJuI zaNJb?h%YwoXYF(Dc8&Xxe{@Z^@!l7H@hkUUZ$0{4(dmneor|JdA(#E9%d2vlwNcig z&MuVd79?R%Q$ai0d(SgPs~`h_#m#5y;**%}Aw7%P5^J4bK^Y>$eFksx#*5cKC=nb< zR-Nd3Kc%%+zRhlJft8VQl|!@R+jn(NyO_uMd#cZ!OIcfxT${HxKi}tS54^QLj@#IK zx;pu6wphi?!<{LSv=u(|CBuG{UWx1SE45$D?AD12dOmSNIHh%0K~A21t9nhmdA1Z6 zF8m#9kOy8meJL_Ffhv%$R^ZUJ;-%ehqEn-AApHx$z7=$Bv|kbmkY-ukW?6|tj+oUj zrX%{(E4vGz0rYMt4!ZtzW|Xt{S-JMYkU=?tq6$)w3=LNGMfU91Z`;RX_+{WcWoR|| zuRXsAegOdC$4$SCcLeqf#gjqdMcZWI%t`{##9~lhbPI7d1J?sXaM-WL-y0e1b7<;*>I!RY@$z zFjXW;1aht<^u+WzhX+V$l(P)p;Er+x;p{N{J}@d#<KF9REy`KfsU0n}{n*5v~a2 zRY@3PSWXoY0QidqRsxG@B5IYP{Bi=!^B_3^Ltf=XvY5X2wgHlkdW*u!p7XGTGLBdA zNHNq~8cqqtvv_3U!$Fl&sSQxQFLG9t3#WkA*aP(zf;+?Td>Y*OjPF)G;=QN%{^l?H z*4>Qki&J(O_4Zz>>;QrkJf5t#x2&?m?uJS~bE%QaN@#TSR%K|Aa+mpshve0$hM=|TSbx9{Q4=d?e6n+Ymrf0>B7 z?_9{98%dm19ZVGH@BVYl^+HzEZo`tJnS&iGF9v+N#m!1d3HTHq@aamxCp_TOrGQV7 z0h-a@PWxs0OPulgR?g^}yUYo*LDt&%Q$Qth};^*$=ThCWO?UoMk_P!{llIvnH5n(vB*VB2phpIL) zRHT=enwLo3Ah+|)zGWVd&J@?`uHBpKb7Q7`%juvuDy^$pSGMlHddyhq+oB$m9@Rk? z6T?}>lQxAt!=8>WOD~MuCEm^7<#5`D+Twm9sIa3;=vzv(`_QWx!%5G2oobQ!|Iw3t z(dwOBqyC<{9PRt)VPE&4$bRid-?mQ&?BqO?EI1r!y#B4jXQi2m;!`h6PPjyLyjS{W zz?|Y@1g0r9O)TxF(U^v zC`kdEv)9MX#0<@DjLvGK9r}8pASkHl)t#*!Z(psAZ?{`n!0k1!mfc!^&F&Nkel4HJ z3*RIUZhPOQ=ooaSu}gm}zq7e((OCY{nRDBN*o|F!{Udf``64sthI(dS7{4#oYnDsU zeLZyK@(<~DW9{BlW4=s+vET98L3}cA8Q;09e7ap*CurQJE)|#MJBPT4E$vm~*dIz(*RH0a-8$?yesOz<=D!1>bun`;{RY`VZ-%&xMt6@>;`t4N> zFGsrjgQMPpOTygb%k6bH48gt@cDFRDCm{Zk+xk;i_ zHKMi}a~J0(iBq%I4)oe(%r}By1}yLHUBxL-U~ULu@8|nN*_1IkNeSNHZ z3cNh6z<;$w8MpwTn3zKo8i-vw3p-a1fCLVXKYjt@fY|7|9M2if#7?74)}&}U?gr#l6%qb67XyU9z?2iJ~#*$ zCbR%GzaM$<$Dxt5d{_7f80K?a;XhxDlq;0sfhK*7Tz@MW*M?eP5>Nx@)&AT}SJ)S5 z_CVje19XA-;#+U&b8y|TyG}U@30-m5*)_Zu+Hu)krv-)1DD^Rb0QdlChTp(<8X;$| z-G;Xw&~H;0fR0uYTd~~r$XR)CkdpI<TKOf8O&tm0xIP(PXz+fGM!mYcPO8a{amP+=i$Bx zKr$p_6>_JNz6d!{K?gf|#A9J`UYaO;(GZwoj7`X%5d0pdBMA;-`f?=J>oMNo{`Mk_ zd{49Tc;@9Y!XXFl-w zBxkeqMV6OWe!`uQVDUw1!D61l5AUigvhWlt51OTBH!N+%sJ?$ z8Y3-CFZ+GTlgA_ARetjep7scA&A(1-=zSIqwR0`MGT86mPwb(;(2^_=ax(=CM{~}| zWgq#T?3W$6Wd^+iIn$nRVw0X{A9?I@-q7Y;ji33jqm5I|=a;j$JcAC^r-6o2x??OQqP60@l|~Xu1&5na0$+%#!j9va0%;bRcIYIVXg{Fz5X)cBWwxO zJU6)Apk}!Cg3pG@l+6XRb3V%L#@yk(4CV==3Yc%EocNN{H{cUnE3zi)SwULQ#;x+v zv_nQZTSUvsEDW7f-7ej;?M|DCV; zyJbNu1$~1AG(pTm{lKiml_9M-_^k%A?vVcB53ci`0ztUVqX37>2}3je!vMYhDWoo0 z00*#9QG_NAedduH7g)yQpBSLw=w6DP4ad)6xquYlqu!m}jL0TpxA=nK51x_B;b-N) z&?h0NUKRKUO~eM&TL5-g>^dI@5QK8(U4b?sD2E_EW1}W}D8)c(J0uLPs31(S(T#}z z2iMViRfMxSbW8&&e#jcVS_RnNpDutOkFf&rzjg<&kAq8t!MHH$czzy)`t6q`Ku1ww zsEZ&bfK>n*r>LdKwAjx{0^y_IUw4x(AaoS7@zRHRYU8_bRXCV9Kfk=@;pUQo30Us5)!gX7}u;wK_w}fVcmmrZO2*&x7 zN%(f)3;y(ue5@0neKk=b(q0R;2F?>e4x-*4t@wIC||36p2Bs8&)X}JWk3+z z*Nr5}e@Ih6mPO(cB)J{sh{78paKOF)zK3G>7Ynl$hCY&MG~_@qeo+~+@j>h!vaAmB zNZKRGobXKNAaU5_CuOuJi};2zqxB)H-hiTT$TC<#Y@5uB~)Kf%~9^a2G+fJN`eA z1(o%gu)aElb@^ZK0Q>181;oOO)Dad?_<+6fAFr2RNsj_QGlTVW`j}hte~=)8z)%I( z2+Ezgpv?g*mfsqQX_%<)pISB+@K@GI^I-Aqo`IC%dMnSM>>}xDn zvLdoG%5+36Z9*nyaAuF=i1V$9yv8ZLl_jZ>o%N<8@@W$ijZ-`OXZ{=u6!R_HoLN8T z_^NO2tElp!ib_rI!;(^GXv%MW7eBC8JRH=-pF@9kS*;!oph^XQkq}%}68S{dz^X!U z&;IQdw+&=-%i%%c!5c5u+$p*~9Q~xIh~F{k&`Yc1@?E>8qKb5#dlM%Niu_7Drr60! zJNF$peCUz-$n~KQkHudq-n?*IIw3yxpw%H~+YBA;hf|T&vzro}Sw?oZAB>9*xV>AQ z@%l_ubatBIk;2>K341y}JJ#C>=hz=8+DQ%`=j-`d(DE~eSEx;$ITaP3{m_u!)m42u zBk#hdGY<{T3a^Zx7`nVF)2-!*C01zKZnR#UCclIgEU3lw{RE zyX=)~7=llbWB~g8H`r(~`dytQkEi3>i(yX%%HU$OO#~|9k?T=!rG>1Kwf^_N`$=o` z`(oHA%JqLc0{#%#R6App}7duj@_A<--@z5yr8Z;(ms4A7z<)C*8G=5{q@x&A`R2lYRhXW%!ce<}nia|9!uM;k7{&R-CJc zHFti2Z}xPj8TSgYf~@l=rY<ZN&B}6^P%d{`Imkg)LL3?Rkilb7iBKY zMrRe#wtZb351FS7d{wE=vr`@{%~I1W)4Ud`BDGUlRd4bK?{3sK`vJdub3a2HX~Q(av%o-xFBmfFu>Juz44>tW$iEZ9(!gVWnc15Dc&1i zT>6)T%ICgqjAD^*Ke)S93r$`{(L^11#xBU-+QyX~v=0M%e=Nm+?tNltd= z#3Ao7f{ z!ZQQ!q0hzRKVBHT+}cUM`UQ5gc!JYphE%%x5d~}8OWi79K)Ay`33*)hy7osgzNeeg zvZa%5*iAWMR(1puc{8T`F|ENH+WEpj{l-L=(3xUfx|VGYtS9D)PyUk61I`08CpNK&Q|K60>|LHi_gBH&D3dKCPU;#j-y zMUkF<1p6x1EXKSV$*vQi+6yuZH9N-kbM#CGdfS58-DIXD_enV06Khsx>bEplP&3%W zShEn**Mu`5NmVPay@0t(bCVWRv&t=2a0b}7>!Si+^_luC2HX+@MJ@;9*9D+-LD)o# za@iW~&td7PkPH=MaVSn;Rszrtl5tX!k_37l#RZ}r*r1U(h>Gt)Q3<#%VxAiifa}cm zL4BH(B>76fxL{)Ql)!Ewc!LDWu^S*2!*M=9=R|*DaThQhF<7;dh*i|*Y#$)aQI0sA zef1ysrSf00g<46h*Z4#p%D~_MiE==$C>V!$niyQ<>9zPEyK$A0BtGyD54#K)$pIb8kX^Fh`>#d}KxdxGo@;7tC;G+NA= zR403nXRx)G0amWi$B^um?&&gO)n$6=DA&BWWlCm8-dO_WsmfGiT$v@ z7#M%6>tnx{$PassnTQk@C6E}uvN6SlJ?j4+>7Kmt$4p7$shJYn)*pU(DOXCVd1uEA z4|jbUCj5`uUUJVq8rxU61W|D7KDha#qgcxh6XJriuX=|O(Q{d zMcRH7B{Ko$ON0qK+c)^DR@#{V(CNo=42LhTZfrSRl=)y~p|+N;XvCkTR({tX$R^~p z%(Oo)Thv?GQ0cK(w_SI8Q2}fH;Jt^2``@Z}G}Fg>PI|@Gy%}DUoYi5gzal7WTc7<2 zBgF}QlRkS#Be||B)c+Y`=+HHiXsdUB#q?D1@_zlo{P4ktmwXIMEbj#xZE;DPI{Ioh zB7xfEqm@W)WUf!X*I`m|DnE|-SBItk?xKgw~efok4$oewYO$$!X`@d)y2KX#{M zN8w=u)10ouZ`UM$i*7$LWH+Gk&ZlYZyU8Z&rxJIvPEFiM$?h=qjqp4+kVyYNb>p`4 zE$8&tp`%`@xQ{+lld1d4qD+(9VET$arvNV^2nMPk2<-q~yAQG$YzjMvS)F8A^|)Fs zhJ@yC?LonXr68yD75-r58q9AM*|!vaQBE926(Fda#}GvJgyDuHqdrW(?R7t6MByjx z1E@q>ur$OFeg&c{3drDbmQHo|Ph~>-S5nXSCfut)saaSlVq8I#V!11R`UF<+uQ;B? zUEI+GdVL%{ECik5F(}A`2^4rwSZ*W1TLfuch7b87gMbJrCqgi63GyHme{)J71%0E{ ze5NdNCyENfSHtjh62y_wMex;dyqhGyhv}n4Kl!%;To;Px@kj(kTf0eG6wbc_ZvffT z>VEP>)I6tq07WH#)vub(6gvhBTZz~SL-M8zf86J+n{YbJ?6q=|c zgs@Q+geDA0RsO;vZdgH4N)+1CO5zeWDvcB`hH^k+|C8$|XiDBMg7zv>XaI8sIVCWx z|5LQCW#X+@;Lc#2$|E0&{$B`hA-tbt1*Ixb{1qz+0O1)T)4xH+zQ}Zs>u6phv0@RF zx}4%a?D`*shXEqjpPh*xy9@`0<6R^KIR*s{}O!ith|0(dpLZvpn>i#uYZ!aeLh}xa69G6 zINGN0yTM7B%70R)X^~a*t038ujtk=WGZSctHXmJu<|8r5WSTC*GHa%5r{i|$OB|mD zFMY{NlS0PA@xb{+>Q5aF2yAhsHmjU%)9qDDT{{ zvH!LG-G9V>6X|tgU$zNLpB9sQ5WXFV{07#EU~STC(AIg3^t?`5k=!xnKat9=NveL` zSyI662Rfw^D=3jfpZv$sz=2po#U%l>ursC zQNMh3cY!CZHE?7@&c|x+6iR*km+xg+A4(*yN%VZXeR%5d9AoBNrpm0I_T zyFcACdiJyLhmQK+zkcT0nd^PRyn_1Y-V`@OH=$nYpR`%ok4CW?BRdNEj1G`S2R;}b z;29n0HfkY_S~Q1UlHE$arF`4UD7kWYg!aJ8=y)ajFw&p+R@5+0&@fNhFi+gj{ce^s%pa>c?O2c8LbJkOxgY7#%X*Gxtwpmk(5$UV z&6|>%zY6;~U3u&bo7O+rS^vO&tmb-uVtRwFX}a@OdOdO}MGrP~r}_4Vt(n*}-OAEK zAIU)L6}%ErjnE5ue|$g^PAS`sYfTwa+t ziX947-f+N|BdWY1B62sPyaA7V&EtuCbEK8CLnH6=c#7Vft<}m;ru>rKf^w>6JA-FR z8XuKW!MOiowlj35M0Uy#Gzy-BBb2r-gP7v7FGWM2*hRE}Jk`TxE=L?^J2rYvaAj`! zDes)1MGX5O9sIB?zmzdnz4fbMABQg!-yIz1xP1euQ;o(_X+g@r&(XqWeH3Q+yFzF9 zPnxQ9N58D|r-7|Nf(t8#h^p74U&Q^3#aHAIRiDkqH`1^v@5=6UJ#gV08*RF#>sWX6 zQA6$frCfhOYHCHTGsZ8ds+Cu!9@Fgb&%*dun`(=csUt+~6vh|e`ioLm5Vcieg_Gt3 zy=OR+iE2>u{nR!OIVFJ^9slwSHih4){sqptuT zpVD>pHFNE*=XNP=%l;raHq@ghoIDLP<5uw142 zzPW?Pkoqs}IRM}!U>#_M{>zVpGv`1Q4n|lFamY`LG6=#b+Q{W_+!fOS`DWmI%dh~a zdrbgJ#IAkBu1P|A*fj~r2fHQ(S@Y6cSrKN&E(1gzzu-qkqYyj~|h7q!vpz9**`ftOq zl|HHy`jcOOM=}zt2)8I)7Le+)FuY$MZR;kNpeI9cfM|(Amq>BZX&nz_FH@^E1ha*LaNxg--yFE{z ztiO?c&(O5+#<<pjH-N6d7cQRdZrO|@r9Ppy3{aSf#E#@x4 z<%(1DMYvpL%ssNPwqy}i=?ZhJ2={CRdp(vX%VY+#m3Y0GNC)>6%Uzz!m84Gm%_)## z4o9*fvX{>B5oIbzuuaL{#@N6hn$z^GH!b8>mJs9tVALCEY6sKt{KX4F>P;l6fqEsft=JyMg6YP!u;lBTF00H`625bbhxi$Z#_yfUSv5h3DmX3Ex!bV&4zpo=n zcl5g;TpEVwkmMQkyQ(QfZUHD!sdd#kgjj!QH>gQsE>%{FmMc!>f-n$ScMT!I#JL;qeGOVE-q^ zv2^^C*njD;6XoU#*dTa zVHAbotC1io_Dj3h@W5_25@upQHGWJV*(`ycRK^;>LgI3gJdutA*~&5;Zzj_Okj-JZ z3D$s`LhG-DM`@$EWo&o^LeD;e}T0H>23G^Pvrh|{IxWyun4N; zk@~0t5ZpGAjMzrP8#KvR;A}9=|I;NeMAagC`x#Ff355lb?N4OS!U~UtF@M=Vqk%c4 zMn^v(v7A^nzei{{$pD7%<6!)w33O&L?6jOx1EUE-{|5C$uv{I}g?XTY&_oYYx*6-| z17tvtHbl+_<5#d;AOU5y5OV4G!#USn$%XpV`cD)}`gPOf)wce_!TT?U?etPl-i-%~ zXrBL5P*wfe)zHxB+rY;3$_m-3kapYIIjCmx6*rIDHB&X=R5v&=(^G}cjkTS@{dpTH>JAtc{ry0 zC|1rMx{$4%qkSQ()~!8GBu6bh?{%k{rwd%;{%Y#Z%Wr*s1&(tkij1XteH@LR*YS7n zeQLkW_vTP&Q}a3b=#)PUHW*shvHc03m^(_|b)_oFdGVD`B^~Fs7nK!{t$HteNB;Fx zU*7$DH8JB(QWAE0^@7V4eK6Il=>s)@cgJaRtvD5F*-Dz!OD!ETkMLOUP<&KrT z!+xeU2Dc2-ix@#RHP$QcP27>5b%=B9I^vhDncx*a{D+Nd&HdN29$(0*-=X(B280ZP zWs}NKk>NaYiyS}?=df~#?w_DlEtV?+KdT^~o&Wz~1Q8JRBgv!a_YHK4e+~4$-*e+6;xJX{CDLqDewf%z(s;0kX7HeI?a80PBe zs$dfj2=2(mB*2dqlkqj~u8_|a_iObiGM49mj)%)2IcG*0!x z#E?1UI1kIK%adt>$bqn*>wNwZ#?$tP>fe1ZO}i^yLAOWmLeMu}T1XWgY*YdniJO|p zfrI*YdtLuE3q_!(yfn+-=XtZuq4*1|VNLnJs|D5~PeSpxSi>Uto$6hDSqAR85~2MD zmiDAU$Qam^)6h+>%)mRvp&_vC#~WdV;g(p#a=5U3e$0{s+r-U(2F4n+%E2<9Q52zp z^&DiHHbN7FW=Qg$u*c|=Ci>ixd68lF!YVmn4F6R{oH2)7G!Yuu2?X~0{429n%x^SR zXe2(HLpTp?GA&+8GSrb`5y+*IFu+DPAjJ?gQb|B_d3eh)-Iqk<0NNk!}jZvvVBz_)xPpS>f8@`Fp3_&$I1oa z)vHZ}UDW?rhC07OX!ZYa;D7r+Zdf^S2yMHO20sI>ohaC&@QXJ8yPE{`;>HZTTO2X~ zDH$JR5M=GJT!1>xZ_+}SG!kY1n3(ff@~SVUySATK`+eNu!SMVh4yz~LcX`?Ct?)vt z_<1v6{!LzE*wV#mZ(m@d54AlnD7GU}m(PyLtFBI-NThl>t-2_l-lJA^@cR9AHtBXx z;{&hU7syuR-2B*Uuq$QA&9vHGy1L!XMks^Y`fZU}O5ayTHQ!!&l~2g)9c#5&J_$WL zH%P@7w|!h19nYcd_q=?fe(vkZo{cY$uWbzsLVk2#S5w*h_w<^vGsd#n`rXBaFS+~k zZEVKWcBg#MRGLxVR8~{lcRN+BAnU%vro7JDC(*^k$G6d|Wp{mW5W>D5tX@nhRr;_*jv-gdQjoQ~IWtpYRW;PAvux3=F zZPrFRJFsnv>@<9?ygnG+T4=Z4Cz%#Gxo>*%t*~ePR((hhX#POTU#+LDfAVZG?%z#W zrZDo4mJiH;3twRK+Ds2CzZ&4@?P()6k7d2~FKBNwrS=SOvi_r(ZEju0mU~fj>Qphi zmUQ9=v)2nUpB*S{x8!C1b=6tB&f@6>uNa-qD;qnnZ0WSH?(W#E+iBt6Zu8kmD}()z z=cL4G-}<6<9Lp2p4vJC@2n#Jv`*Nmd2>UI&&7yy%F%zb`jzm4vn3pR22%;0q-CItS z3P8yq-lu^)vDRH_(nxog(j6)YNVf_@cekK)r%H+v zD$)(oAl)$3(A^C2U7+{<#QQ$)`>pT4{;q|?nl%H%%=w*t_CEWZ>phqO*uJIE)Wija zvQkihKjhu1pK#3Lrvcl zLH$il2hiO|k%37tn7N=EI@lmMaO^MVZI3$0j+wGHBOnl13G};djVE{txZ{*^19u3) zvp^3*00t8ibc2A!{Q~jkVYGs$f+~PRhSCf7)&|D~t`7}_z+iHMr&wU0kU+!Ro;BO! z-^1>A!0_fKQNd(95H<>!7=waUQ&^`Mx(j%743TffU~jiH-&%++;_?F96mLo?Oft0w*93L%|%WP5+|e1=eWC$Gappl!5)@RrZ2@BlZ!gRv3U)n_EPh1bxZ;m+JQ@xP=_-pI#L$-k$6 z&)^?T^(5! zdM6MrJN4cTZ**9n@xcwsw>~kyXerhmG~b_XI1qMuT2}N_l(+~`+|OzqYPg|W>JxL5 z+x_vjrXot!uWKFbXlp{cKW6~s(bmp0#|bp`F-K$)Adj8Lq-%XY+7(^P#8ibRj@>Tc z4u@!m(uZ_wVqOxHHH!!pv zi`)JB7XLNMk{RpZ{Hw&sww<5*q|4 z2b$yt-ir#<6a)+m@1amq3JNetjt(fy2mci2C=~H6O=yD2n4mb=-Xu;Rz%SZ1B5~-?Sz90fYqx zG}H0^KKQJF&4G3uMv)r`Eb6Po0kek&vcO=9QGviTeDO2kN~w96C@}IY24?pQ#GZ%I z2v(AU+5H2R2%Mlm=K5_p0FI5UU?mpVHY89F2D?=wDu7w|yUtL++Li%SH2^r@F2rqJ zG%9Ov0yf&V6Wy9$rxsyUf|VrT?ZDeLhJtRKz$zWU@rrS?*Yr8CP3NE8twy(7OD%yH zE0i0U@ZgUX?j>}$y8YJa3bP-xl)1VSST+(LwBnNn@Ff`tgs$8PQIJDc<8Q5 z0N6)e`1J0LVNVVDro`qKJOxVan+hN zXd(sXPT=*FE}-ab0Di^1{a+LHQa!)~Jn*omz+Uarh5?}h!2Ko+?CoZmQv)gdy}#QE zaLdU8d$?bv2QmORHXqiqQwD^rY_H}3di(1RFrO|(9u@cln96ua>7*$rXawokj1ELq zDGdZ>Z-Fs7Fn8b0=sPJ`mti$KV^GRda1{weiTZo+G#cmk-tL@6sfQFfGQ(2UgHk8> z{}^T$1!H(nn6XeUF;g6>3$L!(|H1}){4v84QyeP%l6p5N#eUnAMg}HOrNk)+8>Jrn zUZx-4C}k~886WJl3k+)l)0&&NQ%E-!e3?m@?u1fs^)C~m?C-d-gaLGt)Y};TKeZm~ zt_T0QjzNXiiRw&0e`uAV@J_7jNtTM`xy9^K(m`LnnCsl-<|_|;w2Y;mH|SCo*;}g* zS0+>QJA|Hk?&nx0!@W9N_(XkZnMUlmZm~5DBoRJaH^$AQ4J&~L_vWIYHw^RyGcV7cpyf)RhX07pOo?}EYJ}K z(-#!P1NZ%tA#*z$*tg*XwMP4Gr@Yy!vkG{WTAF$@!P~n~XbM2*D8a@5vSs5XkYpnA z|8(=jTAMO}OPo+l$ zVp@bKcw9V|iI-!^y>6|0&1oU#P1rOvwtI*x>W!^7r(oOUty_Lo*D`^p3Hfp+7h07i z+IvYA0pBuJv&#~!^}b`5)ikxTdyHP|jb&#@zq)0qX4lX-RkC}m7giww+fs8wV9%nM z);V*J>RFoBeKG%B!JcR8v0-yj>&&y|xnbK}_r>&c1>sPA1@cc1a;wi3QozkC;9g7M z%kFapu5x8X^4`IZvT*p9(7l7vp&-u<;D^lq^woEm<|M>0EkHWH9{=kaf`PbNPQ}}$<(0TmPR8AB;^m_BU0iEjiEriNWy4VGC$Y>3vCL4h z%$@N?bWOv&Ds_iXaGLg6j^k+r(cOmYA<+}>YSX!$aBm58gwMlcZ;azh-c7_Bl`4Bp>i52AQoplVwM#ub)_)NT2bPRb$#{!PZ8Qi_EA=hsgv*xJoB7Rmlit#OY57Hc)OK)~Z zjwexSUX$MzRTD4e2{lN6?q$?H4N*jY?bM)gPeVfrn~3NE(OsGc@vuiq3Rri@W;$1? zi0_bL-61Asc%W%)^8Sget4_0`Vti?I>^)^gs|VfoD=oYkDc3dLHbw(t4J)DtU^y3w zRfjhA*SqBt=Dus0==JDcPUcl)L@2< zo=puCpHEuqnNE=^^&DL!+)&)^om%ad!4{hs1Jzui`QDCbh{F!A%4?ckdYDp^wqFT` zA!I7CjxtGN0gI!t}V^IHdOfebQN+X9~ zlE1c}c7V3OA!-SF1C{}vkDQyT>-!btQ`6m*W+4N~ewJMU*jBTU@cVr1TJl;sK{?3b zVW3M4@7sASF!vS7!nvhcP?<;xZJSZnB9a< zWp=w^+QBPNP{qcYHX6x;9C@Ysy>~-lYQc`u+4<UhZ1<_#1Fkz5s+habjQ`IR_`H{G$3)bF;# zKgz4+^MyIfsuRKHetB6rUP3v_-n)vOdOn>f-utzEW&et=|626g?l*|{HDUR2;-fW2 z6r2uJ_Pes-x<3l|7B1>US7Ag1cE~_B&NPSP9Iga%3b(f6oJgBp~JQy<6@>RWb z*||LF(_5Yq5%+vN$xygKeFH@X105(Md7?z>q%x(QL97M3`L~aYdjy~ zC4+lI`(4B!nlc0559}l$6sFqYtc;W%?jxoP_h5{T=8gS+hDZ%4KByPqQ&cF?E+gzd zOc;g%EAhn8jvc4YeGw3U@Ft=trp`7@{F5;={R|Nb zYHd(cKY0WMZ!y%HQR9;+{=*r>+qwFgHoGs_{65DXK5-L7CITB%FVYXILV0B0v~xq0 ziXQU&j-kI*JJ1Pk=Xk7LnuEz*Am77e&swO++sQ)kwKSJK0}gy}{Q?7zGrk*>af&3i z)QyFBAZSdtntp)mOA)Q62OCm%K~&gfi;cFwYDB1_{C#Gcv6r#ttyLtS-F?gZ8k9GD zm{YvB*ZWcHo+^MB>7*lW%9AYzH0+vwmXyk{K9*118Jax86#W8* zPd@t;ykOpToiw$)6k68mZ3P7Nee%GCBy;c-aSU*hF- z&{c@?<9;2y!m{W3E6)(WL(_cklCs}XL^8*y9gS9CGkOY5am6llFBy;f8aH|t2S@C= zyX`S0#&M;FmsE4WLn&T{ocHf`zdvM&Q!iwLWXH4YVn{h3#I*TNfs4xaS;cIYacx_$ z{Y+l5QMJ9vlr$M67dH%(W=fWUvenNDaE%ejSx0zPawFrFLWOefir&WjX!v~hK^feKeJoiQMSFTrd#;T)V3C3kG{Z)lzTMN zn_1b?K=^XaRHI%*B%$&loqY-PZ4eha*XDpjYJizCanW`$jzWc-EXg8stk<4Km^umr zNwtTPPTdl{uUh_#wg#xiN~lA$G$fv;lZWas>Yi5uTLA!BZ$>IcB1Jo zIB?W<$OJvpT#GGj9iEHny>_V>X*XP(j`1F{9nZ&A=$s!%kWX*6oF!#t*21Yi`_4%U z7(%;2KYf-S7o}?-c#RKF6`h@PWa%|GX66%4jS83YtRyNP?K?DFTdlV)_eP<5E=@ZO ze{<|6gJtPmI4U_`5QDN7u*h<0cmm)%s2ARnVjBj&#t^^C@{*UXQ4KRo#VfYn9TL86 z%r6#K4@7p3ktxPS5PlA4lQ^4aiuQ?1MGvjeuP8%yWG+jzAsida=Zhn8`Sm#4=hfGn zjIT2?N4%*{o##prBQx6Dj=Rj6Dv!{f>Yhcol-fhnPF`KC)$WY%cM0?fou6b)`Sv$l zf1f&%nDaHTKTTRt+?G(7Nr*8Bvv_1syp7^iGVS{=z@#2=l2xAN>2o_0}nOpFCse6|2!^XsX?qg=L*F zY1Rm(l2oz$38feb9%2@Pk1}}{>oX{4d`+*csYGYJcn%P7&$$M72?$c7r7HKQz0cew zQq?hE+LTE9v)vn-y`ETip{?ZaI_qefA-UYMjc!J#gc9*z2kmY~S1rZ}+|Ao7zQ{Rg zy2sOel`fM7;aMX(J`W{u#2J`UTKiJAhC6wox`eUlFrX&3!N1j)Uot3VD3;rQAK8(u z)zF{S7u_#bK0es=0Ji=W`g2%_NlInWSw@jYBPKj^DxRt#kZKYy;Z%t)Px%?vx)qwD zi5Ka+=RVNxV$FT4I6X*I8bg#~eChxC@rgbHLlDx@I@)~qxynzv z7)MY)ylJO=K3uffQGVdjnE>_)KA9@?e`e=R{r$e^6~DS zgi|BDJAMu9#_;Rt zNbH%f9r=d^La>|4i2DrFAtx#OGF=>rSxAb7qQJG3?RYkR#(#Lb@o;H$TQyuBf0@ah z>(e7Tq#^cm->vUi8fm`apBcfS6BfqQE<_|YEE3@@q@kEUR+(QU5C)|gI%>gp$lo## z4X`sQaCN*DD2F%dw#U*uXA5Ry3qE{nllDS7!n+C+zTqaF3K!@xRj+|d!Q)Q6AC;B;r_!`8NzC6C#+#{(ba zTDPbjnN++uZW-%+fLN9tmV9$iV8JIRzNLigLSx~+X6zgHYd-Td`UCIj!^MJkj zc_dEqd}B}>q{BnUUtGquAJt-T+Rm^2a`m`O>d`T~ydgS|^){j3KBb?aKp7n)S0R%` z0~(ECx^A>iyiTlPE7Iahf*Cv)E?I?Ro$KC7pK|8DM;7kREL3RZ3gU!C*$H6`pJMD~ zd@(_Jvp*DZ&yi@F+fg&Z)Qj@57e$6iKqL-M?>(*-)U>KdCO9{Ds}Yu*$)Ql=Ay*9X zy8v|`Ce6ym=J5A9U#Sz2$#RhE!fDhq4dY+vM{8MC#33sh||T0{2AXGE8V-$wGfbg5gR*9gM0MEC=+#mF@wO- zA@*L}w-IN~;fN)a(VO(ce#ey_mF5Wam+ zd{ml-p=Qd@I@1pVmViaW_Q~!YXIKpHD2iF-;r`7}kS)Tb0#SpEU6GW(tOoD$Oj7*n z=6MCDsfi@BKrpe9)b9cxG6!q(?n9dDlc1i^C%1;ydq~!@D+Fr99biEqsXX zsQ-~GXY{kagGXo7!i;5=bgW#AJoI#2lyG0gna3_Z?I`zrK-@1%c&MT;WL12aUP}b9e>QjG@`~dtD}DSjgw9!*!|t;$;Trx`sEiJ-}%KEf@O}mqAt&EHw9l^ zPg}qLyg7`146+U8e8rolSbi>^ZoD*nGQRJwU?USAF4W>Td=fPMxYuKFzN^C1M9(?Y z%NvhbIBzVI>4dH4JZ{p~u!DrDe% zw)Iu?$cY8;GT0@z&Z&5hC3NSaMo;30PuvUXfqVZv6Juk}?o)(*1^X3g@A=6dPV2}C zKrI15+Qi(*$SBAJ-w4&@E^tZ+P*FG^TZ>ck`+ZtOG9fMyWQp&`e2UGZhSbrmru0!h z3mw_}71KHOMeOjKdjwixo+8nQJjMf2o4(JoackAZ!}=6h*|C&*I+d{$lta(5G*8f| z*DPB;WT7iaFygat!Z5(v^)m!hpEe|wPr2V$Mub0*h^jno&5cUEf+58{H1c($PU()Y zU}t?5GgO2YXX?K}NkT&5xIM-Abyyh~0Y9!=k{}rPO1uprXXu%Z$a;#qswi zW|Bj0GWdWyYxc?y+3dh*n_3$pbe5OR%go4=B7Bb3Mvnc)hd3nmLo4f}wU`9|%6)=F z38pRq3|ugN$P6-P`3I8bek(^wJjiVf#~};VpE3>2Ws6cT_p3AQ+!Ho<;pOzL&qwRU zQnmA5`=+5FTYN%Bb>mgz7yOX77Ft_{PiN^L&!~Jk6sFtojFWmcmj-;Al}P0q2twfF z^7&rR_@%y`$@h+8!80EqeggAn^DN!-4<90~zdeoEI%*xNPq!9R_;xOyVf?*bfQ!oP zsBX{7I|^I9roP{Z^vezq2wmqVXEG^kACE4ryww!klMo&aW7~N&2u9Fg^Jo5F#r6Fb zzynnxF`j$d@#@Ykq6`=BIFib4AO_BB=qF$5B@5EBGS$c_)!}*a{Ld=Mv z_p)P+YUVbDnwZ+x=3nB)u$)NR6Jy7{n(R!4gyAbSV}$NEa4Y34yVO zn+}SOit?}|A(hM79te}csFDed_tBDHDn9SeFN*3k1rMx-v&~&xyPj1K31>Jj|Lknd zmNh+$Bw1`i4W~GiHCbrG-g_i!bXW``*qMCKCL-cw?aKVHGER9?pk{8&ZuX*1pe3{h z??@799T{on*_R*d{6)`DYMuzWpld(3E}fN?vKH)YlX0jF!z=DGnOz=F`uxcZ8t_RN z!}fg~28x%)6Sjs2MR8a|e&GqDpB1$pCQd-iQ3na3PGb9O{YSM|<39>FcM^p)Nfrb& z0$kotVGhydln$ly;;Q5m#=Jvipbulvv<~9gw=S@@Pfiy6ReooPFH>V;$b4hd$w@)H z`UiG(GH%&B#vzZNPLr2EyV*peB1F39*U|L(Iv^Yt0#hYQcee#*+->9EJ;bAYn+|R) zukj)g60gWOc}d^i?lrj{>!hY|+#P=%@Z>3!j7C_C&?_6a&r9*&!D{;-j6E#FZ%VsHgzNjB)Q+ z!2!-fiB)F92TARC=lNM^fVvwp ziF>~~q#0<(Qm#1GTges@c5*P=T`C-ychFaN(uY3Y<@gry4jVIo@Q4xG*l1MLieAxp zzK9|ru}KK+fqOMH^AIrC8tyuBhRwA)7Bqc@$_@prejz#>W#0%6>O!OcEOht#oCq3~ z1#SA0&aQl#o)Ia+^Y%qI2;NBPNBf*XI2&$#E9IP>Sr*fw-N>T%&I-2L{q6R6|D9-PDH(I`Ck%T16> zG4JQLCE=@u+{?f0^r>vypkO8%tHCHnS^7EJ#x>Q^%ExyX?1MolUQxTC->@@+IcIvz zsfo$0Mc*68lZ4TA7Sw;zbtWy81$9pF=$GH*d#Jb8?CaT|jJ(m$I6A0NZ;7_-DXZ=_ zofGmtvCTE2?4)FMJSK3?)HKSozOSz#td~k`j&E<*+3F;+qG`0sGTsYna0aRv`?7jP zvQNYD!Wd3~Jv5{uv9QALZE$!%!m{;#S?0NVUqqL?hPcnS74qH$@+7+pj9UOQH8MsD zsPU3CLFGY3C65M5KL!j;qu_nA7*6T*U@4?7SEPmM*4XscoDUZl_rkpFZKO;zOcZ?X zqDE$E$EGBuqAqjiB*5vD%-}0+mUQskr5tX*O*|vX@&14|A0avfdNzKf!1R#&6O1MAjDtP8?5e4rkoS}kvbmohLF7! zYQj{=DsL`{VJ&I*0W*Gu#GHhLj-f@Sn@5S8`(Q!p&LZ|bC2rE}ZDFZKiJ@Q3B&{5( zT71x79lL5>iYn{_3T&vdrivyCA1v(6?WI(G6clV?LOgt)+h}N5DB5^=X!ux5c|mPd zACBYoHCC#qIV<&PjVY+H`ICPDYec7_%on|+i5yYj=tUd2?>6$%=F!EXWTQm7)fMtT zYPRk@+%z7rq3s`b6=0t&~B{{@5yzu$`2o*yo8UnyJZw zob4!`6#T4kYD6eO+Y87hRxpSqaTj0e4&F_f=Na9N`fA%)$}tKBpD|SE;?>ZalhH1M zbb#vfO7>nC$90v`_ZC#w2UrAnBnXeAh(`k(DcYSUx`#Gzb|H9Q%1PD4UO~r1)k0C;M7T%PrY0)g zDHvP1dS83lKCjbnNzUecvD+8lFP>$%15z&8(uy}WvX-J%+7PgpM&V`MCPgKR7OS~3ca^HDZ}3zJ3juBMRm^M zWqQ4^{e1BU5n>aMLY3>(tTfJM?VG>x>30!I%+*Cx$zDTh@pV#U^KFLshUaAJTcEuR zhyA#3WCbKwA1{ZS;&#@a8<3I(Hkx|kH3a7Kv8YaBcZ^fjGI_Q8ASWOSRd7BoqgU3- z2bk$ckE78!77R$_Ce{>8WNnadC7JZ%_2PWI931drwmvT_N1fh}Xe6NjxaBwCg2eZ; zNbOa3T^-xWcklIO44&D@_9u`MTT{~4Ais?%UiqJtPFqNHt{UI2(k1gPb$qG4 z?Djk8ZE*qFFd6lSRBwoUW2guZsZRwa6sqHRtGD={MUatN)YHv%r=85!wksn=6C+De zD&*w$HMDC(FWPk91NhbpH#=3Dc=F;;_XE`}yN-VMW{A$F^0>L$NPm?qN(^%&)!~YQuV1kqN*jC#tBqDMz?3ZH=`YH6 zlOmz2E9PcR`KeV0E*b!2OU31p>ktwo^f_HoRF*1!4Os0w$${SZPrSg8bas-6c5Y67 zs+H)q=w;K5D)UgyW8ASWpS5=obE$*&3^BHdiRzQy{VBehiTU!QsnmKqvy5Z=IC5wQ z+i8)F!v*_SyNC$^Oe+NOeuvY1!h*nIsYKE>v{wye^0Bcx5TAKCl7r8?bB|M zCk9!`{tTCvUC9EU*}L2&5uvyg!YH=pqVIc{i6YUT?pVhMxDBOxoM<@wjI(25KBE~v ze8zNVZHx2eL=#J0?dP;Qwfd(Ggo)P)mnR%!*NcrM*FKjO2d)8z?N8B3$+bt!QlnT{ z67d#%Fi&VJA-SU$0{bcnrga!py#mjl_A$@y49VL~P0(srs3N?07VPVVkT1LzSI9-K ziQ53bqSL0%xyRkmM7G-9>)PGc!~Dyo;kmO02a|yZfn$)=?1~%{QT%y3(fmZ_=_zkZQ7Urz^R`O+|{DkFDaUY1pa? zjS)XXMmk@2-&4|V+}oP+Q?W&&d$B1v^`uymRdn)Hup-_%|%6niIJN%JoG{ zOZs`cLSFH+MIrGvsTkTe_K^VTctdGg7h7UJd(GFP5r-PgKNx`leZ#8YbFGMTHW!J>PN`(M9N4V^IO&S`luc^G7VLL^U| z7^GiNtXu4Ciq!g2CmPYZPp{9lD?cb9Y?x_y!m|&zkT|g4E1w^8G~lX8$&Y}a)E``k z!+B4Aw@s(}9t2M-vx{FP9K@s<7-X`XUm!@wE}TaK*%OtY z&2-|8sp0pyBAmVMxaFRH(XB3h;C#Y%aIrA$_FOIJ;$up#KwU~D5rtclatXVLODOxIFveVBkLsF>kJp_+*^}5%SCr`c2&2glC3mVf^?iqu02MfnuKf)SlhJG z_E0Y60oO3cLo{$#2vKy{vQK}ohEXHILxn`46_^f)71X{HVzi#N=eC@?8hO6or<=&^ zRw&F%1iQq`cDx^cwNxFlN8~j=WrSqan3XIDVTBc|f0<5c;`HjG#6vl6y?HTV4*3PV z9O672^gKdkbPbrVW^w2al1r0ADX2b6lDoh6!q14)(Z83N9G7x0HW`eK_XqMQ@Vefz z>b>HnK8s1cI^Bn$Q7_-&+izEmTzq%pJ0KxkYgxQx4{**gAsiHMU$xOWN5*f7v z-ZU-s-=kjP9z0f;bF#kCblVDH0-Gd(m|lW2N4+G!9k)@03>>59T&XIskq&QRE1zh5 zGZ5zo9-1lv=Z^frAv;Bqvt}tXgts8Fyu@h9qh69u`I-bL^E@MSd3LYrlU?TPIiu@S zEURhbs!MjnhVGy@$0mvGcb=+IpSLz!0q8g_`7dCSl8~#tK00V0dI}G6Cxy*-P{A_0 z&1e=u@x@d3bZhQOuw*wLHks@c^2aTtt|?^OGnvjpoZoQeJc<0Sob2VPXUX7a%F-a? z@03V|c0-LqNt0VQ*aYy(1yds7fX$VxPf zPw#335n@YnhvG&E0TLJ#r3?ktmUF(#Frht#0Zi?Pi&+_k)#j~?bLNhN6TkW~Pon+; zglt|aA^ImwZ5Vp=@eNU$YrBK!DhU5o+ra%#9~FCTvPO@og?vvD+Qv7a#0!#vd~MM2 zXP`Y;+rlH2e$O6p$h|GR`nYyd{Ph-j!);OOFD%k~f_T2)FNtQLfJBnj9R=+ClR zlCs&!c9TE3yb*vttjVd0aGq$=QZ_dS+~4D9dX$QYS;YFS3p_exm!HD`v{q)MWf3HM zTN4FU6HN^tA1vv5!E)*{CLq?skbm~GboMCq`a6&fDjvitaUUEk@Z3Albl{va9bb6< z?zWh{kp(7IITU-ILc4nu*xv0q0ZV#w-Ik1T_T+gu{JTu(ozx3!8y6{>dJ@oPLgFBj9)LzaiL1n^gxhd4Ts3jgMDhuo8s=U{Jr{V5r z?g>?Axozt9id}p*@dQPr_{(T)UFL`9I!GOktZbcf97&}kiyhl5()R5j&qr65=8cC9 zn6cMn(XGZ;)cG&$$4j5HExW|E_;13S*-|mU_vEOKea*p+ZZO-sOUM1~{@lL%8hH&; z?vj(1kKc>Ac@?jxSxyOz`wr_}!3sMF5HF6$%5x9~;~e8wmJVMo?>8OFyt>jwbrvWe zWZ{Wt$QMigD^t4NB&Xf4LU)tb$T0GJr9aomwwrPym$#daaz`FV$s*(m&I@CTpYc%t zH0)5l{#PN5{7d^_Sh3G=~<>iEL7yBzW(~=m07M3fR3nHWt+w@7rtM|HM z^_j>TQ6l)e5CK#h571s9ON5f9BT>5lQ?QN~Z$@*orCE-a&|S5k_&bcpNgv+`S15a$ zUN>{c_xsL(5vZYBIO1fRIl96#jhqgXX!oAdg|xExaGB(kff%0zKtVVc50Lc(j-GQyC$h(!9Ug;l zsMA1>psI7$-BnXF$yPRHNSL8|YJ6OZGUa8?&om_) zrCebwBQy7hJUVml(>Q+fagzWMRptXydnsOOcSqlOf3HgE_+e(8-|C&4$ULjUUAMK# z)wW<#Q5EmG5uzb7N3M!CP1&}FM)nZCjb+o1TiBn^OhsA%Z2ImkmFn}1_ma9^OV!7L zAN8nfV!)*dRyeoze48?>=o~(AjC&lF6}Fi&^nKbV>C%~Pt)Aoq3Yo7V;B*(5F^L5d20?Vsds$CE-R%z+mqLFMJ^(e}FG|w@K;fJOXV+4~ zZV>|b9w0*M`IIo7w6c(flZU;N$OuvZnPBJqxUu%27a~ZVFMy{iOK!O|`h*O)G+K!u zJ@rLH-F9kg^Ghk_rB;Sk2PCAC`@6B=@1QNzN!H%~W~?$1Z@R?yNV0fEo< z;kXIiX@NMjA8Ua=_8&q2rqZG&{@p(F{BI+H6KJO`;{YN0DGU83KtlnoT+;8JH?i9x z*Q4d=BmYzMTm_+&&f$RuR0RpzR3C-{Qe}#qSyTlvj#LkR-XrRIK%6I;VU=aQvTR=P zF%$bN3HeYX7ZA*QLfcMIjTqQ64Gda+5nYellT)Sj|03c9%uqJ^Nn|bq1q@lM>yJ0c zd0YQUz-eA1o-ss`e1?+qH7ja)Tbopp6ocXwI^TBCchkFZ%uHzy~0Qt9Ce* znXljUN2Jy&o)p&}*DtPu(KGs$GDE;Z4(>?A$h>+eXq#Bd_S%br>3|Vpeoh`w85Ry< zz*sspHbGjxdY=Pi=a(eV1@%`GM%Q|FXMy=NYMUAUqR9Eck>LM*BsjhArZv2iy6I|k z;pBz`y}0;Y6N`@9h7c;Uw-?Y5@{*oN$Lu-6FT;|D<7-Lm{g-+IJnTRsw1!EtTJx7e zBk`9)Lp$7o*Y2O3fy^UebO7N)5RDHyn;6hPooqim1mWQ1U)|*!9MLH7cr)1WudPPe z4SV5LTE^Ktk&OAl%In6ft4#@W68_qFdVK?M3f3rF@%rRh z<)8XF$rFnDAAz6v@YXdqTbt#Kji|i6QtB5iZJ>BMTxC8THp<#p>Gi`*p;ptYJ4tp!9xi z2;*`Ek{@Cp;9NJUz|0RxmHHXdg2>3u3Ggb$uhc%zH4UZWZCawaTeD|4bQ-id-ot-U zwu1U;?@#G#P~h{72}0M0*@mNjbHsuE+cpY*;Av2gX`4wVW~@7BBTlXqoa_d*EU0Lo zu=R){Q*%hLy`}M{LOTrqxEi?okF%kriR~8|-?P*jdqGorqurS{n@~Bpm7=^}`gaA7 zRkUEM9*OQ?yfnEzz>JFZ#XO2!paX3;F}V;v!By!Ysy!pYV;?H}y|+pbzRSI32}~vt zbrxTJG!qw$g$1=pWImvA)L$Dr{Gqm$B5C-0>tK2;Ao-%qwW93r%K_1(lZB3Iy>>4} z%?@bies$+`jV|g(i4vE^ke+Tn{43oZ4)njd@fCD+s`Xi98wg={GcLiirc-)E;5DNn ze-XcIO|qYt>(GLK0NYio1v_nORhZl2M`ho@eZTm}kKa%Kb*i#1o|yHg=Pe)iNoM*D zVIzXcx0H*^4L|DE!0xo{T9XLk|7!2|OEr}8lCDcb>#L%6WS~xY{Pq~Bd|IaW+_5>K z;b9by3IHBfXY&tRtVE2yQ%bsvG_o}?2_^i&9aRzPQhrlh-<_wa}|&SM=Nb=oU>9eGCy2hsO6kQs4)`LJ2^wW&tsR1rXb2T}K_uy!gaKkVw~@b4hW zC#ECzw=^)isEzHZ9j0JPdhmspql%74f6FT*Z}_D=lZDMxn8y;3f)h%eK6Lm>nF1~{wBwehbYh)xuK*$si}^%Q0TiY zoJdg!{X4P4I$EwudW^w%(`*6LS7(B|$Rj#PT;%wUlGgaY8z-31M{N)MZWVc>OAPt* z=cTKEDJ;mZsUDr9Uz*B8gZM9WNQN$#bS)~!A$R%?AGRl5 zQzJ3U6~sWOP`E@;Eqof`5?mO=Zm4@=2a1{z`}Z96HHYpgIVu8v8*DEE?2c}{aQ6h9 z)nyj0wY&fGK_4Dad+X#3`IPzL(C!xu$#|R+NsGnf!A0bc0grU>c}I8!$wHSM?Hs4GapZa;+moVp2oLqTJpks57LqDE)ILyidj*@~0LIcT zif&j$_zPgRA^Iwx?3Su8_e z)&PNhgG@$90T|{WacXm<)>o1}$gQk6_>Fg#c~H0r;xUkK042)bm}w0g5IRC+AlR|u zw=hPG%m{8v#63Q_Mbhunv&bC;P!Hn<=*NuC^5d8Pqy+x6#Bu`u-=bCgU!qm>hBHXN zLWvbp*6EP~gPvup{1;)bTtl%^YZ-Hb05RQN?zop4Y zzKc3->rwD&E5K8b#wx6%BSlsxk>$7VzXlnh*i@j3^8g3}08YXAzo|!`r@ij9a`>OJ z;rpU3Ak;4di~k5jKL0Kdd71wfh`JDz1Mh_2mEi>D&mm*{n>euL`b!ETwC6%|uK4q8 zsP{O8OAk&oBK{)_IyfKrblnLNM6>;H=BvYya7v;*0b5=y4jubn!=7N z)G?V%F;%rq_st|-4%iEmx$L|2)I)r4ZH_J>H;$@tBfwFGF!#LaxmP*h~$LsJmIrbh*c)9c?FKSsqM->u;EruLDt)>O6Nc0P8p%h9jGDpfQC`sx9Y8-xJfGP2@7g@}!G$mqFRTZEG3qT2j zN;em)_YQ{$@apN!Zd@AFq{VKMe0^d6qUm%vbIPai2xXT37^m(Eq7PB~k^jscL?h|- zhn~A9-3mtzzm0A&^m(3TZ3L*OHlj@z6Tqua-cKRv0u2a-x6vDi3#BkW2w&qoU^)Wv zZD@x$9XEdzC@N@V9ET|f1Zu@2QvOtxTwPCp^Y3-)CT8Lt>)wv*V@ZFkXCgqD z$WOd~RPK@G{CyVk<%Eoh93mf1K?wm|Q-xY{4Tlc<<9ur}jOp_Z?X9CKQ}{@%g&dCzV?&9zXvZD6?;h>YjqPi&p&l6b_-97`e;qcB$P7;@ zB;g*vt#IVS%E?u?d>bgn-;v0d@<>jHzoO#54u5}&*Zd!({r@+;*d2D*9&eVDNM{lv z;Zbd7-l&{J1L#UR`Yo--^HMHXTvkv&&P}jiAyFN^k8B!hwM5yUu=!p2enq8U?o=ND zV5#mq&hmlbN|~<|^elozyKj=|Z@?6<<>;fE(^qz|_9o_Uyu3@*ic z-ZuPc85422I! z=fU)-AN)%#rx_pmwtYf`$*Vxejsh~ zN%zfA;Z2zQlk@ps@(c29e)$^*jT&(U8*|>E{#}^`reg7sv?lp+?r=Zo>_owG!3YzH z={0RyP~{@LmIB?%*5SEA^vE)2H+Bd7102lc_DB;do6DtgRJAj9nbm{%Ovf6T?R_Iyq+z`NL7qwSK z+kQ(GP5L`5?{0x1^=iPwWoh`^i*zqN7naxGc50JbYwVj0JRgXKSmXKH{-|J6brOLb z1lSyXzN0Co)ZvSRGk(x!RZStZ=FpqNo-s|s0XD=kE5DJ|ey@7QASB8-n?vaZGbhMIo+FjIaVYO%~T zUOakx+=UG^NuntFR=4FUqHymKxJsShPgZcuM~dG8)SYm8p>PG6vom`9vxVV+)(J-r3V1(J$Yl)Tz+M1S-wN0}Sbh$O|HRZAeolYckOkN%XLnXea@OJk1Z#~BtgimZ#3VkuK7H= z%MWMJZ&vy)Q$I%+JG;DcNJOG#qL~@IEs*dh30^8<8iIKeJTg@##g>U;-))krn}<57#Ocf2Hm|Eb^Bfv*+q=8qftg79#PfT zb#lsR${z}>*~nk@F3k^)(jbID; z7O3_7X-q_D*v^cj9O-llT-c#)xhU7j5IYB_(d!9a<2D?P#(zUd=+LwkYrllj$ra~s z$69CSh`}hiXwjB+?92J)@=s0&Ew(N&C69e)o2!2C6YTlMPvBV+J`!@%npl5~7I5mq9TG2PwoL`OHgwBSPfuK2i69}5GaDwK#)uWlp znU_XWD`G2oeD@KtsQe#3a68i%R@bFHe+8Xc0pUM#^Bim+f;(_!UDlMI(I0gyK%V73 zj=JYY$}WaG7LY(p(iny8m1l#nl#MtN_6~af1qisR0eQxNCC`%O7q;70C$k8=K81Y+ zLmsTjD?B)dFX~bx*fnE`m>s;yJaZn7LFP#1gDg)3y^IIf+koYYF$$`M31YCYxNLvv z^MJix;l68_)b#qVqtQ01(-{uh13_#->xSwnXkkX_CFoOt-F|bbmGokgT8~LXA0M0| zz&3tMU%{Lq%%1ALOgF@Mt;9G(oWF}%m(GmBJBuVK(Jyeh=zS-{-WmAqY#jn73hp>d zyP|tLGf8&Rt1KJ=47A09+J%N!-Gn9-{^Js+ZSi~KrwEhRN^bw~ZK7<}*U+W4$}22Q z_Vz`V8R9A`E}bamYg2@b)A7Trn>QdB!GqDo_Vj%>cKYrg8e3jeL}I`I6b^di4*$is zdX42S&;6)9576C#kn_JBBskFysl29r(yBAg@M8_p90zMno`S69C74Sz;h>Vi0_eiX z${Z;_7-`Fys%q=|UNF_tH&K#1NsORM z8VLxp`1q#-9OprC3U`1@Y4KMg_YoQQM*xNIEum-l7e^QS`5Tv1DJn>Ky@v#{kXYFjng8_3UA6VFl5VK0US^10?+rau zSSOJZ3m-h6+q`V6VNP+HJbu{;3;{O4z;%CVYLbHWo`rK7S(_rJHBQ8QU{!34@)Lrd z_G!b!FF{Li2UuO1g<}bNTTGYP=M&_bj0&nA(ErMk8;`2;Td1CYScbJ=O5fkg!1(P> zx{k^F;ZKUpEwAtI3+hu}`M8duKRJ%E^Ib)ns_UaOb~swl$*+aEQA>e{U&0upl%L^eu~rBr z#J)}W`bushlWh~v?Pj)hlPJFA^beWc7FWk2BM;bjBM#b`BS!qrYuqB)Ngi)aAhIS- zAFQ+Y(DW3nN!bSp97QVW9}HGC59F6M8C0~d2Vf*&;igN72IB%yfeWf6_9-L8kuM-?A@bJr`knSci#?laH=?{&|tS_bAVWwYNOnr>HuR}AFz0y~3#yGy3+Kyav zFIVv!(q%G63$k#>+X-6YOkNtwLESM-ilHTZ*LUFi0igcs5@JDve!v5;#^66QB|B$^ z%G)e0u^o|S*THY>ekYp52nijr5S?6eG8Nl|4rpJ+0_fnoV|$)(H)X89ZSv(BYRMB6 z#9>cQR)|5^7cMu{+;DsKFq{j>8C&YD641jwq^Dn1)t5K?aEPg=*2xfBBVp<$$`EKv zC_7SI8qn)}tl&k>`=dt(6NmgQXV(*-`BaiOTdbgIRZm$ra9ivbSh2iM5PnM%lrAT& zMEc+0<|6MP0t3~hPK+P0Y*cC4s4liqyf6MmI7l?FPdnvBJ4$ffbbWWqnIn&S_@;b{ z`%ko1d4=g|D1qO6c_U?VDxn+;HH||B+K?!shIH8VYgFlAU|MNZO|XCIJxkPHD-w~h zowTRH3aXDUWvpQHv_hzTYgis`r%;m}ufMKQk-|*J2ABIFbXT8XDtjjPw&#yMj=Qi( z_^ngEjdIOv0~jCFOU|*v{=qtgIIR`_Yjwr1Z6TM z%fw2sq*`HOLmUDspjCK7amEXLp)txgfkmX?St8HSXQ4N{V|!>48)1i;J*DUm zJ%EiU>BgDo4#J9JOMR_W1RX!*yqg^f5YdhwCesoL64R>lej>;|ZX|<+=tf6FhC*rd zzH+5Rqn&l_0<=*9cM@zl7$T$?#oBlr{07OaI&!K+Sf7hj43wB#zku5N#H04%My2Oy zEOSgxAIpgSwD$4L#MQilSJp#vscACH%^g+?f{wh;v>e&Z=$2%54a3Q?vgir+LI#&b zIO|xV^tv}B*iJwZ3ibb}k8n0VY9s@A350b2HbicsnZgy{>%FrB1;X>IxeUdUZ-MK_~e^TFQIJtRJDzqU5~h9T3owcb2YkNq+l+vc{$a~d~PR2 z9cP}Quvu@|?XE|n{Ned>Xg-V2k=cd(1VxSEQajlsQeW+qm!cI4mN{4JdXwkerE|9< zSP$%Xu6Pw#!^-jS{H}%q?&zs|(@)b|H?$*71n)7Q(!4P#I5p7hWvs0@s`_R$%KN;y zfW&?VhBJ|2r$s0w9>xv9i^}-E%vQs8j5ps+F!xXSdYSe*!%}`<24CmA{_t*DRqA31 z_6G`J6MIDc_(3YfOkE{A8;{(V$8viE$inXS-WBoF2+=8NdvODD&2i)~lxGh+yY|zY z3Wr==9;mjb$$N&)%upXFZH|?%d|)#C_NYNn$*vpByE{KL5Z~p#?(frT$w2nx%a?0| z6UmS2(*m9yEsN4>sCCGGf2Cx)yve8Q-t~*`t?#tercpfULl~OH)}9#7ymB|gjH;aQ zDx+?9_D1J=Raf?CX6s0Og$YHp`lQ3W{h?1j5)&wiW|7JQn-h#a#}w}9=vXhJ$*z5o zU+F31Qy;4*pb1{q;Ui$48&-F#_|ts0YZJ z&|yz&+ojs6vb=q%)3#5JluxxfmT-y@57ez0RfZW_bN6uvqvVcpm#Lwlc89$ zrtm7rfDGx2f>C=xXJKt-fyExZzOkazz6-E6qNb@C^Qhf=r=5D! zjGD72`g^Cp98}J~`Vq=hv=o$~Ic1+$RW~~L$Re}a6OmcQqhZLm zGfta(PI?!!&O@1)*GyMA=lUc(pt5!!SinV`)qhu)EnA|#*igGg!;9Q8FW+or<|GZ0xwFZ!3M-v9S@uW+}JpQ)0yR zlS|W)7N5&z$`Bt4-x+aeyA-4jj&v&XWWVY4X< zinLp3EghV1lSW2A37St=h%;Jeha++zpeC-aN^UmoNIP?K-Xq8OL8q zdO5bUX7z5|Fs))QuY~<4<&O}|5IXZ6T1OXIzsSOmGD0f*wR@wL5xIgGYlINGf1n|c1m=7K=FXe*OVF>h&6q05tC+_Mm~b>C0i%E!n~P|~%*|MpG*YBu!q9wzD38Re z8W>lE04kL+V+nJj*)aj*L+F zs9!s9Kx%2N^NSu~J(1^0ZY_7`o|UZIXGss2?2u>+cvT%i;vCq{@%-R}qohk2oSKX2 zrb~^aRTCw}H#~w?m2UFpG{6;F4MatRBElHOBceo3pS0iAb_sqh{5m=N>(aM0G5vGW ztH{Bek`gYjoYlKKl60$_823mRc7A%MH+-8~z7S4(G5F$A@Ira;ZdDo^MDOPjF?rSx z{4pn2Emx1-nDOG4k@$2f9eu_&HpIIP&gLIF`9oU<4dXiy8mIY3Iv?|3G}G$z;{V z!XCRE7qEnFr?bkc%c1}--v9tA12*&u*zvJ9;+Ofs7(QacE5zk ziCl{;@u!PrpPa%!u;aT`CT~i(I#0m~DHHvVkLfw`!{~919acx=gP2MX%>}7lpb8RH z3rY`~=OKGK9phv`PEBLwU*degn3^we?c0G$+MT#3c@=UpIk4^4?i*2}VfT-s#4pEA z+6cg!gHlMxOU`er6!Q3WDMbB9_}Vmc3Pxta(elf&`RAG)33AF)WnlNw0~5qU!zIUh z{#TgYAyxpr0xhC)CGYWFm3-WiZ*J*L$2uD@3w05;SObQ$kqD<9#KV8+Km(Uy&E1`v zwC8kOvq`9udYHq2Lc#6HI5b6gZJL3JrD$i1IfVivPO$)tB?Nqz@v->l;_0~~zf5p^#V3md(97Krbs%_@yc7Sm^spBX{^Kav8l3z9E4wph1Z$?) z!Ro*)i?nH6e0z4OXwkXF3v_7Vbd*keEAs)qq&rwKtt)u~t4=tbjxy1%bRVH4@mrGb zi$7h$cthr;@j${S-7#|FS$H)eoM}@V->rjJvMTD?j%yP?2AaV3 zFSO)bs3Jzgsvc2S9&<0UoNJ1DPb_12k8pR43ex3;$vpb;2QY& zIQ$Tf&m!NsxSJoFoS}5InhbmZa@+kJ&QHM!jG!J6o(9gJv~+A&cbJQ5V8>n_VSzRF zadKHSa5b>r^m+uzoG(#eE&j)|?q7;rr7eBI<1EU^fpS$zL-*Rk(vgmJ#wZpM z*$GE7IOzTXSg?fYX+%0^ppEEoXAS!yqi3Mk`%mXCAF3V45XCP!ma?W`1bT!(`?VM;*=&hnbt1CO0LPu{Xzpwogw7mPFvaiB)q?t0eLvhndOJpE^E|ju8 zMES`IwUZ7=dAmeK^UjaZ2D2MI=QQFP)}(W(3IFaD6HM{Uit6!&k5pDC)X!2i>kYt; z!2^PP?>M{T{WG&mHs;7|yBcPP4kIuy$2Yh@evK3|Av z#W1+5qLhI;W{6YAu4oyWD#`D%yhsYi0C!bVBY9jFpjIGQYQ@sar6^_TU72Rt4OeE`0n#VKz1PM8x~y&WMfGJCA3dEB&&#nnf-mN ze#l9@Q&;K)A3>#9*y(qon?3+m@_#D&ghHmzNK`EfbBj_^gATg_wA%i$GS~9SXs{Cy zY?G%L6w|dLk$1Xx<>Re&5f-~9Gv?R~Wo~;*1IxbKc4x;(pCkk{hvK16a}u`FU&Zg( zQZ{ha;B>lo88t0Y!JZo~fkWOcLzB-p_DJQd8v!oVtxRlaR+p%&;>Q*}%oe=oMaK5f z8eh)!s^n6I!{*t9P=rUWYA_~+K&`Qp%YTG&N;^m^yx&sF5$u{QFP217x*@#W$SZU^ zz_<;Dv<7P4xn_^35nc3iY2?F)hlHAHv2jm+j7po+wLmakJNoaZYkp~Esf-X)Bmp+= z$;tL`0k?o=@i9TJ%+sIR1xm{sk8oC06gBV$2b^os)7_d56}j z%W9d)D`N74^k}&&FDp6Dyu4XttRTlL*TM@Dum}wKbO)Y4CD-2{Ok>0z@+6qxMvI65 z7uOL1k*n89q#|+rxjTK*%iWft5JLFfXSt-M$~D#XuWM@gj=4WlS9_z%Ryd<~ZV0ZG zb0eegBY&5LUJ;YUVN#K6LQ%)NxOyh2n(o^fvG^}rmOm5pn}o!;?>u?!nq(%T`mtbVse??vQI77{lh+~9j>{SiBqIWV&=AYcD7=$HlEFrLGmCKqbD-D2o=M$wuVT*CxdVW+ow=wuVc!3Ypy-^)PID9h_F{E(sKgh5VE-L~UT8Yy3p^+WQ;0ED+)gr>WxW318K_cxBw#?=~+L@R5i{ ziHswJ=p|VN>)x-5`<>@Eo=pzAlp5q1+ZxJA8)}Qm>e)-`%Mn9bt_$v3<@!ffLgBqj zE%~MFaTkkT(fsYK)$4ViNMjGlAlJz7=*5wdP#USSBS%3RA*s;HeCHC}20yhM*JQoVL;So@3V8X}MZx8Vie89E zMK_|!OTOBS0?8g+e%|nyUR}lmXTC7o=chYWEn!~l)5dUx+;k`Vgk*`#lb&z{<|QQN zgx0T%rORZv3i{VfTM?+Jg9SmSCN}aD+a}HKkPHh7SYt&o@0@&*0CG4w#Q^ZyYUC`# z!lprffMF?8vtU!IHl(z3+q48-{scm4Pl#vA`9% zBvRrMluM47u^r`=nG`0MFn!=5V}`3<~jM6v+l30)|zg#m>XS<6dIWvV9Bsd@#V zl=O{@f=|a1FCjhF9v&Q<#wH=kkQ?1wiSI5a_VUVOb@VsCY3H>Z7Wo6|m$@Cj#w<9rdhw~YtL z2QOgnKmQ?SK`>OV5WB=X;>8+H0{Jm^5qk$d26rIb+M0B`adg8S+rKdB|I*>5{@xS3}?EE*ZR@n8v( zW8e4ZnMhOn?`<+1Pljj(idJno!fjuQs2rElGSRk_Gel_HOY3XPD;<@#bwB1%ArO~9 zLD|=NlsGK0={LEfUKilsrjEjZ{rBI*j{c4y`aX7)N_QaPp8`a`z0~>yf4tOE?Tjvt zPUe~wer*ajyRZz+j+Kf>*Lmz~=^N0)ws#U~I?g>Qtht*Q*5t+7TOe*Imc7@EG)seW zABEbhCYqxe%+Ed3Uh=#+`}jq2X2`?)fr{2&666#NuTH#ddL3({Lit#;;IjB`Z84jM zNEBqejAA1vBPmIxI9#!bv(pTo7is#C-bU265{^^gh^z9T~ zl+Z%|ZqZ#7b8gvr3iio-5;R{Un3OYf_!o@1H<-DH1o{We_RLB%DTRiv+D%rUZ(F!c zk7h`z8Bc(Q#D?;wtAW%b8N?(cGnvh`txni z^QX6Cx@~i+t4BYn9(x0aFhbhu+RFCzRgk_q?C#13H=iggP=!jv?n0;E@zM4QTF>O! zx7rIEb%>mVM)s31XQEDbpRR%;=vb6$d}lAzk9S{+;9Dq01`pock$-En^%?`h5CaW| zVoLJu!V5m%vl>uT*m&S&2VFU0?YJgC($TH?){6FXLC*atbKYdz6`!|X$Y1M-7^ND1 z9(#9<+LzDu79n~jxZ`=Utm&DzuQJ_6-8~WmZLhvYYaXO+#S9+ELOUiRm6uplP>Dzu z<~KB`K8E3G@mNg$O(Z609NN}7XZ8y7MFUekv@Z*ddG_6x79#ZqmK!Gct|nl3G%#=L ze9hEREb&MkPQSDzjBu;tD-0_mDpgxEbk73nB}x6x+1msxmoRy`ZjEr3+}g646f1so z|N66KIbNzBvh3W`y|&diBAsL(y1bmIK$y!BpFGs0*pED@c2e&CHP%s~eMjCusXBWs zMgIIkvWDX%1dV1zY#38Hs?$>|Wi0c>`t)Qn@;m2eEnN+4&Y#A${lOPOx5i<{Q#) zL(*Pt{>E3736qg{+&r2f;uL%T^%F|X@Eh{NR!<1aTJzNRR2|iNv>|X47EGjc4PG_G zMlycE{(?kDE!;qP_bA7{`*K06bj_5-O1HXBXfO>7v^5?#Q7KB5=eeXut8u;N#h}VX zBJPo{yhlaX!}HHthi0WyJ3(=Z*Wj;0P^fX0+&5n3QHVZ7Yy`L{MfkV0P)V#7iq9Z0 z5aHaV$OBK)zw5CpP?QcNR*VpV8--eiT$6@<0jBqgpmacCLH^W9kJC2Enn>m{`jND| zAyzP1AZB~?PRcv39%O=zXi@Tq?yJ4#R=9>uU!8<;+e;$D==@7Uu|3nBd@@d~s38rV zDSd32Jw@-!7j|y~#qhJJ0VqFd&fijgEFfA==gE`sh@ilzfQYE*U>&_(r;PrY^XK3t zbNzX_7AF4<5XS(kqB=lgI!waJ>VbDLW0QsRvB|=}Vy}mWJwVhP@#1_)*rMlV)|`Xv zFH?643D~CZ-30pTn`u~B|Gk?#L)0NuU9j5(rJS(agr%oolLV#5VUvWV5->)B(nGMQ zJ*DBWD3a3iuxrGn7h%^(N)=%}#HGEk9*WW+XPdvGUqT^srmWf&rIF4yqLeelgAkbg zPETcmIeOL)yGk{kS2-#Bhz4a~8)Tk3gma>-XtL5i=T%`!42iz^bDO7dk;;cO%D`#@ z(hNZ$qg?)>kJnpxb(PhLX|)+XBWUE`SfXTXC@icR2Fd;FLbgveNN-xJO(@%ub=LBGT! zV(Q&)vAV$#jJ-^EsPS5$RfdB|*9QaOohDCs5EV15;Me~#xivktvk%g~qCUl-!<@fX zKJDdT7ZjkcGk)t;D@IIq33>=4z^_|R8$V__^t?KSI=7JbSe{|*jhUtXOBnX`w3=Ch zgkY}av6asZBE-mSa;3C$!f|n+I^r?3}xfGu3d{_h@nRmqeX8u`gDB~UsjJ{sY_cg zXhn3cm%re1ROh?C=g^A__TO4khguwQh7v5y`CdLD# zgS3e+51uwQSmnC;f;05%^CyJy0vvDIRnv3c(P^9{U?}^?-H&t9yw^|dkF}7{e8Dbi zT>DenCYWX!*n`Zpka>2=>{g6x$tI1@)V?P$BEpra)Q#-Y2F)!-GulS1-7o9I(T~GlzF~G#dFWZV#w}Ve-#F`iEV#iZ&(Q@^`M}M|r}rU! zYC2h-m7n9#NC1Z&@#Vtq)NF-a3N0Y-_C{}3h23EGwD{aE2JAD&z2<4T7ms6?e925hHAN7>Lr)8bJEzJ16Tbp z_5te&YVJ!6RA;c1l#|po7~8|lzQffS%qXxXS&|koKL#@)kbGBUZ07_zLlcUkPb9wB zKX3~G@^^g8L-%tS?j2d%!8pyvas98}UIjR~$a5C7DHPl8_e0+8-DEb2j@JL+fOe+Z zjzVlImn&lVJ(Fw#5t$^TgddLdsCCrmM!U}b+92;q%4fKLA&j1C;b<|E*MCt!uhCzeC&4VM9Qf_0E4fufX;Td}HAA;A}McFw)JceRNP*u5U$?Ot@8WlR@nPlHvL~@F?#pL>DiFpu@h0grQx|2NLpx-mxd+tEJ+|iiO$&xNV z-iz6tx{d>9k)&VvxTc7-YkGxJY{3SIDpB$6(oJOeIzsEiDIMDr_dYI7` zg$thf{L|^dMGFW`)B^R(4$*)cGdlvK9~dJi#z@GIW7;*ds(NhGd(mO%Ed2)F zQfs7Qe5AjJ(a#BqvMxd2ZuR(%U%nqWf_tsbb$wmbH*!E~deyz{~%s&wKntI&izSveW}+XWZ<@Si^;SN_kQ5x;LJZ;0V)eBy;L z?V)=|cIbV6SSF;vNW(ld6#K{bO>gWbzizR~uUi^(2isYkif-#hjRX{2A4nvqGH)^5wEsD=REh`DsTwi(Rj_&19s$ErIxij4%{jm+7Xz*YFMAEO9+Rbl$C5 z@GrdCTN3ciUG#M&Nzsz8Bxq%BqrdU+ty2}Hp)#Ao!m?nNmvmQ(5} zG1gMA5-ZK>eG{q!f{tG)J4|)(N@!gh5GSMO@j`^h-12|=~$Bk zT_y`QT-pFutI4{}feUPM;2#EV&p;p#eM1@eteBZUvn(!kyJWUOeCL>*rPYo%;>*y zUeWO!nuJhRMABz*nq(+Vu%S?!F{SVB1jAP()6b|mGt8HQQdB^4(Wxf72-a&^=IjI& zY24U72*{5E90>*^3~UdDg%%Re%?-8XF62vB(`Q(6>SjdIA2X6|0mlc#BGrMEPQGIw z8!s}S>NhOR?Ju9pM9a?dkNZ(p%`js3%NWQago(#yu%3@) z$cyQxh7J?`S6jKv%uaNf!!BSB#ZQ4SBM9XFCzc~-e3P)Ide4N|-HOo6CTI;`i!7WE zjP{|Hr{nQaL<&7bek=k(BT9taeT1G?)E6wNf*#E;Twt9qdr9PV9vg;2#*fgJGt@RE z53csV6cKtYFg%tvHXtlCFzAtLjNSznOAs3d!Nt&xy!?Fy&-6c2!RN4Y74E#8W0I6O z!of+HB45c%+$@I;S(&Tz5)qN}s_Yy;Ll<$s>4Ko-$(qZGiu2_}R9oAfo(={F`?XZ8 z3@CWoE0e;#mo4a|*M-S)zNFlGGSPY7gklO4{>F4--Jux0GYyU_qlzBq<|PQ#Cum_f z_34%@uy-&Bo(FfZyqc+;{?-*dSL7W;HE~?!%%*(>|Gb~tiqa*LcO}4Et4MlmQ$08* z&S0Z6R2ELh8OB9cyBWN}JN;l@*xoi6=?XepC)B{^oI*uVZ^UIQ;!+kXvi!ed>_b|! zo3>_+h@9Tkts3s8u)cgL(jlo(p<8D0R+?mSwiq7-hD*`F27y7Pp5{kV4ZX;{SH)(> zb3nY?!$)RPS(bf;j#*TXZ%%*ujY%!e)K|v;*ZqYz^QEuTUu0A!(3pALfmYdqXzUFH5h0FmR3lDc?bCF z#Wxu0pIA8^9%z4);Oq2Rqz;(>I#wB@bOPxBdWG=>Ox@=t$MNsKKY0Ho%B#WY%RamL zVPbRr(H~c<Pc6Ls_Xz^XmPi_1MXv1q~*PmQ%jpElApi7xZCvdyPYuc9Mv6~7L1KeqXTM;qq{$cc?j!Uoykw= zH7}q!GAP=}AK^62RjGO8!zoSsCk~Py^T9IHQc@Ke8;y{VeMuUjscDb-$l`+e29UcM zFA~apYBlB$TJG~Lp=Xc%B9oGX-h1azT2?lBUB-dv^M^+%5a|wA>t}rGZm@Af{nnG) zpQV@Ay)V(ME(nkGkg@0sq8phij%|P9CPvpB# zGQZ9hjB)`!Y~lj3Wa9%2Zz#)vwa56zBHGXg~=SAK|7FroRy%ol=QHH#F8;Vs?u?iKHi2|FLnxIJ%^ca%R#=)+aCfym zb2pcgo7PSf^o*8dkSKF`iweE?c)R?{zBw(B*n8WiUtv&9Cx2ys@^sI`Yx#%#ll;p~ z?|A!6BxXG+7taz`8Y-)#F0y?{GDPXkf1R}XT}0#l3e=Ton!8%Tfg=<_drD1o*O%@E z+3ZwCC|;%ZEe(IOcz&6%Z6^i|MK#NteY}hcdJqzVBMz!8bA;(I)mI&HUQHWi$QbdvF!R=Hor+v4K~vQ3mR$ zY)kmwLs%t2Ku>@|MC`KjsUJ%zCY+w2^!_8!W)lu1d|9l7PlJ{4{f>g$#W`n{8o*Z2 z-@{e`VVYj5vHOBH1C(`NvsAXqm^et_Lj#=QYaOkm{{E#kx6n8C<{dUT=T`9svUsB05}^!z~iXYB0#6*0dyVde zJeV%-hL8atcE+X;dk2;-aSN(Cq3Zrc5_eHxjsCf}03))qHUY?d(Izpz-`v%Z?ShXd0dR0-{j3F zB8vHwYem}!h3wY{W#Tsn1uT2O6V3o$lKz%(cKxS>Gh{lyT`K7QcZBm(QlQ%XL&BLV z9)0*b!1-HN2NP8@CVKrUGoTM<0DS&Et24uZL*%~ED;!ZF2`Kl^%Ep&4%8Ua`g}|m; zp_`0(yZr%k{os`6SaN*tRMfsEpbTgrW$-tU46i~@Z4>nwK%9V0IBxc6|6e!{K?yf= zrd}Zo9nT)lEuZb!ZRbvF1y{Tk^CR(I`=|4OCEka=A>RL6=RuDKj9LC^92eRa_}4p9-++sjP@Cc0I(a71c55;|ziYb&-aw zWAW0WPF?7Oo2ujpu(tp~lq~)W*n+VOYms2m%l(po4tS$^@|FxQqnQlBM7M16(p0|* zg)Y3$*p2`&Vd7~&$9_0@MXP=(2uU?*W4?T*iUuIxSaoOB!sB;f?ie)iY&e{QKHPSW_2C?m7Y99=3S5!3KX&II z62=K?w86~y;5aMTG<>t-z>hyL*p15$kk!K+?tTh|&HuJPs*Up6T*DVMLci z;E?Nq!m@)*xE;P&9CB88E3_*V?=3hk0(k)~QR-LKT{SPoZzKZ=WVL8{^Sj zZP#0ph3Px?AN+FsD`=zu#BPQIn}}Q)$&+D`Ha~450;4w`0^BCSG}iEv-KBfTa*FXk!F%#j zH(}laSWh|5i?T7;1Yn6fPI3oG&W?q4Y@{*$7cSA{dKc%6Enebp#?kvNN^=;lo{{n8 z0`uopU5ciy4F)GsE%F%tLKU{&0^H)-0q<$Vz4Z=OfxEQNQ=P+4!uP<|$YD{Dmji>s zG=gJwb_DP#9h2pi=dI+^cbZ#}KLJpJxNGh|Bzt+!lU+snZ@ogu_?2JKa*Q0!xjFKj zrhN5``|9a4WjpEV=^{9&LZ|6eYi=5N7E}3_ezkHMPuD$sjFIT+hRX9h&JU@jC15WnzZzfcZ(2AZ2$@0P7sqA0IG2 z@$Hi8-==*De^{)jatdcY4}8LDr`^3uYQXL(3QpfiazInzEX(WvMOEsD7?x^W3`=w& zPOwp2XV4BDHGCqT0cFPzQN>H}>R%RD@CVOhGroeqlBqT=%2g-WwnZwuMOk3@*ze5A zMVqgP?-JAQY~r>_>X;y%R0Kij41T|q(b;C@ltqdKQlX~a|7c8N{dX~m3mU(_|9!u` z|C1z0|4ji<3krafe<%QOD@J-w{?nYqyGx=!#Uu{13C*KSIB_wF0DAyCJei1l=CTmy zhYmz1-&%h6-h$b@Z>0i_WgU#9RUAD$aMrCN1d(O7J`5>}&D|<=-JR6iCnAc2B>263 z;ox=yWA;j$M6`S}LTZNVB*RQTzstDe?Jtk&>dX(h-p!}}%N8<-f9S|iNETduh?{8= z4E{+%aHdH5w8OL0DGUPC;w|L;C^;ccP9UBT20FjXc_?)t0vi!dVZ1=uLrQKv)!4Z*nHd6Z@q0Kw-a@>a$L96WF7@dIQ0p?1CMPFgJ>fHu>0yq z)ASq`D2tBnJ-lVV_x^|W`(K~%1ONQa`_3BsH#^?IR{P^{^?0#|!xWYaz#t2q#d7MK zjS?`;Vm|$3ng#Q4tdlxU38joEKoVa207fl;nxTx{0{3S04wVlO%2CcIL+qRfhDSqT zLyy%-sUA~d_g?*Op##@}c(IZv5<_$<%_N>Pw+}#S)PEmGD*8VYM~dCVygThqvx;)< z1%(}2A%R!O5`wU+bH993ZJ(ULSKDtRB1&6lqKu~@->zK74^rS^lxs0G(^%t`_cEOB zPI))^6FN@uPZP^y&G7eG*X+$5U8GUbd03{X1jnK17VgNsD!__j((e`O>MP#aGCkA7 zFg1hy)6(UlAVmSRZ3g*4hh{OA4OOAwIkP`~c6_@<2kXbcdME7qu|d2A*MGZElZfls z2@J^k+Hl& zUTG&Zctc3IB7k=(QVjB0E&+S@cLWN~j;Mp*W4N;G8;I%ee2U*;hX1sn%jxmq`#!{+ zf1#pM_z$zkc*uiQT|q2Ge9nFjzYMP`_NmI}t*g$inn`%c?_R;XpRPI(hqn^E-MJ`j zMw$a5=}vok0PrySF{WU4ueyRjg7lx*4&k?gruo_PLLiVJ6cq4jF+Oz9K`sF>)fKS- z{Y?ii&p_^vJI+tEQuNO|e1jjN^#FeO-mX{ytWPYV$FEP+A3QFr0|9<4w~*}rA6BOq z~t3W4)qNg)r+niG}4zAZ2p5N?Zb zd>1tt=4i}#et-GsbVP0p?$*o46ph_ZqK$d7@&we5E*cq2y(a0-EhxxaI+a&F z6;tahdszC_vB6ddHVdzd{M{P3$;m=xc~E*o)~QwzHlLtGmzylcL;uP?R>URUm0>pQ<< zDfTGVy3Lxx?SL+a&8}qPWBsaWWnMug_}Zt+0L9ugjtg&JlpAhzm36*6rf0OzD3SbR zz(i=tXrT^YVH4kz>b_l%i@hCH^}h};AdVNXt`F3`l}T8C8*&XATaa5cy08cQAXS;y z-P6Ky5cA9OOMDeeWpAl@-qEsY@YO_s1UxprzDb15u(cM~>$>(ViN=DCjoN!cmK`C2 zsgDtb@}0xwZ{Kh$?ImrVv0HsovyLe_V}}xh5zNo3LZY~!$7zwpGq$XJYh6bii_t2yCYniJnn8yOqxqd+4`ktq~WLGM15 zb@h>)Rm&;M(xCfSTMzhnv4^zZyef3>h}6>agc>ap`QdWN^V3kq+=Z8?m-WXOr%bw@ znLawu_xY{S)pEhPH_KV~m7A*Oh13j$&kk}7UiONqSUh!Zl(zhZ!sqI;vd7eKNfXYl z2A&muY|ePn@=Epd`9e6wD{JXij#0lrxhXO|#NH=k%2l*FGFfV`yGuuE>PjC!x}ANL zPmeCBCE?hmV#_DQw;x5ebDvS{SCwmxctag=$moUAE0f(vjoLHn)XWt}FD5S6WMybr zA5UIb8?Dd~UOej;kllfLIQiN&Y(+C(Z~-m7syb%(=_=Q2hr+5@-bk^o@cr3{jPdb> z`@Mq|AuNa|N^q~BSUzo`)&`d8$L22DLSL+p8^!pOqYjZxG36{4H|vnL6E9DFm?^e+ zn9$fbWLN%~;hNFsF3%wC1ktYi+r zPxRTZif$;;Ah;IBJVv8u^Giy>zhweqGd&Wc(JyE77h)x5Hh|WN-xK_6Dj%OzEKKly zNHOg6?J5CyCh4-(*{eFoGdnFXuZ0e)$fKVZd@Oc7(%e>)@s}O*JItZ*kA>-7?6x(Y zquXU^{|~89KT~ei*N2|7U1J?ky#dUwStTl!6gdPWVH$ViE+JO21d;9t30Ow*clUSx ze>rDh+mAUkb(ZDH>BPTWKZ6swJaZm@jIS+wKRHr(Ri}f+W*V+DzH!EmhL!K|Y_NmU zcFwht0kZ@y=z15{(4!g-hJlm&N4&IpU1}r04Vc=DssZCQ<26?=TU^f6cG5N2Mj$rB zWp|~HbbYAqfT~q>RyW4kmjtNeMQ2>PAo%bqlJ;!dmmJ2eQ%)HqviG;-^P*Efz{pDZ zS0-~_IzFG+S6fbU8avM82 z?R_jk!|nhQB?wAsM9s%p#vT|Hnr!ApJ7!4ll&_4DzNmw==INq=sy$lW+%hn-7_d_^O{lk!#f3&Y}Gle_y;4lxbqkp7DU^c14<-w@G zZ2pf@N8gmPd=t6#>yq#~&(RLXzPqjHBCEo6wbAy@^e_x@)-I*aQ5AripZ4y8fbgt2 z!A)`OoLHXCemQaoE-wtoPWG@cqK;QYxqljBk7LTLf6BEk%pP>83z;`srq;Tzwm(;=tNqwotvIHI<5ebY zi@U0wvxdWQUw^a>Bv8UMgSz5ASjW`r|B$qH|3M)ckZ3)2-66w)ze@tv47TRIs3KE^ zcBOheT&PG&EDK2uPC?{$X>Xicc@{dNJW1`Ftq3i(Dn=K5Y>#9d%u-2-X*>4~fE=1? zhh#Ow?67-7+jga|G`2(PQ|$3hhI_~I9G~6;+f`q*@tZ==fUto|r-)RTy^&G&v(n%i zd$uz~5UGqz`5wx^DWEfPC2mY{>;75YKv& zQf8I=0Bs;`E#EVo{@2bz)&(-Kk5p37Z{I5#!x$`l_(WRM;fSxauEXBVw02>T*8XD{ zUeJU^nCK5%2wXRRRZO0DDR{+UJtf#-M-=qV7)Z%GjB#~(2YI?!`3ZLIK|2w#1lVKv zp!{!>9pB}Q0)r5g+okCJ=chxL?_WSz)kE)B0$*Nq@vb+0 z4#aY(X(?BvxN!!eJmT|SnTeG~B$Fc4^1*p!&5FB41Q!zt^jw+`@G4z&CNpDgGjjh* z7%uAU{C@ZmgwWCQ*&1~zNRZ%>SE#HJKD)=lbflhG@*>Zvi!+Uu#3@k%%*TuXcTBaE z9zRAh7rn3`KY!sd|6)*^5(bu5Ae)Moowt5UaUn{5JLdZG+)_`-YRPtv3*(d@ex=+@ z8Pimq|IOtGJ<8Yk5Mx=f6>DXD%ZpO$CX=~q;ZPdY6sZ0wZzP-ByeP>diCs|oz&;ph?KP4K+&$p7Vy|C_w=rJ8NtSOqDJ@3^tg?B6Z?__^L$i~J&b zE>t1|(|}nsrE5OF4&A(|NdNw(O8)arB?WG(MD`a?*g3Z@D#=o?h_}S8jB)4=h_fsG zG0yJtX%&1u9j7G>6bHLi-G6@-LB#9MCE|Pcl>kR`~=`n>L6OUf1#(bP7$z9{L&1>-Bs5?T= zylLM{UVShvzcKLFqMYA&uMmW0spVCEQ?HG}^Qk7!oJ~jeA;6Ryzrll~J^hg9BWu=i zN1#q_=4g`RLruU|2M`>D_1d9WP$${r1_pP7gvB}#yD6tX1cEo&fOPqw9drDruf}{i z4lgpuP6ym^FBrZDmU?2jV*n-t?pS=g@=1jMI!X%fdH!Y(%umNc%?O<*ba?iO!xC?h zrptAi$;=MP9kf$_I1~B*>`ZWhBjLUsi}~L=6aD{d&jeF4TKG|}Kb7O48;XKeSsu;a zI^hViQ=tOb>FC!jFB`_`C%scsIaarz48xm`u8*@su>e?sOPUNM==5$S=&+plzj;&t znY<~9DEfdIlL23BPMfi#2O&JaEJng6OKC2`VK`J{fUo{|hhu!BjZx{Y@tN5Z*k*;L zB^5S)iA>g!Br*^G%9WQtCbu0srVn1fkU;|6$bftA4s1v%SWjj`iCs8C+@o8JUkpUf zYPHwD=4P=za4qHTfN3L`OT~xAL2U!p5bo(<`Bi)Q*uYTtuiV1_SyS`Bl^MM4TvKTe zh-F!X-JF+Cn|OqZZS#a3SqoYw+Dg<-nLqAMzr{0cO$E*lN3miH2#)j|R`$ZUow;uw z<~kAw+Li|A{j@eXT*hogHJ#ZEXb!ryEN_2?fIm;c1H^Ne59W*e!-kh(AC2weSS|gt zN$%uYWQaR~fh@D^&pFq+H{$t)zm{RiVKspM{YVav|3nTuL+Vk}7orPg(wAYM_)RIm z0(vf|XA~|!K*Roc*>!!rix_QQHyQIiy`GM zuC2`X%&I&_!>u@)Z#>N`^g{{xKP~FwWlS30O7E)&1TVN|zafG#4#(ed zwJX`lrXve=!E6eQo1pGn`HY2keu^*aMDwZZ#ICr3T=vRcsTeTW=Ks`5B8Bp+-Fjo| zocW13v-^MAJMW+-*X`d+m)<*4rHMc&3P_14T>+IQ$fk>kLIk9DDT>lTdKW1of`TA5 zfJ8b7(p%_A4LuMDxoacar;EjK18pEI9o={3Pe~_!?{^kHmk_+bFf!O& z7ejk)KJez2;_lu1iTN^uT+MpIqgXlIQG$5&glmA^KKPAmp!Qy@OTKuLzGE2gFEQAq z;XgvhM*wYL)vSm8ySIx&B_e15fbTyB7!7{gcKEOroF8TXT{H6u0HI-qZ$XtBbK96E zE+Hn7COUy)MtlwDJ+Py4q{%$ev{Cl(lfA}jGDWYoUGGp2Y5oOUZ{c_3Z(wEE{K3j5 z96hPTi6Scq@kd(%r?mKj59FSCHus(64!73klqKTHe-*?Jv;c(v&dbIJSV-7kJB5tVTxrfT-9;{`QG9|H#9`DEX?5?(Kh*yX`93?0Bw^V z2s!HjZqQRxqm9uijoDcT2Q<$B(2}CXO$&7&YP`^NgXqNgB)nPi?3Z)A@m6#5uzP3c zUe9D(#HtQX8Tc62gmFs?Fm7>#y%Z0oB=zu!!pJb$Z+mBGQhUYC zBy-Njowa2!U|>8|!dU#M=LV4&iN*_wXpL(ceqxI$2{AFT2`Po|0x~uEYb0rvK9lwK z;#ai!`&CJIj}rVl;dUS|3htRey_d?cY6hF4pg!vg;sj!FJh?vF<04z;Ax_VK`d@`= z)2e8ErGHwlD8A1!ADb3`s6z32v{*=1K6I>~$+`wMDb@Z2SWuRBIuA*aUzGV=eqyb$ z+2!#zvY$e{KjMz0=0E~q_lTeyVbsrT9$U~Diwr~w^*Sp^&t^)J)+oyE7tpm5G5H0eZu>}hI~c%RqqB%5;68+r{(UN-q@XKo~a$u zEx_=HXQ0xLCA5NxFaj>Mt55K5VrT(gsDlQUx9i*Ur_Xqo%Q zjh3JMpstZe1hPXb%uhyU-dB!CJ|namrp1zBDJSw23E(Do>=ADSBIX)yViGeaE<1&z z$$zdD1EbPEy~6>-8Q|xBln$IGuNu0C<}QvBJ{$BFt2~C45J8OL94M?(7Q)i&^%NB-a@9x zLka-lvVs8MJxJHNV;~f;CX)(;bbvRO__+H-1>8G-6KQjCyuv1M0Hc04kt^W+Vbk16 z>1F!oApY_DjONC$Cu%E}Xb1Xxy@%C~{&=5liet5-lr;AOEeHjEq^8P46a8@-`G1|D zkc)Q#0tg^h%#>+sK1U4Teed6=TfkDx7=hVlI#6^co|IMi&d7hu@&j}{HAaVDIrmH=puN5sbg+o?X1$^$+ZN3$u5 zzrES^_e1%gMm57W=;FZ59a1eLK?>&`wEiV{h7C9wOi}*ScK?YxCC542bwdDgY2TY6 z7Fv0?EAB92ZzS|7&`vS{Y9B0BzUk4)P^{=!MD$;({0UVac#oJ}666QV$d3OagedtT zgeb^YH%51c%qdWT#YDkH;!@C3rgK{Adum}`(D2{e4K)=X^yWH~mv-Rn%4fVh_M*^~ zEZeUA*aSc25vaf)O)~R)g5Uf&!OwIC0i@;t2~XB~C#J1;U|v3R$ZdX(S{GxpC4slBO^3c=vrR&JgH{ML_FkCmgYYZvSNx9NGkw?!vZF=G!0RWcD+Y!?drne>&|5B z4v(J`i;IIKubmYc6U$0yYo-d|Wee$^Kh<}yUdc$BLL>ASRfhmea=}>5YGYO0e%OeOt#6 zEn8*~iw?~-nhP(4UXTJh8o!|AU=Ldp3!1NQV%sf1sj)HXDQ6JBl)#3^C2(k8@7Z@g z^GZ$}&whdJ=4N|ktJK1~LYtALkD7qCAMknl>?b?^+yz6Is9-!9QQn2cR zg`%+s+7VQD>S$509z`CxRbtlN6_{;$s=2KTZ&)sHi-77h$HRY>b=h5d?b`D-rI^0o z?!bQ;(C2CYp91>C8Q%jYe#=7hM9Ki&6!QiP3P%O*iil$m^+`@;_20G& z*$DVVTnO6_`~aLDS>8I~l;_;bY=&9hxlh?Sym51}_;j<3yL=3h@f-k3kNInxfkh9` z-`nQ7(5iF$kW&f{d@}Hg03n&_^Dy^SfAS(5eM~x_HS^zocrr=BJp}OczK(zD-*~3~ zk+SMJi47P_{6)aH3)s`ZE)M=TV0^s(_Rj;xre-R?1&o<52wn%e#3Kg03qiw<(2qxj zCd|Aaj%{oJ&er(uYdQ{eO}-?nr{_6$?rb9q!O|tfW4Dpi z)k|UQM)*Q`b(iz&;@Pvj1T^yUo`O86mbr)p#XfSP@JK#9H9?J!d9If)#eE#RK8XzI z@S9bzap9Ck^6NP#@R6w6}vpxDjm00%`1kN6F7r`q<1&ffcJ zpX%na&9$^jWLoC3>wRBW8j2qXpS>Ihb+rUD#LS|<-x8hQW?4dRBO{TBFR5Gkj2+Vp zE8`dXRyFoQ5&U^C=X^ROmnA{Xo^Q7#S>|hamhKJ zHQkOk!iCJqx}yqt@dBg-)t9rf*Dfo_CekdL4zD;*)|{qt0p1o1Wv(=}QLtW|Sy+Gt zJ#Sj}r54-5kbU#aL1u$$z={du5;an)2Ch?z(FgTz9l z({)7RIO~D8&~7}-0sRO^NRyJn*%a!m4?YxF@9bvbNN?CsT@{DAJt99XaC4VUs`M+z zvkLY{lu%S|w)}wRH%!EJ%w26X%QuY2rn7|mM;A9wXW?(YS24auxhM=N_UvOD3i^Z$ zgesgJr)L3?)=3wyu1|57)7e68ks!mXt2(+jtGbabzPGfoCnef1>j1l>{mh-v4G51} zZJMoe8l)58AWJeA@YavHHAGsz*VR>Q)w!*AH?tP*1uX_G5arYQgAn3eL8Pp=-0+XU z@-CF5(eBtdq(oyzJx)Wh?5Q06tt-3Cb`;+a8?8k?$jUHBPKO;AT!B4AY8*hrL0SUa zaL_UcIND|Jf3OW7bc{p$EB9#+KtJ7s*wl#Ms<5j-``_UrW9`Tp#x@*ELw+_K08aK_ zH5?*R4veCWZd%yjI{;7vAHMS_ph7+e`4g;o6a0FWOBQO0Lu^nxMmzFGmUAyG>Ci9s z%sC2RMOoV~BqY`UaGSU6aSDK$iL!sD{`A$hg7cF1mGv*rveKitqRmTdISLW^I`9E+ zSDOmRKCsG)1~8+wjb9%{_925`ZOe-Q&7wn?jW^f`E^$L2t_lk6M*@HByy&S#8863| z30$5KrV;%}-eAIjx3yACg$M^6+W{m*Wof?~mF8cHVwWFJX^>N0^0e3j{+jf(aOQL$ zOjT-gxqLo_swc+B3Vx|DEJEEp%KJ&pK)@YzOrAa*%AvR|F9b}(ICP;#;$+vowVQ!p z8$aa%-93@LTp1(ytJfGxp0~9>Y-|9hi0Xt>^w-<7OaQmYk?;gggH3RKKJ~$!^Kys+ zsT_(a)3NykQ#0fLjYB6o$|(ADHv$l@FlvH@bVaX&)lvc8aXhi0@nB>F&#_q1^GCBd zfs2rwf+~0n2lO$Ev7yVx=`xc4qEpmZON$@dF@4m9Ggjg9k#r#ONIFo-a%A=`GbzA) zi7Q#YTjSvLi}3v_OOzcDGk=?c($Sos9*lV?5ipO z{Q%5p4XB`JKV~)JE{+58Ghj2AXFr|Z2JcU8er!b0YTosH#$;=`r^OwBMFTyuZC(X3 zkqa17kl1?(vmD=thp()?Lxj)p&*@oYvs(0U9n~cMle!3?39Ukh4ke2sd$o^Ybt3n-|4T5+$m7Rw1j_#U4Zyt~`p_@9rCkxp){R0Zup+`R0{ z;yz%`@eX1BJn;r$zRFyPz^ZTd!AD=Z>#~t|1Um${gaF4)372dP4Afp5)b zfx~JK_?`!`Gbik$=GWBF55w~@dqjN8aH6~E^vkRLL{p5he6v=3lqrV^(V@N3O3!>K z&!PbZv|*-)IZE+|0(!C`n2sF>So>^@8v6`@5dc169hsQTBR|kGg4V8~dGF~P4 zed3E{EiJ+sx9MY=edZQUPgA2GTjzDMJ@>$GeP%rX=rt(0NZ51-66c)`9}9XBkUqkC zyC_uG{*FCnLjUw1L_a-PKIh0y2UF{|CMKh}U!A z?+Q7GPpr4)_iemQE!sh!7CjR@RhB%ljp;PYqel|6Kmme>>G&aXX}e~&+sY6cQCfhg zP+i)m;R&wSgMS{CFoI+4yhypD^AeE*_xJN*mqc^=+_rU8_lW}NE4ErB?HtFv3;Sw^ z5z&t(bt4uW=cBoJTT!h(8#NovxKYkKL<*J0&E<(|A5rPRDyyiN6_fEcxLsbi5aTJC zb58I9P-5FGm;xiwT-zVPqGiJl$fy#Xt3u}2K;^Bf($HHsXap6Lxs`7QHJ1$$QV}Z+ zmEsCUCvJzAd=3XQMZ_!%^J{T(Woj5#tP?%*yMw_GZ1lfMttz6XJ4I>sg=1;RP-@3R z>hjI=hU4?w`!(tC_G;uoPIgd}B)IJ$WoEwQfGuKGTglNYRB0eOyWBB!Tx~1;Ex*-3 z5$!`VRm}9dlCM&C`twy761Mr0%u`fgC-9&a&sOt0cX5B<4twj?z_Wh4@ceJ~77XJft#$5(_0$_IIfRNCU-G_PAvIgr7Wa$02HIp5*m=OP zN>6~)5M6bYvVFF%MYzgKV9>1hFp2y*lKPXU04Md}VzViQZ%q)S$eUfFE9O(Si88AqsK$F}_{@VCLn*P`A+Tdzx$K^fisS}W&FbJ$(?SQBDhZyl;uB zqZaihyo=;zR>RJD>F(>aZpHw=LeQ$`^w}O*`G#8WT0V&gY@J8GKiq9|(3ve7P9{@5 zjQT3evJ`PoFk0wf=0RZHC1*Bi{^D?gb zSf!jQPa<3#PQ2kF1wlLQ9idWGIwhpE-_@A2-$d>Iz$ znfW|ZG~_&8mnqye`=Z(juY|A6c|BwG3SWa;-O^Gh(*L<{&~jqYOChHY%Efff0O1U8 zg;4V5iRytle;BollYKueG5qv~e1t@8Eg^CK)mIm)zP>6ip0{)eqn@AV@pRwVVGc@< z%v>3?Yg?Bm&b9Hr80w7aar>~U{iI2WB*KY?QnQj{x@GB{a9a2^w}xC!LO~9_1`dck znF!p6y0xS0TmWoup?)jEUU%bd*G`}h-?wZ7tIDihdFU_rL-VYTNem8hJe!~dulI*^ z+a3zcNT2fJOp3}VLC?)Wf>wHnsE}K{o{9C>l4>7I zDulBwWN^Nz=FNo3%7nc%(TEy6@Tse&&V0!AB8#pweD->ah?y_m8=qRd-cvtz$#&Sk zwIm9Gi76QqZw-2@J+dTPg}J>XOLL#TJ&8z;o&LUAK_nrifA|vd!n{^B;i^d?nGocU zi7)Bh8?Z!DBjhLIy+4wPv{<9hiDzmv6}60NerG5^W{$CIj2&p#s(NM5Zst0JTjb}e zrrit6ee$dZlY1&xh%16m7vU-vu83L9t{E7Ook5V&w?rV{-&jOfj&HEHHEjT8S{nL3+Ae?Cb_udh zB&?qYe&zjN|hwmG*~)rImh zPIEsa(&j$R-Y%&wD;vf)rUFayH{Y<{to1^4w0lDMaZ>c{kPKA@!`?Y#1*3Z;23nvq zp|$ZjpIP6yp1bfap6qKu@wTn8VW}q$4Y{@EAN-vN2JsBy5PMwhFG?^qC*=$}hw!{h zaT`=^EG)BQ^=n%DUcNG$Xchzek+cQSwmmHai)#VP2l4$oRXZP7+aKH84t=86+Iq@i zpM@`lBd*{>_KM%bqorlfAx((G;$UizI8p%*r%bRck(aina>$YyBz1A5AiDZFFDlFG zax{@hkr2*~l{Dto(5?Q`XGFS~Smm zR|uW!ol_!hPWmBZeLCL|ro6#2@#=LbDdO+?sD7iPoF4_=;IHz4``T%5OtDAeT1H%q&nUFAve zsV~#`o)ir;#A#hsy)(N_&Wgs2u{w-w(+AgPTlxw3p5U)^P8J8%Kh7tOQ@X*3zh{0i zS9R6_9x=Uz;WlZXT%MecfxF&&1b_V@l-Kcxcs*tup+|o`u#g-y> zc$&Z9Id}4+I$bAZn@y`GBGm;Src9m${RX*N1fen!erm8ZY1k}D)vxDHCPFukO9828 z0_y~Q8VN76d_+5Cmmqgzw)JsuhBC!f&6ibXBd8$@z@hkZL(}9Bx zs|pWA_jl3XUVXUPZY%i=EsPFLQO5s*BwVkl@0}VqUmua#n9KpWz317!Kl^MAHJz2Y z*99T|TvSyzRye?2C3RaYY?ZuKrU*ZkJGo58OB95%oegN=I6$+2!$)wEhBs?|~#HjgcD&>|l z_ZHhHkgo7uP>EQ@+I+`WZX$8D)6Gp!$r)FHwfqAO&tYhdOoqH{$VAWT9Hcl5`t*YD zo9uvsEo90ZLM^%aTM|_8cGj(s*KID{VP)UFMy44qB#L=n^!MN&^BGA3Z-<*uj=?!? zJtT`~`!d2kU$RttCF;L~W)J7auUDJyxh*6!i&p9lm zo#+3c?j4^?<(06E78#jEp1!{#b$|YP{1D#-hTB0N!FP&-UgqjUrjwJB$;V_Ii`Vl; zkg}9|kA2^;*DQ8Ae|_C-4?mY$DqLiG`tRBonCynwoK+mT}@^} z@M40-jnTvrFWlPL@Oq93$Ro;ZYBQ$L0QEI0H##;v?I*M! z4)fZj6L4MYq?jJUpCIal*LXgW155k<@Osk;4v?P;E3Ty(uH5OIdfEv=&^wfCcDehe z*buvcBWaPap$KD6$vqnK0|+HYJ4VUOm(ZqVc4^t8!*{XgoRko^o55R&k-58bcP>gW zIpgBReTE3&nP{{-xJ9v!j-A~mkxGhC3t>@-itA4ao_$ne3o_7h?-_oq(Lm)A)aLa( zSfFsSq9~^2-B)M*TFx5vYvT!}ox0;FSK2gDz3%yIuiJ7wmm-Ayl03>ZIu#8-vY_+k z?)s^TCOiu)LWT4&m1*^2YXZ&lZ*2Us=36fUJ8%r6G!3nzcKsuFS*wCI+l(dQ59Ts` zp)38Q@)6zrE-gC-;4|7#J6I^j>pHq60acNJYO-8(65F1)Tyzy*-_k~ea5$qK-NvG0 zbm-7(YNB=*lDDNWn5uCIhGk*&P&BfCCw}K(ukTu0(Tuj}J39UPg9WV^Q+@ZR6enVngefqzS5q zGn^V!GR+z-*6qgD;UGEp$VC>x^WRzS*Q(g1WGA2*M5{iYPAnziw(6lXwyHLAs(N~w zxbkV9&Oio?IihRLY&A8?+mK3Yda+%H&6b-)mvPq2iS0I|*zunKTf0|+Ms$DR`&d_I z1(;<ztdx*|ne cs6*M-Lv?gHU(w#)Yx-H$IA0vnfF$()0y#=c3IG5A literal 150328 zcma&NWpLZv-o+bcCWo0DX67`|Ff*q~8fIpOhMAd}8m5M^4Kp({I`PeOo^#$0cjnGq z&3Nq5{##qJw6?Z>Ygt}YO-@vdl#_{tR9;k#@w=6cIRmMZjj_vjdna4I&voK5TpSFf z;!ftqF6L&W_I7-vnxF3y=BA`a2a{j&rhcD zU|=5E=i2f%gq&DzZrr`<;%bsg<0TL%-F>ClU%&yB$ARK;()R)M@v9K(@U-LTDA>#Fj~^b~D}$=DUr&>= zf6eSY0fAFZM}ih;U=9asNXO`1ip^LN6}n^k$hIQQvYtBwqsI}Xf=rOHJb1fl zhZp-Tkj(igoX#Kx3-07E`Ra{n4&_my!V)&CBsdWooo2irv5rs$=?nvC3#xzS(8>Mb z)v{Gie}GW?YEv5P8k|FaKXv0gib!L0hIC;g^={k}vP_PGWC$>B-*BiOM9&HV=Xg6p z9|5dQDus}Kpx2QNL`O_{DVWE0zzu>)l$!(vXAZYr zVV;Xvb&oN=^xPRec@Th2-B6pCLEyPS40>!Rpq~@FfczB;b==QZ!d#q8}cmtN@+ZjNW@t?Hg_k7z^E&{>$1UNcZ& z<3i0(D5%g>lQVCxwBHPI57RWxAr7S-(jBdk7n#FUvGsYT);Z_>5!rrgTwX!gQs61h zI#h)0=psCOIFAwUK}Km24bQDTH1X5FA&3IyKg$pKs{k#A?7#SF-fUs@mOc9pabttN z-7pUQB4O__e{Q#`-pg%J=)NqzhXQ@?eT?oM7Tqg!oNcorFS>8oqMWP{aCl2WIo{W7usO6@9YBSaL6H{8B?{nElqa; zn%}YtS3KWHcqYleD~B4;eoOB@e!_cIaU&(8I^FMjhUAuf?_rk@*tIx%~PZB^lWNqWMs(Y2%&B@#=8G-Qtj;SoXUsnB30 zO5bPtP(3Bzp}^XC%3p}`TRQskqpfW9Y>9FnUHAA@b~R4}9=sUt*~FT9C+vDmQ~gl1 zPLXv_A9PN08s_XAd_=4%Y?CABb@T^Y8f<-k~8i>1gWSs=RYS zpdNSWOvRtRt#{q0<$-Uan?qQ3RHd0TLWwUQ@b|`c&iI%GKi1=43Q{L)# z)U#dT3~1+XE$jIY9}8Wm$#;w#X0)wG35pFgL@hOt0-n0xLMZGu;uJg?Sk5iG74Du0 zyi_!TqFs#0@vHYWpAQE#3{BdO@?7?gxOaav0lmpRnprkllHg+@6+Zu0K{Vb zx00^S=DI0g-EtCl^o+L;mJ4eF;Z3)1(jRXFhkjyD zOTsqf#5~AdqR`G9L`?EPd^W8cv3lt>B!7<7mAuGt=GkrS6$9+Q~ z%~+}zbEEF){c}_WfzGvN?AIl*9uEOntM%#xoHf#T>iHbxR`fi`VtTUg9)aggMp9{{$P}pC=RB>XWBCgIm?b1 z=*2N+HF@rb-u9bao_B`?tVnxSA4qr`T-l@8A9~V$l2z1BknN);`G4W@ZrcRL^LRgE z2m@44epleKkF`x@JF;i`kqHkJNEV`TxYZw#z0$Yw@0s)pBL86$@A+wi)@l?Wf-8bZ z<#l;<++KLn-q@RqTbCNFxo|yr2NUYIFGddzJ^ce^niKgb(?pZ@;s+@{X`WH%S{>Y_ zI`Y#GoJ+o;KlUA?(vB0g&bhsfyEgFrvGO-u5U$dQyV=ECOS)JEJWzdE%TmN<%Mi#U zt;(l)d$CPZgk5{9B=(?JBX9GnrJ z_6KpUb-mpJ?j+Cg&YLX$l&jG<2>PRz?p5;Mp}qSny`t{llN>fBylFh=*fRj^l*P23 zKxokMVqeS2%=2#EkEjcGBzlHeZl-YVZF{05cXy$S{NFNrgYdYe+T}4xiKNPr}azlW7DD$30oyRfAn7_Yi67idxHGV zc%D^QgeS7dhS4cBmNCHJu?w*)jXB63j-ZWw}8)>gl z%!a%PMc*A!=VI)HCQOc-g29h!c|N(hD%DhTu_sjMhM#x_ZtSV+AyIxPVNXbNSbzRi zoo80|-B|pPiqTGfa+haa&qg$*s0g@sOyYa1y%V4zYv1GD%bhn@SVtKMZW7eUxyqZiE z=jyv&7fJJ`w%0I+py}HQT?BXS&QFVN&LnS5^sWi~P4h^=cxJDK0ofaql}DP_BUOtZ zf+nBBixX{?K9YsnZ@d(@mD@&dwhv}!#o3$H+ga=4JHgAgwaI?|+V{kxIC%M)ka<%o zcfGl&V=gmv$?#QfkZX3;k$pmk$SvFMQYe`>l)g>f@6y4lgJn&Q-l`YAt6U$ZmrX%$ zgX*97bPCFyjnj8KG<1wYvLhRn$}o_DhiyRc4+$iJ&Fj zgv}oj50P|Z-b&el=Un%GFF%->OZNBk)f6GG7n5K??9xElBtljko%r*6J#r8n=NHfS z;@``MXgnbhsk0OC>=oB#=Fcl?hR>oSQvMot;ei?TxRQ=+jLBTz)v=LdZ zd43{pefSW>>(HZ)V7>cb1mS_r9nHcjdgqdxF?}wc>ZIwXP@QeUwbsu|d4or-ru(`% z#BK@iPt{>x%=%3{3alvN?$0NF^G*TpUw&TXr3$?X9+ZLfyyOhtZl!_E1^ZXz0&{!p zxhGm4rE!XMGsU-b+INAU>d}j^z<_PT&f7YW{;_v|BM*Z3&!DVnXh|rEn@5>uw2Lp_>qIKkE(PaAgJ$0kqpmv5FTA5xFO|&^83Ka+H zM&0nfT~P>22Z8*1N$~O{uX(;Vq7^}}FkeeBP!kFT_A z-XqSnS7hwo{c$zjtF8U=dyAT4H+PVkLz}QEu$z8}DhAU?9RS|0y}a@vD%g=9 zl<_l?3Fef^j0?`g7p*C`5W~>;ZPB?M$m-qx48yhz)iL?&ZwONCoBEb3t?4K~*Wub9 zNtmrsS2eNX>KSi1wr0!thDcaKn#Bn%0rAnBn^&J8L!q!O@X)+^vVvlrLUR(E9gZq? zULkFBz0O-Hgyvk~ThtrOy*wpgNX@wwvW4n6jUa-8j zP%!bFpxL!^s>?bJy2#; zO0ENbwc4{8+89a1R5sf?9(}3W{{HLn=MoB4FOEL^75?%{Hy`fu?ukgAeh3Pe=C)Tv zTHH<=2XhbYPWeN|_?gIccWzVM;oR(N;%!t1?8I_@i06EQL*@?Es^yH*&$Kl&LE1;F zgeGmO^w6h9Ad^m@XL|L7o2#z2bMC8FZSbM(c{=fr<$f-%Of?v$>)S#ue{e%9k;jD4bhY9*~|Ev2a{6*I)MXS{sASuy~5@cfm%ZRybC}HaaY~%ds-I9Af97} zcapg4E0}jf$RbXI$DWTT3DDHF$Iq1r<|!VWEud^EgeqnRlOZ7h_stfm1{<{P)&Tuvv{=bnhxePfdynic zco>&HXgzpDwF_mj;mGbK&u;uTj?k}K zgutV~2Q4Q_OAiAkCO$cS(B(%vthR9LwWJ#=jT#}wS9%m5=^cn7BDl72%qc-qKdbL- zEJJ{Uqir|~lMQGHOx*dtOIago#_Z4Iffqp<_b>3w$ghTk8MQ%!W1<_M{3dm%d00$7 z2D=Zi2x4Q8xynw+NK#2gI1(>HMG15Mh@(^?VY~%JU4k8I$_7(_ve=Pof%dVIpzBc( zzLC3m%%OkgzQ5Btx@uwq!u?`E3S{GAPvXcsF=~`kUy!jw3M7u!J!+hjh;=hjAB)2U z*mo@FbiC{Vfs&VB3PQmB?)`)$i?b zQ0hOM0M@Z*g79Dzg^fr@zO&B$Tj|F>u=2szy1kcRoG)x@-MW$HafQZP!=5V zJ?X>%lbNyPeK8;|w*Fa!Y@BBB`S#tH4l8IUd>vT~7je(G~xsHUOv za<-DQ2l5280HXhP^t#7dGp^N9X%O{R{`@)8KQ(p4!AZPOXE|VxD_1K#DpcQMV>z*w z7k~a+^85g}FpG!dkR!-=oDl3Ht^x#;mlA07Z2*pc0tSB}sVY;%lCB7gNt)bp4Ai-% z(R`ZCp+(JGy&rnj7cd0Qjt^gZm}egJgvCR5>ejv@@wHR;HZ4l(nLUlY)|<=jy)}g6 zriXq|>$-f!9ju6rvcuY0Y&Uta-c2&srmEfOGY=Q7DJ*PL!Rpa$P* zuSa|d6CkpycrNSX_oOHDZ$+qf2x30h94TdPA`%UxztfT?O{tud3dNO6|#n?9mLy2<1aT7hc6b zkIy>YC;iKO1s0u+R-!s}u6B+InV8u9BwKeiYTjBHbzR24J1i?acl66CN~iNVXPtlBJT5sFTv?{zjfxq_;Tn&yVg~I)&I@I zf@*3#LEJ0tVK7nLX>DNTu@@&;`whwSrR}f%mc*AZe_r9}}w;l!_{DHzqu2;Yl( z=s0U--~7qFs0`ha)IoXWAMqKJg^A-{2~BVgfZg+-ao z-8!31({fzh5!9FoDgQ=idXU|yFdICWnCy-XMjKH6g$nYD-&RDTK^=S+p1VvwaTEU* zt#YQomhtX(*zI}uIK^#0LQyOWS>akdoFBtsL%QJA8$OR&tdXQ+-O{Y4z5H9fe^xom z59O@_s4^AS#U1XGqLk4by8BlAh++MeBSO9^&%e|hjz9_Vj;EGh4@9eEDnKkjJ&0z7 z1RGE(D-v7k2vtcYF7t#6slZDo*ikEnr-WSw1|#zpwq0_M<>s%>SN$tf*FHGZ6^gTi zh5l-WtapN1u^}u*CLcpwjKIxh{}09T{l2w-jeM*LZ{esi{M7Q%6gIQL?S8`{(IlBB zo!PK9d&OZw=HAv}>R`zw{{*VAA6oD9&m7)A_iEYQZLj-_4{PKL-=H%#VPLzv1YLk) zlEycuG_Dv%*wQd!JPY>pd@NvJ!}{vO3QFrQsN@DYGGJ6$Aezx4^*Twifm>#G!b3t# zEb@l_GY*C`W7{jWvD2or%K2xWL%}rSbyC;xFGC6X)AnQf4|Y>=KXHh6fCE6v?Y8MF zQ#Odo4Cc}VbWT^&vMmL1!a$vP6r@uyDX59s7s9iQ`j<2l=Us>JUQRYreI>K?TDgQ7 zT=KWxshF&eC>D*FMI1>;j0}3HDYGvX(y=gj{mso5@V~-M<6Gryb#?vTdZ)jW42g*A z_+Sj-av#3hRr6f!ZOv}bIN{053!=XJd(&xqr%VWU&nA0r;$?@RyN3FJQ(A){CpXQ8+lW$p(OeaO zCwR~#K6aOLGPcB2_Pnv!Rm7X(K8ZEDch8TVXJ?@7VxTPT=Wy}W(ByTl@%Rn6 z_jhyf&Bc#p`T*8H3UC@a`Jg2CxP{vb?j8iVZK*o<=)bxRnn0v8&^nGy5DwSey_=Xh zT zZrxB;wVv{dIp>_dvx{QqBQDw0KzSY{{cJJx3S6@Vk-Q-PSBi?5qPV#lP;t?3V zq(4l=p25E|PdD?s^4VHiVOsv6$v7A4d=q+`T@F_l!TUObKP$cYx^Rb8vimPw$!_-npobHgq z(7>0JzYa^6nyviWO|ijvb*}jQaA8!Ks2kcNpii~>1BNWtM5Bts56i|7)s?i9 zcvYtN&FJ{${7`Dl|9s*0b`SaF=_2w=jqSJD`6-e*k_~_A$USsVZPTvm*l{iYB zgGrn!x1V#1c8$ALcWc+jdn|XP+n&y^spa+d_^1YT_C`GLZ>(-!v7sk042I3XpV+_v zwfjRqa;AawWDf02sZ}1cY=*xQ+BQO-fW^khtlY*k&~iY@k~NgmQbPJ5%5yXg#6K=+WpQm=BAkDP^Mf=V#~MhBmRTp1|}$=mGq8 z@lc(q6ZC8o>SU(ddP9C9FJE+hSPV-yi;ZYCxaLw4#9k!AOUZJi+dWKYGx|$d<+hz` zn4D=yH7Fp-g<)e*tEH1q9ddkM1AV`^wb73LhJ`(S`Z9a_QVZfQV-Yfx?31l!`d6n_ zITm{c4*Ti@U67BTPRN-+h?R$fSeT}q{%Z-jXBDOFD~jE-cp?!Z^YmWPX@}zGjNSkWQieU-)djcxcYkDLa4`Is9%L+C!3A(WK>nSv_z)E|H^E-p zUvU@xQL5U%#}{AyvoqJ6pVlzAU+w&s3O?%AXNcl12?cKgqw6U5n!Y{pCO&Cy=xo-D zZ-OPIRr`-sqjpr+aqERv#Nzuxn825EO7;(3xr&D34@SYrF`7~$Vx*8}C3(hR@luKL zQo#2az?QwXXrF4%CkUyhprOhz39|i36PR;nbFKY#G}>@)TwWR4CCKCnnc4-8R`9TF zsh2!F1;ec|f>Rlu-jVJK!BdA2V5?23O;d_xtEWk3n3*G{CE*msAXkAF9q`(5+L))T z>l?Y)1nXUxvupGk)VF76Jj*kTG+6&_=B(1uw;|uvEj}=FZpa12bWg%mDRDNQkf{gXwkIO2k^G1zIa}dqV|v2IhM4^l26M?o7w|b?48mYaT)~<@ zahWpXXy4?8`a(Vlssyk(I%xemZgTafntos-;RvJ@efM zdl=EAe`%fiMSi+s%YmJe!lp;@JiQreF{>>u4lx3zbFmip~8)iLRlc)W+c`C2{OSg(DtyWhQyw$`+B(%pfW;4FJT zZ@maV9%H~Lo~$o4akl6#@nLYU>JR_%R>iBp@S1(iYkVMKU4FT^`+J6XXE0)fcjvtB zkmqLeC}aly3(c(X_fri!|64ekMB<~6rryjwC=qDGIUyP!1tkTE9*}3FyKzfpwnLQ# zuGW*d7sI0ci!w;~gG9NaE^|+;a|SvOQG-dqHc}ujPyYr2@KsmAS2xxzJP^B>K5#2X~q5~m<3`J_TOCpwo=MCng3U~WeZ}$5$%xH4t zTIDk(2tFm(3Ci&ObjdPaE*iniWZ5gqq-{xC66X0jyEhk!J7-LP{aRlAlMq%D<69o^ zF4Uj%2U5FDg6!-t&j>zzR3d@{;4DkjlH7Fk&zF zPv-uk;PBME^>;#`voBCg_s!}0Hl?oaa@`9T>xkmjJoM$k>5eXW2FF;aS+>bikDDb+ zgZaTZ>u%5WdT$3fpOlbkBVR|~d@b21(g2rT>7obp;yuWUo3Qw0;p9d+KY38G+~y;u zr$&=dZM{6NKCMXSSaJnW;;VfTe;{U{ z_j%4nm;icA`%cCuZ!e0r_QD#F0CM&5(5|*0v54RBm>4?r9NLYX3+iS-miHq%lI;$y zeLgy&FG@t>sR?)e(=VN<^b_H-Bbv_HTJF3%PULBry#{|sP^#4XBO~dL1~qOL2xwQiK!_1l1*xzx}Hj)q)tUk)3|yd zy+XKh*%f_uLFG>Dy{_`?eDW~Cy@XN+qe?LT@zefG{}u|cAZ*e;I@nN%_!TG{dDVhe z!H!m?#O6w5@ya+9Kt0$2pT5X4i{;kUXQq;L@;z#}0EdEKb23=;Yij8|3 zmwhHoM09b%>!-p8gIrYpzCCtx1`e*YE`)I**1A#XZsBRxMYwl6a0}%yzCFY02~p9G z?A(!2k3?&sdxREC!6-`-gO4@>KI)IkGi9MN%Dk|+|2J33!bdAp!)(1~GSNIH;cm;k zgh70PRbz4*MKTxzFN##iH$_cfK?2W+uj4MJvn(;fAY-kzcD5avQ~%r4vCQzW*x7K@ z+{@A39KFC1S#B6i*l#rwD9<-;dZwV~TpNsCBL=gN3ZeM+_w9pM+`I9NrQX-A6)2~X zA{`Z${jHnMo8G47wvQ3_k$*wudAg!BmNMbUmfeRuhal9#P`((WOj3FN?`k}Zgth~E z+5Y>(xM}AR&$-Dpm$O}}coZs+$PSki;`weA;&aktvIr5{>ThNF(MsW)YdOEB1pw~) z-_p#91-|##Z(jZCee&*o%GjuZ0h|9zT+qGQ*|>Oqf~C?RNoeD>C*N#X*gf1-bu(P$ z>qjmm{IKb9D8z+l`p6E;bx{O;UL~qdjZ=DLbyfBkNjIWx(-|aaEj}o^7-Co^zwsmx zt1p4p+IGnvU%~68K$Aa{-fFPMm4J{jrY>!Cco+UBIQttbiMr>aDrAtS`ReefNg(^1 z7Wi9mkl-ASTWP)w-wr?OsV0 zaSMO5#k@<~LSgzwphjfrVJ9l@&I>gMfW!5Wwr#((&%B6Z}dzCy)T}c0Yc_P$( z%A&R|Pb-aU5q}r)ePT9G5ZL1&t%W+5c^&F2+@@rshdmPdL`){A zPd72@Jb<3hKHAatAwWdRIC|2_bN~$OY3TUL!H0@g4yG=c&LfD8s`=LJfYJ&P&Wt%S zZnvqQ7t_Dmwv@d_{H@al2!LO6`GKcZ_jf0CaTI?Sy1I?h*ujh^@1f}iU3~Nr{IZUG&mvSo^YXD%W3E~V7a68e=?^nscXop0f)FI3F@a96m>Gi?C-fW$f zj<#WCKgU@9CvG-AtDT-&BZ&=GPWK3BZ#ojoMDwz>sK~`m98vd#E_>I8q1nFcfFJY$ zY=*ldpPv)i+D4m`>Q8-58Im{psC@x)A~-tWIDzCy#x`pueP{5y&g>Rj(m;maH?Odw z{69%72qZhLFkZ)EVzg~)WRwmzXd^NSJ}8HT)`xJwPHr5*g9yo-j9Tc75&dld!6(Hj_d*4{UnbZXYbRR4IIW zH0G54KRn*a&p<}m4<(UzzYTFxV-%+I42<1shY{?68O($`-&*XB?ORmA?f;v{L+({# zWst-hW@{&AhRrE1laG-QOJ2C%A6!Z@$ULT~I3puZ z&qx;-LN`hX39~zgh#3z(K>-eR-@uYz$_`E1^Ryf5W--duEfs-WB=kV>YFld)#LIS+FO1~io6~jWx(53xhAzdf%WH-bWgkpiH5aU`C091%e zbV+B_2*XV6#JoJ!YRyb|8TJ#&ml9|#pp**l9vGbk$0&mZJ}z7uJ6Q%5?E!)p?@o4- zwo-r^MnM|8cm*LVsSyffCNGO`$oYuI77u?XHdU$FApu#2_^981oQ2!D*-<9p)H?51 zQdKl41bKYjUY>CvFx(tC{l4ZentE^3|m;w%+-nCpLv zA$ftWG9gJKMN!`a19O^cxZe@HdVvZHahdPQdkdx#OBt^n8*qv(JCX3$3DOuvj)d$j zl98Ks4CF56XK1_OWGZs!KTbLZqWjGWV&9K#rNI5F;3+cWh^)oyWIyzl{pDZ=rkT(Y zkMbY_@#i=??uAI7AP2J|2I(FycF{#7I39_)$40@D5A?|VQ^r_0Yu3qp4&xC*k31Omewz$_;KM1FA2IR=YT(t zUe!L!eskwP!=CtC*FZKu;gS=Dt@4zg_eb}8Rj)eok@qk zMY=B4XBq0V=rEz_GW`>R{WR*#jf}RzOumvH2F;R^f*l+k01l`R%`{3%MFw92mcb%c z@?W*`Pqh;!jYZgDOJ{-tgittqN&P-$=;Ws22QBRnmgvXD@Twhu?+noZfp+!ZUHj;B z?tN1^T3Tt!0@?k96EM$H{dd5txoGIk|w48dcEhh#)SlBn>YpD`(L zxCcI$WQ@IdQc1q>N*~7WF|oXfa4qX&PZo#%0!v1XqWS;U{Xafjs@dUD|MN6n1}~jt zg@X_W{!U**J}C`5FM9D1RRblujXw(u|G<9an5GR<`3}M^VBg{}kWfLc3u(k@M@PB; z@Hw{XG3&cMN7q)v#s_M>TKqpJgVpGBM)_kbp8>$K!FfI&3R`qAVA&p^!_>Em$lzkb zd|mVcJ6KmP_q8G&wos3BQU7UOZNwqTr%F(j zJ0BhHj`bDdPyZ?6`M0Pzds*O$##?(D@oj$^TiJO6Z4VVvMO_JJ>AIq0@LygysdBh{P*5>W=np_ zo$dZ)E9>t;6D09p)7v4mCO^$q>33+hGfr62X?cb*89Dm#8Ro!IKp74t4pr(tfVJ=0 zlPbfrqW*j+UL!LNNmlL#FVd5)FFBeRWqH7mm=P%I<69h}U43=4pYC6+J%{a?%QnXixwd$2#!4HS>)afRp(rk znY@+W1073(V&S+z<~L3c zI{)ie!6jd_^WD|X(=-afwIgPaLZ&WvX2;W0JWc}Cl)Wx=5`(|Qi~i+>^>_FsEhK1= zgNz~4m+rbFeGpLE2qV;irPIH^O|M}Bw~s*3i6A^X43yH1=8|q}=eO78*u}$C?3)s> zJ&_}_{T*aFdD(hr%D8C0z1T4SsW@k%b;jq=w~A{15BrV&-hNeO_xb<)-lFMndCw}x zvH73bla2m0pREL|L|>#bG8hIyoFaZMx``&Y1wi`9Xa2jR2oXc^HNjOZ9Gn#=Ir4K$ zutdtEK!%KAo1DSbpc%uRoeCu-HtqUck4=y*V4btrueQ;EP{2h>@a0kT$Hr3DX-Qn& zoT;JIg36$yk}x*GNN~X)#ifPQCMLf+?FtW}nb<^QXkEB7oWKrw=)y16w$;{XxV0NE zi=dG!y1#-4-cd7NWnO+SS(kK6Ojmx3ZSGq7Ma0Bi!1v(Sas~d)+vA4HnA~39)9aO6 z!4e-ux-C^7504k!OS%>@{)J0A=i(RK&9sn?gl+AH8p@~S&trB5#a)h_#0Em#@vN1Z zxQ;;OC@*45o<)h>_s6#cT;0Ptdw;#$nRpON@_zw>Pa`5{P)oOgvwI z4PGYG2-z4mY=yh&?l8-~$CIDm4=f;Wznw>=WjQ%fEhX880m(JKM76-c1|UjO9++|E4mNLw#L|}Dvkzw$Q()SX zeo4q~8ID5Sf+t%-XHw;ES$o(ApGzK@F5Zn7g>^DkI1uM9xlma4r3D)6HN|93gpac; z({+XJzD$d|S{uVH`iIT$*gymUk?o4b4~+tnAqFKYkfV|iu}?k=afggwd#V=6>w^J= z#Yb2ABrrbLolX;0Q-iAB&)f54mQf}m!<@oJk^67m$14va=Dp>as&t zZU`9FDVaEhn&-fyuMlu^EwbC7{nb14@R&#w$8N{yb+^oYaq-lZg2A1e-3C1EY}OI8 zx0D(_WA2|=6W=ndy5Ywm_rx(l9#1vi*6Xav{1dcX5B8hyYsYviAfn7Q6h@T;{sA{q z?=NZzuvhU~cu16q#1iBc83H z;YA0stN6?$zE$bZl*OMVDsOpDie=Zi;VeJHMyP2wA)|IbK?uYF|JY3nq8kgN84%0; zfLPe0y>&xDd#3ASq1`l%g?MP^TKZ#c+N1S#UAabI-u?3V_#=*Eue~rAgzibl+vsz% zmiiIb96a#yk8$Yf2l;`jU%psdItLA=uMbwsZd%$xVSlFYjW9<-~$$x*b}qOY(X_uF!8NpjR= zrID*t=Y1@17ng5`7g=29_bHN6Nm_UQ!6=a;e40 zQDlaEm0K$OR+{6)Q2qmA%RI0yI>+9;?Wd!&UzGPdg1WoJ@P0Wf?V^+!(c2X`5YZ%NIH8n7} z^>}8J(l+Yn+IaVpPW00S(Xn!&PGO8WYEGIH*(R%_Pc_c4eJ_jUXz4bvdnoG&SHJAr zU=}Z=akxGp&MK>)iw%Q(`ZUwQchv>01~GQz^P*eP0dF#AXlDJi5fLiJBqNONKJc1V z@{{+J>1w-DEfHC4GDh=bml~O1sl20*=L{&VeiaTy`KeX)7AjzQ{&?sWZ!Aiu`O=aH zvv5}coqQ-Rd_uy7*;ynk9QupqbyIlU2eJ1;T~lgtE42SINfXsh7zOlA{}`fVMx3>x zm%s%4GMs7tRCDfRfKd@3pijFH+H!T2MAJ;feLT?h&9z{%u5>Px^S@1zO9V7=)qbwQ zOp_gIfN|gtK7Eg*rO=DVSC<`VOTB-TU-hYcSLn(Lh)0(qGdX*RpiL$5X@c^;FR$WPTh(`hIAp%)CPehDR=Yq~siu77 z1}n%|}0)VOSA1<{F0IuakME+H1E z9}^TSOateauTMB5#9>DvZPz^D*)4;7)b6C+_aR-bFsWz?ST6`uCF?^DB6Y%}3dWrQcz5s!dO*hcg9v^6`|&REOe|2(UNQRF#=nAPd;` zl*oS`k6H!yzq%6OmnP_Q%;^yjtQfLW@NxM5@M{7v`runTzgUESx6^-zy_(eDUG~s2sM79IpwE?fVKCn% zUH#!(;0~h@}Yrp%NK6R)>V_0tcYAWGY{{kFHJA@3HEQn!2%^ZuO9@ z5TH8KWZeVwlSPj3i)xxj(O~zI&*X{>)|GNjO#GS{tT-0SMiJ3Q5$W+q2T66rll)FX z8P8L{{{2qQgAO*u!+WH3vdbi)h%4h+;yOb$~>tc)Q-Kfv~`#2q0iOjk~0Q8 z>6%}J9@_$wU_&~tj4HfB77gZ;s6=6?CY3?2Hb?RjM^KD91r%Tm(!gfHb^>ipPDLCT zTSQ`3Tfbig9&UV0hjqLX1==djC00gLge`&p5OsPmyAUYdh;a7wWMFTI8;?$*2^hfl zt=+{-B;;o)K79{^c^Udk1|ONYON052FF_7=!)FapL`^ab`ng%-n){1Ry*M~;dU2m^5lhf)}(GySp2kf%x*CCh<$wyiZ^RuzgehP zI=)vp`x4y=2AM92nCeVFn7xm8ICs-{)#fQE_c}klpSNGdxnH_(;rfr*ZY?<6K3vSK zyYLF@fIKoGNthMovvpQ{^AECC3nwbd7xq;YgHfu)mOeI(&jOt5ulzh zGS;xBy}AHN5~>Zg%Mk6II^yR-we*jj+j|UnZ-p>j3i!oc$)@XEjt7|kmY@B&?W)hN@uy`vlz>kUJoz&03Pub1{0=1l6c7k5~&=X)YK7O%eWfR*&x>q5DI2&QJV` z=8=Xn(Hki)r{2PY)qSb?aOMBV(!eY_>keICz$pouo0}Wr7&C34=LD|VG!)G2EZzT6 z<^c3$2zjM>7Xa@ID#myEZ6K^OYQyEOgfn1a0y^}QxHapEFai$E6t+%QZyow3LW>(G zBl@+NjGUM1zW@loPJGsYx9G)dA9CC@9tHO+F-f4zI)VTGhvG=%G6KF%K+ik%TR-9H zm*jc}7wF+8zr)#F;=3J)K^E&B|65?$PU`FMnxZ{o-!}mbPM?fO3NAw` z*%X5Gzor{76@_&pn!4=eJ`qn|@R%l*u7j^83JNMFPF&f-IA|pq5&i*bo9koKrA=$g^18NS%Ynv^@{ipw(^(lamx(Z7B2C(mdL<>`AtLE3 z%1umSg?%BhtPOtLX2_@UMnuc4vhnm^CZWcv=`lhUJn${qLQ+H@&dWpCWf zIPHaJ2(pw~Az+aGG)Iz)9jcAfkDWn6MbVeO7nlDsOmrVX;4p|B0Nx}RW0?H1fqMB0 zEeNzEUds?1IT)J8B;}Qd@sS}PT4{)Rh$#?lnD2~{#;#@!<;ceD+)pJb@~sMTtxNL<0!pcy12|JZ7V!U=!{^NPR3>q%5$+;H) z^yCNh&T(*I%+vrmRH^it)@%vnLI)ncM}FUXZ1~oMGoKUZ?A0`b#b|6{^Pybb^V6yG z{DG1k?rHR4vu;X>KC!_JEYx_OF!S3Kld$!M&(fP7Lkp=`ZyRa**?BXk&jX+cr27_#kWjhW?SI`N;3o{<)nh2$@NL^s?ErWTsM9N zKlNSzDS%%=PS#-6MDM7K0{_q^8O2`T?LWbc>4(s{3y|FQrTsfn;S&GYSARndra|lf zEYTIh_hr)3)5>bY^J=>n=ZPy71`}=KU5`8xJB@RaTFX`A-&;EtsQ$ej|KGJdZH|ZM z&uKK5*Pob(Mqc_2XSRJ~osGMv+phWn!87nQ_-B_9nLA>YU)nH!xiEFswO%zHJL-AD z|Cok%sj7c*4t`V6uJ^O&xds2L!nFUT^*a8jnmz;G(c_BhzAnItCEnMbglsC*XeK15 zQe(cjW^Cki5IQt8TuiT1E8%i3KG&d27E?%z(4A)~iIU#Rz^Ed zOuvk%RYJO#;o38`_YfGa)~`J^v*We_Fm=1SwX@W`zMLJD$AL4{EIh18FJ7E9Wwu}U zHk7uX^mhH*jE}g9L&6P(SDIb@*bbj@TyoJ|Q<|Kl->0`A7l1C&>hs^z)rpp6;be^> zsVh4w#G05K%FZsnZ)89_$2=7#AIdv@3rRIMdhcwg2%hUpDCiS!!+t@$Cmwweoq)M+ zlXy~4e^Lkpk&)c3mj`XGnfW>WCO9e*)9dGf<})TIlZ7T+!Y+-_cV{TmuuwAA>9_b{ znBG9f7zDLq$@)Sk4LoR9^Yj)uXCj{H3F26f-ZB{}6MyHEjXc7JR5E(86)m4`DR;aI zeC`x&bY?<%Pl?`iy|raN+$D*BBjmcVu)nWndgUhj*ovlLq8Nj{f_%6?&4@Fnr0(l3 zyYeZ$v}nzAKraA?p(DWMn%ps<1_{(G!^0i;c%q{r+WNu1r<Hm`ATHMM&r~EV-4f$@|#20G5{4V%SZJ)jx#g2iYXaXKnUa zKG~aLNzygMBY0!zD-E{7gH1O5bsF^mzE4AiLDx(r{_-pB7wO)U*%^85g+#tLmu+LA zN;sOXwd1A+yq=aLdzUSxDHe~^Ot}enX{0kT55M874l*o&9El?|;Qebes-B3MBw7J< zInUM$6WNH}+qTsn%P20Vs))CxA$BOQ$9BR$8SG@amS0$^_HZ+3>Jge5f+Edw*Q5oo zzFNYJDSg9l@n5{5&Jr{cCr*mlp|O8!rWdvg#CiArM(QMCWn@dyuS$=phsC7|%zV%v z`PHYp{i?ya{g%Qsp1@r2BvfaA(N<{2w(F&Pz4zMB4gT3B|Adpw({#^dZBUGBXw;aw zFa`0KDfxTxqTr5%x0XhxHNlH>@Vte7eZf<)T>XA~8kO9^Xyytf0MDJs^Y!FG)=6n) zY)u?x{OQ5_PEfxk`Hg_7heIQ7aUwb#kv(^lU{(iYjU)Bz6rB@cq~a#x8w)5-TjCfdxtA2|I9=QMiVRgSnyj1AW{iLeNfP z;bf<)nZLOreWI_3zmtWGg+Iyv@NeN%6jlf@|3|C+tuI5vkrHA=21D-fnz(=7FX-rmLn z#g3o)BLZ2;|6k|rukFTSNDwlW(JP|EcMy6l>Z)ksB=dnKST!FxD)U0@2ea*N?AhO7 z0@b8C(PMmnq?U(MVH?UI^OQWo;dh7*r*au}!cWhMf9JmPtqo$u_Kt_v-c!mg*>SBJ zLft6Mm+0+?-=Om-XhJMeiu&!qWR$^no7EJQ_y4$uP;~gz6`qQ!z)lXbbNI6-X67a{ zJOezXxw_bYNG>vb@z3I!t z?0rAxHy_dO?+$_yp}|N6|M-!U%(SBC;{#J!eIlFJLF*TU?gxV*bIvA>*&>WIM(5$| z>bAld)02c)a8!2I3i2qjf?9%FnIbGQ zy6Z^ewjUE{m&2%I-$!JvwK#Z`W^@v4Pjamp+)_lq*{H><`(X5iD9_0;?e&S<;R-Cu zAv4PMQiQ%MA!{6&?(}o;aIe4bvTe4F;b)nAao+;JfnOa!0ic`@w9QOw9^*n^^X0X| zX$%^in>lj|U0$MZa_Z5?yCv`41JtXgMp&zUHBW)NHpORX_(U^kK45<|w88DR`)HUJ zce7gf!;x;z)4FcLN6}26Bef;za8s6``l{^hXY$o@5K8OjQ zl_x?~v#&B<*Sm;(#X><9T6v5$ZJg+SKL5%yKWa{B5@Uoy7xgt>B-hXM(N!k&xW?Ll z8;1U^nx$w}1tt1=lZ5>bu6r4ONCXF!eshuVcf=0@D(4Q|e{j&68_KzDdj=2GCRg}B zQmnkAe^_&=4-mdn4A|bo<+*;Wd9c{<|DNWdeFK{o5JtI;b4b%8fZpZ#jq%1^V|VFX z<XZ;-yOq%EXjkRDFc$RDL$Cyd{dqR&wK=Z zZB^Px@4OtHeIyhQPa3(uLno5&3j7e=NNR%H$vTTzcuuLtv^(MV!7z)|jh)=> zdg&ia`H9ENUHEAv+_7h&Ky*%$*nDo{;o9vO;eGL1vQ_oFKBM> z*f~i54A)-bHCh8}UM$0b2J&pg1VVg2uNI7!Knj_pqQKa1zQkd~qD-idxLX>&uY%Q6 zg2!>E+A9OsiFEiYf3VQ!O1HM{kJLP?mA!gD=PLEC?-dM;SW`uyc%|+(29PZ+R4aV- zkmo%8VX;}K)1B)!(o(9_>Fe}hSkk_)+Hmo0nYa&qs@-&9kyt4xR@cMz<1-G^7ISjk z*;snV1fmD z?1qa+;YCd2=RB4_IGSS|bk0v1$ssJe3AZikSB+4aV~cu93^|*inXjeQqA-SrZT=R} ziaRY|_K&kzUPf}pW-d0vVk7p;{3|?&xS9OXz3wY3>->@S(t?nH9g+K-F{J}LD(P(; zr|a4HJqC@fHI~2i^&ZO}LWVwhg6`kU+h6I-3?I(C9Pa7$ya=~j-JHwGo$!~GvS=<4 zvH;Ypj{pnKw=J(;y9A<$YOu=SPgyRYt_A6h?-AgQS2N25y@w0y5OSj?G5DNtOp;B z<&L?ViGX8&W{;oyXAT_>B8~^qp{E|8F#L;YOT*_Ie4e|DDLH@;NZ|Ty3-&+z$_#`m z!pX&}G-AMGF2om<4*ZVf$wDIEt|cCmAX5Cvv0~x8nYiPuvO_IDo5%BNXU20@f@Am* z(UFCkn%em)KazT9Y;aUEw2WqdEQ^0*jjh9Wef}NC)L+8y=gZd1{Zwa7$3AT6vc>HI zH5AP7s)?&`*7iVc+-c~O1%`1O zvMbAsClUnU*bX|lM+PKElbWrT3z!5)G`@wT7vvYNa56LJV?3;{}sU5Hh7Y*70F_d|i61 zR6YYue){>zrrGbTX>vXtdmnEIp3L^DL;Ok`_D=I!jiio z0%~GXruv{QL3C`=rAru9I&frGZ?1%$)ZVMfI7Wkoj-bNhL?h0!+pNDPR}h2PV|oYU9E?f`UkU2~PR%{_0~ z-Hl?{{d_*vrHekWQI0}x6hN|$a>uR0(7QPsD(l6W%{1xLzH=O`kN*QMlZ25GREe#h zUa6*^ZfmQrb?w@>0N=qB5pbBJ3QiG&q}nGDjpl1-?4>P?8KKjLr^|lixHfToR{TTem)-kstcS1rGbv zlpXl|IcR-;cxq}Qej`DKdAU)xUEGE<4D2XCfvn`wPk(SV?r`1xUk*BCMD!tdkgM55 z>~xIem50`@ZdFrM07)hW4qh(W?qsCT)xAMs*w$ki0u|wW&m9cWDoG1|cYjiDsU#Rd zOR<`z%;3M6L=zw~lwroL_){*4T6V7;cHpdm|B`>E^K!DG0~-bkb@pR^Q|vOHGD8*K zz4od-eDoJYyI|r0=PwBjSh?o+l-Yj0echoA4yAXrRWGhHFd7T8=wN>V>nHWQf|~x zm^INVso!;4Je)CY5#w2SMX7NizsFqgo;GY?lSM5q@yh;+d+~(Cg(<4l;KUHJm|T!t zn=-5#dD0$bHY(2~0)w(2SJ;*~VSTRwl{}JSOiUSzSwqeI0_PLPX)8Zx&RtsUfAfg% zwmZKw_^T>%%3?OOj(RE7u2ZiR#i+CQbYN@U)fj%U28H8m8?hTqMFre}EwWF$N{jtj zW6zN9%W=xg#}>RUy3wiKyDMwZ#X=LnuwRMjHjH51pP%UU+E)wwz}Y=Q(Wod|C^puc zj+2)ah4x;$7TUHFvzYGw9wv!b!6KS2BS%oYZHmDxxZgNsd~!~iH-AMwB)u z%1oO%qEsP`RHx~SOtOHmHm z9gkj|1sreG*pI~2at--_&N)n#-jIDjtc|Htm)DQ7u2E$kzRRh7HW`qn`1i-#sqpYW zW-)9z{X#j-Y$yTPXjZKB0i=PCpCHlZe`WK({Q5ObdLXLWDD_ICM>)-LR<$H5D#hpci)Q>U$^8USay~qZ}AZFRKxN^eV$6n0q%E>eINdvQc zlLq`*2NXK@3_*#S;x;-ivGCK*rG(~QN$q|TFJ(<93?pUJK~x3N4-?*QDV4#2yy_Sq zfi@zdsy#gfw6ajrZyLGg!?}()iN6k-e^U3&binjr{UGfVk+imjl6?Q1{a7xyKVn@; z+VPm|vfU=HR5fLH4tGgj7g>Q7CVeLr_>qHViWvsz5eED^4x}yYW(31sD*m4S!+J@7 zd}nw#w2oV4ls2;JwGaa+bTJvBT$P7Wh#FN5fO@~8Cfq_G?8W83%7c?hnZgFbHQHgy z?=?b1s^P8)<8a#bN|^;jrW0SMvN}1BPcQ`(DT~oBC-gsRqcG3YcWycv3_SgcZpkvK zS7fBlQp7c}5w3eEZZajVFvc6f$?&=qN1%G?@1MdfgLC7JJZ7WTE&55P3^VvAnGP8U z+}M?#|3r%3(W>JU$-zDJF_@nG!c4!}S{6;rv@6zChpU$ z#`4LF7b1Q4ebJZa+x^&R)ja<~!`|<;7Sk64KfJuxZcHIw?oapn&-aI0Q{j7GPQ(bf zNrT5gr^Z}67DvHq1`so;h*y8~SWFBbuV{vOhG8+*5Ggd#q~c6#n{JUB@%eRz~&MSJMkP}e^iRo36}GS6W`5_B?nzX8f)VpxFI5t80x zEJlH+^M41I7ks7ja93SARQfCH=TP_BDXx?bo}}T?$f@OJPgM64+V;_{r>`N{_;%ZF zKTY5A`t8rh85FD@=s;YIS(hpi`u` z@an3hJk{9sd^X&9LQLIo{N>n*gpAe_Fe))qxcVBQEMG|*YtS!nQ>QEBf1zLO3{&!O zBA##`=y{BPKAm=R*wgDtec9f=2ETNv0oo0=a_~pGm9`z;YU3+mE2aG6mpD6~&i)*V zUl}2d%hn=VrB}@}uWa7UhTk2gx$&`PE<|Q47N1C%tAO?+@rBtXXuR3=XwIJOzAL`| zlYTLQ3|1hqY&-;{zfN6HI<{;`AY|^5nUS6MRW&&e78d|(f09LoPo;5%0bHx9r=}T{*uwX5O zZa{=5`yp_Q+iW$j_VQ;&V^Rsw)tGlvN3(edlzI8yPa{SBF!jG5y@)&uAU#Tb_?u+c z*0Hcwl$G`uMV_<_bG)%&iBC1~`k$_*GMsPyg`qE_V{!2;>d*kGbY7PApum@J28t{a z!J8Va|3sN*olPvY`eqmzXUcRGG2SUbBdCJ|Ya1GL;hd@AGT4J4nS0o#-;l62eE5H7 zDZj_@Kx#^Ud>_U`M@4m*j9UL^7z2rNdw!%Qdda#nV@XCK4{6lvb^L1%qCw^?MF%j} zZLO1JKO)iQ{aD=E5*pe`hhh7@RsxERaR-P$QgoT?%b)7vd5B_ZDIBz(1p* z{8SX&6>Z#*Zx>yQ>piSC{>sE55j(BR_TP^O0e}W;cHBpN4s`!@4#{9lH8CDK zKmGemNLTv%%F|nlghY*TTSzUz`z>FFaz|7!-4@d%CP<_h;~ljdq}9acZ>tG?auU!; zn&X}KTyM}La!g(zEFuyKi>SEC;-D}hdZy>CNw$^8`myr*yveuB95c2T_xmodm&2}Y zMO{RwZ)BSTZtEu^jNhEi_)cbri0qQ?&-m%q&-m<+Fp0AF3 z&eybw6TD@@Jab$y{t!@l*4UehC@|j00Mu9!4yRg3c=8tf`u&Pg&sj+xGS;P{fUaw; zWR_iLnAYrXump-khCYwi zBSTdjG?TD@B=Y-t|6LFeg}o6jw?FtSCvcZda0vzoAb~3 zex>fafI_8Aysg}4vY?&&+5TY*MUb+jMa!pf{VmexSBuDPPT^yq zl=)tnt=$DGD(jI%dizT`R9iSWLAcM|z5YEo$NoR3=>i4EYurB*a2piLiZ2yycq$0U zpN&Sp^StYwz7(l`$iUf?Gxxc+P3xiLqutiTJyW|(v_nmLeppA|Si~HzSemQ;s7x(~ zIY=X=EhWn^2(@srQE(PL$jQgnVBm248&Va4rA9lws`YJKYeEC;>-*!~j8{ZS&{m%@ zeI6YDH8+)g@MDfG)+>bjyf62qaC@o?%d&ABcHa86=n^43<9+7aTO(zzJroZfR^z`h za=24IdaX0`*Vt^^H#qstx(^a6uW*s11B5jFf!}pir$4!^E+=l>|z{6$ok1g)h_NJSXBC zn&{jrkTTp!=Bx>)wT)$Vo$1eWm>H$NZC*S~Ido@0489cE&aPF zv}+jOu0U((pAJ1daeIuB-+qRquHl*tH+=noK2TAK`KZcM(Fp($0cePKX@;KGWPH}K zjg~*olGEe|En+S5Petd|lzHBC*7sfdPm(a-Iy+gXeAV0;s*T36#Udok&ZFwoYV)|j zjaxaMT;JQoH{w!~qRZN+rck`f4X`keS{+^V60rI9`$guAEV!0n&*VKpMHQzbOKdEg zwKjq(89PBZocEhj0sH$j6M@3Lb@LYYNh+C>24`WiI(#-qv^Ry%f^-*mY(Hz4IFrN?UYN8FKH*@CyG_TaHk$jSKB z+g;uY?HC2zlPtFz_`7LDj?=$Dwm|S{qe(fj?|y-1IRScZEE#fXhL>}U2AWus@8 z&oM6T(OQJ<#6jUAIZ~v1HQ<==1F^$hPQV@I9u>RtG>p3A`y=b-QRja5ll}}^3}o2X&?6}5 zcdBr_L+*Z~ojmQa!rJ~Oqx+C8@dWW3J3TIfr%&WNd=t<1uX`#5@XDEAy|9J={z2#i zOcWmor;YKSY`(PA*+|AX*nz{J`Pk!?Ee}OHr;{X_01W44=}iu&FG-j8|IbjTRQ?AH?<}Mp>C!^{NZf$w|yfw1_jaCZ&!+J zAjQK^Yi;e^pqb{I#10)LZ#e$2E`|E+AGV%C*Y{Ihl<45ss$$Y3Izy5Ux*Q+MQj()5 zeZFhB&np|_Qp*+5`$ZsdhD(0Kb4s#Q=}nv%YTVsy0{9V2kEi=G^FeWX}yI@!!bWBp}hI*qMGmr_Bxtf zj_u~g$QKYZnVnpy&Ld2PDZ`GzgNO6SjG896v6U*7D)=0Ix-ys$`8p0BwqKY*>vbUP z4=FV5zu>H6{Qq6yCjy6y(KFK8Oe`c7#w;s8HmUR%n??9EnhizevRa!y5Nw720;Q67rrbMUT-Lj`yZ;LroYUU>|xEEEGZoewn2O4}61ArUh=iWUgd*XWdbA&Vkei zP~;x9g&DAW`~Uz1X2SrWk^D`>$@qJFE7BK=khKWR{-ctQ6W%zc{{pq^=PgyYQ&aD{ z?Sx|mxrJ{=D5Az;o%d)6aG1g{-iRR#AU>_zjH3-H66;`WDhg^yji1Qq8_~CCk=H*l zi+|3FU*9=T1Z|f-=Dy~(ulR5NhZ~)FSxvIPc`Wu5-A$rQda+PbM}vss|AW^ldICU( z+#bE`fXVrq6k=*3ShnpzY)gpzEIa5Q2KYaeOxHBb9077XRW2I+NQlSbg&L6u>ZZApzofC@~Yc1dtzM0VPpn~ zyhe?`24gK&3;g~s7%AlYg!!M@h?2Cr=!d*b%>^+PrKLUr9C~T%a9WJ53QUB|!~n%U zu9y2`pL3V3)2_AOcZ;9mBiIUQV~*y@k;c^0%D$t$kyq%7k|!96Vo0WyiL-aGpKh$# zfy*ly9E{Q*vNA3qB+t_!Hz_2{bX6-W$62mX2~#^_IPsiQmA5F%H8S%2`NKU6v7RCE z0Hy*LMle}OHA z@x20%ll)hreetj=<0%oMhl)&+`eZ7SAT(pub_KN+GigaQan$`&bejd4ltN*)rzWi8 zzktpx2B$!t%Nq5lS`4ZU*2!S}Yy~kf?=6(5QuqB=WM`a-3X1TMFUjNRL1(}n*mB^k z#L4C5%obShnToNJNO%3t+d!3hNzZ@dQB|xoEzh8hhbHm`^X|I;?wY62*^l>LjrlBm z@7pAc)6A+$ca36r_i28uXO(e!GhZX{18*4yN@Z+qP5Mh~xz}Fh1U8crmFHeo4frDb zgn9n;w-{i46888$4h363FHg>b&I^XlQ|)Fj;OsMhuIJwM_X+HB0hK7X`rQe7)0Ay#2gvw56H$kKWN30HkdJB><_wAvZ`$T4R z-IfoarL3fS2^>~2$ zad~+pfbknqfxX7_s`%(G&^_LeDAL)VntPvdGESi8qZL*7Y0?i?`-`&sHPPoTNV zRgis_GhbU#0G0EBg7m6nRu$g1GIWpplZgq20ljm00s7Rd*Wq%v%N*gfo7{vdk z#yok0p#a+zGJtalX9Xn0Ko|9;v4P{~!FPVcxs>+xzvUbLsNIq3hnp4t*ib12aKK+K z;`u1&w^N?0t-R_tni5c%rf;6+!O`Xwp5;+IQDeDftdM7@_teC&NhJ7ir?|5J2aL&m z>3D<2eMy_w88Y%}G0ATodPl4HYN+M6Czs&y$7aPFK>W1cGWR4!%7fFQw)(pBO7RVGmYEs)>PPKBacrpsjwV$h)4&fU;b0EEfxJ*!?j8IQhZX))Q| z0IG!NZwX+p9$rO<>Mjz)I$32-W;8e!wdJ?saBYSO?dV%ARtJ3o3wQeaVnCk#7V zo!ym_VZR`R{2~g3R7R)3x)+^8g$3ClvJ|8b48~)Lf?tKV=N=MAwnFbw9R$oiR5Gs- zqJ_OW@Qq&g96L^d?~9)Dj4=+tqd^m3=B{i3cZGJy7lX;N&{;nIyn&`iMJsxP-0&2! zwg~cIEfwL1fz?3keTEJxB>G@>1N~*dRY;@+S{1F5tbs_YR|M=#*2vR@qz5I^r%aD8 zZHM2=v$u@+pC`qCbC)Iy96%jiWsI0Is-RW9in6Ai3w>MVy5d_bQk{eLmKG20a|_Fi z9J?+N^2J~cTDb4DT2#0t!IC)7%5_G4Y0{)oS}$bDQFi%8p=3gjKiOXZY#lybT^+^8 zSnMokAbY^e{evI-wu2=TG}NkyPt3hLU|c7WqOeoJ`{>PJoj==&c=~2g|BTP-vPA!7 z|7E3{KNo-6Rd4f6(pK~cOK6*OTh=MWY0cO~$=3IIFGQTn zV>@ZGR=3bx^I))2z3ijp><;|s&N|H`n&HNuuCFmh<{(Ya5F=NT5*5-?gNry*y72UN z8KCVWcDB3cTw{Wir$|Z~ra(&>YgFv)ud_R}olYP14;5}=VKGNYx&l^KmnqH>OZH8)oOQcg`Do4`t_e6ZYAUo!u7Q%PCI zx)(b+@g+}i;A4N1YnuXH=qHkL3}L6ZJRaI&!UkQh&EEdK;XE$=$=_I9yzQ);J;F~% zFAWcp+_^H6zd-szHr1fg^JnIo6|i7An1uv6k2DOu7;(WNXlW(r3HIy6SEe3H)E+Mo zw(r?bmYbs1$HMCZM+^@ILBBt@Z*xJr5y!n(U2{QS#U5>MfX1ue;mDU(?fW}rkmhAS zWO&CuW^SOHG5EWnbEI8{6TN;yI)O%#g|X9?)G*T=pfs2HOjlHoFiZ|af<;;uvZJJ5 zbc@S}!-0d7?B5+a{k~CHj9-5LNqFp||6`}_X=xYdriCxfr$Sk;7>v3+!YC%=NHSEt zO3X643rhqXg{jP1qMTZo9NM1g#i$on!{4arPA;aX=Q5CL*gWFDX8YZMO?WT^Wm~{W+mA zjZ6+2uo0rl)i(4e;EGZz83bKxfiM_rMGug2hG7_kpo>h7=qV)n-u!Nb5Uo@W8Rkae zqw5@Mi{mSjgnR;3Yn`@x6F2%2k=L4fE*^t|mLV@{VU6QdZ2Hj1S(Yt8f4z=4o{p(* zC)N|InNh9OT`3WxF2HNj;mWx^Df(A-Jus@U?Y2Rj%Zzu1rKNUx+`f0XKv; zsjFt*e6}`^1oHcJ*_7Au+1@-_!Io*E9?2BFq>A?tc7R?VzwQFw9=mQDJic%6(|8Ye zx0C5T7sNk*zN>0-$bg<&@>m5Kms~H7dpx7H#64PWZ0^ej8tGl|d6IaVjjOmWyT-V} zW0!ppF<6fvY^M+(1K~*Q{;ofm7y1l(!kb}qF?s^vwNp=mCwPCZxk#^5m1*ert3p%w z$m!m^8J|)qUjF`QE2*SN#ZE{f3~ZX^a=mW}t!jZwC^S24zB=Y+7W6saw3*;T3_U0! z^t|bF)ZnJdR3DkKKGiPjTwVuL>WVDyxjDaq6GmT!*`jKj5Ornzw0|g$j*J6H1n%TC zXdtggii?|uIOlMZ_S*wM9Tz_G>QjkDSBfHvCzgmGiodm1y@9vDhPk=O&Yb+wW4IBU zspCOc%~$k)j6ZFqh~MfT0@(RG+!=GGtv`D^N2hECnS0;>XND%HlTC)&&nK(HNr<+n zGR9mQyvV)kswoyJ)X{?@)X_;!3e?LYg2Ugv!$rqC8?){cp9seDrbQ~r-x1xO$Q#Q_ zb7kk}ci(R(#ZEL#yqtLOyPUZ6V@^VZ()$2o^!=h`juAzG;NB^0qw|JW`3gwaem;Vr z&4N+)cKXVi#8($TcL=Pnc3wd@CdB+63-vX>bG5nFlvbnC6h)o0_;c!dn-Ds$sk()N zniQKE^}Q&Je!$7m(lq6@s}I(9;DN~=;qKn&$JN16qac<(5Lz<}2fULkEy~Pr1uSaQAc;LQ%Q=}1(Fv@x! zHgpMzk!EEp+{o^(dtk)2Mm(!i1W^-+0^Giet66D%y#~cT103F_{uDUpPUzM$(>!w1 zKaSLfm_1W#YXQz~_wkc_rdRZPnmws=1k_w&-tT8buekfY%>ggLF9N2#Un;z)hkHbC z^=t z-gqEm5pyxdM0#v$Dtz-QxiAeO6Mz4cebyP(qxYk0FAkqFMcmNPTRsN&0Q>LNRdz&6 zKwefAhjm;kiB~7@`>Czx7WuSI)O6@BU~Ade`@3oLmDCYdQf5alSTV)IEq5@qCR`u^!RVR52s>c0;EV!=BxICdh|-xE>meoC|o7o^5H54H6jVu zndPQp>Nd{(%VtxQylI>t=USXhDykBHq#$1+XaKJySR475+%Yzks=Wj1Ry_>i-`g@U z8`F@*7dxSSZ^1qS-b|!B8iwicY32N4e}#%z^bsfGNNDju@`uaDT(x}kzr2!7?Pwm^ zuA!+eelnGxHEpdHRU>{t@O_1@N>NGbI{JSEgK1OhHLMmUMESKLX3 zq1%tfE#0YqhAJ#kNH+x$aXmMek0W`jLA+y`5j2NKzR2b84eRa4;6_EP75)aazAk|P z{v&^(0Z5JRz0SrefM!W1l?1+X9X&6bR=xS$>&E4{=9vBSiu)V21|7Y6wOnbp=X2cz z4HHdu3rwUg_oo9&=0733@!Vun6&@FgH`+D+cHNh(Br}~$G&8kMA8#Mhrv^XE_@kn@ zhi&@m*fVoU`)i{s5&7%CxB~cvJv{gJ`FpW{J>WBPiyxo*i1lz0D+R9ODFwO$B_v0# zDWuVrMlT*V*y;8ne`Xcj0ws=Ce(py)+YPKR>VhwSgZKxn!IY4c)ZZlU|AJTwRj||) z-a^#n>|_+hoTDBALtPUoCQF$dX^&*d=Jp;J_LCM6M6Ag`GQPVEJt`tuh;|T>uIv%< zoo3zap7>`m(#GYqW}HM>QW#atThZB!H;)FNw6gvReM5&q;pz=7az0K-s<3enKW)P>%lVaWv#Grm-Sb(X!=2T^LaUXb#(=?v zP8s{uT&2cZx-5?h?`Qf^w-8#&TD^>|{uFlXkf32-rgdTdmYf3_@4&2Q)Q3Su>4JSF zXi_8+%vhx&o`*ok>^6Ih%9|e?Nu|0J_j)Ulydz=z(8bHIqk}uHp^ojn$yMCu9*mxc zHxnV--2qqXz3dyH1_9G`Z>byku7LBy42!qlM8Kp|uAkq(EtkbcbCpN{To#~g_H)k3 zE+2UV7EZ1m!%G8TPP`Bo)zFh*=HvU@$PI(M3C>krSz@gs0!0K%S;lNuS;Pi4M%43j zeFb_XK){kB&$5m%_E{*Ym=1RTc3mG~#{dA?lF=O1_x3wHw*2E5SHl&$?d6h zEb4~uC|ktHhTYGigAjN+8Z6fT|-DdzCjQD^aCdcp+ZU&bR4$i(eo zi`$=-+Y$Ixn^}9%YgUDF?EUoN-3q?~BF?d;^>Y0%oqYL$Z}oKZOnve9e`wz6^&l?B zdhlj8(mFgyzFzSTi~ycD?SW#dWgCZ^EAusH@7z1zsxbMh@hk8oU3713KXAk@koN6* zdonaN=TelY66bMrFts~4dYC+CNFJBsPjbhR=psS6h_qDO;RI0(|W%9#a#TW zNQz0HL@&8J!Qbm@tEEQz#!%>Kv~6W(=%T^bs?jhiT8b2DB;*v@K?F}79pHVV-QaK6 zdC9^w(>X^mb0yI9!aw*u_!`{fyEC0|csPm`fL z$+7p!BUL_dJzPXe*{yxpIm6idA5|j~J`MHNvZsd~`r2fr zyCt2dSd=$3nq&m5BUE{I6cjlC0Pda{dRt<-yx;`r;95wWxsJiQCbIW^jYeL6uO7_LJ3*f``I8fV1% zJ|uNoeH4(IgtRaeoGKxAEqQ(?%F}e(f-7`7T%|&~`O%nE8cyX0fpPKj`-tYmgzH(| z5h&adddU%6O46c^N}!gui}f53Dh==pNot}o-Lq#d+vB&JDv5g9_e+)Hax{Jrzh19= z1_XTlV)zvQ#zb2$Ty+-pCe4;CO_ljfehQCu66)l``x6`|4Fs&B4c8qQc@YJ`ENfos z`b|Pw7mtlowWgQ{J9Z6QyngBnd&v4bpOMK%7%TCW?J3K$kY-V9kzU3y;pz$ZcpBMx zd9IEa23c%DPc04<7ZbLRw-qRdxBk3TV@;Rj5EIGIP)o-_HOs`@vo@ihl^5zZqyWRs zs|h5(J4bD*r5uK+Cw0pk*ar`2Rai|1v9cBWQ|iV})d$v}NT+?S2o-4V*qRo|3tEL{ zBsNQzG$sBn0-yd2=dS1F`Ed&C3*E}!9|P!+ti>vjC|0&r{40!lXq#7P4s?k z9HdhO&I!hKE(T84tEEy4Y>!#f|BwFsU5yV72;U>~Q#W zX#CVRP~pg-mc!Z>$?QW-210>)%kaoqyUv63w0W%a%{QW~vg1Z$^T`g;6#;=%T^ub%nvnVgcDvm}24>Fb1 z*-Q5d;8MTD&h0V&dyICvLc-OGiD!nrzjCg|)@JT2U*FzZ#_z_G z(rPZWH2u{?s}cvzoh&B-LB>na~cViCiJ7-Aluad_EXELp##5vT_1MdHf*kzpPz~w z<)Y7N?rcr>KC*J>40e8tr^!0miNFzYZfpJI_IB*wILl{58?}>JZnKZbud|#nC)#Y z%|o5*k(w=C64B6cZzAzXiM8XE#~LY0f&zXYN^k9D( zpADo*4#L^s{gkF@rZ1!WBOxs89WDXoM3YBw!&kLIgYOMrrE*t$S-MW@WAi8@HKhL3 zHC@N$)eP-TynLN`hRC#W%CRp@_IsR@GcRz$bnawdq+2|AS@w-$VpvglscH4TmORUp z5TCic3Dh-p3N*63B3rrU#C?osQZa;+HrHCCUu1ZSd;vNfbSCRc-| zfc?=IOl~G_9d#<3@l){zf#8Xy#}foJ7Y8bHIFy!05DQ&gyhf&`l~RY5_h7RvAH;-W z-21n1sx|-4xG;qk7hibeF()2S(8{Ee{}hSkRk_-_@!d)7_t3%c#YgE_BI$Dl^m9dl z<)pPwSr#&#ACXsM1DTXR#zlL}{Cx0I@N%-X@Jx=5CZ!21o!X(A5HmI)6);Ae#7Bti(llUctAt+tYE{m^UtAUSy zw%9^jd1;=>su%^|RLWO=VB!m3Cn3ku0C8RC+G9HGag)o?i)r2bvP>5XNt8J(!2SI|Ge3hyEsL+&4QLKy1Zp^uJy=IF-zU{WE=$9uZ&?HBK=u$QVF{jcoR zETDDjBNc(sLlHVJE1X+8wCRHJ6WZh{yesMQyV*MKo=%qe=PatOc30D@kd65&n{D?V z_Y<4rGcV4%^yo7rFCkY=$>o#}su%1`wx zHv}byv|C#x&)TY~<)7I>r&Jpv(whOA;(HP*tA%)Xegt$k*ZVo(;VjdbII+c4iFmQb zl)~OB9DW}#t$RM23ZKEP3&WI40^hVr3v3q?#mIVr+%bHGhEglV{-o4P=8W#iz*Az;KH4o!5D zC*`y8pH5kpJZqf0sH7X(OtZ5?Ug}iHXJ!SeQZ2dIYra3J(5#lb>|3=pedT;A!OHb4 zyPHY-)0{N_nh}{dEw7jCyY=Y!S4TZloWg$_SQ5-O%=$so+pC`oMHo$Ue0j z+iKMTHh0}L1bcw>n}mm4fO^KIm!?_^&Q)yXDZ$!ig2^=i|Bj4Ba1*V?Y zp>vo2oN)8s+?Aa8FS|~$p~rX~6Pu4n3brLUnD>dlM2qVRWTJ3g`PZ_#Acejb89AIk z(LW)H`C%9DnMOMZCDZ#U`_?KI9)+Ci!b?g>R4|7MJZf5AxL+PpXKi$K8O=Du4qR|U zX8PSvpmXjl#Jgtk+nhqnWTuVyqwPbe52%L?tfwA<(DCR;!ABaS#I2LG2X|iRZSkUt z1V~o>tfGn{FdH;@BgyHw(z0k3=fdcjFX$3y;F$UVp?sQB{gpnvWUZ|~zi;=-j|pxj z=gI+b%%nlpx&t{;eN&A)7QJTqaf(mxptrr7*#$4&AAOQ!{@=)Y@3a|o|x^w8rz*_0ITZ)>-0 zPX}9r+S2hxMwqyRO&zn)*2Ixs-cRk4gHtV0;$8DK)ho3ZmIX^&?b#;T;N0b#_T}e< zocS$f?K#t65^ZQ?*vrMmVCzu6T0a+W{VSIZ#(s{H-|eU)LXFzbA8DH(9=zI6VsI&f z1^hQ`5@LjUz21`yE0%&GR5Z^1_lqX3WgSG*_|+%Gk~x!ZxGWGg-z$R*Ri$+A$G)cM zTkZs(jam25UwCG6t2duf3&nG@rs7=hl>B&vYQWI)U+yRm$fvEzmQUIF-@Wf1701dO zsOQAIi`P|{yznmhwRf$__ug5|M{U{fPp_qf?|g6Ut!mx9Yh#3qFYXq3$mxt9<({GkthX=Em~j?dI;6>aQ-G8_%C4-w0@0 zWb^tJC+K{y_4A(K<*@26Ph4m-xkUu?OFM}^mAxi)7^ikCsYN8)?5UU0@r>CX$iv=s z4RYQNO<LNq>gJG|PZ=8PI0oohs8{3$N4 z${ApJ_dwSaGr%xq=B&jmY@6{1D?mdJ>EmFABgNk}2LztmBwqL0Bk8`u@iETeqi+i| z7H%tllowF9;0_ww(EpR)y6@$cGiCz+@6xPSTvxqSyuZJZZC6eACvl|QT5Zny(>n$% zJx-ds^P3}{2RHVe)ACo>`5hK6zcYS_e$MUzV}*=V{nFoEMzMR)&0z~gi`Q;@x%kl1 zR5+?TwM<(Bwa)rKY88rZzmbZ+vGs?Q&X~O*+22qvJjIM41vLfGf|`yJ_TN>QRnr;w zC>RuGoIs-IQxN$_@k-Xlt(`-fkgdS#j{Bs)7sQ`6B>3}5n7k&odI$uv0B+X7+fsf_V~o-ESNgJ6LhlMFol_Ea6qEgruR2i z)H*Q#&ojgRf72jkeXp$im}|hn!ow(2^}vSdkSml7Uw>fA z#5T%#Pbf!~Xx!;_dlYdJlcN!yRmKK&JS8m#uHR*=-*t#qs#mz~BlN-V_XUQ%E6|{_ zzn~hK8NrPPKY65G0G{cj8Wu&DzuQB<6G69K2-3r5!tp`$0&=V^R3QEsw+SWfjcK_I zvr;|w`GCnY66nwTBj{f}ss6i9@|bUZ+nZg%NbUudcOGJD?;T~`+rboipBzG?2@l3a z9|+%HytWXe0F4wv@!>B0xp$ST`h!x!!D84r2N*&Kq}~wmji##GPd{oKe-iqw~>bZ0;pn zw`+W>%pKF8d;<`NUc8K+HZUDDOUJ9f<4I z!|y-$WFl4})=)!RZ0X;;R9-rxW;b<4ltFCvK7&eM(@{5nUwW+bTvgHaRyKq1_@p3V zWTOk*IyO|<-yE=iYboVgyza94Oo!C6V+eOOn-FJq%KiqIUziElpdI~-#^T1d5oFbax{;#PL7HrP7O> zr)Cq1er5b5YWocBJKEcYNZJ}DzG?Wr;WM`18beh|uP*vkwyry2SeI!tF7VdhH&CR@ zI`(<}S(a}bwF}ZWZA`wup%oa~U@n}T(CaQ3P)>7pKB(Z_*c+v1`9jmOgacNdD|

=vw9@?ik*xtMJ#eA=)mETX-<{BItYO965ez%SgIe8&qYJc@RY4{a=^fdSc`{ zs>>w|7P*ys>zcw=LDEa^+ZJMv&h6_Zs)@;%vR-?kuW&W>>C|L~lal>pxtPG?KR;!D zY!z&sHkRvmmg25m(h@m* zkN9Kbg~NZr%N!s9E%=+g68OUYXU1?A%D0WPHKONhEIEtLhUp-FCxdx+A1iN^FW$Om zqVE^6dFDyG@7rmoi|!~zlZL0Wq2{zL$P4j1_Z5fUh{y&%C+b!r_411y`0|n_vi0yzTZ`pnH7^(HKhE`juWIWz zn_+L+j4lv zn{5JVGgdt3Sd82~-Irffi`BW7xF>23R{uIvP{?O; z=Gu+ryIXPd7lfNJ^Z;qa;t!VA$a|JpRY$FN3a0ZHP)&5{iHVxQB5jv}nLoxc%yYC` z#oYpe-9$kj29nd9eL`ymAr7K4SO9CuN2_ig!8RH0%UvY>}qo&B~@ zhyUaE`S45JvR~ z7mt0NK0Wi%`ahGSn1P(%&KstA#nn-2U+2#MUD)3e9OC~I$V?jiVR$S)>6rXZa`iS1 zQ>w7=<|jS7@99etW_2h_LEG9UuXm)w-!3py%YQ!1i!_=Qusk=cTxhpIz5jc8E^V%M z6s&)I2bgLF?3lsW1w5ud^$AF@^u>Q;`FkXFIVE_E$ z+n$h@jF2%h#tNnF?TcMnMX^D3+%#pOZQKX521sg;UJD(ZuU zUPakD+3LSCwS5s|Yv~kV>16y<_zTljlGdj_{9PZYKpchtEAsp~k^*O3y28bfK891* zZi9;d`BhkZ8t^OO$&8Pn-X&0XoX}LMgQg$#^F&g{#L+c;o8LK*$eqT>?~H~w-;{A* zy^}g6FymHHT|YVFBc}8A)0y;VaSym2LmogLJ~HK^g3z~iT0}!h9jqKki0NJO=C+N= zFY&HNM*AnIDdm|FWm0{jM8ZQd5>nuo6WVC8?1pX<9i$`uhb>)mn9N1@;cc9QP#=GF z)FVE-gLF_iL6;@#X#GWbI-U?DG~n}t2;!em+=x6pwZ{*=E*lYJAOE|EXE8{xgJW^| zu!l*FV-NbHv&x2SXDj4G)nmP|r8gKkKtLb;+CGicH-N+28Zadv9d8{Q2+@)Uc9MWvV4~;QO^G9F=65oq9K7J7rip zsNB-R)mXvLJdXFNElw_@v*ridizyp+}JQE9p4ENt}ix4|zQgWVq=quMz{ zqA#*oB)l%=fITP|K&@B5Lu>z$`VdEz{_wEe!IqGwlD6~pq7mW;Pme*;sj7eTQEE=btRm{TcmAvykKk^zT0{UU8b+4!;X3D|c&pMNRJIzna z2|Ipy{^~NqYwlv}%Z)#88N@cP?Ub9Y9SNYGxQN}FgK#@P@bXLmwVaQSG0#=^<@WCK zC%#~YF`JNGBlT&R$fvj{BMm23Qx1=o3w>+fx9;vpTnY)pJbzd5JnrW23~p>l>sQ*K zSmOFzgu8C#2J=?id(WM#iN+#N4?ol=x$!tpYM%~ae(jlB_?xTMC)6Q0Uh2mq#@Y8z zZ>+a_I=B3O_}d9_UP`9?V*keX#qffeqW0?(a;<;8H5g3IrP{302o`}?r5s8}yaW$3 zJ46mnnSYDv3P}&2d{9>1e|{$E{<-9?mA55qLW@SYoeBMS2F?@DfBdMYw+8(Z!}pv* zl=&t@fPC9!`QS~YB~?D>OXByak6cb*pZyEGRD`7@P| zmDlOP-t~SJ$o=YJwxFO<@9b7ClZY>*sksnNxvE>@?tlATZoaJJ7UzHP>a@FcZII8+ z!qgix9A!$gw~JLDW9M`?uD*2f(6S&id>w9y-XF6X(rx6-y^>nR@#?HXhS+-e*1XAu z#W{vH)9F}*RAtreG1+2n>zKCHz9thh;i@}))#qhgpz_atwZyn28#83pb8vWVD_xwq zQ%(Ev2dgB7ezPTTQ{}&0;TGlkfL6PoyJ`kkpb%@{?5o@NJv$fq#Ox_)i`L^?V4@_S zhecbbU8QeIsL;pUcBulkr=x3U@_x*HbYcH)FgaX6_pVxHX0M_ z2WOw3R8LaK=T1%?$DZr(AaeW}>!9QKCcnihp(E!N!#eqK{Y2rgqgg0|AJ<7lg%KPN zPqlKgnJ6JY&Fip%oDQ|aVy`0;<|+Kz9Yn7%lk3R1d1gM;r+G8BET==ZRv>dc6l~>C zq+V~u^EWmTMcJS|M0+;q0Fjez_QfHYjUGR4-_~BvhJmav_=b5XQ>{)=$&s@lpPdXZ z-k_4S_Nk49EG23&O#$cM)Q*s_p&EwSK~@)H`B9Wlkro%~59PxM!d^R=*t$bdr!_Tx z5twJQr9H?&U3+Z-sz?Qe*=Z~2r{R%S+rty#7t)yICp`qwq+LoxF0}y=ohnVpx|*~b z5A0qoO@Q8!Tjl`3ln=SoOE08@5}x$Tn#e830#u6t;tYV$msKna+9Bhz_6;j?3LNT0q>s&vOQsci3wM5w6bri)|XcFF!@ZvmGf~|UKvh4 z5K#E_Ei8e(a-LsA;Z-X>!Kzx4mEt0zFt+hDxSF2NyZc}N;qOlzuR8Fd$Op=eQhl*s zcG8=2oRI&0i2SmHzQ}uHkqNNui0moUIU@H|T;#1>`q`9|^ay|(zPhdbLtOda#?I-; zT5j_<0CzH;Gqqm_WQul|cmIp7l~__{qRGl-<+Esl+wN{Xy$Bo4yek44%?txd#m4>H zu=L{BT2w=8e(3iy#C`#mxMsew_D?%(2+-(*SxGq(fsf}*;~OQ~+Uv=_A_|%99_PGv z?!SDFnohGgBmBBTrtPjg{PBlK%i+rl+2)1kNjV)bhFHsCo`virKEQo_JwR8c&=-4U zj2kw}X9pbZegQ%ey9fZJv?$9x80k)dMv?Ra0!$9|&&Kf>sA*KxFiftyr`r~PzlKA{IF4-6ouZ(q z@f2Q=QlxlPwmYmi^Mb`;+3`g{+Y+{?w`1=!ZTUrjfvt94@}BvJHTec^`(p!-+?3!l zjQ4$L_pi3SWZX|h#_!dZeOEQ;ulk;8&@KB0Q{Fv=@27++rs|Ygc|*g+*Zlu{;1?$s z^DA5LS}KYzWfpfvB_PIP_~jAnZBd`m?tM?XH`=4((Wt&dF$KzHM%N>FuQ`X|Dqf$j0 z3ST%Gcxf=e46kb!<%7$APL9t zRK10RQqTx1{3O_FZV>bNSKMBGiCac` zXUU&9`-v}NGzB)RG{E%pMlSD^YB$Q2@?cj)QQ$i-N!5T*lF~mM`FzR|8U{@C)>>r% z)^(4!b)6Dvn5fb_u%9ySE_F-Zdoks{)?U)!E!=w04QJE*1h~bQ+Py@xA-lgmS<;j%MSjmuRNb#@Rdx1+Gjx50UpyVKi-f|GDfKsC1 zT6+s=3Br>J#w!wT*GjI~$dH@Skz$>rk-5CA;Lo;w_4fhyWhP_c$%Zin7WcqBw$cDu zB|x@c1|k)G7BnkPw3R~}1E{k=kX8=Rl^H3GJe*j=6Il5k!&KpLFM*-m0jkTBB*+?h z54^&iXxk^N0C0qFc8*?-v!8bxjts3f1oPme0h8j*&X#(yPINsG)b_vPO#&46MJ8iI z$%Zj-4!~SXsv(73viD+ru?)lt`YcEi2KW&FoIJnQKI#latSzmvq9qQXDgYGE2 zl%&P?RM$I7P8Q0{rXUGr-u!))+}!o^DOoy+^3*h-v^;KU;_1`vkp9O@+9{Ss+aVb@ z9H4%UG8%r3Ktr&$2~e!e+k4?GG#Q&wDb_hKp39r|+7O&KmT0?))H$$s*6J=TZ`^y~ z!w5L82DC1LUeu`bM-~|9E1OPP+!G3)aAZb9F0UxX zX_yXb>x%FOMF~nZ@J*U{yKaNY%>$?Z3B(ZBy-Sw(H12pu3Cd`wa>V;T$4hC%er^@- z?7Fn85G5#0Xqg)Vm=+zOx-p*xMLU7M853{ImU$IlN^%2`gf1;b?~l{WqO*yDA(HxF zKjS3ZsC1bIJ`LG;^6bb$ZPv(lUd?>Nn0{rT8gH5b)kx?LEb+>QYkvnK&fbhH*I zfCSXgED%raEpJy_pb^yF3n=v|1v;A&5Rai)=L*MnUbAGNb`+9rH?8F#ulDYN{gQ6CA}k&NIRT(Tps4z?MmuqD zXf=RyPZl)u?*iP(pJvwd?*(=+o1H6KarW!B05}i;GXvg3Khq|V#81@!JEF`riLpe; ziR&yVyQ9i2$L+6rf!kD7+TW^&%2mLQTfXzuR4On{QeWEC(Mta$6ujm>JbXg?qoF15 zW`uM!(LAz9o*3&Gm)1v&PmFb1#C&hCa!p&56?Gv9Po14av{jkbXxUGRP1}~bU2-Q( z_;t~=OWhJ1JY1*VPl2npTDCw_#`70GxD`)>_@)#lncJ(ZYC`O%M5jecw>Y;4CoXi; zo|kSV2f|#L-)mm03TYAIpL#wY^Kq+Y8YDDzX|l7;?@^7ty{5#pS82w@?ZXKr<%a~5 z4_ZbC5vBRg-@PSwI--DSJSNH=zI*2rd1|3I4t|%JL~5mZ=982!ZnL4zwq)=lglnO) z2kB+l7_DSad|RefjgLK6b{byFn?NDiV}|j4>4!DyHHn^Hp1^Q|x$?M^X)AH< zDHdLGb-a*sbuxKw<-)G;G_nfKtd<2Pd(kz@7B_uDBh#>)3hs@!YHE%y*Tz!72|~_x zV%F2hQco{ZZcBT=MNi;#Q0k^S#e05XMfQDUTJdE7uDynB@LeFinqSy_?U2ts4phdG z@2+rqUma&pohf((Fzip?4-KU`8F$Q-9Ho0;staA>iltq}AdpvvB?LFa5% zEQrG;V}hRIB6{r-{TFtPQwzvmN3UDjmy3Iib#R}AIx*5g99~BV{UDAh3GLZ9P4yGE zNiVAAuFqEyLJ#&d83QIX?_`NJwU{I!a*(L?G`-N%#aMEF_Y8hMiBAVB=LV;^Vi|i1+()-2|t@*};;m8y%Nn9+gBMe6I+^cHMY;@cj;OPR|3b zMF2^Em(oHTS)zE+9VT4{xQ+sc-WU8&1UTc|8#oQs@tcO4)u=cpdAhU+9-*e87L6b> z7C0*>?YqK%%WnC7DS1#+6Z9E~{W4IKiTsk}iogY*0#BC#rAe1|Z#ak16A{9<^S_p~ zRGw!{=WG0O%;$dn-jH*QC0XJ(;O~SS*=67?0M!NR(g=vs3Q+oW1%4@i>}OeO1VmX6 z6m1MB8@#htHi2k1c>pU>>n|lHH7fI;07?o#$qZOs04N0krMdz@c?qC21+44=N=ZOj z=8#FHTZGe3bWXHPB8MIGMfg(-0LN1Qw|%N?HcK+$T+;6Eme4HhQn0rCtW#5QE#K4S zt}Rf(-rdHW-oR;Hx};##C29S|?B4dsM=DT{3;;V*s39i{Yw`+LGNmH>!)8VH56>gD z+luqUpDwrLayu?*7fMNM7D|a*TRyU^QThHG;JgcP_H-M|_OK?KKf0(8{Zq{P%0nZ7 zv!`t2qYPm6IMgumCu?%pXcE8~25{y9R`T=1**9BqMc4t#AF`T-KP0U!P3>wbeth$E zxn~AYUI8et0F)}16y#q?SYH{o-lqTWZ9CT_`>5~d`OZ4~JN^3#`S&+Alj%0)j{x=# zu8_@#q3)OhqnmaQ*C6|T{;D^a%ky$8@0%D#cDm3nFuml4=)D77z}qRDNQ&v%;eK;J}A@LlRBu3t8jIaHs*LZ6wnSt(9D+A(KQwLvF_ z^e53|nw`!SUvbTY{bEWJ$E`Q7e5lqf35}R-uvpiyK;H=I=d_ibK-T8_l`wgmWIT&p z%B*Wn>P9s@iwqs-sJeq@e<#oF(fX{neM)NL)ue}@Yba5o+5BU*OUdH}Hy+n$SQ_)x zRf_z(LT+Q9v54fA-@M@dNhzFabCo!Xj4QxP>I>0Mh;vA%l`%2TD~dT9H}dRKk}oz9S~ju z%ilCXSFA1ol_a?ju|um68RjcCZr6tE+K7>XM+QqYmGy^kC_5Tr3+GJt6YAH0&a{qzhvD=Hcpt5g zuGn^(SJ?s_&zq4U4^~Vq3x9!E1O8~fAF0r6Hyqi%3^uCQL#vQZPv-jqp1Y7ElJjQ3 zwqN{ip;fjnP3Grvu;lx4075M}+b;({U@m{-%S@C(oW>i%ykH~5Z2%>`GhBgp$a2z_ zPao3~1yH{M6lo#X1>CFMkNi))5Mc_S!~v8=o8buVQ{b0_pPrV-UtlgX8vx4VV{%@D zEJbBYeqM#-wliGk{}06pHlo}+aQRDVaamzr$n^yQs6fHu>GQ@TC!Y{6|Kb;NQ?t(H z`)2iMscb0&@db)#s%#ko!OG58?7g0^*cLdluGnUV(;b@|xs4ey@z}c?jmf|U#RV>; zJU(!lF==u6iv=9Od`QltNf7c~FufF)wJdMRLW;%qHo7?*Y1E@5%9+ z)>c-4@MSPNL@s?y=riKwj499(gpv_2UA|B=bQn!OB#&hP^qS(fmdWCx<;h7-oM84o zne?$-XNQB~x~Ql=Kw*QfPyx_Tp^kpr-j9hdROm5AiA8$4inHyPV26AuquY?S9KifUmlHmp0t z!{z{R%OUG*70l_DN}SsX*@v73(yJ!9i<-da;D7? zQ6HJCdcXw$fksf0?0IFv3awHF^d@^K0Q?UCQdskY8QTo)nLj40Uf=<<3o1}lJU@6| zQGbM1@k@cZES>{^iU3d#V9Wu4dH`b#H<&#=VYR(!)F&N)z~(Ew-c9QuB!TwgQwDUA z{9bLh^lRy=#@yho3<=vW8an6-ub9n|j?@;HMY)~fj>(1GZl88TW!@eDD4DK0zzcS> zzH0lo{vKMz2fpABN(fNk0ry*9OLtNLE($A3wc!%QK+{~iGMS$$8#>bW7-*uu+708! zKPD%+Cj@?}HCFGp2D(=5e`pmrP!VgY05A;z$^$?v09YNFoV2Y^-3~Fs3N7U3YKD#s z+jw)x&&ZPp*BiV!qG!OAiZ^!XlmCs2>q}w!^jPoWU4f&T*Y864+CE%T2?K6v)f;*O zce#MiyLwIi5A{}R7`y$=S&ACv=flJYH}=!Y%L6I>1Ivx#5_hTbVAY|Qwq80gl#@NI zonxLUC3=w?{GQiAHNv9rqV0!CSQD#q+Nn2@*VE3uiBw8sdlRXccHx-US(S-+xi61l zCay2<^vuIPr&BY-eJi^k=Sw~wYjCb6Jy&HVmi0M>zr7o?%GTMs!qhEh+SK(aMwpcoBG_HiiSpJR z;l%vbo!Lq67Col#0s}5$QsnDY>g4mUQ=yZlU#Ai$&kte*%I)9!JNpT)qM9~!zD|Wq z>VKVzpL{xq;Vn0NOLp?RvU>2`@9gS!XyF&h_p}D#WjFV+jJk8{1?={6ni>(lXm8xoB@z${gW5p0_50#at1(- zI{!u-fjJ8(XG2cnj%H6Oq*CPv6E|rW0OiRkKpAwJCO#E(##-q}5-69V{7=dKPkH{> zu!?@R#$lIm%c6|T@lVMMD5JSQOxu-ZoJzhQbLqoxiaLVvv#&V9p848_!GXlNJAFGn z$NYek-Cnm3EQYW(&oF4wHbx(Vuuf)RBYDQh-7yn#r}`&K0`T}KLg&C@1S|FoLPP^l!s*Js)lM{WNXa=BoHy+)=^XA_vr~ud=CGN$~883Is0x|AOGWFb2oWNmv(7((9y_Gty$w=I#H17PP;)G6RcsCn4G}7 zv|lzB3Tw#reQrBhp>PfV&DYe{DQK+{$#HSB1;zBQNFg>E;`oe_IJYOT;5VjaGNIz-P%fbI}d2fg2L`N}u!zPaWD=+v@)H`};vc-6&?TIBKN$H_9e6=j}+& zS5yOpNo#SZ#WK=vI!Nu~`Uwjc+-W-||d^uqoad`J=!o>`a`sp1lvZ?)N z6g8Au-H3$?yicwErtBf=jO!Rc8>Pe3Zjw|-Q0LFlr)A!!HaK#XU539$O6YCh62nC};(lC?U?K{l~8DD1>oLNEr1ERaZ%wz0SeGq$k z-8VBe@AVD`a#=)c+D%{OeE02558yRa{-w>&LG`A0=-04*3*< zN$Km=0kVXW%4@evM2-Ch8DkP#08{bWZ+$GncGIdw*YYwQ) z|5os+Kz4TpKM7HR?g(TeB>Ll)6O8T( z9hjDx&e4@c2T4c9WEp>kLNg>b^OYS?Hw{`1cH_Z_L;8kp^@ zw)K-6V$&KAFC2H%G`5F9vm>X_{t^elyQIHPollK7G1%^=Olh*aXM8Bh6>eOK4#LBW zrZGcC!ULpbq#3og%)`%2io&CIx6H%WOpc4bAE7XXa`VaRJ+xh||h*wO2AZg7N~2R&Tn05Q(lf6XSJb0mDaMR>4xL5JYE7juhnZ!gAR zkn|)M??r?NXG-3IWuC#t&%;?DCZTv2B2o+jV#1EZkCNCpX>>UDNd+lq9xegNI){~P zCUp~$22G>_A~I%}RBM3cl}7eGJWdfJDl%)w1jpLXFRCA^3u_xc*vrh@%n(@B5^8Y% zO1{6B8H$6iYH9w5#Y<~tabS6yNTHW9!C`pAxub`$Mz&0FI9_({$N<(TqpxLGxQAqi z*s)@(n@L+lBr{}|pNQmzK!5L1KMa$Qp|KkY+C?0PHK(=R-^ZrSEjk_6FloC#-oq7c zHb@R4zySmu0&O+$R0Bsg`P&&S=+8YW9|U>VhJrI1d)nrA~6%Gxx*w21MI9U5}m!b^Qx)yHF4)A5`7xv(b8!} z+^NbY>o^khf^o4!l=A`5y9DP|nqUL4K=;w>T)fBJkrnJjp@qajq>4i5XRy##5|~Jp zh0xDpF_Hy%XhJ6aJsvX$*MJni#U~QcGIQ`75D)VJT=t&p5~E*dCqr&*=xI>o+@im*wit^KpD>G^L}O|fPB$_zp47y$7VxIt?DM$ z==Xq+VJP197wNNoPT-OyK@=MRIvS%$mEiQ;HUhb10t^!y_8A)Xho(+7Aih?!HLwp& z-3zG9Oxw=Z>hVzqSgLV8k>{|5bG0`h)xr3xe_dj0u2u_TAy$Al$i>U-P{F{O=9_3wq1r41)uzXSc6>TfC!8>(3dsL@5-qVBWO&K~%3Upn)WXq@J8*|rR zX}_&oqs-ktJUuk}Sa{cQ!9oAG9~|+=DpnwofVw}Tcd;b_39ILR=|#p=1VpV$h0eka zFhdtGibMfcj2BT8gyL-?+};roCeC&`ULfq)z+#&kq|3CM8~LRJBL0|WC-;!Tr(_?$ z(yvOAxH-B0W~leKt?146b+)12!U3*^mUX!y*}?&yhMx8GxBkLD-$-9c-&h%N8uE7< z&eieNo!Kxn<)B5ETc{j!i*A@t-7Wpm8BtVbabx{Pnf9L|LdY>gLH=Zb_`1ONO!p1P zAIXMVqBXw7w{LRRK6q~}rK^x|mDixKsNH!?Kd?{~+~XSfan;*FuTV*IJz;W4a8o$^ zslkPEA;Fcmt=66?%oj+_&rhq%JzDCxnLEo8KD$q}I*$>Ut7bv{ny=0auQe_1i$1%g zE9#xoEvaVtNuaPRT6IZR(>sT;b|_+c;=}aBXm9PM^#(h4SHGnu9%e##FuAoEnA?$d zhlsiigHAT@OFuiZ7VpJNKW%){+~EuSO19%|)>L$ZpOju?nY5m;kaINq>{lsk8%L_})98W|vV=QE2Luoh$` zto_#GSk#TKy4Rc8xZez(_BhbJFzcrSJ#B!?D|&vwphO zL9}T4iJJ$S#;S%pVZRQfwiEW26L#}Mp@Kclo_T*2YE1BKDY2fBx_u6#8DX~t`CG|K zK#^Xi17)}a{Pn#gjo1Sf9OQ2=P=E(eY9LVJ!3{uw1q4BWfU%EGA|C`BWO6WI7n?~c zM2HXsdkTB$LZ)c5PgETKi8wZr3n}<}Y4IX6h_k8l4pH$u^8Q(nSyShu&{?V6+0+Y| z@;QH1>Ok;pEm4yLm4oQ=Nsq%H&B0H@Y*$-JFNlI1nVe0e%S1F6MDiV8jF>*%3kg5o z>LisZz*Y$NpjBo~2i_$ar>m5k{dgt@{7Nzys|*ueK|dYpTi(RRa~l|&-&B9fWNaQ1 z|Hw1$tnqMj_Z6n`S_2IH0_KQlbqW(ov^s-nCt3~b6phQ&Dlm>O&jn;~jBhmiir3&y z75!@Ry-`zidc1P3t|+;7?4a6oa#mumnxE#jv*saiJQZ`|_Z5?|O3>Z&=RB_Gr_Jnw z$Yjv}z1F7sdOo(e7!K+_pWB>Khj96P$JFjMRIg;jMZUs`*QTt@#6`ZwiPoM$ndlc15(7Z}6fyE2 zq_y|Q6*Y0^c4r~)rww`aT)!4Q3cu|OKP-+wjkY*zUL7AJQ`BekyIm!aug@<()McYx0TR10T)}b+R~NwxU`qH*J=w^ za^uq4sc_erX@**H?_Vj<{6bTYkaQe8C6iP#4HGs$Gtg>~9{yOJNS8?3c2 zelTj%p|xM`WkP#iQ%tx**gynRjtop5Zq1_5r1*TUk__@fLm`fcO^`YS2ZZqqf>?giDKl6c&i*O}&% z(VupQcgx5R-_SjeR@2BJOC*zUOMbXC$XVQNU0lm)+_gC^4m3W5%s{j~hl@-YUq8xq zDba(YQUS7UG~QyBJVN@FPNu%XYhgOz*y2$9cr$5Z{)nAO?YMscsU(|b^0LD+kLd$a zSdVvDwN||5oR9RO^%d>p^M^=DWYNpL+PES7&$G~v{4^nyH53hmDfBb+8Q%*nIjyyxUOa4h_LwPiziu|p&XS#){c=fs(w!kItp)Eytc5q>d5A}*IoMeK!0ngBMUfm32Q&2tGjzQ* z_AD_+g!=Lf^ojt?>I&S731$^i%?_J-S1kma3L$@HJEqnQ;U(vMm=CEA@39$kBr{^I zGIE2CX<9JQSWr0H*f9cl6` zRx*w=8~+k}W=haVpBVV@uPo#6gsdr6@@(B|pz=A2)AfUXzCCZb0F4U`f}qvqGn;9t z9f8WdH6AMhE98rdRN*Trv#r-L;r6K5CaQ46kroRHQ4#E){n`KF+yA#y2K(QHIXid) zOB)ZgYNUkwD01NM_O&vlgtIDg@IDt-=zv(igV%78Jo#7VckgG0uW4||M&qA92KrV9 z{7DF@ga`jzXrMJ9J)Av^R6p5OFWywojh}cVFFN&#xKv9KRBJJF?=8t}9w-|Z$@4V$FL znsKY=jg?EP?rn;*=40SD@%GoD<}1AIk*K0OwwvCF?$_2uV0d9KyI8SL?YE_U1+^Au z)ubbK_r{Q=3Ja~MVqRM|wiNL; z&|h)Wh=>y|L&aLnKH9ZSPSeLp&Sq`tnxtyZtpw;BBViuh`U>RF)*Z`@alLiZCf?J_ zCvnlejAB;F%pKG~!S@h8__^J|6ij~Wb*Lcx%(IvP>4hb@O2VskYVa=k* zkWLuZCz=ew!mzSmUSdhnWOUvT+_rZW0v+b+7m86U(8U{li8zp$fqBUA5sboia1K`p zMoB;>3u8?{Co-TDo2{78kDIO7(SMq)bYPX4;|gI~J*1l*2-|TOHue)CAFszxfNQ}} zDiG+|Ob{zJHUz&vf3%ak34cMzfj~v(j+UNO;MwPVbPlJvwADhe`OWwdM(wQASyM8B z?)iJQ@h!2s2GA?aRP{@!^fOT7Fi?I|tl7LCClevn09Vd{?r)xAK+88zv7if^r}Exw zXBF<%Y9Y5zWohajPV;N~2V-sKebf%8g|x|UvG^vu4{#O9%HKOe9wJX8h0kR%H{+X$ z@Ow@8Z^Wa^x!7cxz((tNJ(FBe0|RO=3=}x0XLmTnf!YfPF>;|>6VR=UXwfFk%jldY zga{1GKxh}=gI5gWd*?`ehY-~k;06L5f^1~awmY9C*@TZE!Y?B;t$Vazll?z>2eFo7 z%t|pM*AB>*n}j!;1mB6-jZ%!-vmlSQ6Wn`RLu~?CZO4D$%;xx=r~Z)$CH>uc1v~L0 z<>cayV`(LNE#jfn5%Xvl$W%1wb~IJvfoPDINuI&UpJkUg=Q?EcQYgJ3;nuzm)6L+@4T!U+l9T99-KF>_ZN z4XWV)&1oY)P>7edTRUqwvVeo1H5fZ7IEIagV!{MXw|GfG4NGvnTgObu~lQ-vB$?oSbdyZeLPWp{IUA@ANBDY z>f@Ck5j9V{|9=-dgNghD8Oo^kUIA^@jQQH}qqzORpHV>iy&ov!9+;&xMwWgZm?h&J zm}O9vOGh9Q@XLh*Brbt1_|N_SL)MqTL$&{ZmnB)Ju1XS9Nh(DWl9|zln{Lf*)nch6 zZA?s=-B^-)i>558a8$0;tw_t2%#7`3k~o$MVV1}lkvW`UR^~bG?f3uxp6Bs$eCN!( zj2F)NoX>mv9H8i+j0TJWfiHvza}e+Hv;_!!CPY5(hiJB6W#7l<07ZxMJm;Q$;c5Me zk#UOWc@SM9d7fVA@<{yTao>}l#7|6wr^Qb!gbTz^jD?5v9*%LNT!)N7jNX5W?SB6` z{@6Ls*1g(Oq<S>(iwNaDN+KsW`TH#hfDJyv>o{hJSn%=SbGdULYQ|jXsOrNTWH8 zajKoe!{v$`Dgb@$bQBSKhTK;EjT~Fb`O9nn==_|n${C$S8$Z>3e!026_pEa|PS}5} z-tw&T^@S(M5Bq-i$leAVCztn~%W)b~40j2e9&Ih&TwNxx}21sfhgqH`j*9AO%L#b4qQ;o<3!J$ z^)@o`j%lPN)QqYeGvOTgzRB?iR?Mq3i*dO{N5RPF?}Ugd=oe+~Trt^#*^~^@U@t5I zOac)JqNn7Za~z{xZ-w-fK{N9oiOKHF;so%eMgE|eoY4x+4ag5%p)oEq<%f*sM??7`7b&_SGRy>r7ite)W zuTHWqB`RjiY$F*qFLw{y z3Hso3a}O{A?e+8uZF(4->Qh9Y&)zw(`dq9#y6+yWE62Y@gnkeW zYdJ&6xs4yvRU9Z5KB7!$-?gu?W3 zSPbY`g{+|xW&^}TNCM;Z0RPxhs8|=_=Y^w8_>k8!0loZ)YN!*YSun4Xl?yTXZCQkf z<*cTCO4oe@f^{j_Hi`c_?QaR#QaEge_U1$Jj$cQYZTO!vFOlL*ZQC$FzTXP1Qs$cH zll7QQNuUa**)ai3zEu^J4AW*aojbO%ocF4O4Dzo?$mY!AWbgu9E|ieT;oX|ir!3W2)imvPZcTC3XcMNWW;Pu`5N#EV!al8M7!U|ydANvse~4boA3_k^GY{8 z4V;lybaYU*-I48<2Vdehv``Gy#al)DKDU3PJ!wHUP(v`F%@Q0b5o(0FhCo>j;z1Q! zfZk$S#AUiLT+X!t6jjJ3YTQB~KOS<_pHeik(|}M{dR&`0tfWQ2kLRRFdS@%Ca|m`x zoC!F(s#$R=OcbHV%J)TqoPs82O=pE}6=kQ(wSTrCXJG9HT;*(uYBe>^2EbG!N2vro zP*#Ohz*?d8cy0$J6H=rBKJgGnqB5mU{sdGeLM8e@<#pPrMp4Z;=+{*_KT>DygLm{# z+et84ubRJ;kdQ%?^tr9~n&Fsl6U2@f(y;ExFj9@Z+Rk5ODP{b`Vh6O2mH4$+R*%Wf zP556NtQ4zBuXbjt+b_(3f+Nlg#|}1CH1%-@-#feOh!N2q?a@%MHxvxT3NP59%LP>I zwferH61m}W-lM_FE9Yy&m?2Rh=xpk@e{^O1dLs?nnWwm3OT(UO(!3qua)K`L4O3aB zGt@v5AG#-_Ne|Ctf&L=X7bPE&H$_srud1IQeCRhW)F4ljs!Y(w16=5lSaq7}YzF#@ z%a`LqGwuObtnsKWg)#&?;Gh{mLk+n+9?FrR1OPd_0Qxoq`zDPLV8G10$k`3=T0kgH z;n;|K{kDh>r?N=qa-KPh5N= z-ET8B!~nb^p>4ZN4>>L8ngQ9h$PB7*CYU3pk*kn-RN)yp7nIT}s|6+noUG~CN8&Jd z=Hmp;OSsg6@X1CU$cIEmpXc0^A z6^X1h!PhF5P-<1f9h}O5&VAZUNm9o9(et52a;_cVS%uW0|2+xK z6h}&iB4MsAK&e7@QiWMWybRSd^+AS2H6Mpffh=KWYp-e!PLSI4+;szJy^P`FNf=+j z8d50NPs18XdS@{gUgFrp(R(FcYhLrWEqhIR7R@r9-|qS575`z~*bcX1(k2!2B~ZKY zwLfjAXA^mGFV5;lJ`wayMS?!82XEEUoKNIJU(n@fE|iWg;iE-Rs~@CV*Ne-K%7u_L zgqaWxxU6eJe3yMj-qg|fhX%@XTalM0V0b2>30AJRBs3**o=bWcqBjC1H0_b|wstCZ z6GaWpiWoUhk5#f&^i0awmk2aC;REBL%P@1tMQBj0qEq?P0jFwmIJH<0^sGU4(1yI? zFkAZ0ygZv7ryNo@#6?#4Y>Ww0p4H1g2zP$yMPe&_ejT;-z@&G7?ypX-(1NS;ZTEeB z-~9e$ZSC3%mr^47n`#>aFlAI+w+UvSf;SeLcNY*3mGGpZwkWA%~zw@8WVRbFn{52+zOyPfTDbrWSZWZm6b{$mT zFun&x2ZFfa@IdU4A`9vHMV>nxrC=PXEE*Cese1I03Ksx_`J#enp$h}RaE`=b_BY8K zGZBsT84?Vny)1i8WoVr?&Vd7!fx1Tlx)PeUa(F~H zLtAOA!&d7Au+CV^{x+hs*0LYTb$P8iq6v|-0?+$CBDcWtOo_7UHVrJFj$=KLYRaF< ztN?!KJz1bsXXZ9rfk}g!N3smaNC)p`FAF+<8)H!h` zG?Q5D^(5VL$X-I5gF{=rdKhO26wz_SBuEtinq~s1aV2%XTG`bbX2wiS=0wA;c7$c9 zn&c}Qc*l3cu_ErtR>||y_~d4av$|<}GqSl5@`btcf$Xi+kQrcugl32oqOCDu zjDYW_ju4mrWDtH6lfmr({BCltY3hV7*$X3(pX&!aBDOa@_41Fo-&mgh{A^P#>I9&< zd1D>Qd5t^H6+P@TVXXXqYI!B+hQ@Yi!gXzlhP5iB!hn{m<(>H>?#3*wg0m z(S`jZqlB-cYFlJ$dHxZZ<56H0velcIm3tgT)yH$%9E!Gn^C@_pdzyT|Z=J8G{~dod zj&=AR$w?lW#*b_+Tdn>p*{%D0q63vMz^I<2hQ!BNO17&^Xq4>Lk7c)4OR&4 zEppvTJh}P(U>p-5X90-V3kw+4Ad9GWX5bbakWzyP13>#MK(L%C-=&rgjRQ1x zn??G~lxXyOcGC%{(I^2bT>OvSNUS=CHiuJ} zY!hmTG5F}%2jp}i33YDBddaJdLw5vz_-`38VX zGDpHd*hOBpU|VG2K|nL^G4uzTroGXeC?Y8M08WJn-ZMN{MS zfc%RPdKR6c#x3*1`#h3s7vg*{AgKz;fwl8+mET9S7C1I)ExOf;w3}dEmb19hk&&O6 zTr+G*mEaLPvVh4gmTHQh$ru1%RvGF7mMjGRIx?$)JHBt+dIA)*Qz+1x3|} z0@mu|bTdJpY6Nusrn2Hd=9^wYp%RtnRR4bg+iC%try||W7a79Z^UEXkif*bq zi<*$SxQ{j^lj;ZJhMmp>>hoLaHkB7L9htx+285N_f<$IXe zfA3cDzWu`4tibt#kutOSgZNiht;ykAPE;8MIxGPkiMnkfmv+iHjEhWbh>MHPMps@~^;L z-i*$%ztSxuqa0~Z8^1eXO3Rb_mgaZ|?7aE`Uy{tb{iSo{?d;B+V@cI?GQ<7yq^)X_ zJ-9lY{bv#C+1s&2bY9-LQ8ZiXy}QM8Pp4-?o2Lzn-0W$^LYh6XEYmqG(=65%9P3I; znE`8iOPLuq4 zN2N!6?hZ!(dwBRg@Qlz7Ajy>|cCqv$Xwy7)N7LiI?F>R`_EE%xDUaSza4)BevdThaqNaekwxbKD$CO1-v^9?E&{ zQ1aZ%f0Uj>b|5|VayeHiVD{mR{=Y$7J5+R!`fV7*=-y!KeR>;|oBRD5>8pORZ$_@i;jwI~LJ=w>1{C283hS)i7ETsfZu%yO9^#c90>3Y`a?K8@38Gt*2j;#n z3`BSK$XWiKieREh(X3#}C#JD{wu(5-l)zN7+_DfMO0;h1eS7~_WuKdzo69zbL{+M? zbCb5YYz*Y{;W^T@=@o*-H#sGqgM4VY=)@SuBfOwb>;zq?#HVS!E-e+Q%#WV5$vLOn zk&1|Fq}sA|8+70M{Kwh2iTiSSg`f=!%N=nOhD3I4n-4r^x!S}1HD8kh^BYqK8S&Aq z-n4%TjcYN9yyDK7=rp#cR$J!L#J1_xmSv?hvl+cw%98YDKE8An*$=Y1(>0GEb6=5#?!NC1)H)TOR6#y1F;T5}-(tGmgR|3IoIC?2_p&{14 zR^SRpKfXr_3>RhKS;S4EC~221i*biUl;hp~zzFoxVhr-c<&@u`=VBFl7kDE81*Uws z8v|%+k@y+kXm?u4dN@oXw3ljU0iJ?$hevX!gSP^}g8`t*1p9jcHVIF-ROSB@b7`&M zSLOT}*cF%g_L(eyx*AB~Lj^KJskaHszd&|#K0d+;4^@$!aZobVIUXv7gJy!haF7}3 z00*I1!~6rXz7QILanpfE657hC26Mm;bQ9AOTBlmZLKE!Q0PI{ll)rPGO;}bfIIg^@ zhuwFX@0P_ngLavBWoPAiNqlk(#ZKLXg5M>D&>J|&6x_ZU=aK|{g}HhF+9Rx_hM0qA z#I#8LG49R*8XiZAhjzeR>#1wqe$EtB3m%}Qv?4o`Icc%7%75Fzj~AYP*f&3A#8hv| z(B18GhBo@HNSc*(E$Y{SoepNRO!q$ZKDlbaiUG7A+^KI_(M*B(O|&{y-Xqy$?eKe2 zzc&Q*Xi)ue%PNPltX+1FL^|!ycNykT=htnHVAX+u0E=Ac1F|UwIIK9*Njs0Zo)@V2 zwNrH-laUvyfDe3w-mpWLF=OWqJ*HDGcBfg>{b$hq?^4#$1$QW`=z_Zx?u_HAK+=hx zG5znBZ6{sQ6dui*jJ_D_o{aG9k9c37rP;W&v9o{Xy0_qW#O~>73-@fpZ;2)MxP_NB zK1t_YKI4WTpXe3e1!eMvr2K`e3 zP7UHpC76SuHAo<=y-NC|qtn-i|uuySWA*BfJt#JzizN;3i>h2vtz6D?p= zn#zGqGKF+vI?v~x!cjh%dj}Gw0_+sXN2~&8g6wLtHc2;<+e8Bg@)S$}0o>NhP*ELl zD<=<@9|?E?A;BGFVy>c9b1V1-V%o=bYN{BZ?T01=xr+RDnofl-BAU)H=!MQSPr)vK zuBxo*)P@f31}8a=&{^PF`AH(m(Ph@sh^TQVvw=n|M;Af!;pPs;t~-ij@_Cy{N97@j z!tE`LTjPf<~voGIgj|hy4b|tQI-V}|CSxdJ&E7t( zoGlPxfCDc=zJB19G$3$3Gu2bATrUpOWBziHvki8&Cfu(QI9?JStP^%72)(3vS5W(Z z9(u1wY4FWEkb@t%T|%?Qxo}|aPe5Qba+(^V529$r7FUu2nQ!|>D`-KMQH5q8Lrg;l zhbKW3(?KJ#>W>y=MFG?{1A91?@Yf9H*(A<)xKy7ITO)8*c0@|?Cx`HJr1(^!y%c|0 z7$(JE6fD$_;;m=DhxJ=DS`{(12 zSKfGUO>7e)0nB7^pWk;&K*>ecvwG5QTi;!qGSzP{5brXcbw6J;+t+tJg`M`Sr%iayybF+tS;oldx^SEnTM;yVW9v6YX7}Nq;!NJ^(q5jIUwh7(FAOAA)>E$(GJ6?k(0I)e zCh0Es*G+SDtj88Fau$5<#U1X&TiM9Uw}#{c4XKJC)PwW2j#0cuNG==!1{cW60d&cE zFYm6B;yl+0$@abYG7sTYkj51Jt_O70l06Hd;7p*x3Fow`%W+DsfK89F*0td*eP8aY`A8Jl2PS%h(nQfh>qkn~Pd&Yy} z^#IaEC`YV1LFGG$Rr{%Y;sAOdL&$#)p?I(Q)k<;iY2~XKgkm&NBkrXuUu|k(|AkPCp zuo^*N?F?L{F-WRLx~5NwNJRl){t7(%2|SY6D!4Ko>ryRffJaQ2ToY_bwP5hFkdnod z8PY}mC_*ci~K3PHsSOPntEF2F`{ z^jv_Q^e@4tONJb#Pt}zvKCKX1ZGx?IVrgf?BaTe1A(mY$@PSLG5$3I=XRlyn8_@&r zP#oxicPZ}l_B)iw+koeCJo>jnyCbhUWIt6n1MHG`sqSlKUJZ1x^An>uoCht;xdo6T zxm`F4!3HAt;Y4Vp=7}QcG!I%kh;J_ylFQQ+K}UJevi(r`!;iG6@I4XUUka+eG3R`y zVtqepem)?pML!S83OeXmhs(l%a8l1k5?=nvpQJDM*h;dOd)x?l0-bPwA)rM?@t}F1 z7*Q)qh~Seaitai(7>OKL*V`BrTe$ z{_NBi!W(k;_{relv)=DbH}cLZ=69}$6*TO8>Ah+Ec!g!sh0qq!t)M$!U$ zTT4y?I`z-S>Y@&N1^@kE&kM)iQimAbSqA&^(AkPT;m}(I^D^*Z?$^%eYdcl3*$vK5 zD>ld8?a6v}WvDnk_$=k+&`%X-j)SEY9_LB~8;0mZGluG_csp~>2~&F#doF9b&e=^| zp8VbhD+01L{hy1?a>2}=QzeA;vQZocfNII+xb_;dEv}t`^Q3T2}IV$%kC^O_ekw$KjZI(MSL9QN!Jt%^C2uI&(6>PG@8r2FG!_mu` zk1uiD;pm(96eq)Fu7EJCg|U#%@s}A(@w0i3Z=|Zdg;1MVb)HJF{~I|7Gd*zm`XE$; z&|oG37dj2JiaG)oB%K4TF7(ojo3h_cSozoFg&qUDqJ@j0>>6D-%*Ja)({!FSx*c{p z&srTmK&Mza;qwQ4zPz<wcVgj;Ki_1!kW#1!$WOa38Y(kS%3lX*=RCh31?=l+9(6RkB_I(*;ViCuJ!p?Et?R*pRD}C58t`;$LQb~1 z;Ym^FfwDDC$c;Lhuzo%0U5hxw+(!Z=3eNpQj@volbx=ZcD&#!D6aGrzL`uTEl^u43 z*m#cZTwa9}LjlXLZbIXvwpWBy`La8nXv@}{1)#lm`v`)7-80C0WxOS`N=H(48*SEl`#u>t4^&nZu%) zx*f2{Ot%^qndl#EBJxJ_i-tz z$V-aJZBftMKyGIRuCqJBEql(DHv#WfE^=~rn3qwa!)|+)+hp|i>5Kk^^oEmmOUoal zT3o}aof$zPi<k-34kJ)ZmMAK!3+{>f)1M?*pt#O+@6x)EG(%ofzV64;8GSHc^wEDdbo9*Eh; zJ>j0`a-C-1h$-4yiCNHaI#KlS;c%$ECP$)(x(eN2Qr0XZtx?`QDtC1ghs|TYzr^u^ zU9AZH)dJ=gQDGgwLGQn{Uw1Vj^A7aV4;&Pue1gwU5|ryF{l89?(T9+K8h}lL1QHdE z8aEvXy$EIN0il-ZJ=EX5sJ zh`c9-uW3=tm9yM8fu#BPA5Fz^JNfjUV+xVZ@Zwo zn|TsS2^U%+aT|07lRn8hl0@gN)Y(n4XDW5GCv|Jpx-Mzu9q$d^cEo&Zysa@+y%6BX z7r96VoT%yr0N+)qtM5=i8%3ebia_~ri72M0Oi(~D2bgZ|+{|D#fq%%+Sc z=4pV9HQv)x`Kndg`)54ok)(Hl@__}`U0kq?8FWT^xT~XV=N(e8{7DMm^Dc=ckBsMg zI!en+TgaBwC=;-839c+2x&e2a0Hg%yuteqY4@LU62smtm|0np{Z4Ok_PBq}xQ#KQ$ z`FPAaI=@R?kk{g`iRW0rEwc$5s{JFBQax<2Ig4SV88?>mELpP6BEGZ>!_pLxPA39J z)_BY%XdQJY2WDb$B2y5hKqg?E!IXlwhH3{0fGzoDZZRVZ$7tSdzTRL=OMV$PUS}j> z>uHG>b=zPcFEQIh3%aZGBjlAG;uT%eQ^%{?mQxp)6T`%(R^if;ibgK+_oT6k4AndR zMb=Vp%OCt&#vPr?PiHDdi=oS9xYA$}y&A4nhFa*H#B2v`Nuur}ZAe7tpGk!(=0Oz} zPzB)&(^Jg!M88Uyp1sU6F|+IovrNJ)gGN+!B3-ANm)GjB1##{sS44x~tMO%?=fLk7 zwEO)N>Ce|;ui-W$)nUUv!p4{9!NpcAD?1NivVZqTkCQhnRH0%ms@2}OaBV+I&iTxX zJ$R#$eB;nl?_X>5Rv8!!{ObRDkFoyQjlT|Ata)1Dee%>V3r_9b{JH`s8XC+sf`AL6 zG0b>QxmzVoHZjcNGx}9|F0S*g6qegp+m3Z#w`-VK`r5wM*0lBBe*S&<^WOKmEB{{rXE`-uB`v~` z8j(b?phAfhJ1Ue!Nl2vJO{eUNr?^tH<0&hs*$EUcYT!)LyGm+?gD2)`$@?VU0)E%# z;?S?fCC;>$4em=(oyvytBD3?5=NSiDUc(cI5=wbmpSg2c7PsYVY`SN8cgX08Z110i zUt;`^rm{CIruYpfcJGVPYI@elu6FB}I~L25XjeT0-bpWT6FV3H&=8+UnHV05QObovZp0e5qz6r%@_I!u#UL8N&XW97{I)6=k&-`=xiN4YDC!^SZ#NU%yX%=Kb~J zk6EghQ9>JZ21{jA-=vTlH4ww9&uhlywP1pqF~Ry1&5eyVKM$X|$EZBI>hnb0JDuOe z+`*oJa^VyG!JZj|J@W>8ECze*279It_Ux+e3a;<6uj;bo@~RkkDrp*t1dp!}PqGSP zbbMotqOqfr^m|98(GeYgu0|1w?g=JYM&mN?Qno00LNi>zWv6Jd59I7$t8~@VbtzT4 zyRdGy5^Yi0W|Ka4sQpB#)9!HoRj6e6ao$Vk$*1s*tRD9Z>C z7U^+`NeXM2U@C;FyccrqO{BUj0lLscoxMcYFnhAnL>HQ*E2-6aigh`#ZnaY9p=CqM zHCVP{*JNc*if$KBX_PNY0Yj@$^ougOs=;^^07J$B`KW;fw@)H43h*JADMw~&mGk46 zdOn0?Y<@KdoXZuhq*a>2SM_8k;j7bS2jHvvGNqmxw`%}ds>E3nh-f-z0TZyuM?L*m zF^Zy9j!LZ?bF%Q7TKlLKx&_nbF+&XUt!g0$n0BfP3WsTFtx#nqfwWiYdU!yP8;>PR z1URKDHf~iswz8U&Y$E&`Ae=j0D5};NQFR8g0JvCB_DxUC-9LbAP;%`Eq~BngB~xgY zUsi<*ax@#J&?28w1?44wfPw?^DYYo4UH;n`!SR5MylarE0^Mw#P{|ND_{l;wi ztNgiESsFNi`dP6WiD0@idRE-RL~M%0|Cj2V;}^JZBG-|gjd2|wLpw@=vOmVS4?iLI zjY~d3?{OUkOmxCUL>Ld;4-oUWAC!?#q3@6GhCfl1=Z+B|^e55=S;a?m`5^n>xpM7> zsBaMUKu_W44BwTnwlBK0wEEc6zYVwleD2uXlh<#2X-2zBhUwfNfs*ehVs1{jkv%gq zZtYCJ<&89+2o)-ZD=MF7TwXNu(2NT{S#S5f{g{5Z z=UV#fzQXa-$zx`nqOM^uvs=)=s(wr4)pXqZ{*(2!kyo$dYWfdo8`mGio@#&Yz$q;^ zAAgaR8&(p;ypQYj`7{g)Am^$x*^8~-$ugDK3%hR&?vo|Rf2l@sG#lWyJHL`RFOHw!n?0o9AE#@AV9mvRf``Msk|4Q1uM)FeP zv+`d?kLNTv5KC#rsO<*YwzHJR@7tSWWiU(&`i(o2<~o{Qg)f?0t?TvLG2mqj6xEOk zIIAl1Vw@EXXH`qS)k-c$Wv^t8Ss~{a4(Akn-4NReU)RT$!`F+X-oc%eOGUC@b z=l|;4l%4i?a33A@wICAOrr&-ztg8NT#*pXY0&B@T+{U;itw2m$oDTB$2@6CE2#`;Ux)BYmosMH0gQ3+(JFHC;AZ4-m zkWtFhiHg>7Y(SUJ&*Oc4N`NDlmdiAA%&)31IyY*a%d~I|T^__P8PX&b$v9GtrFt@z zUwKDXBGnwW57s?AKVcQ5GjG>jd{sO#%{v%H#22>r2FXt34(_ijkBZD4^r$Nr_N<%m z;`zl{MOHk{$UTD4y9MUYfRpW>0jP`R?Ct0iZE0@aA1~%KJ{`dVa`W{|V3RWU%$XXf`w-*F-|Cf}l_|#g?AdjVm9ce=K1qyD zbHy|7;cyJd8#>kfelX&^TS?_8!Th@B!!@r~p|t;JBTIt+h6SGf8?4dI#?$}xd~`$i zm&`?NlH)xMZ4{Ec$B4zaOCrg?C-GT@C9%Wi4~iHa-8Lt?yKRo6+bS7Y?m34{n%^%x z_ntTVCd1xUac_;n@8~dklil+6YtUjp74C03kg^_!8KK(MiD~n%Kt~q>DI=F5&uyKQ z#3I>NdEP~SMhnG6y{v$A`JQZDxM&qobXMNDNfab++#+JiSN|$sy?cE1xIFJF->sRl zOx?6u)G0l@gvHW@f)Alw6K~GDb9Pz1xIe3Cdw)kBm_WN;LbyMxX)l6kc29l<{2$>( zqW_^A&wh-UDwq0omup!Gu9PXijEBeZH9;p1@Ti7=&2w^o)6=u~*6|MJ8VaTCeUE29 zbRWH?%E367u5#TAPg;g!Q6)nokMwao74TTT@8C{%uep7H)PPA-`jm$Mkf9gKi{)NZQ(Xp8Q!Jc!wcb{JN})!5Bn*N159j3zn9(;to}^gS}YiJ@%hq zxpOkQiR9A0$=ibMc6VrreR~@%9g0o?OTB`T4-O zmk6aC1E>zeeDmQ)PY9mA^p~|D;V4Vo)BKv^dxI~(lk9unw~3~o)itwT)|*ii%7Kx@Pnnh-Ul*?LEoA=S)L6VmwL9ociKCMcaD_bouO#oF-oY=;`vnRAmHax14p zq#D)XbCVvqmHLqEMk(S~dJ>Wu=0bvdd6n36lL_z1u3(!g1#Ql>Y;&EcN>>K!f~#~2 zSXa@a!}{sw1`Q19sOk>sKt_BKQ8M86U&ua5hfQU%&EyltEVkdj$R7V2ztUkqM=a1) zighF9j$nTLVo5#t7Nr=n^f|Nt!ez-?%#aAeFXq`J3bkf3K2$F7&O55!=Kl zmT{pOO^hh%JvLz-A3+(I78KL3K*@oRG_c5*O3(*To%J8PN|YHI=|;-o z?mu$rQK#kIW_#5#YE0PyEMx zZ3CdcaS#=-nhK8u&c~OmqlZMmu5YAa=rp!<%9|EgH*tZ%KOWXCBEveqsXoiT9fHFR3dSC%y=-gPw+5x-86%U55 zUlQ)B6SgD>U8gwTXsInnXe`Zpz&oY;)>v4v=?-i6vhQDE;UzlzS+`3G!NR< z%Tl5}KF2vC?E-kMXRG3u&K(!P^qyZ7XFD4&fY*CAD}p*#UjQ?D0&FZxK6OMs?K)Q0 zmPchXaw%2Azx5a^ynAsY0nG6%n6~c|11WrD()8%t@G_!DZeW|n^vghg^f8yr;4O-k zoemdDZUhG?7IYR~D9H+*A$tB8D9J!>zb+FL=qygx@3E=eW6P`DGTi<~7L1X7znUkZ zp_1T|0?wQ1KgQi9alXQ(dW8K8=9qgj%-k_e9 ztH>mXK0`yJZTb1KvpUe_oDfMyX*@lk{~pP4l|QlkTgHg(}o#zT)qn@?mebl zJ{_A~B`AcWt(ielQeIsLBl1q!9QyWxGBbL^J;erjNd6yCPAbq)O{P(cXGv7^sQkGA zDQPOE;*ASTgr*olUwoiDov#l(swU&9#Td|BTz<3)35L7hOUuh!$TmrwZ+=+H4CaS; z&TV*?DdBXjzpe7Y87Z%;gF(Eb2$2g@gnrVq{*;TlE9?(@y zW>ANxfwq!zOC04Aq}lTU(f0#`#pO;oA2X0sg%rTr164>btmU>Krhedr8R4}x>pVtD zokg%qMKbcWP*2WwXYeUb#tDCY`Y0B{h4m--aqSKuRq#lWJ!zQ5jJu zX9Mg+D1Ry+!np*w!Z;6KJjac0hXF0cv<)~g9!1hPCo#TL!0nwl>|Tq&WjeO9 zMzBZBi~pXm>(1L~wk?qn{ZLZ8diUMppYQ7Z7`@nY z`19tXjaObkJ5j6O1~R6$Y-+-66PFy5&5G?5o!zx+-u7qhH@+Nrd|-UPw_ayg%@)ni zWr3%^rxtcN?HH%3x+)>-QSSF~+O75Av%qJ(OP!BQz`R8Y*;7SegYXn3Z76tDts1|* zJmP5g(#~zM#3{{rPUnRoU}Z&dPuuaL4t#LzpFM8J+n+P;ue-!K*zvp+Is#_d64-W4 zP?$?q$Zr}e366P@M4m<{Nr(x({e8hjr21L*C7CI-ISD#VElz+!;O?&8atsc$k8XEgjth_!1Pv6_^rABJ>uP_BQaT-rmlOoFbOm;H zfo)w_o_@3Utf^ynK5xqxIXAl%IY+gd4%*xQIAG@iC~T!tfoUM479kjaqlFei6Ji>h z3K*j<74*ObN2ma5C7lX8;jw?huDb@p(gpuIQ1?i}(8e@{V|`gjdnZ%@Q--eJguYVz zG@j8tN^~xey#kLl0F7#q#j~eUB1d87dK`8-=wE~Ef|=`ZSj2~6p~J3=;v{$Viet^Y zi<7%DB;#{9U3It=$XSD#6vrQY@jO}|-@Av2ZyWM`fxw^(5ZMSXLYp>_? z`FPwPR&a_sjo&0xH>bfMrKUU0e?3BxFBp5#NewZFl{HaK1!Jr6wW_eNCaU922H_qV zhQm5J^NTpsTI4*USW^^hTm**Q11L!#e?TgOd?JlP55bfT9MY}$4@kYya&5qF)idz3 z^P67gsPs&Z^&O$p0OZP4Xwx>a;TFcA1H?lr4S<{-L}5-)6d>F`+54d0CaR9)`+OKl50Yp3hTXiu+rPE65(p=sZyx_hiL*skf(T?>~bL4UD4D($a)|@9k-qpwnLo3js_Q z_&gT*JQw*C3i=KY6CYCltLxIozqwAZy~#N6k7AfF=E7X62m=7j>kaOwQydbVm7*-UiYKNdk22O zO4SnoJHo)8w27}u;Mxc$I>RF~HxTuRTOJK5na@K?=Ht=28Hje?^jMfqmhd7DuyUmF z4pepRj&>O|p7`n~&si%Lj!tiIP>7AuVT+^RO~tt3M~)K)D6|_*ymhFI(f&|-z7@?a zQyjL9zgFzpDOrmO|~H zt~i^eFpyBTx;W9oykY^S4h>Z=Oq`X(LAx3>+)0B*TZ@=!yWMQ0=DNdB7<`{LOk7VT z3&LUeK3$mZ8Z69f0?8YWnM?L45U&*>(-^@WvWxcs|AW}rg@8WK%s*d7V(=qv5og-0Rb%c&eN9XdhUm-f}R z2o&VfK4}U%wA<5Spi7r#Pn%8?!t1Z$%+KY3W~uGMbVwj$*M)uOfUGgeC4{c-b49W7 zqK)mY9?)rXyK5M9@)R|%$E6ja7GNu#`R_RWI^J{{5$p7MkdjRI932SeK1E@@} zOUM({s>At^Ub8{Sm@zf#CV(-OuY#HUUfElg16Mrycy*t2<6^mN;B6OUXvb>#kWWhmEYOrZ0@1n)U`~oWiH^-2u*vp9j0gJbN7oxs~_7LlZo`~ ztBk{<^c$UV*ExNSuQg=aF)ypYcOI!6+y3r@A_E@3lQE@188Z7*Xi5 z;tu?d$n~lZ=GR9n?<>`RP9rEhzJ*Nl6gj_CoHZW!`TSkY^X5ydUqM=#TQgdjXG0Bi zk@!}O-+@}x@;^OwO{p=-xXJYG%sc;VFh-)7{j$|SmtEG78o&#%;rJPpU3w;?w#p-* zMw?ZcRC{`AWwpuh50&E~FEIs!s~=gog}%U444!>dv?sI_^J388QIT8db4<VxSmxv!x4MgZY^kN11bk7v=+ z4|Xekj42;n^eAhO)pN}A!9$O-+^o{X8;B!qLFA`H+H?Wm*|PcqJM0BfX7^EEBO#5j z-V#=HcY~G2_)oTz57=Y>^e~cRb6}dRfIE-*8Uf5qV1|XTb+Xi%`IbY{iRq>eV>0Of zI&V8?SnN>WZ83mq5Qd^>83-8v)wt+8muWH^h`}*}h*Bh+s}d$wFjPl;uS_qPqG7b1v)npr8-E=PgL3Qkt{;5T)t3q+3}^XCUJGl06hd}xax zGoFl1uk+96KewOG+cc@rkW;QJ!gfr>sVkUG3SEI>#gsxt;nbwC7AQgtrsL$ zFr^OnADByX@ELGuPz54uAQfOueWX&b(5IsZZWuls0zw-DB7p)&%C8gR2H5_R6m8CH zWJPtoYxGX0Py09Vazln4T{R|>lpkhpDEfS>PTFBdnRtsm@G&2{wgU~(R)ceCN#nxd z>Svm8!^i{>IyoAm>%OZ3*5L`@US9~)owXI=&$|eeT}}XhS_$yVaOOOkT|?x20)$qP z>JUN4G=OhABU4%Nfz4hgse-^N34{<9dz+++(IGYnVBQ7l3Og#dOx|~9o}`OyMP$SQ zT2R{GD!6X_dm%!Aw}vy-Y5D`z%l}ga-}kuysU?wACV9rbzPOni+c7B+b=#oJZc;Dq8@_zo< z|EP3x2dZsmz8eTZ70@a+YGsVpk&*kqCOPtl8soy8loTF~3Qd7x`4mM(fk4P{4T|kV zg|mxdr#1j=#$tc4pF6_Gdtc!&86asVqD-IftKZ&zx`1 zykXCDvuC#2GuPTPpW8FfKg8FS^D&Q*cK$V@_dVmC~~p@*0! zj`N9_+`+m>m3t3-#Si3Ew>rLHoKO$CmwkDkMN$@HA;RCzZ8^g{9 zFg`WZKD>pop>2d2n#ipFh*}9go@3Z1)k68L!#(YVJ`L5rR=9V) z`W0Z6?^;}G0Sc%<#pa`wu!aSwg;+x(YCbm0J*+(r`#MOh@y5FBDOt7dU1gs?i&uG% z+&Ox*!n;*$9qs{hILU6G{OC6l?bI{U$Fs(fdzAyjF5~jKX`#Az$*rRe6?P=VE)#ay zfQgKrj!x|@6HOnGxfNOk|N==9$GL10b4mf~!r11%EF4a&;q zFte?A!#8QCiWC||Vc5Q(7ro&hQro>Cxaz&o+9H!?+{cX!ucu=`MJg2fK+i7YTFw(0 z6jaV5f8ba;hpol7J@Fo)R6Lqkqj(ENu29j6BY&ocnI^L#EF;EzO5K?wFg778yC1sq^BJL=RV;0Xy;Fw)wG;qwWG9J5O%^!>4i)P46oOzJdN*ahp zs{Xf9U(Awz(HqA<>J$zO@M`~DABWL(O9!Mo&~@&^Qi#G}s)t;?HfEpBe-SnT8u%P# z7`P5=eQ3gO35Tpg&MFXZ7Wt(!)_357?gC|=*g6BCED;=m#>z8GuJE$}uL);r{0m-j zy@{>!8vg5dh9!WmEa@h6EPOyZA06vCEL~LycIzW~o|9E}18k(E3WhX~CqN9JWfJr; zy6j1X`1y8z7bixIOe+vOh>!$^A%q*N==_gc4I*r#V;2L=t6(KdYKD$A1el4S80r?P zyU*0eu7atp@Hk}}vr&jrnh|S5n=QyiLs^T*zZ8wR)l-WEW5#&A4$Qxvnk5*^ED);) z@d*ixybhTSHqIFuCFfpe47*{0LJghNo#*Y3`BeGC~FCaUX5`jn&|*!i;evB8y@`QJw#VH_ChpEoAw)zs6x*U)EbKctTz#i8GJGo~z!T|y@eSe7 zNX$KG@$JLH^uNiTy@3*0c84K?!eUSg|Gz?Mi1H6bMl~C1+*`iPz7Tiv&2E#FQ*N(} z=DVew+4NIGY2CGVDq#sTu~C0-9i)t=T7O6W*@!*{pR=X|M&wSG;#O^_cH!?A@=wer^&yi!Z%adbQNRtfo$F`~+tk2g?oHju6coM=qRpzZ;WL zQWp5dYggH;V$I*rE8^T=6;hWWzCs}?uS?Pww$%clZkbS1be|k zUF6e5g7HAWYRQ8_L3V-2k;<~uhe&%UtEs0=VQN!n-(`RoSJ4~>91P*mb{-CcThF0s zHVBtP)E~HEJh(&P^Cshu4|f0)QlAGx=@BaM?yKOo8561L61cT0O?@54uW(ShKowT# zj{LX;e=m`sA@H1!d{OVZRr1VJ;`>z8%Mp;4#Cq5B-6j3HvEpQ=@{iWYjJx1hXxt&d zztW{a^f()|pC-_q0FDn}lp&lNU^l7)hvbu`Z~VU9tZV&!g~P@^XI>mJ-NjTs%2zEG zCw!Hey+ocGG2QKSZhSS}<2d=as7(>@z~SyvoQrWB;A(0{WAEF0X-~Zq)7J4%Nl)pK zXLhafor&^llu<;OW(5D3=#RbV4_fp`#nswl7caN)6Zv&!H7a4b>$`Q4f!QlubzIYz zBrI`Q4%yz~%|Tx*~X5iJ{{yQX7An}+Ci zA2Fhm2=nPDRdHqO`ApMvnRqpid9o@lj4dZ8%EVSYCQgHr2j#B(o()^kq4?MHvjj5z zso4H@j3_t4JcfV~DG$*JNFgWq6VZPoA@&1&Qd`JDeIhz-B*@>xCyNt7&u7e7xT3$A zpBsBoq5Q5gag^5_fU{$l_cx(0inquwiZ`40DyOB7I)CI3;vT#UU$k-Cfo;Zd2ez3K zGJI31Zieje&add4C>wJN(no&sJIQE?$aF~1s~+3Lsw)QTgp|N zY@~}h#^Kj-!c-<5m8Nr3OQCT~;X@5dt22$H*;vTQRowG$pVanFA&Yr2}{+d;fXuh6%zC1GRH<45K%KJC)@*h7R_+ z(=a+gct#yu^^TD;8Sy;ps$#RiUsrBguQ(*2d}@eWAqhM5hjOAd?)BB8h*ci?I>5RH zFMae2HIJx4qD~)lEM!`N<-8-na@%-?Dd%VLu9oFsJP}$83 zEfSx9!;$+NyGJc9++f~%s$8NP?az7>0idDf&iJf(^@PW#PZir*t2so;n7 zid}c!G%4nw&ghY`J_D@cR5j%hZ&^k0i1`b?zfb8mtnI$`9~^TlQVDNiMenfrS`wM( zS>ebrw%>m9&2!eQ}Xq5wY+(1ql25Q^Uz;S?&GN^PL(5DB?TFw#JP9iE#&APdTMkrSp^ zzRd&!_AfJTnFyK6aP5$ty9?xP#K!)Oj9USB()?#|oeQVTqggiy+XPeYH?gr_Isb%m z2@v3L3TpEk3Z{_oILP^5NEf2iU|~ivwZ?)m1N@Q%0#OjIg-mav_FiY`rjlW5Sf?F) zDrZ`SoL3;W5yb*ez_L_;a(yN}u6N!)kJ|q?J??%15NC&#E6=3I)wbi>p?nmtTyYK) zGQWJr&_3jTj+`GX#MiVTW!6af=1Ga;02?Mrap14W5+WlU`D{HfW^j|}sl&-ICBy!c z9a6>)j%6xiImhxQn61I@0N%rF-81^6IHhKZi>oP6d;T@nexG^Eu$N!0?R)m6eR z7JHGTN)KseBRaZe;;4q`s0;rHhipPV(t*>)mhJD1yh8lPQd|ZR6a{!2cy~Pb2m+e` zAx)8H=+f*0V8j@~oJ$*LRjbZyRH4c9k$T}JL0>CpM#G|;NKkWuX)7a58e9V;=jOup zvxvs{Ep{SCDEE>X=Tai$9p_RqV}dgp&q#N}^3I6*^Z`;sq<9_;!KyZ#AuS+h0|)2R zVptB-aT7ka2BQuu)M>}%gA)Bo@Zh;V`6f*2SaLcro7 zu;VQ3cmC|U)^+7}<`Ia1W%%9q)bqj*-y<)ndb;Z!+_mHAHof7{RTsA_eVFU!xLsBM z;zB*G8d4Ut%I*5a<+5|EZTP3rJbzR$qlcM;K=Dx^FZfWzf-MjMD=}tuZ@p7&SfdU;0I#;j{455Ftk z++N(mJDX>pC0#@*@P9c2BE^nkl6+Axd!g||qOyXqJIA)?F*m)k$T zDr0xFw(QG$=Hb1(vPy9Xn_rsP9ZfA=@5H>D6MNsLYAR+?`RmsH;}fCLIpA%v+nsJj z9I%&1dneAg44iBSzYA+Cz#q9D6L6BS4am!p8yAkMMjPHEAEc9fdPt33q($W7j_jL^ zuN>b*#@o(pqib>Lihx_@D9K-F})Bf(q>*k8ep8j1E z(WLB;e~B)Jv#7^SzcG+Xc~-gt+38op^R9wj=Ct4esZ${cK@q6gqSwV^;oFDV`BdsM ziMDiUMp*K!=QQfITQI1XUo4 zn{9if0d#`sZUy1MYiJHg3I`$|d>7?(ap2(Q_Q<>8fTl4hJ;8?i2j_qz`>Q}x2)dL_ z$JF^k51cOIQwJZnJdFxg0`>9=Y|SAA2}0U+f}cTw`R@ zahlk$OvuOXcy9)6+$iu_`99L~A2aKWz-I}tw?5JhZKY2H_(!l-+K{0OS}3uJ4`=_zXD*q;Ouwi6FDW<8NWFt z3k$&??zAfd)mHFs%~=67#LAngRA&(_)tlgUH#}+kGlA>|s2%WMdCJ6W9;g>K)^E5v ztI<`nkZ|ApADShB@J>M2LH<~e%{w#^Jtm6Y9cCwrcKuh;x(rKI3qeCxwK`m^H8!;f zPSK)~S=uRW*AsL4!(QRy^ z6J9HxP{|5dir2bIXt>D`-y`#(!S8l{GG}@o8AcQ@7R8zrg0y?HHs%3LV9E>?0U80B z0Ip3!BeYy?b|MUs7{%^?@dyx83erPC-Q8rWFi!yY8phn8jZMwFhm4(&7-_;N^;CO_ zk?xElCF~}Ha*vz=Cuh(dRmom-M{RN!-EjrPtH}J1^zJ7{32qIcUS=t#^}<859Mga= zLXE2r5HLd41%eOyp7A|8bj}sA`h$&p7?1+ z;Pl^O#6W`lXQG*J>L%fx1vKh_)E=G}4`vAP8h}TW&=`$0B?8cJEiW0=6y&V^38(JP z0VOHIoCWj6ISxPJ7Q0K^g{%JK6h4@FdghDMY&hZLh37Sr0O1b-E z!Bz$rRmXk6Uw1qAC+acx@Xj!ki{z4py#4Apn|j8+S9W{H-+7WR71~Y5k&30b6-o zF}}xl%5Q1f{<5SC)`xKAKlYxPa`1i8p7osUGphevp830W_^XKFT`Vqk;jN$Wefzui zz=W0j!sB*o+w}G+MCgxp{*4ORr0;T49<#7QCi7iQde3+M&EJqERFdQGa!=1wEZH~V zO`Zfy2IZ_*81oyF%WBA?`;Va$?? z05uV?hzE)ifTBde)S1@1oQrYn5c+(F=4PLTXWrB9j+JX)M6O=W4Oqkp*vuiCi|BJE zAIzP6aDmg$_)glni=X}ib^Uklb8PT)M$ZdWI`sH7j}G%cwR1$Z3q-YhfHH)&62e*) zVXcg?R!5Z0L6oT=_$pY2@#ik#x@-NV6JYTd=>-RWWh_HqRIAIu_;(0n^TFwb6ZknC z>7MUUP;xfNUg)&9nHu^^`rYg_3>T05b`|+80Xd-(!&RO9-rIr8FBj*hFcOdOm%R`l z{EB<<8{so*= zLT^d0GYu6F@Kq2@RcxK92(Jsl<~xKj=Kz48{8^}+52`!UJQ9FBHH4EgHrC)Yjg|mu z?>-AnUtwYm$6g2G;VRjLkC4mUAOwH*{2x03=3E3t8yo8iy)P7XY%EMPrNoi$>=3%@`a+Q#T;pHhtPT+P7b|6O13o9)54tJKZ9E(l0~*K|7BcuNC(v}pAhB@ zVW{hep5#vT?utjnD1N8*XfW?ITh2UNW1mj1(~& z=y7+5iu823WA!UVd%7IAEnDH&K1883#Jzis`51oMqdFbRk8#ic_&=S} zJtS|-R5YCY9`}VWTsD6yIY;*hkh~U30|(1LM!x;yvzS$V6jN%44c&+h-6Amx6?raX z5f4e99YVUSfvw0Scz&dw+ZmQyj>`ExZTN4t{8u)Uw8;I=K*yl~kCQLnK$xsE2`VZ1 z;dV=}uB;+C9*&=3=+E97ds?$*NHRUcm5P-Qt8Mr>eL;B}WZAiCnn^oGN58)Jo6kD< zjL1D5jk=5Ik{*W{#?2OC#Vf8?&k<@6t~p!Vik;;!~PRCJBD zXXc(p0o;8gVd17fUh%#uzSn#=IR23=%E>yDbvlbJzhO_9+T|xpK$F#4V~)QI+1Q@k z0%a!KXLF=bc?DkRuWO_vuZgG!or0{x(A?|W+*VR@t`J4x*T0+1Xx28S(bD&8Y&Yhz5 z?`QzZQh!#ffo~%eM_8vo?_Qxsj`v6DRzaNQ6jM!6*`zQN#1&B$z5>OoPQ?m$g~vL$ zZ;>d9OzqMZM6H1Lt9aNoby*6ciVMV{L3{+jz|nCqEZ>!{%!ye**8RXycor(C1B!4- z-12&bmq4*)%1K#4Yg9xE6!0m^9EG**t2ibo-Rn7}?ht1T`2P?5L4cMo04RsB@)N^S z^(2CKCelwRL7O2N@dP^-+fsryMKU}^u}`?u-@E=dpgmvQW`u|%ivEFM{!h~@HAMdf zN-6#c!dz!itDBaG6!ypAtBJ?=@_O#Po_6Sob&?qGw(1o_}9%$q&Y}?O# zX3I(G6wZMtVtPm&uSpJTEZiQyL<#2FNc9wiZ^17iaz=^V(UD<Y$f678M+1RZDPe?b zGga=4I3{k}R4{sm5_6|BuDnyRE2${3ut<+kbQtZPSVR|WQ3IMAyX<#|-LJ6g?aEGM z_=tuc+rh}HP^W<&2Wf8BPGvR3Vd7`t494>H1C&Mb;sJ_@yr^FB#bpwM+%Lr-&1N(< ze@8Te+7>ou6C9dW`4x+5-B`qxJ_MDU9HzYdYsf4HZA*s@PwAUqZPSiwfD4J&;F(*&J4H7E z)1~AWXZ-d@qA(EwemiNp_k_le)MtS)gPo74d#s3$IH-#}*ROXEjdowCzm;~!$4%%Hqv-l|{^e`w=8ytR!r;?K zhVG$HF?R-s9vSWpeT=y=c>hsWqp(76yta??H~ipltFB)7Eq(?;%j8Jo=|ay$!Vwo( zu`=>oJ@tg-m^y5P6`+j2xJA?-$|bGnKv_)kb};)nB=s0^0l#h~0=5MUiQbc0(mkml zB*9$kIvRU0O%O4L0ucf}J;%eTvCBgcwFHQ@l_;9Ni)q`Lln!y2 zXj(mH1t@#!z_iO^Kwr}4!NM8jY0);mQ(m3Zbde+9i6VrIBz#IfbaLQRUJ2#5px>Ug z9anslS)Q$B{;Xmys$$;VB*v}gRqFA?8~XS?Rm{lC6!2#(t!Wy_YZ9AI#tqLkr1%%R zj^Vbjrs|^F`EBcSnOTL<;q5@NE{h(MRip}K6<5Rkk8a_$oz#;3X}lp9^K+W^P_vd0gp6k!1+?q}5CWkzZn6cLDzj2Zxws+#alZ87TVaE~ftT zj6jvRDo_j&Q_-b5w5?D$5R~ULD)3nhm^KK_1b7QL6YBQa!7DdoLobQ?8U~2>>8_*k zglz&(L*(xU*BHsUIWTSQ82+Y-OG`MtDlypwVK$;m>2;PJmC*3H*9cLW1V#(`kj*ok zR25n-s~Va;&+uKKc{&ejbCOIE;&@QT`U@PCL7ovMnn(SNXT;hBK{+cJi>Ff)m0-FJ zt{xJODonSDxKFpK8K01<8{5i(TqCinfPdQ9OyCuS z7Hbrq6inH|Datc-Id1K5X$%q69jJ!Eb(6t`f|+5w>WpT7tqaX74G1>Ii|i(i76>*i zK&mxRPf3jC!gjI(9z5n71u)AK>ewA9_~e1@%p0>8kHs+N5nULC29#(v0dU%N&_Mt< z1i%I%9_2U!?TDE{c8s8$7lE{?yEUjvwc`Wfo!B~dMu@08y_-Ap9>f?9e50e=V1 zf^s$FHVUI%D_eXdZTj0xBI&g=k58c#9*~7vjQabpPbOBJlW0ls-k_kkw!l};X8 zw+3VA3Z{jo<4K;?Ws0LZSp5f?`3K7B7XE@Dtdu!mQbb)#u3?)WH~I#5RcO{nzZ0H9 z<0Jf_(5yB;zj7ftB$GTcmpnozDUnU-r1>+0{N32s1rl2L<@^|&8 z73YN1f}7chEQo+w2dPpXpdscG1c;0R(&(7b$AX;TDCD30wS>9s7(Ej{u>}qL&@5ZC ziQ)RZpz=;dWqAIqZ3JZ~;@xEQcaTVsVz&1L1Xbmqu7#q&`{2!gL&0#3ks-4@!Rw%{ zpwHF~QR#)9wUkKbppj6E7lI!s&m?$2aU(JJ0Cfngc6jo;#Xx|+XR;puh1(k-_^>p01tAK1BLYxT71#swN^*6g@mSegEAjCr5>Y3v0v=G_h%w-i0D1+$^K@vz^}>e&ya7B<`>*pAj&MUjamM&raG`hO zKZELG0p1eMd@902vSx$^%y3zyUU9H^2BJqkAs7j40L?)!krJcF1h8 zOt%i93{tqv5|%wvL5~5c7y2Kfa6q~jE!O}j5Z0Ty1`#)#2~sAQGKDL2XmKiV#eAAD z6EK7%!bc{1DLJwvIOug#9RJP2GN~y!0V+r=K>kr27!1VjRTP-?UBG&jMclX z!H({Qbxks`-^6E+GqW$ngr!f# zy#<6J=LtfeQ)F<*2*R*c))jeU9N1eT_Bl%iBOq#OC8Ts2LD;>4;J?{9fa%Fxa5Y3d zg&rUJgf9V3)Nq zSr^*`_p@+x2or3(;?ADKcX0;`xG$EAqXru$u~~sVFYosq8N;rQxYGamZokQc?t6|q zdC-oBBK%Rq+&3|D%Fi489OUO8sR`i-D)03jj9lNEw#8zV-8ZgQZAn^fk2%A3;F2aI zdf<{SLuX+0S?xmwtK=yrC3#v9@!gS4-g$+R!9~&W*9J=;IgT*PEX0>{uVfyt8(Oi7 z(9yU5&z{e&Zsvv3bFIX!uoczYBT=mZTfjZ$#i`Fjmi$2v?iif^$cvwsB3(HMQ3}83 zUB&!%kC||g)M7b)x~$(fFxH>Rze-avuzvo-4YE`(D1Niji20i8+#%is zs+EBrPjF`-!$X)7IHhoot5zS_hpBNoG@<^pk0ivrY#=aPoF>szElDtHBcV<}giUdD zoz#rb$tIX&44RjlRLL97$d}h)SzAPn z!<;0Wm9!5wd!vxFF2lmjPWy!TD5^s<&%XP+nc?atc+P3j<)_r9GiZBF^Y-h>kpnCr z^szIXG*uTyk~w4d0Ag|Ntp<`xZE%8^t1;1xX=WU|$*_l!!=3kq`CMaE8Ii;1W7&s9 z%|V7Xf*M$9dF|w#xToQlR>J-*`fJL zeDZ*=cLM`m|J_u#!0sE-&iv+ZnrnwCp}@{I-_Cqz*u`C8@N@=xE_p2Q5w1xrW3BZF zlf*i~wV8Pd{IYuSXTkIlN!out=;!( z_e8F!91(x!aY`N2d~2Kb=X_=<`#jL~H;IvaWH)sSSf&zzC0?R~#OuOhH%er$?}!a` z`DFvs+O?EKv93TqpFz>8J(81F`QjGX-@Ci^tIvB9;TGD)_x;KK-L+eN?87Wqgk91N zGyBUP`=%bIEU-Q77vf}VnT#lfiLZD%@xX%EK7R#LHn!bxJmCJV$?}KLQ4JkQ&`}5- znYSi44R`hu;7n(GW`jL*nLYEdy?;oKwJ8{qD15tLD3wztxa-GruWaU_H2d0mM!%KH zs+*_bZ23lZZ0vxa^MK#!0YA?H#+!Qb&wBFRcyg6E(?o1&D$aV8GDSOXP*u74a#&_? z-H(>H&9D3!k>AvKC7OLFVO5n4HcTTyEH7*`H%pxJIRST4S^Q3wH=6QLF6rWTv5vtp z`rPH$7MTBm{)sH#>8JJQwi$Qn*H7nlY`XY&j32a7`O_2y|Cbb5cX!wFF-sQZZk&Rz zsTU6`azV5w|KGyea)(>d@+Hfsr%ki6`t7`th!B-mHWzLm4{c2GsJ4Uxx zs`o2JC3l!PqqKZu77lH4=O~R$E0}P=9*$oXaOmy)T}=yia@_&Fg*PwNp=Oq zUUV*DW^C&$5Yo!j~g?ODjsm{E? zz_O6spEagl$Gq2+A<#Oy0(@Tn$S$!~e`J(3oxHm{k*8ck;2`x+n|C_og;T6CK%!nL zOsBnf-cWjh=}x=!(7F99YX;vaNEe-y@jpI0+rj$JM77Z~9~W=;zEP^t?-F&AKDw*Y z&R$o2lXzndk&~{DvpvOgiz=e$YEN8j=)1)^LHE_1xY*R!%i$H^jJQ2_nu6<;=Q>o- zZk;OYMpO9o@q&?^-GtCN{Yz_>MXil$;<()0s5_hkt76jNky6cW1@wGipDZo6+AZ$) ziPG$_bgrE1^Uj*u_m%Ul;3Of`re>5AP3$Fc|?D!g7a(a zThA#ahGd{@++uD|#>}(1OhHCXbJRMt3ru%p?Xc70{Vfo< z?VEHGH)t@(-DySQtM110CSc%7na zxs!qP+aR&kS|-KiUd$S*d(0``m-ood`8P~Ac1kkFrV?OI|NnPjt%_Ou)0x2dIY-qD z)LfQ+p7%?rG^VrktnwM1mElL%Dc=^oK24`xeF7{_(KosrpYmL1flIP-4e8axTU?z3&+Jw99DL@l z`;s}w%}LW>df%Q&)%e;e_#U*De$3$e-gOJm`onV;W=73ZO(+>&fPGP^{I;_Q`K6yY ztU1@keX@pZDV}&&c}M5!sinjDKONjYM0(XU_1J8OXajFWLG|%_{9DFSKF78Es+e;x zFDJu4=fu4e^E&;Vw^PszN(3ZglHQcIp;v%Q4B9lz^C(#B*i_Lee=ylT#eHRA@gtgRixm+qMtx(<6{ zXHMs_ot#mFi|mChY@__>#5u}Z`HvFArV=uhBBz{H8f!I8PpT@NU9-O}+}LN-Vh7ud ztMzQuZh@1f4f)NQuM3*|F0xwU4btyTW=xGyG&|4%;qe_B2TxqRz}|EHpiI3vjsm3@$qMePI`Y!)$OlJuH47gEChZZ%V{3X zowH;kkUV@sJNL%nL%9R%jPNC!8b!v>P}06WJ=)Na$LptcTbdR#USrTDr^mh>tIa>1 zExEs>F0H}4Y9P^;qLQ#YTmF50)uHy1z3C|b>CFOGEA8#>pzu`OILCRA!B*u>XYyJ5 zWN=rs%$TuFy-a_vfi>Oq6ZO|pVUO_zI~Iv1Q1#^oO4n%@k32hYR^?*fo0@jyb_xP{pdnKl(Wvvuw5*cZa)2iJ@m9z0zm+J40|$>jY_wGF<_ zcQ-75aW(KndVt%VB)xl!_w+@{L&Kx=zOz#}C7wsN&Rw|3ihO0`wrvX#7O6R*j$aps zB)m9r(0BfKv~vE}4}_!vw5H*Pc0%&A*oR}cep$rZyqI^)&Ap{=W8t~QH5%-ZVy{I9 z+$y%$t$DVfXwKV_)4=pR9mOJF58xa-`;cKk_j~*FlJ?pqTUfSiTUMuHZR_B>%Xo7ivsd6+`lYuz z63m44U|Z~`*P*ZO1aon{w{W(3RR17?tYk2{GL9Mj-dR_`@0G`p?D1*J9->&)RgEhO z{4Ug@27jCX96Ab~Jy0iW=x^zh)=WhJUZ%2+PH^f9jqiU$!v7la!Ta&}J!M%@+-Gm~ z7nkh4JdCewUwp-h@@@Jjn3W~{kk~JadvIQRWq z4tVWIb=YJcj0eJ9rm~KT7X8eANew!*cDWb9#XqDVZXX@|bIEM^In;jBbP8c@>w(qv z2ToLE1oeGDtBe>9AwT^h<*~cj)|6ktZ=DFk-QH3e zec5~}ZKUL>Ef{>D#e}_T&%zBq?(Ys^nk8;GJ=CTKq&~l)y>i#V7pHO`8Ccz02DrNH zM5_M!b^c&pmXG<8Ro7P84!+B2Xr({ALEoD+%zFG9ys3Qq_I0#M&;Bnx`{Ntp?XT0j z;N-!fpXePes3%qE@VRf?wU&Cd?iydb{yv$r;8_{1^ue2pKj$jSw=cC+W_5S1mQ@$O z&uTj`{OR_$lXXXGgE?=Q$Iepib=PtuU+6d+6khM|4KPhlTE{zYQ1Z1gDCOY7-?tFc z+83rZ^)m=SLtWj*={3cY4?!uGKE4&}3e2`5tO-{q!}Z3IYExLIj?<61Q=HpVb2@8- z%QEHMMVS2RfHHZz8Pln_6_$7If|F*&dfCI0UKD6BuKs4@m4_-3_>6e(uGr4r8@RV$ z;gsc5>FfNx&S)*RmNICYTGwU1ds4KO-j*=A?H9L-zm&rMaAoL&Md|A`Biwa@k$rWQ zO|=$3l0Lbrm~GR%$j-TgLc`Tpx3!KVYfCStz$Xfal{kV32Iey6`I*6Hh* z(0hn3HlidBNzK{fAKNy?qE;BPQLn@Tnf5?8E|nSJQ+~2)IhXw70>D&BHl}a00a_L#L*`A_@nx|TS>2{N&$?arz`_GocV6VUFSFEG zvOPooaO<}g`Ll9s7nbQobV1(7dG?#`n|?GNxn|)u_TCI#pr^~)!(mTnWVY&>3O_wI zHRYC+g?!3xEU0T3|zl*)MX} z2MWf$@TZd_=?@;nx|0yh<&Li@C{x)e#n8I{`?`kDyQ9wrzkd9B@`3ZQUBk5-*q!2a zW%=;N2=jfujaT2_x~|c4_5Eq*`-dD>2JNc*DbM}MnRg6Y+!4w*3)Gh{_qjl8sh2!V zX!ydp!C=P>hdx=OFTea#`#5@M2YY~e;quEHn*2`$b?xc7zYM!P;3m40Y0NQM!_5HK?NRVR$*x8NNL5+2fhkRO^y6wpR zBfE?PkW6~}2o!cv<#S=)jWZ_UU8BDG@uknNZayxj3 z>GVOa%jHU0=D|IxYKntaZ*~ZwzfSvIr&Gm`^|u7(4}m@=<4gW?#Sb9i)!RnH8vUbZ zY!J&^-119C7&~rl?2;vTb&N>?>Uzx`-&^)Oto0=D6&LcxZN1#l>yt=xP6zfd=`L(( z9QHMH?fuz5^?-gIKO_aHnf3Ky=CS2hXsr6IO zZhz`7k!1(ug$D8>Ih|U(-jPZ33eo%MRs30RcE_urCDYrk8S(Dp;r&wS#e?I6pJ(Tl z#HH8u4qq9Bel$W0e|@Sz-}m;IqlLNc{%ooN??78-L?63+Uf9JR{_f+5{6$}_7MDm9|vY+?pp5sw*>Bslhudenp%WG>K-U1AK#ZQe*V4J#>fE5 z7w8=^yR!b?JUT4Hs^EzXAaoKdJ%iK8c9*0=g-KVkeG;9e)IzG!0v+p#$8?<%eTo9* za^-@GDkh^3<#T8VLLq}Ef1fe=y*sb0M+j1`zZ5|dvWHx}ugoFY-IRQ_&-9h*AGoVj|KD;D1HEU(kFTYX@hvsS)aUX7s zoyckIBu<*B>>Nvv_0GA4S?Yv2?wjgtlnr+fd&MUX0TyDhdRvhWkgWftq+P;^r`a%} zQI!(@d<4OP$T;#TZaIHE8Xe?w=DqOkw2K5T=7MC7y5ayBPEgk3`gt|6ya|DIVQO*& zq_izsG0^y4)`-A=Pfd25ACGlbp^NmPwV>CWKLN(8wN?6kAtXOhX`XCJ4ZrTa?k!vF z&06lB8YV%pltn^w@C&JN0?E10GzGa=?^xI4R+3xB2oVhV6UI&>;lry{%e%c0I?VY$ zR%Xa*@h8Ab2&0I}C>!DB-`Q&L@=SND0?-#ovcT!XM6AP-hpu#rBeHrFj{9IpYeKOR zVcLsWU>XD*6UMMU`5@XwA>u1~=W1|=AbqV_wq+(d#samzvB}1YO6>s+*B%7_!X3x^ zW%k;SE-9X!U7jBjCEEC21NQ;rqM9?GQFbxrkqxKKxqpzFlpw~|HJU@dWe4yFvp^dz zz7>t_53Em%b}7;rzy`5nAS7pVvaNK5W9bc`0%k6p?F#a&C^QK&fBjf3Wg{a|PXQkg zr~)>bbWlI{3gv~@2J8RJ>FfNjoqq3`HVA2ETW9rk8yoGeo{fEW~Lq;=VKyn=@eIuNnVCiflJz zuoQ@u$BL}6B!>ec2J@c{jMcWbCvoN}Z7VTi<{C`J%8p=-e#)AxYtpo_w{e=u=r7S% z61>8a8L4PGo$!kmZ$bjWHHouey_s+WfxJZcof;Nj*3`Rgn&$DdqAtzcc{YQuhDr~d zo@XijEUF*=(n98uQvYe#{(zZq{3NQyzSNPZeKCrxwod=)i|8Vy2478z+u zguZ~G{~D?>sYZeJBi{G8F^GQg2lKf$-HomG{?GA`5_lAC> zvrCdLJJ5K(!SKM;>)dWhMLC`3Y+TtUy@*oww7rG-dSqZ+hocMu;w z{*57;44!0_v&=>ClwkPn_ZD&PeAoqdw`-ka1}s|`-HHM>c(z?u`+^d40?OQ`!A^vB zBR;>0q7PUMvRI*U)*)CKo#Jn3iv1=>4Nq1Doqw=32BW@~AADO`WO3m(n51e>EX5Lh z=Lw5*akI3nyw;u@vkLvm6ESL0@%^SbSHNca@Kw&z=81JfZM4nO5YD>dxPV(`-O8B2 z&YSQCi;U}xMz9AVe5F^e_in+1OlhnO)Ka<%I! za-ap?CS$mEM=jS@?HM=S_u^BJ%}vtxWpBqAMmjgMpBGB5z(KWT4&#=(C9$Vzy2fbo zohwf2Mz7KBX5YCh?JP&We&^F-?~b9tYa>poR6HUXAS)be@TRRJumA(p^z9b@OP$EE zcLZ^e>ilZF?3wG-NSOEPJfExhWQ7c4BZj0`;@Cx;l*`Q5x4TbW;A9Zk$8n3}#*JZd z4;Y1nCca&|#<-oJMv?Je`VoP*uefUtKAmKc#3&7-Gz5h)DFo*wLln8 zj{@idL_Z_8`BerzJG6c3PA&nbSRc1w?O2m76PI6A58JWJGjq@{{BZjqP)!Uq!u$j4 zb0WhFW_0+uJguV2+IX2NEf<7&3icn9@Q5mVhc1LIf}lh>c`-cQsxS5VUzk7O^^__e zH9hmRMQGOTD2>MKhhj}~z8WCX9DT#Z_fi&h0h@oSi0gR?SO!PqdQOcWR9ZieUXzwt{JdB4Pw%H$TQQoq zRU(@#gePMTnc4|KZ1^Z6Y9qw=*l0_p%kPY(s;0tUs(BcGzvT}rG;49p3_mA&C>1|9$2!51 z7_X=hZOc<@$dc}W8vd4Z+u;4OM=WN;CzLS82(wrOGm;GyV?^kM!%p!`UQ3;Q&>nYW znB#jUO=KL+Gou%63&yLU6%m9X?UcBB6GDQ*%qoWp z5&CMv&}>5#SuYGjC!J2qZuNZp+CmmdWy4j%$y&BHvk2frbvrb_+xIT(hX)+WvS{L; z!JlVkZAmVSaRz2R(G}HMHh&Y3mr}1)O>`uHD|-KA`1{KTbn)B?0&ZD*B2b#&t73lN zPNW#ED|nn(+hWESJBihD^ON#d&HV{;%{rz87~i7}Q=IXMu;cGVC%HH#LyXCr6xQEK zaSIRd9J0QDE2_qW8w%npj(fPe;Ey?|Gng3z-x$0WF1Pc_?HGTEBp_|s6*@eIwOzXp z{7Bg?`7INJ#NZnkzduTb>te$5WBS#!i=o6$0B(tp%KlljqRM8e0^!B`ihVMU*0hMr zKCUQ5@6)@EaOW2)v+hF~RxfohS>{|SRJ!AiI!Q&g@$nd!)Pyy!Oii0J;I`cxaz;7U znjd&NTXfRb-w|IJ_xIxLE`X|+J8NeQ7H-gvJ|JsccEPDU zZ2s%+E)D7lA^P^4KnA{?|_-W0UdHlB)0y9aM#g`tPjY}{gy zo6%c!{toUA$sYTgutfB2uQ%0@hz~#QXJ-YK(OrA*;Gg`vJxxt7oE%~NmoT@yNj;|r zx-u}R=q7|yqs)P(cu*>i0P`yN*>=J|V+cf;>&r(BarO4IghUGc=OdYD7(-5QTe}%2 zSeXMXZz{50f%Hq&2_lUu5>Y=9y&~tMEw80wVx#4tree#0w#jF6M0fht{3*-cj4n)E=PwJTEWzzQEcL&(~%ZFP@rEE2(kxx`UQ zRYk|b)=kazqMWmkDvPeAm8aah@tB*f6f5^m{FUoJqKgSn6R~l`Rs3HNV_ZtO`uwZ5 zr?MRb?A5le!mYMp&aK@I_OiR%tk9XAAEC{6;~Ras9ZJ8N<~}<0m3jc25BS3K;o`yb zz?u}wK=7x~1W(-48Y5AjeuUCqCBD`mLpAnUP6=xt1}F)0W^Y%awoNP@(k_0KZ9T&xt;6St*6ZYjfC5=bjC# z54C&Vz0)@cw)gx-mdPJ=b)G*y=f#Is*O_QI!(3T7sit%3Lk)*^8j-oo>7JFD&tSgQdrtL4 z>g^CFE-#%3FV&IP1TK%T4XmTEaeWEsbxbY=B!8-k(}CD>noOXcvCLjk@rBxt_~S{l zwH?@x%#N?%yRp)j_0vgsp4P{G3wujzaQamsOIss;m+Ts6FRw&&|6)pL6jPix7$4!a z`4jJ+Go}zBe3J97O45=iWv@lw4I^c8SYE33L{ONwS~lscQ+J6-6ns&^e@W2;3gN(L zFyLo7vZa0&V^4VtQYa}3Is9(JoB)9lG8s$wfz-?u^C`IdOG`;3rs98GeI`8-;-#FFv1!Ye^DHNDwMg#$=F1meKJt;Juj((n3zHa)z=gEQ zHdSk6LJ96Bq--`$R!xTigc(Z5cy7s*AP9Y3kDf7^B%OX({PYxM>iy(mQ& zN6!VA{R?rPJ8o#VM&o*2Zw7r+p}hWQqjh4CiX+Pz3+v8z>S@9gY`nvbKLMjjRA(}a z8-JMA!60jeqNvY-Pf%vpj&+&iA{UX5;1cWJB@1KjUBy+(pknFC3A*(9re$#H?-f$3 zCI$w}2Hwzuh(hERP@Psvws@aV8RLhabiM+(CAdco93e0}j|EDGj0n$zN&5Pwj|Oyb zO{QU^{r!l&n=lILQC0uawAria=G9eT<@>)@8_=MC3d*XSNU~E(^!lX8f_(Txvhr>B z0H#{1RQ1CUZ=arRyob@!jhe}DdcoScyw6t!At9$;y)Jt!Ox?CaGH&~n(Sd+#j3+|V zx#RxrVYqV6A>;x0u(2;;VXuym5eRkB4eHyVMES)*S3b+P2B20Q6DK=%@=aPKe!@wF}mF;c~CU?&WQ$z+s8z?dVpksz<$Wx>u9E%<+vrBz9 zjDX03H#MGL^&RpbjK%OfY!FT+m35VV_p$a*+m5E;A3o*3OB79r9*D;zG=uoYrsaXaTDSr`N~+AkU?ws@>~>M1jE(F$%#(eNAUVUI zH7-nZWiQXFcuxt3fxY8rm;wxx3US#Ev1^9PqHC!+k)R(FNk!Q#M&tOGLCG&2kAH=nR^fv+7t3@?y<4pNLF(QK?r{(^guDDTjCk=jAc7+B=e zKYTW=`M%w{V17wDRnR_UnInAM>%FT5KR+}Hh6ma)A|Z`8Q`76o7-yyxXr2MTgy#- zxUbzm(976Mj38yi>XU9)NQq_|kg~>3cCpK1b(`Z<6*Z6H@tO9`&47Mv?dCgNrv+qM*pd&GKArk(?CeP074HV(?mQrhv^YNSY%B3qWk^-qD)I}>3565%N0Rwsw zs_l*CW6!^RqqTc@TJ%9mo3S8}CHyXa$?F&$jL>rQrI5YPNPzx-ea{8_R^*b7bQ z`ndSw-Nuc5J?_ENLL2rCq1vTsy9=VT?@3dQ9vJsvw@zl@coR}FY}ueenN_0Aw_z^T zP^nH)wJWvN)*}>ti{TXYx)q^X?WP5aGsv zpxd2kE{}FUNf4X-voQv^ce~4@ob90P03gv&lMgh!lD3n|{t1G>lc#hCb_p^`Lu_Hn zVVFK3r;@Z*N*+VAdKf+T_bMERUI0%INI25c!rIl!0p_e>AEjI0Q#Lm8AP#IXPtp|! zw&c?oY?}j*`_#-}Poo2~Hp*tlE25ilq&an+^qK`B1JCI|#{QaFRYs2t-+CgGOjzg# zTaK&(Crn|$IYq^#-p0#DOUNXYs$jUn!9MmmJ($)w_yYT;Us)nUyP&Du%aE{dv*kU| zQFqWIfKeS)USwpNisY%fL&}ZV6ybUW2n+(pI{ooEWS!YK)(i8M^M-xAg@h0$+!0ps z)$zJ%VL3G2U6noQpPtbR-AJ8mn&0O+-V1bi_keS^->v7dxK^nSv6GMCf8NkjvLKzg z=ij7r>ry@s@i%)cq_?)|5KR!(jZDf^{b~} zonOvvZPp<4D;@$7^B_7p;SZd`V<0lYF~+*9BY}=XizuMZ1zD%VE|N0-Q+e~FSVHZ- zb@YLbSuzE(^gt~sOFTx7Jyw`pJC;4WswmbtAwdt>X0FV2H~g~!1gbmbaWegTKksjV z^{qn!;O4U)UcRWdb8u*M`4G+%_soX*Gdxa`8=3JPdgi1%>nt$Q;}JH zFL;Z#F>47ClFr+x3Fk2sQfsqxYyP3ecZLhl3h70_ z#NXb>jN$S^H92;*y!1qdPbC^0fd#;2TN=$+%w9+$mbrfY9JRF=k%H>TZl-&KLWsDN zWD%51%nxKbsBaDuSFN;5lW;ZXiQW7BYW9#Mu<^+Smh_kS8;?&kD-Q3vr~4bG$Z+*= z7ReTzZq!%W;#6t1c(eoFyBD&RyOY^hTlZ01r$cxhbQfDF946oKn&C2I-=r@Og2DRS zLlg#A(c9R<%%|gp)hO>7FL5iuo>aC{T~lzH9jB_rD%&Wu4s8*&A0n-}2V#S9%GDg7 z!IW~OlIfW#PtMS46j$(vw~(K-vzG6@1{HjKN`E}hl!~~jxD{K9w%HW*ikT!;%Qblk zYZ2}EwjR~pbK~UQ!^sZeASU%z%K>ib8?uAuv&iAn?8DoZdgWW>Sw&%3us;98QRq0P zbH?cHAz#?Hq2^Zap;G0;MXAf%pMd$QbyHoarT!?%z(a4(x2lnE)r!9{=V60KW69{w zpr!RXbQ!T^X@E#eH>z17t!ksNim_s@d8tTz-liG)fTwY(_GlQ`-|lBtC$<*h8^npP zJnuy_qkX$8=(2X<$+BlsX}y*jvbai2UF}^J$ONB&CSQ?$QIJOotCyl}#KAdHtgX;G&#nv$-L>k0kn>-#k)gwpVv&R>ik(kLJtcHf-~De1396 zj*0w=6iNM-;e5Y-ck5pxHPSaY7CnJ`BbMZy5L#4A#$@^3_cP_u(zwLTmwWg}p{8#j zOtF7JCW1wpsTUCVgvf=UJFP?ppgWmRF1(0l zBBmI7cM}5{9kE~-R)&lvRfzi&X|fQeK1_RKzdzLlj;!h`y8AUjw$T$0Ce+A$>ML>& zJn8G{vMn)3VcJlBp=rNUM9h(4-vWK;;5qp8mpIzo(+`u{_sgGqu-(ka6hp%xx+;sWLXPi&+@8hY?aYCKDcykI{{70?jGeujUj& z3nLdd>dsAY-2Y*~j0Iq!tYH3AOYfb!DMH?8p0aNX&7*XzZ^TBv9hrK6c}xZuPx2`N zT@QwhAJ)_*Y|zUH_0ti;sv874?TbqYFY{-MkbGWhXo)NM<`DSxgqjeS1k|k!WVY?6 zDT+2;tx%u$q};EW4!4X=L^@x*A`8}6N{x?8c|~$JA+0`~^^;!q0e%qOK#TGUDp`o_ zX?x2!ua?&+h>Z6L(wvxkI~;*{?ujR``Yx%ZJSq9m{AULK+#W0>$h!8MJL8X^rBkTW zb0O2Wv_0Obi=f-(@J?SfcxfrEHf)UpkqxPFMy7O0Nmt#4iLI8?0oeag=$e`h33%_G zc_K{QBCO^{yj3=NFux}r1WycsZ2&Z6&*>47ekxIV-p7w1e*L^^9))3$a?Z=?%hJJ} z=Rx`1b>VY22q#Gm`009nokJhB8}*^{2rlY_Ax9G7pw6cU0+F>JTc=wuPs}|5zjG{5 z9|ohy2m%$|!j&GRhygu0$~+1;0Rl}(pVAvb4O{_tg+{87dliv-wMPm2yk$^?J?h!o z;OVP}-^`Q|0AdZGjU*ACEW;VWli%NwJ^2Ys{0fL7X9QlpUyS5Mbw&qSS#1g|nNkEa zW(71G;solWfDVGNQKT^bR?C%g{(!mDw>~KD&{u0M?9*hV(vahvlzs#*Y*XexHSrs` z&RtYYr{`%w!12@F`yKu@unR_EF~vDaCd4{nXuD>LK4mi;4ccXSlhxbf?s@}@5IqP~ zZygUj=TkOz@>RS7j7}Ch`M%y)1(BXAYlGBP-n$N-h1YkB2N$Gs4jx#M8y@673x>o_x@OCwPJ^XT@aUk|GegcM^lA43JoT|l~v!$)Wg0n@Lqs7BmWW9z^8uE1f zei`_`Iw%;~%4irVn952U@xj8{?mczQ^8)O`mAV7oiKNXOKrpz&h9HE~4KE}yo0u1NC7z1y3ToU0JuCM(we<*!imVnYR=7r{b% z+&+?;;vSiB%ugjx2$|f07p{{T8w7EoG;b49uGw;Qxc0EbZBowAh8OCyAdL9M03DL~ zRzix-Hdt|%asum?oP0lFK-QlcJ!jn5Q?I$rSyw~o>u+kE4d=RTQkR-5H32?W{rAT{ z0Drqa#hLT7T5*Cwv$8|NL9>YgGjiYLbH+bFt-dr4hydI)t}3?&L!V8a+m20Dx)t@b z@~edTY4;e_?h3)d`TpeO!ds`3+8}aB0{c!wx#=2dZXa|^j?zA}|WfND(^)ncQA!KI;TdcrkvilxWBZJZuWa=!s=3b$7WMFwQ>TqqWdJb*WTxWh8cm zZ6)RL{Tk6-BlMHR&np3{LqSWw;Hnt*y!Pol1BG5fmUD1aM||+CnkFwo!u;(<&Grc_ zUH(Ts%C3{Q%e*Hs-}?mtlJ*+d*R#QOAK2|(H?1Y$o1j)hC%&)(hDO=^!N4k9D*8P) zQ@sn)Fs#vRcon&Um>5L^-a0@G3p*H_O!H?b#F?7fenKy11_&`tDYkWsmrbr~KZp>$ z;#WD)g)#tO`F;8Hp~tN1$iM&uFkdV(7EI^1V!bz-V2}`qdwOt%;%Dbf6C0B zt#$j#`eTfv-uf9Yac8;wVNkA$wTG`%g{)-+#$~e4yB)~HB&`a}wphzua|v^eN8JD$ znQu0g+_oNXe#%3TYwXr@sWO9NMTOjv|KcW65s`Z{KBC-}7Y-R@K%ccOd27hav=E@h!d`)7+yi$hM7rLqKTH@?UE zb?w_8bbJLDYdoj|Gn;$*{jL49?=LR&nmu<$-<>-fUtOt}EI(F$xit10B_yqK(9eIZ45aXfK6{18(ps5*PESff|L(lF61<;Ssm z+B}{>OB(*o7`T?9bj7S>!vg-~Vcv|v$0OsZ)dSfZLr1qAj*GM7KR`54dte@G4<^*{ z@d*LJrMDIAuL&h`Q=h&H(W`LI5q$5wD6}vkJSvZLks_#0&8X1grJ?4xUc6sE+4ooS zoU<^AUENOYl?i`%*|i+krr;J`_g7_S&Dg&-O~=Xim&IyQS_rB@@s{U#1P`0OFkWcVIc69TbRGyE6i+25s!@g4Pd&fNI?AWC8O(#YT9<8@!XzGbJ z`C8YjQnLE~x832Z!lr>)V*=mqoGSjPIbautZ)OVPwl@|ay;QkEop0(#>2TuethYhG zN>27YtS`p-7H9UMQ5TlpbLo{XKn!dZ@oZdNOmuUbo7F-rGw}0)?QBt2@>~Y$Jg_n_ z4`5<*$yNS>hz)!sVoR7JhX?wZLI55XmR*HC4qNUxO!8#Tpyv@PB2jESRu^EZ>)+^q zKF}Nw=xWywzl(n*Xa#S5tBevqo^qG?-luC2z^^e2kzFv&-nU2kGd^0|AOh(!j%YHk zOc(0U5`WRTwfyefP}sJyes^x)Tv(l=zYfDh2}vS|&$plYT*Bwe@TT-mj4E0-*5%Fk$xUXchCUl{-lEF@}j+^j3^I*j5Up>GJrq$69xn6TamfRs%|@B~;l`|KtJdxk^iSX(-w6=WuVO7a$#=z_0b5AC( z{6GIT)8X#c*5yBtNaHUg;@3%-oebTVq{ddJb9(O~joR=#Z)aY1pOIWwVfY7X;GQ$`y2INyDzhp}9wcXsa zuB)jjF8=rnn?T9ol85>p!;*}2V5HTBn?s(D`N0KTpCRPA6CrQV=WmBiAFDxs*317b zJj56N@=V&3XJOa~W+KpI{=HdASv9b3QK4Mel;wW~O???xfWDt)Qi`>@%r@)Um5Lq@ z2*rSQ%z5_|wRRjAAJ(*f%$v1s8~F_j3KWtuc_NIFi_$Y=|1C0y4f#hD2n}4og`mWS zL&Cn^pT?ucY@;UGpEi0ND1JA6-9H-17g_!oTG*rN>_g!9)jZ)d?4_U1%kTW-(8-Ea z3g>8XY}L0D2MIav-m=n}J3@^=>qTrm4GF=#&lnnY6d*Z81DgJ7f!AilLU(WN`eI@y zLa~fHMsK+Yj(a~0=s%Ob`U=}CU|Fe+$ken32N7#-lHI#6hnTy4tZWJ`08cn%u1b6I z4ZAfhy>n8HxkD@o6L3q)y=VCL(E2gPENUFvjr1me62&=bn#WumsmDRS0x@OB$ApUaK*@aT8O;pF$W0F1f@*PY@|9ux|H50(;_e7X_?Kr7$?&N@kAR=NKP z02ib|fm3G_`1(}*KEzSpkS=P&5Z)AeijZwor4t0ECSz!{nwpJ8ZjNWsr;_qs?pGKv zeSj6(OOU*6$Xm17=mbmvYw7ND`R~$JDUh}ZwgZzLf(Hs~gbko(1d{oCen=@a)Bg=z zjMs%x=5Of4-icN-mM{{4XYIxMc?0zxFiN6mv6(i5i!TiK35%sD3`~CHt``DAk8;PT zqh&}8b%9%X7d9-cr9j&)Zz_w_33b&;{wTTCQu{Fy*IWQ{CIH+6P$lPT%#UmYW}8W@ zmtsGGN#uot!C0!XF@Un;=n6jAa_cod5WRtK+hEbt;eBUg-o&m_XI*#aqfLQIG*}Q> zZ67iwtOXup0Bp0FsS(xoa^V9~f7)hKFutGva?O5#;#Q~qOn`oM&OmkWNvXKWl5JLx z#JZGSiJLSHOU8xwVywT{cq$KtvLNHP)byv&iS#IR0!dEEmiw2`8SD@8#+LZ+Z1b6a z{@qD>3ZxA*x@A0-dW4_ntLOitZJzht|2&Q)P5&Z}XalZ{Ila)%Zr}RFx9~*|7>jaX z2$E|0ltBIkVNEnb%N=NVcTfRTF+(71?Bb_w4CzH>+pIUYb1+Db2m{BsX%C$QN^2;c ze@)|)m%7UjeC?Fx>C6)|5o)@FhV6m0&4WsW?2hF@7Agv+>>p3#QioKZ)3Iz4EIRkF zYUn?&OQ)<}45~A$Bn|M6c@q_z_Go)20bK9Yl7F|o6C)b`7uS2s_;1rY{2d!L;b-a) zAP*%aX1m|-2%NJ#VfH#&?bCGg8$JJN?hz`sB$5Y2pDKXLfaq&8zkh~$W%3fjQqwlA zm(K}2DY<*EcaIK)exH0acS&Dx4mgG)*5}wR@*-{R6f*n2b^M+dk4nIhvG4&;_x4~F z{w`XPx+Fu*iyGk%jQ)nXGirbD*aGqPf6bvMA;}DdJzae-`tQX8UvD9991l!S8B2+f zZ0f5cID~(qeq;>q2?q7W1if4+H%ifem0htYsW(|)U9#OVGvYLKuo9EwQm|r^hoHD@ zTF3bDmRW(p^VrZ8?>rvMYuH#PHR4aW4?-fo8PFB(U65ZYG|azMq4fb3nr#e?Z5#8y z_B&DO?y7%MRQ{_GPbGvY#o%B!HqvJuqIToH0C#NumxPfAB#eT`gz@m0FtWS;JhD>n zwrPbwj!bR$i0tL80*Q4YkR5;oA50b(uNB)P;^H!ON^TJ5+l70>6<6<|WyVyczIFDn zeC>Q}?v_AzmwQHEJceJsVbNpmR@FJ;4m=lu?(D=T>RSd@r7Ee5eyoona(R#tfUQ|>K2~(y;%buvi*Zrh-9iHyE|5RN5H8-%G?f9G# zk#GNt^$zn18D1r@@;eS(7?8P}f2)}{h~kEQBmYU7k=NNkPKvmLyfMp!RqYu+ng%d=O+ zDuQA?UZ|+kCtc?C#Jt;fgL%vulZ4uP*w4c@#dYS4$yjHo=)iBkHf@ZWXtqR6$R!^cfRec4$) zVNu-O^sjE#v8-6~Z0pW+Nb9EE!$l{3l~Qd=Gd)it{fi7EMqu?)q7*PR6p!$nM=>3n zk0SQk+Lx+{Lc{8C0$o2#ma#8{ia&trtP7#$4Uv(!x}wIsTAlFi%;}81eU3mNTuQ~k z!iCuPR+@28j=6VWIBZxNaFfV%^^i@EWeC7p*25m1k)R-ZlT?dGYj#~XM^XqyDjb0% z5duwRTtndD#q-T1aqI~RPs{x&*{+GRu9=dhQKUe0!Z`Fg1}mLPDw@%K-l${j_Db-5 zCt=^hP_W`wayC+^2~%8-$ODexL#PQ+m7E62m%*Hshww*X<7#Ncob0!8-&Eq{98~(f zN0VbUVn1o>XrfxO1I@F=r$Pud4Ro<=FB8JJ%p=}78Vcd%l?myc`N>C+`f*H-1H?I? zAuo@RGi#l0z7KnZeR6!lV1FVPmc1Gu&Z9)RM9cB~Sn$O>$m)jZji<_lo_X*GsBw&T z@=Dlvh&iD(%Ls_9_@|g<-U-h4m~s7eW0Ao^a!-l3o*)@JNlQCN70-Ybb0H$stG6#9 z6>53z+|a!OI(v`x`qwneFCj2<_x%*}m`a%RQI??EEO5yZX&xel#o4mxR|(6b>Q~=n zcosN076xYbixDwMJN0q$$@SprPxBC;BI~J%H)=Czlp$icPWq+XR>oP+$~&oQ%ORL9 zHOn-!*eo{kxL~7C7b8)LgwgX>sD1|dg^S4#MztZiHvQQ3oryEG;dV13G22PE$Jh+7 z;k~wkH++t3@|iAYCR~ua?~uyF84FdhZ#TnWXELQ}DZyG1C7wsOqdB>|nLwo8TCu5? zb#v6}&QbHEw&$=~?TCg%At~u6$@$U-fxSGN7drHuLgKKEXScW0!l%q1Av$B(j-WRN znv}WJ{!--VkkZ;97W6E=@(-}6%n(20O^LOb9}i~&^WTr_94EqvrV+Y*BC0;xs&&6r zR?Yu#ST*?~c)`9EYz{7m^7C(V z@fDdC)lpg0yZRx%{86mOeP_x9z~$3RDR;Zqujlmd8uOak`*C>imr^pUBbk#ukg?E0 zsr`dJ7NXghK)$lAKR)LC{08|XLcfEh9Fxf?B3Rm+b}rLW%a7D(D|L1c3Lk6@i0|Jb zBP1pwCGOMZjT=hGRTK+{?c&&6*$`=oA_D|7L>|n!6tbw7*RQ{`lz^c=8xWSsD{~#R zqB7v3q2`~B5+>lN2};=v7)m3zmhad`T+zM0&#%u;mqif_=wHoaiV?c1uM2mPHYinQ zD+>&+vp9F?=ffG4+IZa&n-iF4v@bBh`Bb)Rzgd2{IpmvczTDg#QPF$p*E3QdKT$TZ z2lNGUEcP@LNiKe!ms~suB#{?#B!0UKHBj5H?sUiIBww~ZWvh)GY1K@@S-s@M87$mH z`*Hq3i3h=jEb!@OT)MTB#?dn;6Ty#^D)E6IMA7CAmj_k948KY4Kn^~(5?=2I4OBdj zGjk$rCjTgryLqY`cF^GZFSA{6QV= zPbsYSAa|rEC(PKfI!KhA3;qMfT}GKtVqI8UQS(EPSWM#&jZAwK<#MILh|nIsk77e; z->q+K<3#Lw_{92d-Yv2i)kPe(jll@!3RD4^Kgb-BZg3Pv;Q$YAKmy%N0b%|2IVk&n z^p<<%su+jelJhOlLQCksAE zQIFM%PfA{kO-qYqFS4>uwpRZ-dfey!f!<@f5tCN1f zzLJFh@_6vWfX!>aauT_{(jpx@ZI>2A=I~kNA&Ll3DF;bfrQ8LV_Y-8zA~)*f8Cn&%Q5OL za#@xY5Cwx-+StKMX}8bw@DSEJz%aG^2FqcNl1P$!5b(f`LN5j7M71R60x za25H+|7d^!uqnb5qaso*0CtyXfxJ~Hc+yfb! zvRH_k=W&A6F+9tW@lncd$zf-yf>ZX0f^azhF)}a&ZB;WSu<+>ad;=UPqHgZq!h(LCp4a9LxNwp?s=w@;ql-_M-b)ZVJ{vSU{6oa@@GDu6?Q(bw zGi@NuNKT`wwWa2YfiQbdV!8Im9KhpDau6#pk={DG+KQM5_`lFP1IEZ7jSJ5WF_-;A z#k?O$u-0p|U)Hf<|2%!Dp8jED0|MD=m?!=iC|Z|vP)7%QiV18=D`PDWr{^nvD|2-G;FXI2dqmWNWheHd< zI-Q1wds&Rgg`3_o%VP>+eFzZve`SIdvgsjg!zn5Mr7PR5L@;B&3_z!Fx4B|kLyBpWB@Dn=K;wC=($|k;9 zJ&AEey2W5y9*eV9pl3djnd0!|sH?cy8^^7qRD3B|0Ur4hm(z1Mw%9`e$Ba?p$n2L2 zn>;4%H-ZYmy!IY87kq{20UHBg|Da9uTu0{5*E+=XB;aR*>bY0QZq2Dd@uknA2XZBE z5;M2m?e`xk)EQ!ed!Jda%{_{5lIR8{cOzs$`Hl^a_vQ_bmAYXC;Ah*G=#=7j1|(6x zQ_!lhfk7FR5jQ!+`yV4M6P7HRQ)Fz|S3(#&))ShXML5dGkZv1=98-wN{E-4|VLqSo z&}>}NbL=*4=-yY{<<;RzhihP-Ci-CdM(?tE@Gqy{wR-@3#&&Nkazq9fy(9cb@chx( zLKmVOk0$^zE;UYF;+%F-PP+g(QgHJj>a`-908gh`>u#r|eVn;RG`kjt*zkW!WX7k+ zm;2AIK?T4y2*1kD-+)V9U;-ghXT`S-#DUch9DQNB}e&xp2Nd?Nkw77eb&*mR2I+WHrp71rgb3C(7ip}z>ywCeJ#iT3f zJC{$NyEg`k5e_tN*5U}B&5zGJ83b7QjYU&?rK9w`RhQl#=;!a&4>2avE6A*q*t5EB zW=9>j%^Ps!h3#A=6xDldTcKVTLK*sw<1#5E!GydP5eRykgJ`l3hcMs_bVa|>$E!zY zx^;FuEF88`ErEPIR5tWakPPQcz!zmo9|G~Cv4QtB4%^=<91D$Xh+mx=1PddvjruvC z8TiuV&_?Kugh{bbAyBM*LPX=4-`;QEt**V(6zOR;;q$1tYi@S&%CL9=MP7sv_)Odq zgl5kAk-cB3gHkCGtK&nsfXxJAVN`TT=}fEj@efsZ`2y0gjQ&=C{~QS43So}3sD!g6 z9cjBQoYjkWJN0FL#4CHY2WtXdbIZ$U&~Ed=i$;yQ zs7k|nKUqGumc>CBt6Tg40Y67ysVrGJ%U$wSdr^20yEKWnrNuq+?4>UhL!CfLQagO; za{86@&f~r`b6{VZtZmanE1LmFHD2VFWnvPwq1oX_bb(Q0={CAF`d0jYCqBJ1Zm(Mt z#^NN%%;C)Wy{2P<=h?(1nBVH%=2m-G47Fpydl;E_!KVJ4QRqyF$fAofDb)Ch zv0qAW{lv0N;AZ<0a1eOv_XHn4Z$A=Pf4LpfEu!X$DY6##Mp{?j1K%%N zDncCGdI%2qN5=FohdR#?`hY7CR9i$J9R#hsui+}GsArm4L)b0k1KPj;%=1@`#iAt( z|B6}YZ82q>bVo&UPhFpAwYM^>>UUd9w;b%OieU_6G@ZS{`C3xLCUws`2gc>@D^_eG z*o6>j+ZnZw9V5U&I}eJOuwT}s+MJ({;Q@@wAl)mURb*PCKJL`?>4s;(bipQw~zL#s%Y+fhE`$Mu1GOEPb-|W}>v>AzSa-22YKW6nTfZPw<6&NK?#<5!cyHaX`FIUY~%md-2-ErpkMTlL-7_G+h3eUf`2!--po|fIEM+t6oM=8$Y;|TGx*V$D6B`a5x^q&b^z}@Zn zNZ87%Sjrel|4Cs`%pAcZpgl!5xCRmUJ9>{1zrcY!It?dIW`uro8Z^M-$+Z~VElWK* zGVx6+yd-~Wh)IDzRRM>{pglRJ9;f0(t+yY*+VVfLwm|@En}B`}`-`;4`%T)T{aez$ z5g_eNL|D{=WupFDTbbxlVE;mVyb}r`9#QB0 zMd}e**U(4;?;*ba6-d|QKp?&Ndm!=r4kU!1mD;_f7(&x=X^P}0$~Ak0&u!pd33#-5 zq9-2P0UL=Ph4oGNWZ}b&M}yt3;;g6$%m{$@+mR7bsU&$nBcerP-jl@p_2QjnNj_(j zrXrpEKkU6_Sk~FU_Dx75A)p}LQj$uS3P^`2AYIZR-7SrzbW4|XcXxMpcQ@R>3(#?D z@Bj1Md%wG1%`nF?>ddvSwZ3tlpHrt~Dx2M`c`K`wS*=n>`cTaUW)oDT~W+C%m?LIU`~zfdRP^f>^IL-?Rvr|4NfGl zm7=EJUCL37km9Fc6k3_N-vlbP2y<0BiXC4E&?yVF+F{vpEweXtC2t%Q1aIU|X%X;A zP^gQL3-r(K3k;;X%~!OX{-dZL^ne?CW8R$?Vq_C38&x#E+N zI-b<1)_WQky5x^#B?62IYT_ZxS?|*cvO-PB30}cV3v*s!*Iv1K*Cpu{=k)A}Bkko( zt>6zNcy+BK{*blf(4Uzk8#gvivgGci2R|1gkIA6JHErf8Jcg zm)oLd)BA$KQc@`dKNW| zTj7pHjuZ$fGoqa}RuT4x7Z!7)?P{S4SNofFF>d+_*4IiVmwr^r0}A|JGUI4DOtt0J z6wx>?8(>PY42pfvq&wlKan>n)E3fa8Cqpegv%&%4c8aM(y%LSXPWxhra$4_<29+d5m$ggcBE3co=69vq28adqnO$21Kf!EC`T)b^P$|+wp8V zYv3U~K6nt=iRQHbj==|k=m0_JS1X;cPjCPMY@!>~@DPHm0X`NoF)fP<#vD3U4Q5%A&!c`+nnt1|NqLG08j;E5W9vSu3(a1hDO7 z$DO_2&5QlH!87JTw$xuHst67SXT=3^!Hsy@ixMRKq#{B4ZDqz+lcL#&?TE=huYCY= z83-71;_+_T*fG@r12*W*v#p0x4%pONvKgt4z-5Vx09=-HTiO7?0k;FVEJx}3GzYkc zCb11#f|4BzmG1BiS9HE0o$?`E{Hp70Qhq1OqORQ^_zU|t?OJHJJ@k+>k5wPX6yqst znzfkJp52E{usLj2yHn%`$H1cuU1+we13bLrhMJhC78@&X##U1ak%4;_q+b@l!_w6N zPdhO%)p4b&L0q1fRaBK|lNH^mzEz>C}#g13UvMDGr#Z@-rRCV##7! z{eAu11FUWyQ!m32M393u32H_JoD})nVE$gt@1-Iq8;5;4A9uz*Qwa9c|A;A#Odj$jQSUBZPg?ou*Py&30SkTo|>pJ0| zH;w9pfoY!{;LE-r?A;JoPOWclK4t*wECtYVjWHk*=3PZd256QA6k!bU$&mahz{3ta z;Ik9ihMEXB>8V^mNd`KP_qY&E)u($~AJ)6V{FVy{qk8ThUK1+$Q*q9t^uPZP!H0x& zg}L=rpd2vpfKh!zex&u=L27|tbUGzCxF5I?M_OkgQme3IC0P8m8U_SXP(IcWZ~zLLlW>3T7m!xx{JQR_1*wn#wP54n+p?GF?UJ|KfM?`V_CjBOzivRL zCckrbV3~dbY)`wifK@uy$gEz86zx>Qc=o$@xCEELdH7*g%XwdC+f}?cGsQRE>%-A$4RZbOyZVo{x7giVmPsosnF)E+2RPl`L?@6z(ESf$r zb!2~&didGNi8H?Nh#fX-Ltrn!J^35-&_EF40Ht4&855$U&e^`)sU4VZM6@#ZGx0Ev z>xmxKr#)KDlIhAfj~(!GtBX_co1Wpm3n^v1ZW=ZyD9v26wXD{}f9QBAXEBorj%_~u ztww>NNPRkotUJ0(5!LjdUEAUD7)~X{_<@pVn18|JT{i6>{WV$w=i@cK0+~ZH>Gp*Y zwmEDGGWbzcYl-F5GD|XNwwK-oJH{o`lQxiU8(Y0UCR^CDZn`?BTBHhA6Pl)4$}eOk zrn!cV_D)LziftIDM%WBi7&vdVC42o_h8+Ni9wVQfYl-F_arY70yL zIzc|4ep-IiM#0+oa^*$qW`ncj(E$HLFU2;Wyi6$^k0hOZUpP+^Zo_+pv&&1&5mE(&YUUIYPbNrZ+CL#x0=OQtR;^XpMc`dy&T$ z9P@pR!*Iw$=@w zK#XhFpk0B3dM03;;^GbqY;AT45MQzL==ePbgpis*O-S(k8#MTbXK|=-u3+TSI1m7= zD+gxS$SElf%Ey6>kZc`PZoc|eYqt5*(g70oyZ7)N?`;Y6Ur8W2U?ArB4uJI) z3ntRr^28Kw0_(R;fYhG{qg55)2pipTgs1MPau&b`e20dr z=RB7#{YlZC8tbd%=tiZJqGD{0GUe6h+Z(pW_#Y;HpTO39;$Hcuo_a9#+pRF}YoCQ4 z?;`N-N-TxVh4(PQs8)pN{xKTq1%@xTPy3H4_>ENVV~%O6iY@mm2yN>yx^Y8N-WzTE zyA5v!`?w*EC-9adWn2OxxQOY$^w#HhD?mu|@$AJBps8u=A`duAn>en(!DhMEopC=o z2<+&%6Fvbp7En(uQ)M*3gU-!v@Ydry5#gYlKVXWMHW+|_hg}rrg(ab+{Pv-ihlSlj zeSTcPPN!|y8Fh~^REVzDv9__c6ATj4G$G>wMUy-f<@7l?5{u zaWhpj2L-TTD5LTD6If58Q7!rFv8ME^g4c|DuB3Oeudklj{DA9J_C6rDxrD=u66=-p zSP|CmQraE0JxMz8*LRw!P@Wv~S4*`($m^QhRAn=3rY3?8@(Jb37%{*|BqI8NS_;Hk zy?YT3Ul^2*GR06}t+9+)D!D^mKzc zgyfQ+oT7}zdW6Z*KB+ySfi8=KW&2qLkA2mVZMA*;@no7qpV`M3Xjm)K4?_?cbGnA#M3&{?i6_c$eV6G4p(-ZP}6FX+YrZlSUfH}magu2R> z-ojqjSk9(-9T!P<=X-UC&>@$>dk3iO#Ppj=qmY$Dk-?JUC(0H?Jz~XjGf#D=bI9q| z<(vKxcr zxVQ~(yRT^+4H90dJtTAgEQO3oK*+<2qUOsESI0BhwN)+=PC9z)z$~LM$4MuD#Y+$ zs1?d25Fz3L*8zttYcwideZ%@4s44OXq5-*@Z0)klDS6bIsk=C%R-Scw`*p%}RtCkL zv_i~omCw+vjx73{BQ!qGbFqjbiczg;CA@kq_{JE9a&+aiEuR)XLv8F`j#9veHvJ5H zm$@%vDIBsP&g2FE64FMZ4-5{fpR*>p&q_(P#pfODkO6PP#~9T9UaSg1U)#QCh^l0> zIW{R+(bo!%4Pv{GpSHF;+Tx0-@8Pho4`E-sDm}0`8SYEW|1hs92+Lp7U%jPe$;sgu zr!2_v@uD%?Zcr-IvidWv!(?2=?iM6-Medo!QQf;Ak9wk1X?w)w@R@P8Sq{FA>J%?w zY52vZW}}X&cPK6%Rp39@)1u1dSk;!O*^$^EzX=e)UXm%YHv7UV?mDa2iMP>~sQY{* z052oHr00wiZS)McSq@Wc7GEpzX1eMH%5+XmBzcZ-8v9i#<5aa%))C_OY=i#N-D!9{ zJYTnyVc>7-CgnG{k&8=h78*suQb)>|mu!1RlpK~~&lWpI5Dgn$JDObz{0QdT_ass5 zuJJOv94u}sk8N*g4YziohvfZ+K50eK5cjX-5vo_GWw;+zJ=ZPud{_kQmxUQb)Lsl* z7DR*@l%cUN+txlG%dyr{!8p5&8*=e3lHb#ZB6ONNFtR-IX`2E*&Re8Cd)a}EdDBKW zY-b02?hlC``c-q<1`ZrL9n6?DEDjKfSzfip(Ige*p@V9?Be}VZ6(m^Jf^EI{pP2L) z>xwr7-HsMHu9Nd)*_oZn4@OSqzpEU2`)FVnjMj46$c<_8<`+kMPoe&>qbqFXl3;gq8qMhi0dzMg-MbN`ktQN@{+>x*yea!~}UH z9h{BSz^#`I)RageZOUH#1yfp3o9G`1j#@%zPvG#=#)0O|tgxMuRB3wG&Qr84;pT0D zh1&wkAXrSDBZ@N68iz@{aOx>&Q*%2(D44AqF-#UJuc@MW;;DeU?X)_G2;=GKi^FvZ z191Vgn~)#bVE>p)l;5|$z(@+z7pC3#hUB zBuYOj+&4h+0}>n!>XZa2~!8=iiiF;ZQFvA(5D3^>y-f zBY-s9%60Xy_eD&X9EvX& zE9xZ5dg39Nx>?fNYW!<3nQ>0`riYf*G%A(@dwdE_sk*zb9>!jAHDr%q!2E&O_36z5+UlBiXd~EIj_B>|Ba&bKV;wm!yqstTshj(;Rm>^-um$Rk%@&fZ2*o{!8=u9^~Sg}!YD@zSMHU%=whb8XWxEsH+YwTA57a8Q_Mwc`J5 zo;k0bgVtj49BFph-jO5c(wZyBAeuXLV5&OU?VZ&7nmFU4#Wg=FsiN-Jm;1&R(8p61 zyqCG?ZgCL1XBbX->qhl2ObrFXluu~5ti$YgkB1gK#JRPe)F{(z-t02iUeC9zl>C@# zYkt3?1;xBwy8iyq?3_^t5}uisO7l`VUD zBS&@uE5lAMwf+xXZ%*Sg5*Wzdk#@uan7 z#aw=47IG<$GV^sFG4hF}QRxRy&X0aX8HE?7J)Di5I-MIGIHzMk+)1~ zs_4P97d{_O*=@5O&p7wC@qZjt9a24$8eENWjRUaYI0n?W3 z59BWoh~@fQ-lxY#Ex;~2A}_ZXyX0f%k7YCJM_PDIrYS!^P1k~ejSAQ%H|Wu^s|YZk z^0brcFZKP>q>kfX@O?NeFhnWq8?!RFPZe0b)bpGXzO^&l!&T!U7tN1KJI3K(i?z-r z)0IY)5AC!y4MaJKsN_DNKiXam`&gppAoFO2R*L!6JJX%-BV1imTQOHpW6tPV2d}O* z59?b!QcH5g1%MnR8cN@TnDZqUEcWFq-OJ7rFJ7`4TBKD@^}{+UU;F8p&3=brVm73w znS(}C0p-WEgMGRSnUidk=jJt2-Xl(ZGExGXu{lEi6bUky7o4lzCleivv^@c)u@B!_ zTLkCJbaN4Ev?e{t%Xp|F`L;aY$ed!^=Y`RXP$Vf5iP6mZmV6-l#c+EK%uHg)vS78s zwmlkOkCtHd$aN>#%HjKtuZ0c)z98r3jtjvRp=uqtd{^D{J3lJYso} z;+QC`w|?>&wfZByQogQq?`L`vOi@uRa0R;=N%70JAHJcjok~)BQ;Q`<)kC$_N$?bBnA+E~^t%tNperFhIgiwGv!kiKavtGY-s*$C>Mh>8&6ajP|o*{{LEeLvAbH}zy7Lo z3`O(H)fnAr{IdSej)}O>Y4V{3N=ejX;XK+)- zfo1+=*;9E|`v#Lnamer3U*MtzG4X1lP8zwdAiC_)Ol3>aNo18!&yQle?)2lw1v@3= zXIy!X%qQzJ9$L!pvafY{GHPJY{GGvVt1(5xh{+WVV_L5?b;e#?;MnHCl$?`~d1$)B z&?R%^iPxNPnG9R5CwDZX4(2Rt@pQ=mr5=EXvlHakF_cnL`y{rfT@$IwsyX-$KrSUA!{vLfj5eiHjEp5VYUf-AfSn;5V2p49*H z9255a%I5-=rl^!2S$}}9uE9vI^kokV2-a2rIz+hE-;tn-z*fyqK3(o4_f@HlrR5)3Y84EVF}-oua#zm1>HcVzSZwTn^=-w2anr%5 zNcs5Mc&%dwa3$itU3(PwdomX5k@C-F-h$d6pMtTjU?u(1HeOd;;#u(cSpgb_qhCr+ zU~u*7(DSwLuPVM=p5Ca48=hw6c;_k-pL9;Uu5_N53_~6ZkObKx`p4v+$jXnQm1+M! zr{e#GQ}Kk3@J~)f*k>kpPQ}+OUmpL-syK~0_>WG-J)o1jb1L4e`qaiT{uXAZLhz$H z83ejU2f^pyv4G5pKgQ7U_`n!C{-zSC*u>P#LHBc~_`_s}^B-SWAg{1m=9ZT7`T&Cl zw>{?Z0QlYguHxie*cmMitsxPs{7q3IARO@tO%HWjYo`wkg)aym3Ffs2zK8geHk6?W zd>whoUhANsIPL${{V4^o#~%qldf`Lm12WJ8AabU`cL$GxojxRMJa%16ioRUjv|4G5 zj!tS^)HlaP>|$F>jv#pYDJzAn5wKNEwsWgFa_2BG*A!w>A~Cdp`LhC1dq^U2 zFhN{OO!oQ`oIsNa%3ue)?}m@izNCb(%jT87e$a*skR9njsu5Q&Vh<`nHWE+w-U;iG z#NwTq%i}XFP47Gy!-$JhS?l)Vo4pc{e*_2CjrJ`*fOXb~_IY3Scb6zJi7f+6GY;@T36B z0$VuzUmJD2-1N}DJIJi>9ArOGg74WhDtbnN|BMxSHvPFQD%#AUo`%mlcvko#_n26C z$l&Fua%sSI{b`4wt@9I8OHsX8(cDTvY6sZA?w12>>X=3Ha3OIZ2iTpJP9v30d=L& zuCNPW@(#IGc$#g)>bAgt2lh2}M^;L@a35cAMb6C5F-6X#Ma(QeRACP_T*C*{o-Kgd z(_%AJC?n80}@d3#I*j}eO*IY*-{)9&nzFdZ3 zLEUwy+u@UDWwCLD%J2%kj|cj;ho_5tjA0?*FF2hBy@1pLRUH^IF)#Kyg7{W&5pG!5 zUZgpckMT|5oRfJGKAU2I`Oxf^xdo#(|J4heb^7)(^4Y2TZUm5>sdETYY45C$lSE{m z73m=$)d&5Yo08u$2pH`TY~MYB?R!pIC+#z1_ydvqD0(`6lN)UZY#@H1+sG$ye*%%@ zz*C2I_pg~Z&d#OBkW>AC_cD_5AhAPUO*jIJ_{npAHTL7HkZcCaY5fvzqQFUYtIaP} zt-#0p0Dvk`-a-{t_fZG^FkS(EI@gW8pzn>;h2EgUQh$eb%*L#>pa%UmbmM+d;NK2& zO#oveXt`f%vH1qX8;K2@y*fciT*w1{J)}D;kiZCHqQy@*BX9^czV)U3mJRTjB2E<0 zdOY2d`MI;Zx141W=TF@cThsumCko^(Stb8rxRkR1%Ao3Q+!vQ9y*< z`5)*)IIv%ybPaIc8D9aIt7`V#`XPT-uG0k;NFgN}DJ*4B2{*4DxRSzmV_bv+n3h*6K? z!+ZPI{qx}cXXJuXRcXr35Or(G!nHWf1*`6X1BW(n(ZHC4@7zI-vdC7WAZ2Q_7Ts)3v~l>jjo z!4$1iA%G1Pusu^htZP)A6Y=|pJLEF={th|3zeDzMffw%*gg`?LQ--;P8|QMkMpu*E zf%9R)3AR%{+{T#P)5M5VaRi}5Ae+Otn;wfJ0y4`70B61$rz>o*I}9dpUlYjQZ7ihy zn_>?D_1XJGi?@pHl-7bDfD0N89ttep!PYMEpBk(H9HzcQU{0(yDf*Ffw=QyA@5WXOp~eJ?WWAO(8P_v~!1RrafX7Euq=dZ!bN1A66$G(cM$RaJXLj zj<+POn;J9Wb;<1RVs^<4cFME_?!Si&vL4i)>F177hxlw|@Dj&hbHkS4ej%hy)lj9goh!vf$ zqf6QI8FK40Df&g5wNX9}>}@UYba-F9O-ZHy5^ zCBO{`k~rRb39A_Xe^o~?F;OREbE6xG%% zor=drurJfOd79KHisp49Gzz9lbsh!FZP-YCBa#|?jVf7*Ub)IG!C@WH@6($Y?`8}#_&9ls|c&*#p|GR&0g3k@(| zd0*q$N{_RyFHZ_r?6cjOMEax2}yYq^A485B$4P$GknUwWXTyd{>XT!iDP+-NwkZdM?bj z;SrOK3FOTS0H=cm7m1i$@apL@2~!fqI)QX%W{yO6SmW0)mZZHJB@fa6( zJFA+t%p$mWHCM3}^`wG|9p*!X?!n^Rfhqo{eyHV>ypdpk2O7Eq{t%JQF2=r)Fr&C> zTggFo;kAdXhy7(L*$w`c`F4u}965vUKXF$%ie1Fa=+RkPp&o1l|3K@T$}r{vieSJ1 zI#k5Xh70@)PxObfvi#qv-#&0L6I%{UYi&dP_AW?5ioBy~idV&--M0cpdI(m*(|m2p z6_Pj%T8!Mo|Cq$jR8itRXOn4b3iE^Vj?+E_f6~h8&zcUC!n+vlw4rfe?U@kqq%=au zFlgSPL+@L2IAc&G`M(99HYLGJLZei~mSvG|?b0^eoWDh$2rTPVd}1|7G09X+4~6Qx zVXYW~u7Td=XTj?py_fzi?TMC{)T#bH;x`hc{juZjMVvPmKFY%bS)D<`NOh!HE zzhSU)|5!BJw_`LP@vl^d&snjj+1wppkv(Eu#TFT(v3CtS==Eoz-Hfk}HlHg3vyD}Y zo`3M*%(qsHb?JjqfYt<|vV~eK%{%MkFa0Y5j@{*_najpCfw^8c)#A*iX&lCsXqB1{`Ql zdUgVjAURqYJGgmc&my#Dig%|!9+b|!b+M&-ERU1LvYqV+bm)Ml4w!}kV2q!GFj+*< zAne;e-&mmfrDPzc7z8OH+pyyOHZEK85RHdeL{UmKJu;KxQuy{EZbnpw?|pJ+QST;SlVpY{86V1 zoYz)hM;{@X>t?0ES^VlWbG3%AXL{z~H+sG%Do!?Xf5xe5p7%8PKq?xtP{+((ay1{T z`FRXXA+qjh*7&KvuA+5$snnC{>dEboeJ{TpRbGD9w}0JgR3&R`vQsw8-J=vYgSflz zoW;IROY@wC%~JVr$2I_nsKKk*9vRG4*EUaIS=~@i%(C{09>6d`v&XNjRznU$K3j-XWhKP1t?jz4F;))fe*# zvICjDUVn*8!-hOJfu@07-gC2&67iH&F8Cdtst!_nJ%rOmdmD*MczFRwa(k-Eh{J5$ z5LyBH9#|drY@@GVPc8)eOCIg*IxPfOzgUxBSd*V{#J58m?+RufK*;H~zb3jY-#xEO zj1hM}+Q(f8J2*QUeA8RG1FNW9XPE8NzCu%7bUJo$(6UpbJj^;L>Qd2B@>t7noCvQ2 zMMokZ5t4Pppy|uwH||gh@&Xw@v#~{v6QOp9G4FNJyG_)s= zl#g3G7bg!Flk1Q6`tp4G>6p4C?3OtkSm_?+`m25>Y7$NQIMJd$SY5a2Qy~sEBm$Ky zCG}#bF+=seK3cn@mdtzU4@VGkvUG%$kWWVn$a>!GZ_(y$^^XDcP&?7`>{ji!a&;}T zUtp2OUrY=le(_o6srmjIZYCpb{2`5wy8?xRdn6feSwD9n3`e2#doMuIh~&P3ZDY5G zioNcxB>ytwWsJX+j2Ow8gXcb%uj>jH*SO_5{_XchO+}@&qtOYh zQz8=C^C5th@nm%hhobBTz%s9f7+y6&0cn(=|bAb^|VjWBXocR<7Z@+XrV@8@6te%4{#n#?EM8v1cR zQsJ9Bu2mY&9h(C*7*ctlhWZH_nv9_9kEuY%?NoqDnv+->CrJ!&+uR+dry8-~LDtmT z%k-~?>O0W@TEJ~G5HC+00f1BDCM_r>AgYNcVI_XS%1%*JkJ)ww4gkzm>HVSFIDqx4 z6Vxl7K*(?h6zBxpdcr~;AHZOQ0I^Ku!T3`xzrrJO%8>8{4P-Ym-eZ*orP94~sbmTh zv(})s|9l=I*J3mp7w~qQp2MPEX|`!naUfD_0<9fiA3%}4zROf1_x=V-Vf!y|M9`g= z>=J7?+?ZCZi!%UXzao7Se4dur1DQb87HFXyHCEKA!Ggj-@Bq9F; z2U|1WB3bMR$rS%nT-CPq7FS~CpeeG_Ha&{mHtNK4CxHH|1fu`u+|hqYJtWzOfuCux@ZPQNJ!5f;BZNpkN(c9<6XuAJ|>q> zc*N2)og5(G&^>qRr*YF0AlLoG)~N@u0%s{#mEHrY4F`0VthxR&Mb`KM1#TMH5QavH z1P;pLF(n{Vh`U}oa~ZWu zarv{#@ZXSDp=;NmQzRk@z;cK_u7d6P2R6V2u8dl$ST2`6Yl9qeio;2;2ADhgfy`a2U4057c>7ML!wSGa-L0Wu(VfQV^8 zk$if{w(8cfA_(>KR0|-JCCr!hI}Za@-W`Ns*bLk`=RiFcm`VNyAy@}~{ONXWu}fhF zOqJ4tC%G0It_HR4dV0xHV=VL%kNe!wge^}k^!Xxi*(u*V=EW?V7 zxUrvK>DamZuk-;u9i0^zJvNFd7(FfIgIr)-Z_NMflhgiv>?MCEA|e6TpRm6H*3iIZ z6Ccq6`yPQ&9N?tgVi18$BM4x3Gdea#^QWsxLkuj4RbRGKm6yQ-DE(Dpk^i*DGzN>% z1LBVtcb9%b*l<8^9Q5L!A36A#{RsO1Zr2sR%!&d_`!VI>MrC$sS4AGccF6Dwa#NW3ao0EwqW0z%^9 zMIt92lP8!+U;=?*%AuhVk-?8#6fo4yxr?pTRd~KKhgbL6u|B#paHwKAd?=G7SStW#T@>Ln%~|n1K`J68;+pzqtn~1 z4B)to+KSh2kz&09LHBMciWWa9iY4lzo4!wXvh6r;->%(EnY(rFrktqApahD;1!Oz8 zf}>igAOu7dio@4AjS3Z~7bq_u^iG@?PiRsl8;r}Si0cBtie}93&tu?_9}sJO_h06IM=oZrbbWe=T_oGlXucH!KI{IUXHq5nAD-Q*1)S^D~nUm$0T1HY0ZQl{GSvLd@OV3&#?a=VH%~qq@ zx}Dr6@sd_S26t1JJ0$-ETiK)vE?MZT-IKi zBfN!lC9lJL_7H+WJc{F5=JI;kVT15|>$&rj!nv^x*#tgCgHhQ73EqW(mHx!f5Kh@w z6`7YaVyk|Nb8%rk2`5sJTNwB@FSs@#x7RJvWj8#wN}XiooGx`&@im+$!m6x+s-F#1!tl4OG(1IF0K2X)b=Xv8k0&Z zTxwiz?M>V$B`YOpZZcz2KJWHa9T<;v@${gOLl3+zs~3`RfBVf@2f-6fcAAct9|N<| z>lFin8&i*AgsGdADWa^k$5wGTiB6*{rmzmS_gAE5n;_ztEnM<<*%Cntd-N)G51oo3 ztj!h#q8#ex_pN$!TRcG~#%JVtPTvq)1(7Jv6$fO~!pl#_z}G>tCY3A!H`a@HTcNKj`;y*g-Hjwq>3FZ0kV3l2UUs zqM5UKGgS#wHEVt2Xf~aKdx-?57pFGCwo!h`HPPxnqos5_2G*ywXglF!`f@8EC;y<@ zX|T!YMI*B0_1So{YpG-PanDG6>A{hOaajF9v)iVt-q)S;|0a&2awd`N?B|k! z=a+{CIo&l>=NG`d`l3+b(u7?A=A^f}sChnhLPso+-z%>5ii`1J;Upr={$-)h#c=+C z1AE!w&870{liO#1Q|7KepE_*8`}hH6O%z!daPcc5^!t#!M~45Pmwm;n8le$vSU%7h z&{;ec6_57-Ira^TxKgF{qsBy!dEQ=EbUyglq!v65c(yT-P5sF7HACI7Aee?l(S0Ct ze8)C8j0>z*^JV!cOFcjBZc^~Zwv9J(?UBQd2{FxN1sQm6*K)N}m7f#m$=HHR72-&a ztaJ&D=kqn_ECMzibp~)REu$o7&h+ls2l4N-=b9fVustB(&J31&d~{QVto+8d8oz74 z`Py07d28~VMTQ&$BjO{+DZlkZ*N!0g2!_iB%4bgfXpM!1RJX3aIOQeA9LL449vk}= z4qK8ATUF6xcGt&kRaz!=alEmXE-@V3%Zi4llY1lbdj({{#ZplLUh}z z0I9{+snzxR@!o5pZQK!p7<;)XufAaKseko}2x!=0cU7LR$pfq?q^k(!Nnr#=&=f_8_H@`KIX->I%6!r=w%n-KT(@YXjQCfJ_T5dP=w7Vo&<(fPlAlVnbu1&T|1Q{B;yK%%RirIQ}MAp(szd#hgBP zA-$m&k*>*g*~)(%e{5;qltel}31lL{CXoUhpK%p#euC;B+nA{W-|G6!%_T>)#gsqk zP``pN5E~+deP^MKgtYotdMtC4yz*rxtlm;RpJxDk(LRqM3`>aw{nQw9R2M(cl|x*Y zu@&aNSFFeI$SE<|Zk9YLN!}`-LFNv+F_Q_p@%T{fVZ3`OHp_j5{P!Z6mx&nN6$~52 z2M|U?V4^r-2_1mvflK4Qn+iDr?yth5IRoF+gS*foxMaw5w}& zilDvUoaS|+Sh{wC@*scdd#I;e{zKv`FAg1UE+fyRmp0CgZ6t3>pFaU`O_|*rI zKFkM=IIoH)CwLYY>F#bdT@xxTvDGHL+_i&2RQ zO+2N2CGZ>?EbwH(7|)*t&vs9{qz5Wn+ECLBjB|&;bw$G0#AT#swy1QM=uiPB2U0ka zmpU)o*+M!N11lWM$K0y5=G6?ErdD0cxFv*j zxEU@T=OtgeCkDsj9qNZ(kjb&-V08rXmPTb5Z{=$zgY6 zPfupXk+rR~x)~<^@lmOfS5wJqDWZOHOc9!Pz20<3ovL`;OTHdM znBR7=16!npnSdN}3{q){EV$PLErCkPReZW|r5oOHRvJr=RY)GP94&q}NAB0(pMXc% zZmgop(e8RvKS)$In7JHPoVc2Wkui$pur*nDt+q^Tc{q47^dzU+L>TXApVSrGcrL$e zHjCJ^(!>t^4M$FsZb94>cgfZEM$;Cq5}6INdePVzucoH}o*eu1H7dxfbVfV; zeskqL9EygoPDvj4SF5}k%;?!&{xE5FA$vXxG>mqyH5ZXm$cc%Kow9^3P5i*XjP&Hn4|HpG#OBPNl_Tm= z)-#Cgm&cr9SBMudQ5M2CvnvjmZ=!p)zjN8+KkIo%wBX=oAXCpVu`3>~#k(Al_toBp zals+MhiMh%M}YfP0Q6QOq-q>e$k_)v}=t&WqL6vbNoe{_gg$8~UDQi_w$h`1$Fx>cY3DD$g&g->j5)yPna+ z%HQ1AH@vs&VEy7DJW49hO;Kba`DX?rE{CD|GC;l#Q4uA2sNl=7M$zDa&W~Y~(gvK? zyV6joj&4%6hXhsW7`pjIoBoe~5(EGuS@U6qxx zfw)q(Fg*%g13&Y5KcAee%qUiYhjNB+EzGs%7oYtUpZQLqUa$<%I3uu;A@~n&h10HBrz4v)8=I zMSVre2J@Tfr)*6vO|BK;FdntjC$@q!<(%7&oAPd?n);gCz;fcHn>Y~q(3F$5vTD~~ zq6GN7jx)ksWwlPmbBw;aom5vJC4W22-oCWpD2=-h! ziz~$`pYDE@f5=K3Mo}YD3*c<0O@UHp8n3Bt<)MYv-oP0`Gk&FVYVh0(mnbdE$6C!r z)*PP*`r}owpiPDi+HQ9c9Ka6Zxy}!`#f;}fL%lxmgTj%8OVNl6Q*g5@xOp%KDPCR( zUbMEKIk>GUxIb2!e0pa20n;f3%d5w?hZYk0^)WrXpQSNzdd${>e(;7$(}6&z;=Gcty;{l;DqJbfq5U}1i{a@% zD#3g>?kia|b@riqie=p)@Jjxq;^z)Rd&wRXrU!p}&+^>puG;yFMs+DQnI6!nf;5Kj zTOdNTNMFSP!x;`>IAf=!Rr1H2kL53LDxNV!aK3vaEUZT_1Pwqpqk#=aXrMD?Ras^L zLFIa!!#``jg2TU+7JZ*r&s`-ZpSH+tq+6p`DiM#X9w=IxH~ssl?^ibLZ%Jc6VzA~7 z1FQi;oO(UTy(9aN330c0ln%2vOIy%12MLK6$m=6-B4Opx_C(DCSHR)&Z_y<&TY9!rG!w8CcS*hJq-87J;er?~oRdi4wvO{- zVq(k%QX^EgJ`{w(+pj?=!e&d?2R~O zc!N#17w6P?nZ01fv4(YpeWqLP%i%KpIdwedTbN~VQ{O$N1`Dh>bF76imA1OsZ)njzlHKT62xA({L%59Gh9tsm*$XxEVeRFd_QNa+FZaFW-o3Xu-3saHbj8`W zYD;WEe7apVFgD$VGS&6XFolnKieaa*yN`CJG~G4^kJIqGWl+Cqi&yZluxlFQ!>B`| z4@J1L=nzMxs8}}oE@zR)m2qi#qy<5i7F-_H9wu@X`|$|-D$n~Dl8)v%XZ{awZyi*=Wm|paXi7VvS`YWV&$jTwSGX>ge#wm-XX!D{5-cp_2tu{FVRx`eTPz@ zz)=%EmT<)j+RND`A$>EmQ(TSUV-fF?7EtdOs#{0%9@sU^Ih!$N7ggF$Nm@_dN}Z)& zPHV@DS+6dbOAH(KW*+&R5Id~X*@myTF6s8n&t?tx+^s!0>pLLuczTZIOih%f)}p3E zHYB``-BJ8uTE!VLu!uS^%2YCueCM6+J00O!R>4@e`}Byy9xqZ}$2ro;y_&+U%2t;r zw`T5r9{MtOtwOor$ef9R@zD{Ho`^UtSd;k+qawaBY0Qp3W-Z#${GxS~E{EKnUiYoO zF?`ZqhKE5#@Od_sYD$kexW{Ns?hEclVV~lE@{hzF9!2Q6Rocl^G&r-W#||p(nr^a9 zjI;DM#L&Sc$~ON<(S8@d>zr4s!Q=R&SDL76?L*tH8cbFEi+Ho{y>Qz@c2R`Bq+&$G zwrUOo)!7H^u?9KjU}E{OotyzpATaLSGg1Q%=j@wpD)I|~m!JEPYU^?A*^S+HPC6E~ zG&yimAMSP$*Rz5yzs^rp?xA&uFQ4=5m7PbjyU`N=T0*n!Y3b61a2Hor3}Fm%bvM@} zSC+X_=_+oE9&U_-r$b+`)ATHzrAsB&0}aP)sv${CYqm}{!}$`-x{t6aO5Nm zWcG8?8-7xvooV%^#X(Se8}rCep7R?fC!ZmHQ^5vJf@>P%<+Z1ym+Q{#im} z2CA8OTAdg_Rl^bJ(CK(&j5eNjvO1on@aL+wVB`O^`pO_jeulb~!ii+EIT3DNPSJKC z#eK}h^UnxB`)c^F;=nFWyV=zyo;l6E^VNrU9BM@>7$)?)%pn>w_6I2qmRqkjf505D;NwBrxT%GY zg|LaB$n-{kf@Mj&BZv-l*G212;HHP&*$6qa8&O7qcLJ*;n!pK`Kys35bWFVB8?ZK9 z6q5|YGkOVnz@Xx_vnTOn@40Q-i-6KT$b59?Ipp|t6XZ>@;_Gv7hRHUTv=2Nu+S5g8 zeJ&2bJE7s!47B(&b{xr~R6 z1H@KOM&`MmP5BqB0Hc)sJ}Deb7G;GP?`(&AG>K;d=S`4vNc+TjpI$a+x|1*Ls|6yq z-3uEd;hHReo*;A2#&%hojzP#cQ0q)GtEt&>z>}Cahr004Q2)RO05&_8;qRhJY~X@9J(k1kj<$U(hB0+=vo? z>w(D!IA=%3H2yQii&t1BL~`*o2b_SZK9m2I!fR zcUM(29F?mDz^iTx#y66XJC2V(MghNX_Qrmu23+R_q5qT*0GqelI@fb4oeQLAr)q`E z#zK8eHyvvXDtB0f24oG$BR^@b#e9c)4;hoSj!gEm4bL)B1c^3qsS2mlW5cn;gg>(2 zfIIQWh4X}qQBalOBD55P8Vb;D_5a=w4efAnNH{_36F>2~q8N{DTTwwT1nL3xYgT0a zUo-;jF#WJR@J%VLi@Mk5=zp{oHTe^#-w7juYM0l@WJ>3*U8??%$1 zGibEKMr(w|F+V6#qkQrbyL6f#xQY|`5hHoU^+g|{Odk{5J6xvF&o`O1&x}Ff%`CvB?Z^C>Yp9&B> zCjN0|=m;`mM25$JuFBY-reVZE=!6$i55G4xMS_u0Bd)6eB_r26+6QOwKMZp{dY4sf z6x(myW&TUY_Xm{mEdKr`QUV9yYNw{(6lRb3dqc%j2eR_*cVee4=uj=%1yqX$$pExy z`-Nojq$78NLa)8T{{q8&=UWGn-oFKTQ!Pw=7`=zN<@l=N3YPvLV_tU57)YG_NG<`T znvJ@qN7hRw)!f^sNEFcM5~+o8j4aK>SDSS#%PRz&B`b&19`-8y^pc`%q zl0OcgSl5S79}%)&`nO+UB@_xmF9WQ5gtn@Yo!|ebr405uXaXRU7IeH|p@?BXYYaGy zf8^hM{aWOD#bh9wbhIPH)7FC?{XevhSEgYoZ=yk_VENllR}vTo?2Iq5h^x2Grl6|3g3O zZ&v!(BzG!#5M81N&NLT@rZ&j?d|xZ3p_JqJ^nokiCQUw3t=+hzUl5=8%g=_OFg^~@ zUdy}QLppf?2Cj5%`RgCIv#7nvCI8-){^jxdbGCs9>;4LuZJf_Tt8WjG3jYdZ_{SF| z>?FWtFcfBq^Myr%@?(KSoD-0ULx(2f;N^E7Uq|BD9!a_S7J!O}=R9Uzb|fp@#ezm+ zGGa9j`$uf|SUl;Ae`z2KOA&r=aVK@5;Yux_$0nr;y?~+nHuzt)d#^;`Z9>Atsl!jc z5|(%wbdC+zjx`W+RaJLvZ0uEeYm^sg69HK`rhm%9Rc;G0(fk|#`EAD-W$bG%nH}F8 zM+{HZ^yO5@5tm9kc=V@+O}k>A>xiK*ApbZx%1A4JDTqpe+aJ^M1DFA|n52%gw<+-+Ah#PM*AD`6NJT zZY4|fi%T7bJcyeV9(^fFUOV`a_9Kl8o3iTT;7t*xF7OCYkW2CiTJmuhT?)zmY&f2y ztj#C#v7mJ$FziD|R19NWf$J%``4yaNKGBfcbQ5^w=~qmq(R+3bRi5c~G=qH$CAtG3 zYx1;+7+5xK?_V7!QAMj?{_UQq-6fOLyId=wS{uIW~n( zXwIZ2Vsj$;iVqtINL`=;0jbODfK+%5S^dUyFrdCmYb9%B)^@)wyzv~U-C;c*V+888 zPFI{`j3nl9?^eWQ3YJ&UxUg=gt>TkQS$*+oUV$f{qr$1x4_Jmx;PLkUvJe6f>uK}u zjN2Csy2Zk1{6+ zv}hny>C7NkKKk!9Fj24z(T4YrYTl0(B19>{@v}!+d<;PLR%R#2&@jq}>4K!gIb1Z_ zalrU|dEoTwYk85?{i21}UEKzZoyqN*sl?#;Xt8v2u|5`}!Vd2uAo1{BoYXSWl0Mv> zv_`18IpUT804lWWw|l@@Wb!s79P{nQs0ayx9g7%g=O_+=*V1qd_w;+_9jcMu@CeDL z{-L|}N`enor6I4KgJuc=QemTzQ$O)tMd^ogDhu{m-0cCG__kT;x~+1Lu)@zpNfVgX z4EDRQu&XY`?a$Zr&L7-Pj8#)BY!By{Zm+o~Hswj=uvGw32J^aQ@z7tQ1Ss{AueI zrR}c|cl6doCHvK9#qFK=$m6pRmJA65Gt;2FLAHeX(dkI0E4|cnI~^3Wq$hxfd^Vt+L)b=iM(=;^}3 z?K$W=d;YaIY=0w*rgnc)+tjI6a#gu6daqRTG~`Q!&Fqyz#U}Rlix+&gEIi0g(Z(Kb z(Y&E7JxmH`cUYT)qg^t$gaC?;OIB%(YF(lqY{%--e~J0u+#jdgdva&y=yQp z!9XsY@qHY~Bd}Rsp^L*W_9H|8 zLrfAjtzjeiFt7stLUNgbQSbhj8`57GwEv&v)idij9-ZQGH6Z@1jMQnz2&X&cpGguA z6t9W%WRbO|1u~fQI^-=fPTyRYtz#6z8^*x%tG486*v1zm&_L1<{=s#U6XO{hv{DJxf!39l`?HQuQJRePKsbBS3qF;{kxPWaJm zDq2QwHjHtCgXiX?RR#Eq=V4vG*mu*e~^2%;mp}E%jI!gc8^Y<2zK0TZA5;u6+Mv_ zNnhJ^(qXSE)@8V=(C)H%e^t3!;o~PqOdXn@2#tt)SdPg%>gO0o{ioxDzS@IBy;w#d zOrHYgsv`xll)Wr%o*JJ?i?bs)CksBg6Pw$6>+`U@6-f1G#dxV2Ih9UUw7eAoOUgK% zp9ilzw!`+4XgH>8)T@Ut!s%W~w6KE;tfwU>_Ozc=;$kx znF4QyGDz%;@wd3WlN=Svh&eEXUOX%6tk2mQ?U=ijll$Ol*P_o6QU;X^rRKVKIPQE!LJ*i@R^wZr&NxO9raZU9Ovmf)7@tm+YcaF3aDGy zW$S^0+mJQTmn;r=$JFO3Q!4Rm67j|wJE(i~t-NdbbA0X~XKm#MS8f6#Y#Fj>*PpdH z11}hU^247CbT;QTnL-aBQy`@MJ9ZN6QAzp={0_QAjLnmnocCnlD&5n<&pa^VWcLW& z0c0eUaM3h<&#gLprpUdKK1RhyQ)T_C^k%Bb^pmE215P4<;w^5tC$}i#zi-|jPWgw8 z9iWEeVZWw0XIx8{!fOIERZxrX=8dQ{xfYT^qZmd^4Wm$22 zRDVpef88|Qoaz7HGqt>qfm1yZ0dF~Idt$3*;KcRNQ~d#4CNQu2WlM8$1AsUk?Outb z0;|Hmm1+OCo(n0}Kb{L0uEd{6PXxJrL96F#M$i6`i1q%S*s+LQ3uPXBNU1|#@cp|a zXzU6p)3xqgOxjamH!=jitk3(-H=Dn-(AW0a-Mc&6|D&W9`aicp}I`zo9SdLy3=9Z1*Zh)3(->Suk@j>F}pnu0zOJ+fDnjDZQ z09wPzHmrZP@pOQMPUIhLy!XHPV~aOcx&Hx_1|9l=u1uuLxF=c<24R7uU_<(OF(0d)Ke+$KQ?Gd{HCfy8INS!WFUGs{? zf&jmLy=}9sSoJ)u(r~LU`Af1yei|SeKzRmM*F1xBB<-rVw7|ppL#Vt>^UdN%HTLIn zK@B!1zRe(9pjxcV_&^oA_yz%gf#{f;@bTkq*aZxrVEqw{_%VW@jn@c&Fa8eR z9&P<8edInffR+F_d;}&>o{(is`+8Lm>?33Rkz)31zrXhTWdVk2Hy!_Sn;lfkaqJ>r zuYZ=&qtq$8R9$-2e;4;5m1iG+`gU7Xn|sMd?_3N~*9&E&fqj_gG{5)0o&RtTcg@;^ zUV~6v+c<&Xl#{-mKsX09IW;@$TDW{KXdkhIu60H7rc6uJ1ZT}r22BZ3XAyTn8+Byq zy9$5Q#GTli>O{GNtMW(0|cyZ=Ux+@_x}o5 zz^|zkpYZSPO~BvN3M&*)1OC7y z1`+>~>W!bR&)Q9+7XUATKRRgoz-ItDXnIhI=<#lsRi|ZbaxgJ>oz%s_Wjm2LN-ynpj@@!;NXtZ@yxe<;p1w$mc*>`STFZK5b5j9 z4#wkL!7w>B-o~boc&+t}m3b$F$k+tE|I4?{K12|ATgQG^_g01F6y)es9lcXtBqQ;e z&$A{xot3b~x#w?AHl7oEX&U4|uo)W@+p#7hn{@U1K5n-1^lq%pT}4?5wRjclCt2@t zgQRLKuxsLdnUK{Q?y%Cl`9sc0`{EshkoT{nnhO1(?(u75RWi9RuMHX86CtHx&95#&DLxc(sSJXxZf zp7;C1E!zN&*;zyV(L*xVtFrtHk3Be5Tb!LrV!AGmp(~5C$*Z`>mL|coAM`UvKM(gg zQ^erp%C)X=vwLz-BG}@rap|nxRb~}0Q;h5~qfoYEV0g;#UZT$Zs(JPUD(77Is-`bW zRGsgej^(>|q%g5bWx;D3n=3@z_l0U^nP+Fhyz(hL_I>BfUzDdSy>o|+(-l*~EKv1Hc40ch78BE#r1Ek zjIPI8L69x5tri~*rj+G#be6DP`8g9Bqy|f+7Hye>E`;+k`_=rBNc}%Xi`QH0?Cg+U zel(b{WK9g*EXQE8;=ywiOl|B;C*;rOZ1tNS{(i*vaO2G7K~+caUQ$IMnM@vJ!D#a+ zZ=k1U5l_rhtJdm}Dlp&8#d>Q9zQ={=Fwf3!t6!oyZkn6>lI$SQ9xFM=7#}`USPhQ` z!Tk&H<$&&MUpDi`I2Kyw0iTxpIJMByzS$e^Fi&?H&7sD!OUv!x`}X<0P2?O0v@FyJTc@N)szP&c2UPDH|2 z;HnO2WxA2A0l$^x-XI`Y*Y7+K`hsfdaJg-yqoGIkwUhC}Uh~3HCpfU5quY+2#nHI7 z*7@)l@u^jTd}SBbM113>pCt$BaN|JLtATGxGklrb4U8^*PME4|Mlm!c7;Nrn?ayE0 zb;I0>V9+gizkl{LnB-IN^vP%J2Laq_wdXM3Bfu~LsjR8vmoo5YpK(3#SA?(xPeRBW zAfIIC@$HE}POUF=CgBixvlKY(h$VtH-BpF>)Lay4Ic$Pnpsc6lQHeRR^|aw_MY!eI z@;uvmxjWh3Fsv}m&L5kyb+^s~WXVE0%rIRvl-tWvDQm{0f_}A|C}x~i4s2>JoT)&+bKjwv%AG+Q|po4VO3#`}WoYUGQ!1(IkIAMQ)EHPrB~EIN|Z zZ94jG$!60!ym(evdb!gyuR8mDckx@@%;RBXrNJ0b;H%2}-?sF`m~1{h;=p6<38#_1 zBs3)IkP%?|2$v@Q#^6jyu+5N_V7Dq4QCwE?q4;IIVtOjl2dy5-buqh`yXOe#NQf8l0LsSS)}Omz5&bxa{%RgV6Ort%+&m# zc|v@C(LCAc|B+M81VxkN(6juy=?~KV8OTy&xasaQZy>0CLG0xUZl=-==1O>UKX?U0 zZVws|`ny|p?zDw3T{;fvJ?EGvu-}wA!ftWM_3E4I&&uNcYZ1&GxZ?g@1p8!q zQv{>Qb^@H^b^#fV9TdnxpQ0KAuLN{JKw?@z61fZ5-U6G}#<~iP(Y`BY&!inI02v$m z3mIE#4)~;?lgk^Q)ZvX!DzHqWezg{#Q@{Y&Fjw{oBB%U}L#(UFLL=0kXDa>}z9_+U zSOI7s@{wO5FN=#i%4_^#N(#8FYSrN#>32ohJVE*cO4`#1~{RrV?|8;NOKB1nT-Am#Ttf`;OI%Qd)Z$ z>-4qgD$DvqqTwp|?yTAe)~d0)tUb(|GmgdMbp$0muY4c$;;f#d zN=D$OK=gc24}Xjn*>dU5`&+~V*43AN=S~7~Ot>D*=Lm0nn&65vIj4A;sTZFV`^AGx z^pm3({SdU`BO{}czGz~Hy2-ZBYSVY*=xY|Txu=rq-pNcMQHo#=#vh<2G6*IjU^6W* zFNAwHm=~Q4;p>C68sITE?Xl`TVc4kk9uM3jCdDi>H&1jg405+8JS%*SApg*y8S<$| zCE9T^=xn@R+gclwM~K~lm~tJa36frr456j(GK_QSvvS>aCuYo@oye-B9u9A8-*wmb zKgL?7gH6kO#>#u;jm_IrbCKiR*Jmr(Na6|p+=;*u$nim;JN zG<;I(R6Sle9?HVhJrQ0~C7djcdzw5zaPZ}|7-^dX@y-hy6ioP;^_o2DtsWVUBWVt? z?+}Tjbsv~o%kPBVNls}LRSi`(HFL7kq3K4;gxJ)BU1oLDSG8pwNmHJuQbPI9)yr(l{IT|-Q8R#zOM$b)->k}+Li->)fTo9c& z(yx(m=(aTZyLu#9dxt7OWm#h8NXxFpSyvyL=oE<{9de27*OW_Cy(|qE?Ib`&P5t#f zSuo3_X1pdE!-k&xAyv#I$Hv*l_1IpE1;&f!fsiQt9bFxXluYDSlj2lGb$UL+Dl1JX zaXs~KoBMdx39oUHXr3d`bk49wTl-*?7C$cPiqU3U53WSpo6~U^HKJK!Vuq{{EE8FB8LO)mc11 zjUd8+)&2JBLNncb9Xf1~O`WDn`}J_%exzY`)I;&*aILQ<%&W~jb1{29y6lkUF!vny z@$M}NCy%XqIgj0rCqx&QXU#?DG@F4+TNV@Qt|!YLD=sR?<-6xWCtqILwxkw(mA&H4 ztJY*VRPIAQD)+6HNXz1cC)0KWI->B!2vaD0>`|ZnW zf=Z|Df!d1GBjuT{>ayLvnR_axskbvauDD8?7%)4TnDRZRvf~t_s$Upb!85*KCtA06 zic)cS4Vl?$;sIa@lMzNilR+?YFHL0ifL(x6YF(TCF`K)WN|xVRON(TLHcjx@sE zfEKMNiD*L@tlBF_fhhm{ZTUc(9>fe@W=fuqJA2KqGE(nO@AvxN^m^Oi-0Dd__l7&! zYlb^qGj*6=CQ+QR`Yjp`7xk0PJB69RuwJhPbtah+7}kr}%SgRUC{2HAt?%%>{t+V8 zGTANerbjv_Y#Mre#dI}_9P4$#M^8R-*#v234CUasa7IfJn+ z7caDqzaOnAo?oUX?tMc~?IBC!zrcYWf5dAW%IQ2(&6`?!SeW+K)iBTYtLHBqo^v8! z@TY|MBKKgMfG?4+cR2xCz+SHdE?e*>)Zn_B$fJ~<)|1vop z6bYR?t_w0CMUi`V?Nj-D#_1bj>5s`fzhgyKZJ6Ko>*<~KBHg@> zco9Wm{YZF0n3>62?%hDo_*9{JMxOC%$n5{4+lKpLaO~0v)3OJX+%>?!_T7<~q{ebv?Hy`k82kvO!V?)E%X&^?6F?m)Njd(@^1c(;FG#mbIG zn^$Uxw1B_!2XD#(*hj&wZ2_7~y2hC{rbcG4Iq{nf<@VpPzCzRZvY!{F@c@ZL4#!K| zVZ2PeltB0+GQp=2p%t(y`g3+AL3Bb5^U&tT(`e}l0Nl)BdG?+Z!CW5uIUV9vT}%i? z&^vQnPr>tQCtMLaG?#4(K*|@h$3DuQls{?CG5&GBzGYneNlY6gL41l)0L2{EO@K7g z_jQz6J4WG1^2$Tj1tfnIT*Qtf1Y9x0K79Ey(NFhFVY-!M^qBZR9WJ*D7qI(Z@h6eK zEqh2K31K;nIUyOAT&Q3QCe`mvO2P@;^7uIYMhMjMp%xB>1jA)>!)b21=WWH%g6H1V z`s66Y?!@+L(_Nbs%x%qRrOSO;Y4gd{ zbb%#CCr*$+d^SFu)NFOoslVu<1O3mVvA(P3h5Cwwn_c^T&Im#wrEIR z4St$WiRsZDkYip`Bz;}iwUico!9IRAZs2~4jxT)OY{K2e=+wUxy!VnMF<#~U*B(_Z zrKBas`dKY_3%JHQ%^6%kg@+1((}Lgfim1b$i5s@!B#KAIhY9tfs(X@l`ypbxH=6*1 z9P%p|c6beMqcqGB#C0TLatspzd`=i*I2Z3Z0nlTVWJE?7BEYd{KSLO4sTP;88MF6l zP1x`Y7f>QYRg5@Wa01hF%^r$tfFW~-;uW&*axTDal*=sHKrF2%5CqzA%>eJzj}+Kpo5C*UW0{5f1*ZKjXlU47(w(Gi#CF!zerT7kO$RyT9#Y8U1#fZQ75oto z8{KryZ;|m|)oHq3xDx0Bru^jP|0P26aN9HzZos*Cje#rop9-79mX>iW!k$u3+BZ2> z{R^?x-Usc^7Rnb6kuCfmzhX^#d4oTJ-nsNnz+cbT4TaE*<6T<;&j3CvkC$oKJiN|n zlQ7DaOcuOLr9KPMXi73h>&g${O4B_+K>;l8P~yt8uLv}YqN*h*qm75Ns7X!v`RU&u zTE%2eHY?c&XLsUH4YpypL0zfufXiFc)KvX>cYN6|Be!VofmO{M!PcvT}PRAl@$MM(UyA zYMWiIK!UQoB-oEVTV+5IUO-yPSpCg>vQ zany`!zrXMBcS{Ne4#w{QXYozwKeq)qmr?})b_27=^D*D!Yh^G1mUQL{3A$>eD>U1* z0W9?D=V0Kt3|!&mq=7zAJ}9G%I^UlfGCPWLZP2Gp#EN9#wlGFhwjVc*Yv8kxJAFmZiLyP*WkAEBU1=$_#rfI5X{wXa<_ z1jhcm!1EKz4-LMj+qC|5*da=Z(c9CCgKGcRiy54X1N94z@?=BpqsjDznhki@r)zJc z+RZyQuqV)TM@-lUf8%Z6eMY`vsQTe|KR$|Fllkw?;PpjaF%Q?B$o_vf?;!ez3;g8W z_mpMtn!Z{6`p=-sI3EOBKEF^s|E=O`Env!to+^R~1nfgGia;@?`ns6%9w??9*J6|= zr@)rDH7{OQQ{Z;~UJ%ntr~Mz1@AAXNXQo-AkL9$wtz9bTnNj(O&9k6*9MViBXj`M2 zeN2Xdne}#;w(or~M$5Uq`{QzjN77rWbtXInuIJOY&9lPG74AGU%X-(6q!3Rty26`2 zH`px3vA15al#J6C<6$t(ofj4%t{dgj@A6p+|dM&&JBN za<9I|maH4*xl=`)@s)FwYTe11D4)2j&%+4_Gg8D@ADnko6;x9#l5gSb|?_!)7a4r@EK0C>U7MXzF=v>s_6`3C6 zsBHC8R9DG92e7AlYmZ@t2?%+dyiT;RP<6%t()_*A6GC*ac@jX0)O_^-IxUM|pu3?x z5&a|W=>&M$1xHx~i3i>!whPO60$;kmm4h(9TQ)WbGDw3YYxI)TolC5=nebfWL?7Px zw)%S=UIugh{_>4|3sWSlU0UFP=K=WXKQZC4FHLC|P~&0q@!qxRo|oCyNZoqBG0^Ms zhW+5-wV-`}(1fR~={4Z>{IPjmWBKN3&u_W^U- zGcuMC4iDb;9y1=hAe=0>3gvrR zaD_bF67vsFhSfhl89)f==E?YX2MgDpU(W>%=%+-jJ_O)_Gl}OtWH$Wu!+8Mv$kQHR z_4*l+y6_gmY5q437io4?GBMMU{&#bd z7L!vpl<^$=EJu2s(v%RsOV5ZumX38*=~wqe@JX)_-?86+_9%qnxhU1c;MRzkrw?iS zxTUkRO(X^~GWimAT-Zq=p6lITcQ8@?W=7sg1l=M&=JE3L!&g7ggk?rTt zCwU|;2Z&TsJ(gG&4hzg?)=t*YhTX-#ZN%8wM)RG!`d)Tyl+G-DOU-a#54ccHFAC4q z2s`+yM0RzkC3xscquJZ7MgFz^8~;haKj%^`((LCV-1-&`mdLp_NQ{&FAn9tDzYM1y zM7zUP0Q$uU17qo%YGgo|8GZJ*L8l3>`rxWl3}W zq=w$_R_rUoQOtX`WVmG|xQUtY#0HsPWQHp>$5=UVV@K((`MDSppR!3fs`ims45wHs zg~gFQjb?0-6z*@w8m-%ImSzn8UMv!9Xj3iWH~gewl7 ziwh3M6b?qyyrrb38oGp|aP&w#Zq8O2Q>*TqKoXAGU16g;vB746$~1>!3URknnVZ?{ zGxXq-SigmDMa)HC?l`y`@zj4%pY9Eh@f4%f3^$)AZ)Auq(%l$|gIt{}h`WHU22EOP z+qbo+Bn zZ1Qis3Jdmyt@%a8;kTAfI(@oUOG7GSc}gIK4i?|-b{bxIIMlF)z2fQRP?RFyjP@?hkRij8(8VSN3z5A}b)$Fb}^$!Gg*lyK29I)e(bx zmNt_Q+%O4fsC_PG2gHPLd4GQ_Bn zKe)R1>0vuuOEGnW`}>(EcV$va2AD9}dr4A?);+*w&8Z!!L`X3OEqd7;F!a=JDr zjT{SkU`1wton_4brUNn>iL1It9Edo5*6L4c5RRN7b>~BnA4Q@1fWb(*D10Bc;DfdM z?X^8HgSFm}^6y^|lH{yT%rx$et8nDs9@c)S1$j{gqsbvZVG!WNqQlS-E^f7eQ^9Y~ z$;0Tki`mTBC*x(Wi7?R8U~nulzLQvk-gP<7ZiFd?x%0Hq{}ZfGHGgP=taM31r2E=u zJ?ESqM%qM7Eyz_@hfbn4Kt z%$keZx33vyI4wI1i!pvjufMu}=vgc0y@iV>$a}}~mIAne`pIgmgV09IUh1Gz&!KYx z_r_Z5h);?Nea8%Pf_!~V5_Q4M12?k@LoeAy4khhZdcs}#vlW%c>ffA*kUZv$t2d55 zSKPSH2vgvfP)p6pzuY&tsNiu!x;7;+a z5xS2uFEFinm@Adc-R@5})wJcN2$hAI-*aXnWX!{pN}@v?(B&l(JrJ@KqiyxEnt<$h zS%2*g)!rj#B1)q{ZRuLd(5e~84dEq{M;=D@AfW->{XTj4czWP0^N`XbyhKGYS;^q5 z)`*{$P^zox(MCX^91{YXrC!LZ)tiy71N{E$1Wyfi6o}O)ujwmM%0@YR>c{K^|=mjC@xo&n|B_Ck;9g5mfJA z%2yIyZtzc{JBDxiD|{wm#SI**T{`b4i5U9a=b$1`p-J4nrr;~73erb54F zifMn2#mC%Rb4qVCMMlF=iVNcmu}Kkdc`M_nTKKA5RYgQ_1bLlyqhpjat70TZ`%=W$ zg1UX*o!a-Dtq$fMsVE@8eA3s)M9Ie4 zq+}eZ)9UEnQ{qnkw;@=tOz+${vx-za5~_FWn7fqPCU4E#L?>4+J*%Z(M{Y=%+rZsU zq=Y0>D(LXU95^RxCtSWuF}PSb2=S&Ov;ACh@^)qP?k?@Un8>k0A>u%!X})&530g@3MkXv910@K7Y9AdXLg zl`FWgfP@_7x!tpt>Wi(`{fIL{@Pkqtt^rBuZ@FrHp?f$yPDXt@)!XiU&LWhv!ZvD6 zXI~qhLxw+!MUxCk+9YciS9>WqdDaB!DR&a-d4y;<=9MxoVHyZcf5_Rtl!#t}h}}=W zE68md{w$&hA-UL30qfB6WvK*C-z#)klX4b!4AW(Lkr9D_MWyu6rkThd9*Yzi)0FO` zycoO!%I|OWw!fk_)nJO>g0YK%yQRXKb&u&pZfs2%>Je=bnPfkW1&TBO__y~oY36s{TM>J`Itxs^;14Lr=sCpb z*~|}}HvAkx9^f+Y={&6(XJ6iQcZj<1e1a47T5T;X-Tm=$qiE0^slSE!ky()Olh0Wm zo$kW;!(zjs`G^r69W-S-fg7=_;C<79L9d!OU%secNhHZ~xQkw?3`HY9Gy?{LrcJ|HI5c2= zH+$5bgBY(kk!f`f&xrePD{}e9?_GSfyUY}=9a~nRIuT7dv03fR8t<1f+Mrp5j?u9K`RqYjfSu()RP@RBFI1<_Yte;o*_{p8MVg2g`6E z&Rv-O`xR7~6YwL{uD#{(haJWSkYwxAvq7fh%W;kuCvhq)zTZfqPTBj{>icX&k?&5dXl5FLdfZ$>7NRTVj zHqROgIgQ_Q%73K*zb1T-Yr@;PqNH19%>z8Sb&Ktae{0(vJb8Y4H9ve7r|r7jkVJ%U zZ@N1x3#NY*S`d*>;*?vt(s86(yuc^NeI(wXgSjR9?S+u<#_|Et|;_cr2RNqKcH&v=$vSwApP( zTd)Zy1R9H1={m0>V9QU6wEZF?MPjD*yrJA^LE1=4=Y93XowdD(s#)*m-)mnMTx=(5 zgE=A`oW<0)UA~=;x$xe<=OFn0rSb8ZD|=6FOYc{Rx&v7XgqywvtKFFw_V%qE#ALWm zm{jCsM4Y-%7^Fg&J+C<6V#EG>kL;Ny4PK) zMP41;Z7fQFj1$BJI}K9M^&ZM`-{3uE7UQne@Uv5#WGF2}Y#E~+^m{{@=!aP{ zvn5viy=0;|vb|*Iwjk51sQ7bu=956Z-J|CDCB0oS{oS~?PUpz%BN1Obt<~9ttwS2f zP`3Tol}hpsu0)rrb_&vmcF3NF?GV|x1l)?rlFsuH;gT{=c=@!q%*kbTc_k}?KY^b= z#nUOoIyK)+*XG5FFTvoh3&V2m5o0{-~bt$g@anHl;*!>3p0RR8vV_;yg0Ae;E=77>5zzXFv zB4H5Vgo;DJ2YWss>42o41&e+zB>e(VeqMf2ZemVmRcZ=E9Au6G0dts9%wcB8PfHt8 z`T_`qGYeWcD=^>!AM9Z?$Xw+3W5QxC0}{;&v;{dnNA(Z9{thJloLKZnAgO19@);OC fePQ}N2-uHoAIN@IC?7=oI{OF1%mD!aaId99QP^KR diff --git a/ProgramFiles/sysplotter.m b/ProgramFiles/sysplotter.m index f903962..d2703a1 100644 --- a/ProgramFiles/sysplotter.m +++ b/ProgramFiles/sysplotter.m @@ -22,7 +22,7 @@ % Edit the above text to modify the response to help sysplotter -% Last Modified by GUIDE v2.5 13-Jul-2016 14:49:31 +% Last Modified by GUIDE v2.5 21-Apr-2017 14:10:54 addpath('./Utilities') @@ -165,3 +165,16 @@ function sysplotter_OpeningFcn(hObject, eventdata, handles, varargin) varargout{1} = handles.output; end + + +% --- Executes on button press in pushbutton20. +function pushbutton20_Callback(hObject, eventdata, handles) +% hObject handle to pushbutton20 (see GCBO) +% eventdata reserved - to be defined in a future version of MATLAB +% handles structure with handles and user data (see GUIDATA) + plot_info = plotpushbutton_Callback_optimize(findall(0,'tag','plotpushbutton3'), eventdata, handles); + +% Execute the gait_gui_draw command + gait_gui_optimize(plot_info(1).axes(1),hObject, eventdata, handles); +waitbar2a(1,handles.progresspanel,'Finished Plotting') +end \ No newline at end of file diff --git a/ProgramFiles/sysplotter_gui_fcns/gait_gui_draw_Callback.m b/ProgramFiles/sysplotter_gui_fcns/gait_gui_draw_Callback.m index 8ab89bd..70d49dc 100644 --- a/ProgramFiles/sysplotter_gui_fcns/gait_gui_draw_Callback.m +++ b/ProgramFiles/sysplotter_gui_fcns/gait_gui_draw_Callback.m @@ -8,6 +8,9 @@ function gait_gui_draw_Callback(hObject, eventdata, handles) plot_info = plotpushbutton_Callback(findall(0,'tag','plotpushbutton3'), eventdata, handles); % Execute the gait_gui_draw command - gait_gui_draw(plot_info(1).axes(1)); + gait_gui_draw(plot_info(1).axes(1),hObject, eventdata, handles); + +% set(handles.shapechangemenu,'Value',rn(1)); +% plot_info = plotpushbutton_Callback(hObject, eventdata, handles); end diff --git a/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback_optimize.m b/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback_optimize.m new file mode 100644 index 0000000..7501481 --- /dev/null +++ b/ProgramFiles/sysplotter_gui_fcns/plotpushbutton_Callback_optimize.m @@ -0,0 +1,71 @@ +% --- Executes on button press in any plotpushbutton. +function plot_info = plotpushbutton_Callback_optimize(hObject, eventdata, handles) +% hObject handle to plotpushbutton2 (see GCBO) +% eventdata reserved - to be defined in a future version of MATLAB +% handles structure with handles and user data (see GUIDATA) + + +%Update the waitbar to indicate that the process has started +waitbar2a(0,handles.progresspanel,'Gathering plot data'); + +%Remove old subplots +delete(get(handles.plot_thumbnails,'Children')) + +%extract name of source +source_name = get(hObject,'Tag'); + +%extract the column number as text +source_number_text = source_name(end); + +%get the checkbox values +[box_names, box_active, box_values, box_enabled, plot_types, ... + plot_subtypes,merged_plot_subtypes, plot_style] =... + get_box_values(source_number_text,handles); %#ok + +%get the height function type to plot +hfuntype = get(findobj(handles.(['CCFradio' source_number_text]),'Value',1),'Tag'); +hfuntype(3) = []; + +% Get the state of the Stretch menu (coordinate conversion to flatten +% metric) +stretchstate = get(handles.stretchmenu,'Value'); + + +% Initialize the plot windows +plots_to_make = initialize_plot_windows(box_active,plot_types,merged_plot_subtypes... + ,plot_style,hfuntype,stretchstate,handles,source_number_text); + + +%%%%%%%%%%% +%Get the system and shape change info +system_index = get(handles.systemmenu,'Value'); +system_names = get(handles.systemmenu,'UserData'); + +current_system = system_names{system_index}; + +shch_index = get(handles.shapechangemenu,'Value'); +shch_names = get(handles.shapechangemenu,'UserData'); +shch_index=1; + +current_shch = shch_names{shch_index}; +% current_shch='null'; + + +%%%%%%%%%%%%%% +% Get the desired vector and scalar plotting resolutions +resolution.vector = str2num(get(handles.vectorresolution,'String')); +resolution.scalar = str2num(get(handles.scalarresolution,'String')); +resolution.vector_range = get(handles.vectorresolution,'UserData'); +resolution.scalar_range = get(handles.scalarresolution,'UserData'); + + +% current_shch='null'; +%Call the draw function +% test_plot(plots_to_make,current_system,current_shch) +plot_info = sys_draw(plots_to_make,current_system,current_shch,handles.progresspanel,1,resolution,handles); + +%Show full progress bar +waitbar2a(1,handles.progresspanel,'Optimizing') + + +end \ No newline at end of file From a61488166c4b612a111fdc90f880e31a6a3b7298 Mon Sep 17 00:00:00 2001 From: rlhatton Date: Wed, 26 Apr 2017 14:43:01 -0700 Subject: [PATCH 006/286] removed spurious transpose operator in makecurvedef, eliminated error when canceling a drawn gait at save box --- ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef.m | 2 +- ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef.m index 6a79916..dbf8d36 100644 --- a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef.m +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef.m @@ -36,7 +36,7 @@ function make_curvdef(curv_fun_string,paramlist,name,attempt_analytic,sysplotter % Take the derivative of the curvature with respect to each parameter if attempt_analytic(3) - d_curv_dp_fun = jacobian(curv_fun,sym(paramlist)).'; + d_curv_dp_fun = jacobian(curv_fun,sym(paramlist)); flist = [flist,{d_curv_dp_fun}]; else flist = [flist,{[]}]; diff --git a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m index da03297..d1549ab 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m +++ b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_draw.m @@ -133,6 +133,10 @@ function gait_gui_draw(hAx,hObject, eventdata, handles) refresh_handle = findall(0,'tag','refresh_gui'); % Get the handle for the button refresh_handle.Callback(refresh_handle,0) % Push the refresh button +else + + return + end shch_index = get(handles.shapechangemenu,'Value'); From 578bff1a759226f7369d7211703bb70c66305468 Mon Sep 17 00:00:00 2001 From: rlhatton Date: Wed, 26 Apr 2017 15:04:23 -0700 Subject: [PATCH 007/286] small cleanup on optimize button, tried inserting some parfor commands into optimalgaitgenerator, but haven't seen them working -- maybe they need to be elsewhere --- .../gait_gui_draw/optimalgaitgenerator.m | 4 ++-- ProgramFiles/sysplotter.fig | Bin 129051 -> 151836 bytes ProgramFiles/sysplotter.m | 15 +-------------- .../OptimizeButton_Callback.m | 11 +++++++++++ 4 files changed, 14 insertions(+), 16 deletions(-) create mode 100644 ProgramFiles/sysplotter_gui_fcns/OptimizeButton_Callback.m diff --git a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m index 214fcc7..7eed959 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m +++ b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m @@ -199,7 +199,7 @@ %% Jacobiandisp-jacobian for displacement produced by gait -for i=2:1:n-1 +parfor i=2:1:n-1 jacobiandisp(i,:)=jacobiandispcalculator3(y(i-1,:),y(i,:),y(i+1,:),height(i,:),dimension); end jacobiandisp(1,:)=jacobiandispcalculator3(y(n,:),y(1,:),y(2,:),height(1,:),dimension); @@ -208,7 +208,7 @@ %% Jacobianeqi-term that keeps points eqi distant from each other -for i=2:n-1; +parfor i=2:n-1; len=sqrt((y(i+1,:)-y(i-1,:))*((metric{i-1}+metric{i+1})/2)*(y(i+1,:)-y(i-1,:))'); midpoint=y(i-1,:)+((y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2))/2; betacos=(y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2)*((y(i,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i})/2))'/(l(i-1)*len); diff --git a/ProgramFiles/sysplotter.fig b/ProgramFiles/sysplotter.fig index f4e98f976e6de1393765c783c7bc9ee4fadc03d4..f295015a23652d5ef371e25afc7e7c7d192110ce 100644 GIT binary patch literal 151836 zcma&Nbx<73ANGq&aLeLOaCg@r!GgQHTX1J_fFaDo9tv{FRJUM< z=w4UO$V6xM4LzmYC2cIKc%0uQed1SY(*U+Yq`;J&lK5!+@|)wyoO|0lt2+ia$S()1 zPv+MkSSK`e!fk)@Y0?@2&K+`K!9@%HS_7o!P`3{*{y~}9tWj%RAS_6ia3qLXxG+6E z$|8VRZo)_H(WQ@0jD<@;?6JjHcfccO&5Dx(ECJkRr`&edyi4AW6q9e#w$VJ{H^w13 z{zbK7MgHyc(cRZh0Aa?<4&NaBmls zR;{z@i#AKhYYv;_QbMikXtX*9Q6?xS;~7QtnhfbpuRTT89x*ym`s_6o`-Ou)EcD%lf&aPw?w?=74#OL6{+~nbOrM58TjuWELL}>$ zNho^2#=b7lH8D(Ig5{aYV$7n8c2THW;XECGM;!O;~3_t0>^dxX?=mj;3$1f;_CX7Yt#eNTL-4)a!V)V{As z`^J0f=rf%XLoKLXw8H^vG-EmKk}LvVu&m5i1v>3^I&0ax~SgJ(pthL6Upxj2Q;>~T@j-o(rnll?aM zK9_i?6pN^sQbkkgjV{HneM*8v<91jCM-51@-9&I{B1AD!$$QD&RSc|M8{uXO#gee@ zNX7ISnDca|HtMt@fr#bKo>zbNQQ%oEn6&rhDcg{e@9;jc0KLV6A!P=haKIEx&EdY-zD6W*TVTvIk@r`=~~w#><%exxN{G%M;p z*Ged(-myq5c?p(eY<{h;0oVwf`F^{5aeQC*4l(w2GKuWN(}((n2v(N6mx^HZuRD6H z*~&}7EXCPh2OA4=~&Io*k7N*AD+hhm#H#ieAG5r z*1H3rJFI#_bXq+Ek)6A497?D{z96IWe`!3hdcx^@U8>sl{jf^-B)yjo4o=_>cozUt zp_G5CbuIi5Y|c04baUkV)Jrh~lb}9eT6Z$bPA4y(vR7PxkmO{T#F+331Tk?VA-5l9 zqXbgb!(blScbS~4=i{hsl3K-Hg#mG**dn_uU9{>kNxyXj+N2~7T_i~lFL~jn!p@(7 z^d0GchhD9ve;THLQcprKRehEh(IA2xlk32C0bx%Sdr#H)RJjTqyAEVQPsV33 zmZGhqT%?m(x-Rm5OI&q_1cH|g1VbY6##aK-!QW{VGhJl$j1DsG9l-_|AFDpF- zy`sXw!CzXcg_? zVr1}y?jeDD;5SUhx;0JuykZe_lR~#cM@8>KOqVh^Bl{&_iZoyfdp^C1dAC zN08VVzBnYh5bAQ2gMK700n`KqGCZo0JgPZ7;#bs4EA`WC7snZ<&V1S1HDKPR5_}j* zcu*a*lw-O(TYky!6Bo?Dc#DoHN*-98+Tcxv94vl|FaCrnu9@VJKWs^<$=Kqnw)+|2 z?nr7UXT11kzxFFAdrAEmW#{<>VkWqm++#reaxlxN40@@*Jj2^Be1MKbUG(hZ>`w=` znOjXChKZM{{m?yGh1}b3x;0pnH@x5&KBcDJ1rFN3<29HHMDj<|BdO@T4~?+=OS zM`M1w^l}+TZLTg%RC4hCARISC&MVaQSyVn{32>z;DJO_SOWoi!;`BZwU%ZH0x+tFg z`A)Hgv?WhdV&D1NXgNP*4_R*u_xHWnRs}U5t$)o?*2~h4u06>H1s5`m;rTo+#-~kXhDF>)Qi# z_K(5bq#4@9l%2!hoEtH?N+Ry03pUN8fhWjIkeGcJLdokl^2X1JRxv?8sjH>{>prqi zyrk9imx70Q>b7hl51+YPSESKik!9`I9}N_C{aY$bPeJ5J5(6i{UB#0~^UIJS%a$qS zG}hBz;y$ZxJ`ujcYul@*1XWm@H@bIi--Nb&5)f_k+1C_`1a9&-HP!Lsf|k!*Rs);E zzj+ZztraM#t98OK+t}6DcT~gmO;h0hI2&EM$g+zrwh$Q9g7@nN2 zZ(!mt;mMISXRpg6%RPFn{C@aXQF1y8Y|pm4j)HE-`|l&dtku-HLx%(S?mYy9k zna>DNkxJ%tRx!z~k5HjwhDTGL8zlqX(bBZt9gFUK& zwyc_GtFbM$Os_y%Ox6SF05td+_WD=v1fEE;hh7D~b{$QFt8RYO79ItrYqu7(U(Ii{ zUnMOhN(N(l?}ozvJJ)B=I+4F8?iE~Cc3vFBC~s0Cl2uVe)bmo3b*^>?5CCyhjRG88 zr2b5uP1%f0Oky@Rc9|Bve-pt(8_UU3x&w@Wg>ycx+m+0AL3<3 zC8u${@ehF35t0)m%ZpB5ibM|_6u@Q3e}{Wvm|8f9r^!uRw964f>|mKRnp*OPZLHrla5+*38n z8WnKQdj|Co%5bv}iF>w=Ls=`}z~%_m#)Pr7l|A>-;JPo;xX`DRJ>wNgHt60%%bH>e zNn!CNRn}JOdHK7Xr|yrKQ%Y9i4m*raM-W?feDnO_%`B|I%u|fssL2w#X@gbo9((r; z%((9w?N>#+I%gk>Y0Klus)dAs=}sQxgB1S1_w{M8?0#=y=Hy3xI{C22CJ{KbD^!I! zRsDA4{o=RrSql4sj^bg>Zd7@!&94r6L<_jCf3h{rl1Gft*U^EZ^#DCXwmpmRb8N}c zb8evI(oSQTDDE!tK*z2t%??2wvI}6zzBT@4ofqX^B_S|psa7@+YdyHdu-OKoNiSvk zF8#ZozU{mrVeCc$#)j!0wPJpB<|dAZw?eC1!*DfJ0LwaK?VdVIqEc=qtSUai0x0V2 zx%kt;=Uo9v2`K1r9rT-op0G{824QhV+#cgFq3M|!D4CfiNp&gUQSe(w@-@N10xImu&Nw5t$BeiVc zBa~RKRq`2Hw1L-5?PXpPD)>{e>gQAL064jPk~^FK*0hfzP5X`DHgIt)g07)@JkiAF zj{lghi^J>=*GJfSbX(w8?wvsc?fAz2vyFdBDM&SR5X%1zPiH)er!1CfK=g+j8u%JX zS+?n37oYLxW;?T!@7RbQ-k|HCL(3+?HId^!sMV|Fq}q#{<4JjliX&L`L8D%5C$ZoZ zR`oChy2TQ>cDlN+V#PUJD*|*tUDZ~zLI$Wl=sM+K++G+x9oIKX_3lRpiGmWZ)encY-X|?XoJGpd3f^k9 zgRr2_uiLROz2qIxalr#fvDz2+O7d>9O#LD0x;A^Qvh4v*6iv(hf{& zr-wjP0+%vlJiyg|Yn~OS=c)U-mGQbaV$sOooJJnzz84+`Q>D11`fD1%V3y`#a3c{B z`4fACX%o+4S%YbEC@s&OXEpQsElGag*VC!Es|~=M#V$OrE70p>+KG2VOx)W4dU&AGm}y9*=;JA zXfT3!RNW?bq$}wV?x^Dnsk!OM_mXsJA-cs_ogXD)rQtnC`wx%LHJv@v=N)psPLIfE(7C{G}C-O5&wS}ligWb9EuO;c? zg+F8B$sL#3zPg<>Ke{;!k8kd&T^bc$sGnl}(359rVQ&d_XN|NdTUme~h1p^PSz&n= zvyx)hJ*)PwcEn;($uz~_rr$8ucEoHmW~`)Vw<)gH>mK2^F9UQir?8Do?p&Bd8f?@< zK}AWPWyT0m7yGy2(+A4?KryBLhZOuzqI63Opjr*t- zegIl63}>d~b>uA$bq_HqrphbhUg35Y>{cEkIj}VfLlnmTc)w8s?mh$drNXdK4PFJw z3!z28S@TciVHTgrrNZGgu*vncUp~Dg1Om&*xk#e&7Bq8<*?RW}? zObSAtCVf$*+7kPfid*16n4C&Q#|a{lAgSXeCvNR3c7aBp=sH^Hpl4{5+?}VR(LuqveUZxiE+2nTw-(mK=z9y`ACl+ zEQq2D!Lum^rdNpKz< zhVQAda~|hn##PP7Ds0jE2q6aTY*J6(4l@|WWHJr$&w4ufCn*O-`}U1+<6y94=7w;t zqCx5ft9ShY4j0L(a2TGfV%a0EOA18KW=lXWN+X>RHZIeujeu)dqgl5wROj;N%UZ!h z$#jhFY4?c4hmFu{*+2&y!XVFwg30aBP~cThj{!8)Jpoqi@lf<_-j(hFw(;p5QD9X@~6cKObMkUS!b~x+!g9q_lDE67-KtIB=O^UF)qF6-JS?hbSQ6c0LXn;NS`~`K3%$QRo>xd z=VVcD#~qunXnE{oyQ)HXQ!qAfFme4yIRR&$ut6-vqW~jEed>2@uk?9ex3%7@{XWB9 z9VOpD7WX(5L@|N7^V|IQ#cGUL_O`5z$H#VC;~kZX%-++Jwy9RThS(vUwzKo3pKCL8 zn?d1(nF7&2@*JBVY7gwPt_p_4v2Z9U@E$1LH(piq5~!cWe?ZqP21}YgLIDrw*JtY7 zXC`@_KW$7kLX+v;cnTk0v8}|y?L3Lw3@YN$>qu@@yFB>UU<85FStm(tKVXcx-+snw zQgvQGra~I^^iG#UV6Uf_*Hm|s{Kvq=xhSEpg~^9DuZenStt9Oq-HcVMFqDnj>nbo7 z+v_^Iz`%;3?^vZ6)hLTm+5^Y^J^!0uRP70*2@7v}EE&Y1z?nB6jJ{T$Nk>r%@N0@S zHLW&jb9(qRDlIwtE^jEUEhyu>y(vZJjG(^V(cz5PQo1Y!V7y`1k^XQ(CC(iC0Gy&1 zJ+j8n<(m~44Ca~$>40o@`$INc8p|TePy5e=T=`oUSHx2t$vU#-%Qw5#_j=b-vJTaC zf1c>=&D5gk^t$XCtOs~wVL82NI6XM!Po=SDG0YzF(6KGVIsOtsXj1kEps`TQTvbQK zGo~MaDXT-TsI4Z0L~uc+S*iIB>Zfg!qmIQ()sl#1G8?-q2g;KTMXge=tIV_dIFy96 z{Bro)0@dB;`nD%&o=!jhx2E<2W85qCA0eu5QUMZtyFRx8p!LBj2I*%Wowk6dvdduG zo15;+s(xq!tGcUk2g4;~`%JUM$AJ<|pf0FbgyXPF^IjJiBJzX7((bJ@hdPLK3#JX}3Rcd1uyZadC#Z_ty@s_WNy1FcktW z4Tl8w(7%48%_wC)y_BErtk(#JoS1~y8s7zCY?Gb1pVd?GCiGk07gWShZB{+l=5CXf zDxS4B{;_$X**(B`PV)C411d(9R-Z6I*VC}&*Qfw~$ z4)c@#^07lKDT_Pyq-QeTDEb>6ecliD29)>D--<060yGvY?8ER?lmnwZ1BEJ63UghY zSo2#-DxI#l#pT<$m)kW)bz#myq-`D?&eb46F1bt7l++&h5WLtftS zX<2S8*><0dxgn2wPe}#qPiS}004({-J;Pja#QqaPVu~>&Q6x+CVvZ8 ziy^_ecJ@y9UvmC51AhxgL9jW6I#asMzCwdrz=gjw-#j6Q#$C%qo7s$D%uhkVu-{}x z{vmC5*L|(Vl0-|5p4- zbpmPf0t8(ynfR;XL8NEu8AT*vVmEfnVBT(~$kJ{@OCCO*p>%pb9b6XHx4MrjxT zejts%^k4KY+(rK~v$)qJXggbNpD;gVrhMdx|4AcXzM;fwd`76y^V6(n5OdBVzgbVC zUktg*@)5oUZwZ~V=rlCYaJVk&hCZ1$w_lu!-#Ie1gjeh8=ch^1dj>)fmpI+R;*ws14KyG)O0)*u*Hh1@knfalx+#@&W9=QY~IOZaO zwJD#vHR|1*TY83Wf71EFA9R5qCYSOKMkHLj67t2!DbG4zXs$bAK{Mf>1+^oymSvxM zI3T`kAC55xNi*06dfN_uS;}Bo4j^Ej5Ffo+Go?;lvdLB9COY;=YqKPeAL=oQl^p6a zwp{HRK-`r@1XwOVK1~&-Pf5++WZ=L9+~95y-2Ca25=3^-7th#|eqa}F?ey;;xexE% zb03BC`3~e;R5%liL6?Lhb;?KVN3zlD-;kRmFzlz}?kLw69G)ile5adJeLpNd#%3@q zv;wmbwaUv4uebE}WfsZ!{e9>6lqthxiWavmmx(wsFfh$QuJ*G4IR~hv#Pu+Tgl@94 zexbcy(-{W2av*v{Mw`Ff`b|8fAT9kmJovsiC`-88RvHx|Gpv4laXe6Dc82Yrh-c}}i+oK?LR=~;vr8MY(+|IQ8xHWm9bimt}<=zN=riu#O#xV6> z%;%H~HoFY&JHv=0b0VwK+tiKXRMDyCjQyv7Dud1bu$n#mhZyut?B}J()mMLt*fi?M zZH&KT^5Sx#kiEASVI7D`)L9$7TQHe-7S3YeZgV{;e59QSr`iIRGRfiwX$NUrMBp5! zBTC~EY6!YVY>fbmBiaOxI2`Ise$*_GlaF3-z|3G&zCEHJwA$oP)Qeu77Xq@Dx(v-~ zy^|$OtE_VUNPUPK#YU1C%9)+1XimEX?kM}aO;6YjCB3?RT|J=;>1}gur$xb2emJi} z;(n*hbVUKM!=1M8nEP0-;mh_YwF$9|+Vq9;%3{QfB`hPKi$y%G0BDq1SU9Se3l2RC z#a7RRVex8k@b9e5o904NZyUx1kMz1E3ddJ|exysS(tP>W@(|_mrXeksP>I@a>Dn@}H2Usdk6@ zcYTH~v5zBI!&eF+;QoFMAyo4k4q|>9a~fqGZa{i}>c{N8VqQO@pON9=vZCrWN+cQa z-cRfuB@PiDz4m!`H(Ak200e@-`yAi{*(_9_Xi4;S{X`isF89_db)x^rY4_{7>Gti) zWt#UeNYW>(g~R=I7#?3rCY3%TPfwVH2~O#ajX9olD(@F={xp08;{_p{!SY^>C9yx? z+7(UI&xnHv8i>Ig^_%AdSGyE_FR1uWVQg92fYm`|E%R zPM)yZhW_KTk_*+ZY6qRAFPu9W;y)hVt5pZlMy2R#SS7Ul0%SKQS5k+NM!L9wk7;ok zxWzdtFwdBEIm=cG#v6k3f!C0L^W%z{Lt(RroLtKtAQC>Al2?!+p->q zyE)PzJVmf{AN9qxB- zadb)v>RFc217VJ8j7-_LPGhs^3XGo$(1M`eZfonB@4ZX)C4w`ADc1+KDd#If*k6;G z7Hf0oquwe2$W6FT`h!Eaww-P3Nk3V9{oq~F`%l)#vy*bYFpqO zH8mUeE!+RwY01&4X2$hM5k^6pu#nLlj1Qkgw9EnT#lxW z1~;C~z5rc0FncF#WUg^aE(xU|IB24x9Z`FLjNVQgBpy42G+`C}2@5%%7$SQD&J3JV zFZ=}M{xG}@{IqN}7hjqYz^_Yr9{{5^Ile6mc97z>Tuq12>^kyJmhHQPgG@s30dXj&t=H*`3uHZ zaDVtg$bH2Wi0p4TNb#wHxz}3Xqa+m>{%WQ6@I z{FN3@0>($uQ^oyB^I})1l*>I8EEP~c`!P7DH z=$cv22#cotkLFSt1XztKrszH<;aLR8i27=gnAe^NSx?a>!XM<>(svC;Ae7D_ z(#5xZ#(cyatf2c8jQuf~LIo}OfBsI6xILjX;fSE!L>9g28)+A9?KJy%TqNWK@i-(r zdd9X$q$sbuU024I90T726%GLhr1}{t(%Io*(;3qQ!g@6NC~6t0I04-VRVfTRS6|M? z-3DRKV~P<8Vjs|HryvaaxWSQ?V!WoVjLOb#>~UgLVLDw@%%CU75>Bktotjpm+zBow zsmUJj>8lSjtS$f!hB1wk+OkVw>MqNUTN$p3QT(83_ssuUejwU5FIydArIItN!}Aq1 zi#H1gkEk|Uuc8v`dVha}#?-`$B?A6#Y1y1Y0bf}S*E}QmV03BTjkdC=F3PoatbA5l zt2Hwc6vo9exl_8k*eE88=O45SiJVlgo%tDM+b+N(F!fBgE@Fcf#wTL$fv4ZiYTWHA zt&m5!jyfTEy6O6^)y`zon{#((chx6O+1;Z$_SLYH`|5?;Y!>|^mI*tPU&x>F#zC-B zLXO2 zUS;?~Awv#%=^ERa*Sra_&y0B57IN}^9qFn*q1x+yo*UA$a=I3{O`;5BC2NtaWs?kI zfhlv`pzT^nh=yvd!`Gk!zAY|(GHxaEqS=>8!59!+ZazJBjKa{RXye)_HpcblrvSXQ z;uthW^V~j9_c9Bls`+iVYA_^k(w5@zkt4P}Hwk0f@^8L-+og#A-SN^WyMG`=D!~7f z>MN8A1i*f?Ytj9#vu+uPv3Tq#!qFMmhU-Q1JBrMV=V&N#ad@l$6VTJ5eYEY8dtYWE ziW=~I5gWZFQz`wodQT3;sD_{SXU!hlQBA%aGtDgWp8ZdG4Lc+2e|QB;r&?M!(E|=b zotFE_o_PXcGZ6Lb76lMU^__r>{{X^E=V(f2C*@K|*D$D_ki9W1TdJP>-8sbUKeNI> z!KpC!c27KkNdE95~qvb2jxRm=b}guZ8(o^cdDc8n(`T@0 zLD&Rrvd4>~p#+h{Tk4~+HMcVj?fZ|nY(NV~o#PoEbc8iO5MS*}r|Y(NdQh$Un0TiI zosmX#xtN5*8WP#ZKb|8vYF}_vx;6b9xvu&pf-zTrx%txexvCGk;t(IWkam?W7)|^* z1moX4wt^`%C2AfRZV1dF0tk-PmiTAcWoiS>C9|gm12suM;{EC^Wpz>Umq*Yc)x*!M z)-8|EavrTAijql~0`Z&sV_?KUwsUrb_%Cml&(kSM>C&OiV(iv zxiNI3^=~@Gcl8k`h2UyH8%v$G zF_=8h$|urz2U1cv|2ApF@=?aNNtaIXo){x2mk@MyJ9SmXC0|K!BM^Qlu{LyaYovGI zZ6;Bb2+lHlxw=DLjX`Vy`JHrtnvw;kHJ_&q*fBu#P%n(wN7>)Gv(-bcbK{7o!huW5LL7B8?(O>It971uNgLHj5Ux?eF8fWpMqvPwtX@aDy zHYb~dky}^L^9AFVX5Wc*LEbD*2ZE~Umq*}z^DjK8Oh?EV`83eCNRLxryq4=e5Km45 zaSxEr^h?%dkL$Csc@25Z&qPd2B?8}Es4pL9o8mLH=whD%hrejgDnRBAXw5*Ol$jhE z;P9|_GkNw@`1%_0>;AT)(X4*DnYT)Qasw*a>?_%o4%=H(&bdx)zTOERji_yb6B##i z@c1MGV|urx?@QT+clont5G8rDwpCE`hR7I*=<1g^xcy^O7qm6 zf4|t9O(dl#XFR}2e6BgaPBCS-1BgZJhV{KbA&tLsDTzY=1jQMprD^ zxUhZ(997f#KfH%;Zf?GXu+#Zmx;~gc@oj++g=-7Z5|P>#(Gr{5HXMz&P6qn`Kh`21sP`Wb5vpFMOX_+ViVM41fl;|#dWNWv#`!mP0g-g*(I zPFNtX4q||Thxvm$Xo9kwb0W?1s~8U%QiO6m4`ePCnkihZ zcnuF7%3;WX`g3)A$=j-Z&|t~ONt73IXJh(3s-lME;Gx8(gtSJ5Ig!NWZ+T5bhUnND z@qi4?@u!XyP(V>$kfz=*GLR14sBroJmo90soVf;r|1KmU*3^!q=06QQQ7S7zi6 z;qESg=fjYg-y>f3Kh+?}V*fFrC7A zoJ`VZV*`_UeNr3O;j8ClKH$jy|D!sa>?Lu>V*Zt8_&?F7uWnDIKnx1z&ixv9RoP|V=ZH`e z7Y8dI3g%`wlfF{NhvhH%Kiz>7b51ckAbje$_z_zrF_dzKt1_HK7|2m`31|#N5#szY z0_CV(vBVmev`q1bDw|Wbo7UdT_xSi{*qD$IUdUgj*TM^W?p_8`tX@bRJ5cr$$WuK9WSX3JhBrrI)TVIuJ-ddh70EQcf$6_`^44t3(+L_spBq3 zL1eY%Vl3zlTAVlK4Nq75Qst1S!Z+j9td5ibLCK%@9zA=2ZN|j6aY4x|n6YD`Q|7)i zbiHo^rloRYl13SGk!Cvg*KS<~Lp{mlLQ~$(aR_fJ44nk@^z1dV zAIXoZdz`%y?LoG$&srE#oYRUk=?r=%$Zd8C(6RA&CjBmsev!>sbeSZ)$qh~eO<>$3 zY+kW#Q=nhq{yiSd{bKxpS#%fn+Dp5Bt+D8tg%1^56dq@W_M0@TUwy4JEvZJ372$A_ z7cY}Uf)8p;CW(fx@Yr*GZ=?<1hG-YgBvRAh^J@5yz`_-@8zgWlEA6xzd0!v-Z2}zm z^2c>17+)y@{4pu>_zIWW=MUuFhyfR%iHqQ?4iD(nMn4e1JFL0B+Zyuijxzc1k?ejE zuYogl`E+Tl(5`6oQpQ-tIZI~E3W=L~iL#y@?W4Kx!Ye>rU8zXrIwR$U#Ti8lKz47Htw4-~dG4+T?puXR}_)hGSpx1uQ)zj|Bc`YQ*J_@=n zs<(0*IV>=vBn^$e1P;Yxs2V~;{Ma{ocKeWnu>SM?RaO2WaZB;$NaI-QmZk9cGSa29 zS_wLqrAQf;)HKzNk}e}09eICk|IX~gK4Jp#k~r>w+kHG?5-ZHY!E{fqt1X;>rN*fy zQ5&DtnK}7&KG9L@ySySdP^bUJiL)pi+`W^b~HPe?aY;5=DKU4^3*p)v}T!N4t z6_tAVC@!e^hp(boE~A9I>$DEE6c;lbgv-VZM)k=n#j1n~zp(f;3%~q8{=~PmeFJgf z?^s3ZV49*?nW?w2Cs!Bunf2ToUW_nF2=v)^+vf~WD;vyZrm$EeIVf_-8GJi8FE-`G zA}C?;2aQhFPN+~i*Rq=7l-#QN^S_RNR(=%m+fB*1FCQ{WC0U@&$gM9Q>K&*HNKMDv zP610=HDpWV=p76?D-Bk4Z*Xw^9GiP|^cDUF-L!`wI8))!Y$e6GYJz@L3C4uF$f?&l z%b9|pB*BXeAc}y-x5#( zLej13T2ibO13mdzrnJp_+eQN*asFK$PzW6M4$s$dH7W?peJ3q!)ZgvOS3|Z2Zt>fc zz9w|vG)msAiL?bGhU3iM009TCT`)?M@5O?jXm+vmw!mj4kmZwSiiA`V)Or+#aV~d{ zbzN0^X=nW~3ko_Dn}m! zIUk&AW2GNjs~;jYf@1=mhslJ2uV^c;q>qSSJOl$m(ChzqqXrM6!+8?&z}V`$4CO8i zG`p0-a)R`CgCtvjZtKQEG$TTpe`$@NSas!i9Obg?hIki}m&siBOi!&<+M3rGc8Pz( zX1HcSUWwA3!xYZ5Mwp*B`_(F0Alqcq6dZheBCvoZE@`)yEubqZsLKMDyeLw$Fb(5M z92#L{mOvWY5oD%B0E_+_H%&kso!0NLFP({&u+wioub6tL#E)qem=VwP!!+RXa2CirdFs<((C(n=f+@;1 z(Y*rg_J5k3Sj#~VlX-L1kht%~Cpg<#w2xv6`t2db#4Z{QZlblL7aKnfM1Fb)cnUM8 zDp!Z!y!aYp0yJNif#Bs9N#;Eh<`~9Nirjj=fb%Y9hp_#--L8TOoyGibx2ATPAmf8db72KsA zhp!CU74+DySCXf(k^|z1?LTQrc+704FMA&r!xOHY>;j&qK2(+bL_BD1g<=sxvBD@R zlM7adS~t43rgr{JT}9#oSk=Pzypdy>;}&+}Nt~@!D8_uwFlimihYSWOO>xA# z8INK)2W+q9+-gL{X;qnd;+TX*KBFs||Cz{Zk4M+|e9rM6h=0ZsJ~64OS)U(=Bcqd9 zoPQLbL9C!@F!*8IMaXyy0NGmJ*&5+msQXehY>>Vjn3$I-C+T|S;M;`pQGEbNXNBn- zkp?C6#YTYmzQ0^P-kL>0d zIuf9);MS*V+DLRPL{>GPF&P;h+gvzk_hmRXyeT6V^4^m#UX}iM*_^Z*UACT^N?sKG zIymk_zb(wle#*ySDs;tAnJr3aiF=Ot%5xYTHc)7RMK=Fwb&@%bozfJB2)Dj$*8CLz z;SQB5ON;EKM?yg_M&xhA+7AU#+bPcL7mlWgoePWXpFMdy2z#L;{v*AqCDCuGpzNvQ=21Yl>L;J@X4B6T&HHti#E=D_-X<7Tn{_p3Xwq2wF zx_PYgQGntAlVYpP4PC~E+la*AjR(#P&Z13mSRi;9@bt>F2QquS&w72a*;qF-^eTIM z!MX8z@d^L1x%I+*SI74$i617Wnfw&*I7K%p>@CpQpUU?+od~+`Y z7z6A0w!@X1EJsQH&%QBJB$OsD;^oI`YBW7%9=OI)d`+m!x|^trmDA$9KFVJ++L-kA zT`AD2rQ``1tvi%v`%E2Q8fzLs9rP`>q3R7o9n)9T*@!~=h?LwbpXs)?3ej5SX$VU6 z8t60x^xA!q2c4`t(51Hyt5}Nuq;yp2A@%m_6ZHwKm3eDlxMWXh-I^%M8$VR6)Z6)&;zL2O9j0J(3jz7|6iF5}%#rn@}izz8Cp zizuFVJ4QPiL_;{{&x2!fOvDPv*4@mmt zdjB*10bAj5hh&RL`%GbZd++rJVH0;`?-JMDu_KvCY$<~~nQq3&O;keN?}o~R}VGx zBuX*b)I>+)vYW>KV~pZrcoY#ma|C~)be7q+l7={~c97qJImA4x=S+nH?PvMBSdA5J zP)O5jSXFc7w}4t-!G)&m;~g}}30x-iuYd+0j(JxuD}R4BuKK*OgiOXT1k$eB9Y%WL zpklMdKuoOblGzaSxU?M_oB+O9IXGJHC5}S1cRfgCCLQ05Z7dt_%X`b-l;C8|#w=U3 z;c@Ya1*aBgWu{?Fy2YAG%Cwd);dB0o<@$bjr@Xi9sc%YI%OUe#2chd5Xs*!ywjp<; zJ1Db()x6NlTwN7w(gn#45f8F7@UG}VR0TS2<)?3G4P|WQ@`G{%+gp&?&UCJZZ+q@; zCnuiJu!|6zzcR1T8{P;m{wj zrA~59#Ef$M(9TcNkXC$U7ID2>QBvFU(1I2DdNStY`kK_ry=jdZ@5Bp#28C=pr5(yC zq@6^H|C2|?T0#J;#Bi0J0U-A|J1H^hdUXMbBkD<{w{C(GAJ0f{~_Qt>mo)ajQZJ^b7( z15M0Kh5wKE;YNC1Nt|KdsoxVy%pam4viPZdh~ZY!(rUJze>XQNTPo51dEJ^|X-z%c z?u!_bbXI)D3%ka+=7mUMqaOKE7Z+iuO2!stnPucNja~#(4oeAEA z@DPthrAQlcn72Cp$;5c`*WR#i3p3=H7|rjVZw7CNWnn1Uc$C&9h+%XV2Lqt#tWMBKMsk^-*^9-D8*keOgp9zS#H<=FJebZ4VD@Cw}8|* z@)2;pc0wcs(Ub%2V~O$QUsp={A6JSwX9$@I%ZDCf%k{A(sQA}E$gSSIDW8~~@#A6jc|z)GuEIbOMEjSTcAd-fc|dR@9~H1X90+^4-q~RF{Aa9yEeBL4RqoAa-LIi zY_PDM_IFK@DnShNHC4pXyy@kwxmkKwT%8IZMBhWdPi#;BJ^$Ja)cVT&Q5jl4B1IXp zh$$Ii6_3VmE!8Y%T229Fsq_o}xmxFYP+!}t68ttK{K;U#Rz)ktVRC-DJdsv*wx2KQ zI}d;IG@Jacg*}U6cy8iT*ta)QpKaacG#F&3CX7Z39J<$fs7e2~HF)qzTXU5pj zDi>=YS>ulx2x2#Gg3}^_osf5C8Ia)C&cIc^{KWFOu_PI?iR++?&aXRjy|r$kJ9u_P zmB)@v^+byLT>al0=3O>53`$OUo@F$vjYp*DY!9VITCz1YH>1z$MH{)NTYZYX@!92SSHYk^HMX8Kr&cB z@#(z6>#N~Pr!tFCwfv#5NQu@_oT_`6wobBv4uLjRi~NPzoZOdN#yK+aCpM9zU|11m z?Fa~s@%9wo9o|!x2xI5HN7Kaqeoz6XjbQ}CPH5x-J?vuA=TA+>dMbzE_ceJ#;(}F6rs1E^b;>`;DLM-WU7!B?Bb1K1pab5p zr2A7Sk1+IEaU3Iez7vLrn)Zat&V&5uxG$66GNeXSF8X)AI!gL+jKTR8S47yzliKV>4Ii{W%EUPD&3o`{4 z-~XcwPdNV_e-Y~oB{MhfJ*F<$r5<)Ut)jSiVm^B`!RRDIQ3|MBwl?B=Qa6w@qIf9c5SF_XjH$bLv%_>1y--h8GeGN0e7StWg@)5cK)aRM*}!Z@9w@zk8w7?j|n%#Ewv$ zWfx74mwa#QtC_xRQvhACD*IrQ1mirPy@_3v<1mS;;VuvU7AhL(%f%Y&JP-Ntb_4YF zoYy#%AYZDNe2x4jtr@0#3th2?r-x-`#NIBsOql#;xn zJc2%zUVf(oIsO;8{G)P@G}>E2h+)!I{`8AG{>?bmKcly>sdCph@q5q{Y+hJ}2b3v0 zuyE+F9}Y4M&}#x(LJNY0XnDXFj5BY4Jigp7xW-|SsY|;1=ON8|2UVKj#pcf>?=xVC zH#H82X}F_@YrjY|ie*a&JbZQgRceXRMou~j`+`5A{+4tW<4!QD&ku|}U^zxwB(8Uq zjvfL_N{WTt^3F^rc1^m33M|m{L?7tQQBl;EeW9Gx&jd4tG%ERTj3+Tms-yW4d*F6{tPdyOhNM@8Qt+99eom3(H9{Y> z4@XFFEBF8rGy75B0mu~Tj3sj4#>7=bU*h!)j?nLy#Tvr)(u5o2drXed6jC4uT&hax zb;0#uJ>z&Ch{>?LP2AJ>E^hnD$yHm_a6z5WLQOB;hsGxBaCEQH0VYxLy3*AsTM~pf zQXC8rl^j3{IAz zkvCQW!RudMyiQ1|G%pde{})7*wsx^i{EH4_PCsfSB&BDe@glJQ12waBk?VtSA~*ul zUPXumq#?78y+Bl%9pd~=1Pzch$kIreN3I=-l7{}H|B>g(YDIXWvSo-+x4D7T zKzN8QC+pJFIGd^4B_(@>j9*idrMieM)Zo5|*uOZvqRS^=#13 z`G>mgt$k%N^4Yfa#}LWO_QrG5M2P_dMDg7&xDf+Jl+A8reJFi!S1<85s@zs?|M_Ex z)Kq_nJQdv+$q#wMUip5w*-0M_@KIvc39J!{!hi|a=9j2dzQXyNi7;uYg+QD^WA4Sk z0N)qu7~)^+7^0hoCJ6hB$aVuJ5&?x)=gAKfMvknP1R}Z=*3fvqcY0nK8p?n@E?Tkc zJ#X?501;uAJ1``RmD)4TQq;zmW`JQk)g=&whu$}w4YWn&5>n~oNw(1g?ko{n*o-BMh!uO@Mp@!ms?1%W;m$6L)uJr)Wl!V ztimw*j4Q${NLaS_1~K1{IbxRzmnsWKv-!sPa^Fxb;qdQ3?!wp<09L_H2m)@d^Bc`o z`aAs99AWAH8>BJ6h{ZqQnL^e>=K-mJi)ph%P8aGAkdUM!=b;~D_WQB)MD9|e^?LJL#Dc* z&o5%Yp~a(;!@c^=*X$`+oy2f!SzT3i(!u>Wn(ekblI}Li!N8mYW-bolf(LPHr=cMFf#=xR`oujnmG2L1R zhr{`q{3?#CUED%i;+Nr-xQA$?&^299$y4xAu{bTJuq2mXtU&@@e%(DjfFI zG_G(w$tz&o+@YT{PnshYKc(`Gk&BU*y3VL?t3D(V%`=V(S2fU_Ba1cpU%{!WYdn$( zhy=za+r;z^6edu?z3G>gV2%m@)v^X8hTX-_mN?&yWFI*^I(DU}Z$sl!aZHAxUM!>=y%+YkO@mu()DflPcMyymbo8t+O9%!lHRi_O}>ZnK(%;jsIcO}E1b zaP!_UJ7W8==lF2yut&A>LbUUgz13nxDuqzC?<3{h;Xu^UfYyEanr9je!}~Es3+xyR znqCpOCOS5To&AyPcJOjaa%tOJ^`D37??MN-=Bln0(NtPFtwtD_px|O?fccz@;k4=Z1*jo3%r{3JvXp%16KIC4&uh0c^dTeegLN;r&DFyMFaR%ES@d3y}9~kgd+(! z04<`Hdj8+i^bE7Lpl`ULWt1AtD<(F48{4F=f*X-%77zY&;OKsU{ zfo{fI;9d2%I`pSO52ZdAj_QyVBqvz2u08D7cRhoB5#R?CN^CEnJ5leadO}AnKNeRx zEZJCX?n5W#xV*?8aRT^!g!o6uDaVCA$+i-IP*! zx(JE(y>iKtt}4ct?apht=OcmBw0m}{3v3@VuCcnracPlqPf*}1rZu|&?Kv?P^hh0s z0IYs*?gJ5B`XUwi0eFR_f^kwYTN-M6=eD98kuu?KtWQmGiCF2;TM1HZZJPX0Mp?DlvAwk$;HreO%kIfnrrKkE zEzRdp1lbr`(&A@EGnZ|Cv?l3#SX;hp+m zQtd^9gt6Dn@A*8oi?a?}N3L*rPr+qy<=wd#Dq}RSZ|vsevY{V(*5ws?(dFfS+4XH4 zQ<96|A_(eRw>$k*LD+>kiLn!E?S6?se0j=cxT_Co`Tg}am1(WrHq*BSA9VJxQxLA+ zcK27|C<22IOjqn(#9&{&zzai5DlP5HG%@|o^t=r|$^%dK?kgJtY}jj6LpV-deV0 zuY7=$BKsw&!QKL?S;W>;pCYY%sQq}WkK8VpNmacQLu10Ld;gxbO={oAu8ukSxuUo7rc7m3}gu^4EY7s-E)hP z#u{$BkybgMUh@`$hQ2hC7)KogW#hpxlWj`@HexjeCBO&h$Z7MhRvPXYx_kLjK?$kV$AI z4->%oCltfzB?C>Zxqj{8>EBd|K{|(=@pCyv6#o7DAlEtz-=@h*NBi1#$oeMOJ<${o+)_EupJT@Ql@%yJgT=bml*Za2%o5S{QhXW=JLVT=-?=7Y(Mke@+_n%MsE{n^}WC#lC6({rL!c}Oh zCsbHds+BppC7uY!o({;(IKm-EKaK12!)l@YV=fM5DMChBH|@l^occg2dD6(ZIKF1G zcV%mZ66jc`F#$w1=j(a{=jp8#UiYh9;zxCh3cJ@8V-&s)TRi$1(wj&AienVD7q(4q ziozTI@d3MHI{X(BRd*`!?1r$0tu?yOu*M5m5ul=YIuu!*NZgQlF7#>bgIORO)p8zY zITU=*^CIe-j!wTk9CF{dK0F^j---Rgxi41oKTqKe?wnv;;D2+mx^Mof_NzTVN+(FE zP^s>OnH_#FevlSN%bZ1JO+nGO^HpKWROR((u0BzFn0V6@9pQw7;iIA6icTpf?u~0d zDT_!OH6L6Xg!WB{D~NBSOPd~fya#0aKm(Gfk5C|2PsBC}?p z3{OPnk!y;*g;$M6C<4YOX+)>nKKl|WDf!t5V7+1u_%V;eoq$bC;n_8PPh+dRB72Ch zg;@CE_f0R>=eNCMs6i_O}To9~F1uCL(BllZa(R?So8_T_VM<$hDFNrJw3@ka4`-AV}&bGz?aVrwaLHsHne0+wUP*e;juL7q(#w zyu-M9C}bR5k;LDTd3(|Vb_5x8p1F*1)#cKQo1MA5^^y8jX^NKqlmegZcZA!c{9Vzy zKLXxa%gkeil{dFx-8kyk-R!Q0e-)jN)_dmyQKb|fh0XR((%)FGOv^H^-G5+zv-nP2 zQ#JlQEcrP?mD@eGI)n_sqLf>=7>43`Zp<;S$TN{B$s3^c+K#Kv(ZeMQyb5Fs0ZD!< z^*2^z>a{D`i^jRotS(N!8j>*x!!v5}TuHi9j~*+lY;Is&BH!>q2ZrfQ_}oHn8G6 z88t0{O;(Q9@wXz5&$M=P&XMA3bCEem{q7MEugx`^gC52ifH-H1=SY*4*KHKAO()qE zNIYzW%eYh8J5yz&(MI`!f7p*>e-}A9`h|Bx&PQB~Y(lq|A$91kIf|6?1M z;vnjhOI3xvb9*UB!+dw3_=3g$g0a-Ul?enLC1_}jxWc88ROI{icWw1lcLFW z1o*bqNi8F7EB;QaE#8+)x;SuoaZ%U~yjbo8*d1u^r6mY~Uu{_h-myymcrVfvt`a26 zl)2^tB^-S{Jy?J)aGRCqK>sd>-8tX@qw-476qc)l9x1py&$m^loL_ z|JqMdPy8%LHN(*&c0P$3M23jzG+T8MPU71BN*5Y+UU@qg1uefXeJk}%wzn&-FlQ+P zokOV-xxo?F!rIR_@Vp_v$_zt3AFuc;+a8Vnv%1Q?l~1NdnuorzRbG8H+h>TqZ@FU3Q$lDYFgKa5yAY7HnC78 z0uq`Vvw;wLjE>n;sk-}^H}{{KBtT6oYxocyM_X2#Ka2;wVF%B*i|9);JTw`9rpib( z@?|x9n0)2?ZP|O^r#dMi^J9P)1_@0ywFSJ9?j?<=3Esc6}WT7H`TYHEu;>B#Fftx}( z_vxr&OE~vqRKA2d3)y0p+Iw*}x3I#pF~Z&~oDW}6L&n>3+B>mN=jz*vB%r{-)Nvmh z$+uRIPIB`BkDZ}1TdZQ7?9DI9!Gyuk)irg6IYk|nAk0quogi|Z1s8Y&&qlas9M1n% znHc}g>*Y2VaFo=fAjL9n<}%xman|f1W>{CvQR181TOS9K2O3!3-kcP#ERlFxg%gMj%z$vY(DwpYUKE3^w`O> z%?Z5rLTaQhP{MUsdh~{5q)JoS5gKN`KmQHy0qiX|f_Yc0l`B>*(a$q2Tq87dzLSIi zy?1`Nin_xV!^d-U4DOa0LR;GXo}&TAEX$|!te{~0yVys8`e8JWOqn|@rE}-9LxSC) zys6ddaU|e5E|8~F9p_Q2J>J_vDw8q*g>~1&yVbjOmU@l0q7b$`yfB;&PoqA1p`y|v z?2!udwbkDzISy&`Tp^uC<)vwOY~(d&--gOVRai?T!)4nHvOvFAeF3=Q`WWm-9* z&Q=E#6+$389K(UyQqFBr1ELPR)HyR_e#1MwnsUstimdnU2&7>cwF{&thYG_@zZan? zk78pdLDe1vts=iKZ)a|9QwS4`vqZfQs$3c6oEl8mJ-K@-2Eyyx$z3RhD}Q2?!oSBf zKWwdcN8nKUjf`NgWpUVfg}~51b7#W(E>G8jPG?N^<8yB6#rXMmZf?lr;Q6xH79iBq znB>jr2Ty643{srmqU}7~7#U=WRfc`_kHT$r;*QtnAQ~>|9Jp+{O>s+(1WnjFbDgCF zLha&oLBxjy-St!lom_d(wQKcr zhOZLWz~UlEGBB5I~k#vyB)s89*rvYL0h~|>4sd}fRn80P~&jtbHOde z(rdwX5%J%7St_f3{<|lNLvh*A?drm;!=GlKPcu`-L=ta|jU=Z}nlNW|tn_vOpD6cW z8#_fB{&;gq+>+`le!?EOz4MixA_HW6pD@Mf>Dy|baIQaF3V$0L3GNe3lC4qGvB(}E zjlh+Tw8*{(9w^ORsuY}t{}Ng_Ho|<3r-lh4^#^M1F~K{R66gZkJjPktnS-PCPJiWp z`gA+KrvAa|`P~V_@GZb|oHgF8eZoFRFMHgo9_nj=UddbD?+<1DE{1Z)#Ap-|8tJH6 zxO7adr~lF6n;jbI3unA(JnlajefeJK`IL6Q_g}fi%)-RvBV3Q;OaARe?qcZ0!VMTf z30(j3ZKUP11?ZC+>leR|W@;?F!2hR&h=qvoZ@s5n!t1}~o|V2qd_UI}F5rJ7<5t7- zpyF0b_3GyPDSRiVduISQ#5FKJg6NG@xE2@y;^cp#1{r}g9nG*OXjsrZiE+8Z;YZ2S zBxP>g3SK;C(fHcDmq{vbRPv-F9f4&3=KB7&5j-HE?VC$a^`rM-NG)H-ti3%s20eb3 zKN$e1jUO}B92PRWw$}*pq67}#ge)T>qTS+B#f>m;bdIcVTBFU*1r)}kM@w43su5Io z{{sopxqn#}O97}EPNdZ0LpB2etd#duNXZm;30?3CVz|zzOo+A*aOZFMk^)7Fn1QH+ zohK?UdZFK6y$~xom9Ah1rR$#$0O&hve1WaC9vHbmcCX<_VJyM)uoA2} zDA$Nx)*@0# zt^o;RA16oP&$BPxE~1Ge+)!~cK)CJnKnV#ZLQU!feM)P^oGXl_s{s({9_CS*6Xa&; z!^5s6@>*SPUruK3y*Zxz4!p>D5*7xLY{WA*%3%s-a+6gQb$R*>h1c9(xCYDg)eMQ#Hjh z0!Vy9DKwy-{TpHYPoaiVW90?*UQAwgDr({XPB{wyUn$1~h5wau{HDi$9MOYxT&&1(4~?%vSREzRRl1lS)vA=deCX*co;(@!cOduwAT@U+m0G>5+|3 zfU@-XLio)V*0RUTUg2uX7O0U=zVE*U+1to`7O{-Juo)AFhO*BvF zn14WAd?!=1AO9Kj3vLkfX}*KhENst>Qw+&F3{S8>U+ooo+5BXREDr9~wjH>Ly1x?t z-PZ&vb>4eWf&}G|l&d)Z#PeSNB~JUd+@kx1(3|}$S(}r+qRBWeF8ZzGscO4aD+U+f zH>1@CBTB`$CvtI5$M`qhXBJ3gA!*JrPG$b`YpNO_TRtqM#fsJpa7%m-p!j%XYRq#_ ze7h0&QPNeyFWGIr{zROnS$yL{j#r(XJvZvapN|W<;+?U-4opRctOMZQ1tN~yF`YY8 zrgBfzqcxba8;N!Em0Vri-Meci z(jsR*#)sD2u%hsV+CKDDM0r$+Wx5IG<7r-X;)-LU4ES@2BvI}BVKt!XBwU3#(2!DB zAl_ow^Sq_?YS6qw9}5Qc)vdm|eXu*wi~&==sfUObnY!>eZ$1AahH*=m*9*oPl}Ok> zFVUU~q~EwGecl)1VLU%gv6TYg+atu`O(qOYW5$Feb_ER*g)mFe>0HT*!cGCuap#|O z+`nd5$2xPyIM)uk9UzL(@I2FPLYy4>R>}#Ci)cDcwYr_+*3kRJx%aZz?an}We4Z@t zw^r6Z7t!eUVeE*kk@WylblZV`#s@5=Ah^O+#Dg0?+PhR!yKR%qWrE|&_)-iT&GAWd ztO=-79c@a!xy-xjQcd{@^;8V&5B66_AJOlHJNfGh(duKu1O#1cM@M@v1?7n4`&`o8 z%*)-jI1Hb~p0t@pE;UqJSNsvNPT^V3j{rE*ElfX=#e|7mpRi8jfS?P}wm(Z-wm0wX zDQK;9<44z6%KFbN= z9}jV)NIDBmPHaRASD{m4&TF(Ig4Sweh zs?~?iSUDUV`;DQ#0Mc^mziycq4y30CljvpH26DAC6Qx0aXlXOM{ik)A_#Q74^qSy_ z9gCrqkb&AC9_wxzu}V_IM+0sX5+7er!JcE&4w3o%^CZ>o24$9w?(0&@5>*3XSLLMr z4+(}HM3D`+i|Bk3IWX!A)!VYKtTLP{t?&Ud9(Lxb?`TGZeC)89k>yR?h5isG6z&{ zECaCs^j>ntuw=A{J=lF*TdMdCXN{HD7EQN_|KO@K_cnN1It8X0ZueYIH44KDW`-$Z z8$5##cD8@pO@+QRMx!qH1x#{h<5-(I6GQ$^2n?VYCC3FKFXB++xP|FsQ^fC~aLX|3l09RGp=iSlcyH1L$=O8Cy}UUeNWhiq*lB3!23Via?R> ze3w8S_3=zL^ffK0QsYU>t}{q)Mn>`-65dtj*m3TQgL8BhxOBNs*L}Q{d3)0;bo#Ul zQ9z(%kS52yV<#z|Q#_bg==T6yCZBmn#x(%>NDIwF;ykOhiI~Q-zvy5@A04H(rQA|L z*XK`CKkU@9Rj*$K3VkXTY7JctKxpLwTe{-7xt`@7c|U?!A|29+C?}p`{?BE(yAKYs4?_rFSzAEAnzb2AHct z<+W+vuP?bvcIAGeX^W{J#wp}8|8p?qqGz&oM$!~Z$`P1sSglF{K=}1r)5lP*hB=zk znm~wXYu^j`OVbxkC-@n05PxmHN6RL)V7x=4=WA6a&s4+$g_f5cl8G3@GsSq!v-bqj+S(`opP#-?myo* zwLA|jpI!A^ZP#+uT%8__FSqRoOz8P5UgNApX^ZV$UAL1!JjM^&J)WA4BXQe<#Pb}m zaI_`A@$qul%S2OKBi2TJ9u2~pw+H-CI*$wTIGUGcl?db@Cuh#SVri@;nS)&-LbAbZ zCT_X3f-J~p0yQMaT6O_08363@XhS6sogZgpYs~z&h$m(BYX&@@%~w8~)JM3>oSeE* zVU=@JVUj>rb+aqh@0}iJ7A)yYAlTH)H3B_{f9%A-iG0a#c4v2P)qoG{JE>frSCj;V z@iY^}IDK<2viZ{2*UQ%8cC+Okhxa(x;|RVPwMW2y5)EgF=mO(drT-y;)dPvnw__zV zAACn~j(XH1#&5LcROv1Y&!m`oA->}=J$1Y>t?!a(wBP*CHvE_gS)bvlSea|?OgbgsLy|a9 z>n6fwq>+%3vloC1E6T@=jb5=ElDx;ymU}Pqx|1d75@Lx3cgD|E&|<&EfNY@bE8ICu zdCE$^WlF{)gJsvJ@II3#=!o$*O9j=|PGmysq~Hxcjqg&c4^96EOz(WyIYl6dR{=OG z(Kg&&;=Q2Gt=|)&o5zArpf&r-@KeOP8RBMBn{lrRJdbRAonC-DweqA?GA(&IP>!Ac zZRn3(W`P6@d5Giy^%<14K&OaOZ|e`|a{)CeIFLp9V~ooFp83^j@)dGlkHL!$ri2L{ zC_)fR7xd_IA%aN%X!aiR`gqrjl@9-tk!Hl-@qi#B0S|CT%opO`9j`swHx}~#F2u&~ zn;b0Mtj|A}-!afi*3EpBGE3jfqg;bU;*0Oy??bG@nONDF6}cWqgpr5yBQ37egKT9F zqJ9?~uCUF`e)LL0QbP-Ymy7=BdJL+V-(}V+;@VLg;Jsoas6sh|ic<0A;1u3r*#Ds% z+9@Hu{F8czk~wR{eNyeYdCT`#p?+<-`I){g=2A*mfE9uF-% zF&1tszA0sxm{bioQ1v^_W^tXvW4u0-GHCD8mdnpoTzkImc7AUtm#<{D0@C(_KxBxZ zoXyTy{CdA=D>Ydd?1v6T-y|lA=XuHMqqe|%zguY<-K|!8I{XBLz24+o%T;@N828>S z8|HJm8Q?R^5gg*{9$|9<6*7p~Fy#~{MPDZw3w8m*jh+0ejv%=i;^&i$XFb0zqcZ^c zox{Ee?O}0DQZ~^{9VX{;oz#c;#N;^|6_DqL?t&7O2&NxuAt>=o{|ve)T6$iky_AFh z@n$oYz)s!_*X_Gk!O|)2Z>(w%J{bJi+vHcpSth#HSC9+r5jmfkF_lg~n&7!O{bj zNJ{wgzgJYH|Fb@ISh)?_d=;zkB9#9j&*7Q4#Tj+C*Q?4|RAb$0=e8G2ZCWL!+_#kZ zg0_C)g=isN=hI3OP!Swz%gYlW{k+QGlx35ls+ncVpZIyTVZaV80N_pYuq$`a>`UO2=pBznsfjV`&CfApr^fta zK5*IgEAI&?et_T&av_{!8N2cplub@CmZz0P)hPu@9GJ+U-8+<6stXOz6Q(MdsMc z-2hgrCy9LDas`LeO?OqYs7fQU-$~@E`Qyy0x7mjQ8iju3uDNf{p)g6VBBy&`8Kcv)}&>t`Hb$4FN* zN>aAX#N;$@TTQF)4U-Vx2>!(4ta?T083^sEGE z)OuI_JkWW2f2ze!_05I8q1Z<6*iD-n(%?$X`0Pu2Pvm3%oH4*@W){UmYs9Fy)_fhz z^>pL3FPyZpJ3{TY8=>e(Vx?vPcucs2fyaa?Nvy|e&MVfk4ray;@qnQxrV6DyV?Oh1 z+e33xnVVyo{TJ>)VB@c5P=o$qZs3QLfDc#BHcuAFDcsS1R(7TssV$)nVo2q$wE{of zDYd_QM&i{VUwj6&d|Hc#{o7!os~Yig?ki8vHjJgoL}&c26Nlsp!i!g-#TlH7o_xj1^DJ%4zs zoVeHYkLUFAQj&UKtNu~pZ65hso$1qS-wGqJ;h(R_EE;fdF&7>@uR73xtHWf#YYX8H zmeTttl1jFY=$1bQ-}v65qlNzZh&G_rZE4r`A;~$B`~2`9d$=+G~}S;_~~xn*=O0OG_r0E;SqkG46(91RPdfo*uk zJqTpV)E<|uVIh{ks;lgj>S`FJFZzyk921(rUrv~V9~>VoYTdOeJ-CY98;>`kCxigp z&wb8Fd0rwS7Xr+6x?gEYmsRC-T)wi-=K**0tF*kP_YEcX6(jUTU=tuDi=Uvf{mqAD z{cHDNRN04);)?f6&i6!~)wr>u*ig)NJ7B9t`}KXg0A#j0x?o40%XZDrY8y5HE=6xX z4TzQ46GLE+WBfd?X>Dc>KkJ)aVr91Z^=a|-RmBsBg|YNLtafj0i}VC{?gkF{N^gIt z;`8ZDRcWYwSR&#Tir_0U^dL9(LUZe&!gEib9K$m0E_+*)rU!MTk zx?2my`YJpAhzuxkJamMQEU76*M{hrCF68A#(nFJbe~qZAJ!K6^RTjOJNO$IUmLl;! z&m&s^)g)Vx=#I!XDa`_$J^=tv>5EH~`Xo`BhHrZ6Bf5ngs7GQv{k0g0#%B^$R~RJk z`WazqqNC=J_jRFGE7%~r@LqS|=gQe&5zbA;(@n3{BBbHK2Q2yw|tGPv2o)v=?^kUYi#8aTWUSa?%1H zzI;r?FOXBU#UXIAzY^&ar}yvkCZ3egQrWb-vG@%6Zy)jzT>8`(l zgV*gUP97BeNB7=0IkBygHJ8}dC6t^HF&z_lzEADHVznER-`eYP^!(|2mzV8_ z&~EXJUR2@53|JWSsHEFl`I-CH^AvUCl-Gi>Y%!S^21eDLxM7v(2{8@onoDo0n61k> zB)FwhSw>KQW4`s4ij}iPBde6$n-+Gb{fEVxA+xwU#V~FhY>uq{Wfu&`JPaC zP?A?7%$|(Q8nZspw=N#~AFs6Tzjv6uIngp#ZkY&YjbO314i5Je#D@f*Fq8^}GP0=B z-sR0Tt~4&EwPw3}a5_AgQ9^I2wfrah_k$t9IC%NYK{W&_D(BK6uP0?}@i1mnsW+2E ztA%`p>OFS_Glxmyv9YSxPC)JVZ7&DA$5DGOIO<+IqKeydQsg51q$(ZSs@UPW)VX+q zR>?JAyf}UyK>?2KaIaB9j%-u2PZtxsZ<9sj_gl0d33(Eqm(xT*th%qiG`E#D{bdl_(GM$54G1w`+!n!H!~j}|=J+jy&QbyR)bo@QtIJ!{2;+9`aFphAni!wR+%*IyZ($5|UF z+@1fNN1hw`6te39M33cP76z0tZx_c8Su^K9_9|?3>RZ6KPMVaem``8Zz_)A|woi*3 zJ0;$qqU(f0-|#K9*0B7>`$Q}vHEuqgH?ZkRL3Ti#LH!-JA_)sM=n?%*%uw7yH4D~U zh3hwf>4*slmAkNTUHXLR^Vym14(uJ)GEc{t*{OXcQY{qUbNlvvs6R3oS>5a6BZHq~ z;&h3Dg8fpDC;@9YO>nuy^xaz$-T|MR2KnTMWQQP*4W$H^rnM3-i|7f2+!Lz=&EEx+ zK5-v5U^V?#jk|N1 zjf~y%J|>R!$XA!q1}suyoTr+{wqiMOfLkwwWA+?kfk;W5XWtxQVfrBl2ZKUDNrmls zcy8;}N=~lc7j^pv%IYFGh;WX^-bBr!?k8lX&2G(cQ1D{w@LWZLdLFsFn&eF55oWcb z?ByF#$w~0m#Vg2=)$#VkR=W+;8dY1Z>$$eW&V+^8b1Rnt=wADNtoLaB;R(k#Cv~?L zE*-r(8TW(F2{oD402*?R{Y%ZY)56{OwcVx$7wD<&4pXG`trC+653ifO1;5*-$>HF} zF<_z&G4@R%h7iIR>iNb@V=j*C6j4Ef9M>=uCMpzO z6|s(=Oz<=2LgVC|6S5D>zF#Ksy+3_5;5PN?9wo(!#Z>LYnIvc>iIIyF8ob#zL*{l^Gh-JpB{DLK?0}gnV)>8Fa5my;8m++ zZsUU1y|WEZCI@h~Pls{CS2ZS8pm({rLuI0hw|{8)Kx5-L<2ad5y8no2G%6?E}YaSN+SdCXd%a^HZqe%nr1N340N3M-07|0RWtQUV8AO6n8W(|}*k#WaP zC`=)4vu+{YV_Rl$qDKOZzAC4r=W*_1r2Db>^F1aZ$Veh}cc7D~lJz7PG$9>FaB(??MPX zLaymsf2bU_Vv+e*=cZpdzm#)-=@pSJWadN=9kBd#C0u*QhV#m*^xCKhwz2xmsm$?a zw41NJN!2sB=VYHobkj|2JY^5xI)!s%#a*!%Vt-qE-1)Sy?MUJs z3M*Mf$(i)}HcvIY9QJ(n(`v76z@n^uSd^yQtix%)37^#1PSeRmhuJ4gl*zU&GmS#Hn_@Kf3n|?I*sz+^&6LWN`g`=1Vg}+v0+PDYJyt+ljKU`!Z)HnJM_)?ut(aeE9 zy@l#wI8-8gKp;iV?Isz%qqo4=ZZ!RRz@n73Q89kZ+fMr#vEN&_vd4L_ddNZt(bKrE z>)-T-r9B;vp;uJt(vgV8Z*49{yX)irO7rx_?9Fhj_!9kg0sYx;x_YEEZ!TS00d=s1 z`87U{cp z2I;SF&=z4DmakqYC)fd?GGXLgsoqCJx4y&Ph8opq9T7sTKkA;?out>f5TZmYx33sl*( zC!W>OcwS70-0?%i;R&H}Zl?!%e2mE;v_rx>34JuPAtl~lz7H76nT;5C`#Uj@>G9+f z^H^O@iCv7o0wG;WGJfv#?W@js;-`v_O7?BrPwM1!EEKbax-Uu-Isd$OH$bm?otr(` z=WmtuQv}(5sV2tiTjG}=R$A7zZ2U$eEUonzj+mX_`nF&9DHv#kfs#HE!DGnWj`I)ZI*A68K4(`x{F>6`g9|IdDCnX<8!YlL@6z$MK8<_MqiE( zIiPg0Y)YH?iQfBG)P~9^Uj=ox+2=)A*apGrpG^v0TtDmVF&Are+DJ3#AsaUPykPUx zhi{+1xhIZx-#f*lUhb$oc(F?`=HBMa+H2`KS24%@<qoaCv#abaPh_soy4Qh#NTI%>h1G8qhDCPA7JWS5^BGB1uP`Fa2c4lyo0%@kN8ei z>>PYVkkr_F0-oZ?K7-JF5pWCLt$?<*T{H`{#Cx zE8TwW=sx`V4fc9@lx1opV(B};SAN~jw*dJ);U&q#k9bxFoaIhHm0rf?&b_0N4POxbEw%a?C! ze}6gEHkA#nf5aH|a@X`+$lplLUi4lubX&U~`m4INF$UOgevH@@z)U!HVxs%Cz5sF7qW|o9Kxo$OPIad_((* z)y*XPY&$6jixZ&`k;K0)Ut!mNSPD^nAu`=P$rs*o4>1&9Yq#zO@ccM` z_1bQ+tF|@cOx1qurclPhP_^0DCarNZfe}rg6%}vPoUyaWgQ?YrLTncd*jq}mszNV^ za9+#(O7d(xT%izGAIs`VvHcq1lf!FD8gEE2UMnywb=@wX{pc$HC`GISFQhId{%kFuFWR zxPG_XX8L?50{h7knt1Kp;BJZy7wWk0hwaD*q2%hX2cEC>sRgfdd>}T_=exNqok(p{_x$@i3uLSB<0BRiNOw0$V$h4iE^bfoIZRnQ239~iM zPBKv#6epLltsB-DSRS{47ad;c8_&G4k=sO?)V-afGzU&K<;gdZZF z041lO&hb<|T4r)YT=OthS&y}@gPDD}z zG@tn$C-kxW#tJMl;k`B^K9VE$^U^v0wL4$Ukal~)NEpl~)WnM!1ZODUiukm*mf71= z{c-87^OJ^v1Mt3f>4a8SNB)#h*!?PdQ~G3VnAA*5;C=g0uGPT7JJt8}`9QBJnjaG6 z`Un5$!tY*t{u3)5?DXsCO6;=Og;?gnjA4mdKC8_3hmT=?%Ar9CgDj%cn>)n^oW%FI zLlW|K^@X3|R~@9!+VmfhhkWcpwwRvJlY{<%uuxMq z=hjKV((9{B((|q+4R`}n^8P1PiFq{A;)-Aj|97d%&F*8F&u_vzd zp6Hgl|NP%PJ1&21_w4@;_EJ-luDf#WlsL!LK48Mzz01prN?)&^FHHs(wqeuJ_qcQB zu02C46d3PzJ;L%ttPA0$L($PMc~NpVRN}%(*zfok9o)zO>VKEf%;DoYZW5j2RIT?t zxv3qdRNH-)#p}4k#fK#odP(kp@6C1%qh0U++4$u4$A25241xL&YWA6?HS_Opg8#p( zApPGP=)H~VIJZ`L64*e`ieaz_7#MzY^3}4-%UU5m(K>C>uOBWegN1YKbJF4@LBK2o ztJIt#mPHM>$IBlsmUQlaUx{S;f5(F#b+oUsrb(+6vgkCwxyrD_{B=wbEGW2Yeso(E1XG^?v}6|o=XV7wc&6_nWZ~9aN=2l%iC~uh5-`x z?Ru0v&AWXr@n}}VK~Zt(#k{C2%UO3b4$*N2iN%f3fB!dA00+-s{5QPN0T|uR^yB7m zH^Yhl%zs>FTu2DO!Gs&$H{K#AmW(k!@AYZU7Ho*zVSOcuO1;UL-xb{zCoD8q?bZ~$EOC5$&_MJNq{RoF&Lm$b6@OT(j_!T76HLZ#F=k57_KUvkLZGV9I;nhSDx$he!C>RGNFa=KJO14^?%Z&kNjtCOiPO@)ReTh6-~8 zyxn*emT6s_ap(0$?wCw??eF_A6Y1YW_fo&O)Tw5zwACC-F=SIjiaZb1rFR?p11o?@y#xG0~02Yc8z4%pc}`>(x5_wmRe} z#QQAM*^9Dl0WCMkWnrh?U)}#&Y-`BW-jzGMV}=$c?0mkXolXeSPS16r9JGI!&S!~w zGX2q7PS%PMUd1ejkD}HW{eTAWm2)a!CpRxMGtBYcyZ*I=@}ftx+VP^mwX+XTS_y4q zFIjEYiJ$Bs*Yi&YdF=#vc}%HggQbY?%enRV$L`pDtJVx|%i<_AYqe8sxU4iH`LZ=_ z|58QcJtww`cXxvX8cxrsT^)XuaUu6afH#=+#-;f(I{wF_;ystTr!TL5`6Jh0uMGS6 zlwWJ@myyHOy#?8Co@ER?HaV`@x!q5No;YQDx8~k|@yc5gC-}1sJs ziSG}&Zrt;z@c8lEe2kz0uVKb@jIVnueWvfYJW_Qw8=bzT()oOkk#ge?+!UqX{q~Pf zwy1aRhZCgHIHI=l6D<|}236F1(EDGMNMom4mck<3?*@<5|1QH{Ewd^(+so#!uD%dt{npiVgO)+Xqu_ zYjeZCzp|45+b7EI*ozOx*7LqURSwuo_sqF}+jSnDO`8CC6VYgMt+F-HBySGHnJTLWi2#>8$}OgVmm|AMrKuPUWC zNrt?wD7yDkO=p&>S%#BpKTR{LU9 zSsou7uPgafr^>jmGS*lb;{Vg2xa*>g?g&ko+;J-N_uGWkUBd<;6>L)K*~<;5ub71m zBMN?vsjFmwZ@dUYP_aLvuL^?*LQ_xA zvv-cJ47&(tXc?QA=*eI-K@NzU7IR&`Rd5ubBoYrZW%dSRO%(X<>jms3Aga&~c zf;O%~o}ZuHe7`F?G$(s^>+$OS48nS5L4Y7k`jOSdI`c=%sHrhSp zerX?7W8ljyAq5xieKAj+I^;Zkd?q3JbT58R%iIQhOx1OXQR*ctMECI*I>6PskbKMG z^febasEfuAZ6`~1nVmIJ4oR8UISX>#bBqQ#?w#(^;}1)pcRmYp+dJ7M%^#L9Z+5oG zb?z>b9dd&Q1 zyK>xFbbs|Srq3=Uw6jMouw`#qB$EW=r5DVXvDiY?{w(~ikEeH#TUe~Zh5R;)_>cD; zdFij`mGx{x)<4Bp3Hfi@^K&G(z_(t-hhxaw`n>3NGT5YfkF(V7u!Wx&9q_A%?zDI0 zuh15N>p{29EofamRO+I4v)7N9pWBd407+y5n~#?qUav_n5(Q3QmmG>X$UY?gwGHmV+SRGzQ4y2mlpp(!*Z?QDT`}dO+Uy0GO{PUCUT* z$%M;rKMe>fImv{_Sq>Im%G`1TGMxod0cH%qOaW4#0jUv|gZ2Pr7La-Yh|&jWF9NiH zBrP4eC9OMa>3-mC4K1bL5=&9J&jLG-*b{g?bj`h&OqCVN-bAPKdh~K%8%x=`H3EN> zxC=+Ta~(dj`rg%+8$OZX$(XzvW<6)B41KR_{SfwvAAI`QG7G~B`L(HjZS32>Jg`KS z3eNZO zNs>P)8Hs@=vcYWoZ+q)sh1_@E095WRKMnC176!x(+x_z_UVZ(fgunk(xbos|*)7|N z!m2Znu%RlpeFr1^b6XvJ_={WG@|%`W3{RkWY`pc>m-hFWPXOA~#uQEueZ78`Yh7;p zw({lY7K$^=&p z7q-zm&EbJdZ#Cz$dB{0t#~8_ z=5>8BQyP*T;a9}!$Q(1kKO`HS!`otl+a_`~hnFZy5TF@dXERU+*^YjgFOJbenq^V^ zGRQA6{8ETS#rING{H_UvhR%e^ni=t1(wi8ZwIvKGl**CW{79S<} zftRAH4_@|8JIZdd@*BpAw_3KC2iN$v0Kliy$=({0eT@ZU@!l;Tf^KJP`iW3>2NAVHB>siaPnNeM5dE&V9_ActVN*SzgC&pS3mB2<0gl|ZK*S?)Cu zvZ;xHI!$Bo2)rTq;38JEc&3PJPh^|VGGZoWK)sphcE|R#^-W;JmVjX zRxzQanha{z`gJU$u6ry+?e0V`6qo7s%pga?j$e2J zO4sjf+oO%w1(O4sN?Xj+k#E!tlHRE4Cv~V9CKWXGwHB9=pA;eEagEE9zle+)p666C~N`3_^Zoro7|K@y-0Aqh|# zEFr`;SZPoHPtT~EizkX%G%DpeQTH+q=I{Qit)HK#?J9%ID)ARf6pPsGET2N%3ep16o z39qNkUGT5QRG6HPG)?Ji1Hlrj8(h-}Tvgsk05}Q&HSQ)g2m?S3fHm+9OpYW50LuWN z5dZ|PDsK}2*aiTR0Anivqydb(X)rmEBmhJcEH!Qh*95-Zc3O7;fb#$_24K_yfH44L z(p@RK)+tZoV5s7Apc4Mx9Z-6nKEq3L&*--NoKNF8xNvnKEjz()j{ z5!(k|GhPF*D>xHYK620HDAZc=sQEUa+-HJi%RRu9LrYN0wp$yK9iET1epRLmd0GG( zR%XKF>}6Z|P^P=i>o*2!0$YKiFat#~8jJ710>G!4LY_@PnV)9BcoY05wA2j z@+4LqSJ)BQe+27jWF-lE<-utuu?o1hj=;Dk`|4Idba=I0C(B8!JT9VRH#X>gb?Aby z&|1n2=)4!2{H}u|HpsF%azR*Rts1U(QbU2N$E+b9^04~-g0S#fHoWhoh8V79X0$&f z+?JfSAPhR2{kMP%qA5`qq?TuDc}Y=>P{D(hm^rfnK74e?uX?I1tO59nWB!O z9CA*Fe_YTbvh6~FFeDjHJP8)15}7fwAuw{tLIDVZhVz~TU&cjs#19_b>0mo!FNCUw zXPpF#<4QW>Uk6!{ANYkM$P1koC&6O4j1I%NAanBAf}Jo5HRBdJbQ*ARL3U)n1(!V8 z*ev!+0mxB!Iby4>7(Tsh&^f(4xFynvjzh(aR9+%E=6Mc;Ha36rZETK)Pao$lxYT*Z zXL(nGsng3h0PME~7uxFUtdXapu*T-sGj4f;tblu+weBMaQ*HSSF#10TBgv;0xy5CT zKn<_wg*KvME~%tZtCxs_$f>nuKag*suPQBMbLLi_1zxTLEnAens-= zJJ)T(%HZxj-U}{^BrdQ`n9m@o)qIO$yji;$bjEFwlu51Lr1m49421$VqKh?Sdhy`= z#PFLaufxcN5;4yBto3l)jk?X`({76(Zm=Ld8}8nJ0kBcg8=BW)TIcj$Y4=dCmOM;g zs~j+A7GRr-v?2^(uW;CPEd3=aW*rzI)U}J2!<+cS-jGVqRP|VlUL4&;OOPCC_PoG} zSbif)CjSyjiu9O<&kU+PA`NOxA15zCy%8qYjo|hGO@wbFT?ZkJrN2R?HHL_jKAaIg zpF^rUDvHZmr{4nr%>aOHA9>fm&1fGvb!mUUWab^W{h87;_CrNXMti!)LQgt_wnTC% z{)5Qhm$cBlVD^3O>lJ&ZI33xrROD3TLy4P8hebY}f^G#hx9ie!*mOtT=oL z%D!(1U~Pa1(B@bi2ViA80yOdO<^1RXU}vWlIhgeib5wnC=}hUJ*;nH!8vsDF+fX+6 zb=ITpG+OoCVHhoV=2+%y0GYNZYr$G7 zCQHy%dHfBio{RG;kH4T|J{qM_zi0CM#Y7KZG}duFQz}*$HJ+lr<^Ln@)YehGQ>Cx9 zl1Z3?wUT|9fI?1StD7I6qp53!Hf4GVHgXB}#?xb*5BI58!;iP-5EG zZD?a0OMR$Az}Kh{KEU1YT8r0Z>6S=eMY0HL|4dSvI)6aw1Wh7t%543@5sO@xrs19&%EtJS}_Y9$B zz6^%un(1Hn{wxRk{ooEjkqdXXkZ(5e|H4)(e+`h~0Z>fvfW1G1sqWUo^D3p4aCbvZ zfPxvIFd{(LJuc@jtDFaWy8{ek4*`a0`Ud@f?j%epGc0_1YFY9B?i~NV`gy+_z114L zu}QO}25gQiX?A#2i{eV8wqXl~TW&Ali(1`Z->w^eecO6rqA2u4E(<2Jlgi?A4x-1Z z#f35_ugM%bkOOPOFW>Z>k724mM|v~o-GfwtBR56Za8|p?EGwdiw_hYJX!4`d;1@c+ z#j2TAi_{kJl$Vi*JHEYE)3glQbUpLS3}qF$6L0a6UL!K#2HtdK`(*>)bqFOC3UwR| zYN|)>WFh@d3Chu$BiXqMrKfIgF0-rNMeV<2Kj(AoAn_P|v-({p8?)dg+^vr2_$J@# zHw*ITy~@{k*;NhTH4g84Y#>v7o0+FojZspOM#lR%Fla^He`6cqSvxGRn6g14&&W6N>c%wk62aBP#KXU8An$-T+dVqcs0VyPUT79{&p#iscCgXE&lq{m3gC=6+AxU4xT^*|Mfac*E=;-paBLSauDn`Y*7VTqBjpX@wWm^ z#UtKV;49Ecc;*4E9%zl9W@Ye562ZR|?mnq7U%#o+9P_b2f%?5tnIQ7}dD7Z=rE=7G zZ(XxTg>ztU)I*fYy5Htl zrRRe-Ds+Izy-?x~bPVnm1DYxnkLH+PcCw^W_sId8`)~Hm!5p9mDcnw=ejgTGGPVv% z^UV#c16+K_QX@hR+*|J#V5e&Ws5ja1~5*&`Y1wjq?n17=6* zT~BPa*m##n1w@cfG{-PQ#c3*J?Rk}5vCXmGm>xqW;HJSI@?h6}&biZlZE>L_(IhsD zc?0OmLLLE;W}WVH;|nFNnAj{;DA2dZap z2B7SRme<)2Zv$Lrn`2X$9z#KNW~jhkl&`>E3BYBsP*Q{M{@05p#w>{l>_q}`O@L}a zew>L%Fra)|gBRjOubq=+2(zaN)T!u;1BcsCuQUweeot zPIsTDn`6Teps4%ZhJtJZQ14-I{w@y}ctj59OD!!?^)+7spf~_D1%OTfPznGJ^+Ubo zWb$`2&jUbt0Qd+176U*(0Ehs9tN<_r0G5>=(gjjN9`S%j%Ej|9S!5uexL<3Ias8Eo zeBvrRU7B+(YMcNJwk>JsF;rfS%W_ps56!g#Zr+t(nDy_Q04vZ`ot39c6BDDxahDcK za*P0A9?*^(GedKyZ(Sep0tz%`000vKAj@=Vt9R7+a3COl9jGdexGdGcjL_d${p%xZ zaYn?FMKKAm4g>NA|wU?4NxkGd;s_Z0P+FA8UVNm0HueZ z@&%&#uErO^Bl(g5@D2cUH2^bTDl+RabS^zpS~9*QVtqqr<6TJ|LBv|qWY>MoYrZ}p z3GV*Kc5`fOf1%`Oyh~B90++ENZ(LTU!g;W~9dOV8c5Byt@4>uEU=9ETF5IyUz=o^9 z#j8C)ys|k){@LkH5@?R;tpp6d77Uy`1sZLe_VxAI%P@f!eUwUIJluVaW4aVrzI+_# z4K!jbpidBRm2CV28t&o$^JJ?#>r}P5`Ne47P9_=m`?t8bPuZkA_|^h^v_JgwTQo8@ z?i=**ob{SqC|5?d(vF8v%8LoZYt8Yb^`>Kbclcx&!s%QhfjdT=J~ZTYvFfWB1XQPl zD&&~o&oLr!cU2D_sAuk*iP6{;1zF(Qu8R>xw}vkC}jbwW>eH+PH=Rj$=)akghBYr1mw@@9X_*T;JEb*G_+5A6`4Tf{&UuZEv}%!5q+{q`?u;qO5Ty z0I8_Ken5S^t2Eb|9m*J>^*E4qW!E*3c_plSjd2AZGi}vQyQ;wwKvUA-44^5uoDN`7 zY+*g%d>nX&tUav2G}|#;$uKK6TzO*l-7xgjQH)Xx$DXgN+KY|Tu4)mL!+$X^0I%gO z{fTQ6Ll%FS;L2cm8&iPGBRtc$t7W9f#M06csIkbq{k z9c9G-OThn2z%v0Jr*?SGPb~%ow+IlxPG-4j;ksk;&y)CW@4AC|F=REz`&L%@(BiFZ z-GSOa5Bx8I^kS&|m}zB@f8OL@s?S>*{E^=6b#UDQ2*Biu7yli!64kx^5Rj!L0R+mE z{^{7qXzTj?^kLKW z3MJHjeA?`UdVq-)3{hYC_FoV`aVo&XwXJ_XI{ACBBqCgkMl$4{Es{zL8Vxg`7iEiU z8PY@3sS<_ro6pfRF(;#?Ct%J9O=r0HEd8U$9^~~_6I|+=^+5Vit5Idc4ECZmaPk>A zd1&o6E}~r}foxyxKev3tFS>_29x9`4W+$#~6O;RqYULuqO;@6uG4r?zgI9R@%{8>i!gP31 zcO4!2+KnE19&=11U>aBUDuloL6exzR3ZQ|-?hbl=m=>GfZDKFKz-OK~YGhq(YS_f~ z?s1x$|oJ*kjM6mcg$$x-#a7&UkbLr1u zG3D^!el>A2i%eP7+t}ZcrXDh%=C#+3y8k6serVo>>}#^|1~ z&!O@6u+7t2eYuV(ldzXm+vOn7KgTkJ<)07zC?2^R8PhX2r_XM+`F|+X#|0%#)b;0? zJ-}S@G1k|NL8(ja*lsPSPf+^vj2>X5eN^{J&W2`9SD$;DHHlFR8?T`XK4bH~MNZ@2 zh|}4*6fkU;Eem;5hbZEH2$+!q#RzClE^3S5VlZ}FP9L~r-mp{mmdRtPOO>9 zQm-gA>9)|!H$#1Xe*2c%3Lx2mC1-O6v>@ZbEMG6_(qd5EW=qfBtjFO~<*+7C^jidO z=OpPere$CW!PyKU{cKgm&<2+F8JZy=$t2aaS}g&e*GnqxCAsyI$$JF1y|oD(j<**LFDwtubU??M`V7R>#2xtdGy`=GtzL@?&HSB#?_r$vo99v@5b+< z2CfpZqnhrjbV6&+?DTXqX{m1uns!o~OY*ltlZ%&pgZa6KZMxF}-m>)#osWWYEPnqL zqg+9#_Wk0Uu4ugWX!%-W?*Qu8FL=)6bgn2R*ye%@&cQQvSkT)j6OmRSld80v8;1~B z{*&$2FNCDuTXSFH<~CZCeW|nDUuhd0GojRz8*Md@@~HCFKiQ~%I~~vy{^5w; zDOFC|eyvHh_lx1zjqK^_U5!pT%HFbX)Q1`$G;&EA3b z`2@j#Z*=_H;fo6Tu$CK@(ULHSFB0AnHe@}**PLBbUfRFW=;Bx;PkW5@bE)*SDIAt* zTpG$3cytWvSysWax)@s!M$DH-D1;F`93w&gHZHi|284*0tor5u{z|PL;;GOLjL|J( z^XJ2m;HM%tF!I2;%L=54wSf5R9cAWHKp{4I)W7BW&Pya)$?VN9#G@RuM^^eTpT?^CBRLIcLd`gqO)b$j{D( z2$l6~80Q3`q)8_U1+l2Kl%T6y#@e{g*R~-#e-M`-n3u%qbA`lC%4>4Sc}US&Oldm> z0x#smuz5`Tn{urq-t|#BMSoMou{@4w%iZ{{75sc@C*7SKE^=7JN#|{+M~TpRJLu*H zbPL%d{9AJU?LU74l1r86{@jD#U@IJrF7==LV|xb|pMd~x5?U`JvcyR){YdpKSOm)A z*LV6g1Nvkq{W&>2^c7ujo_=W$&426@LARNwtL~wJ9ZqA-=s{PG@JpNFO?`Ataya-< ziMZZ9%f9Ru|k?FN#bXfzs&lSjQ>2?6RZ=8v|Eeg>*X~NkxEbZRqQF1D)5{F#RUPzIGF|r-y=ji_y%)}MjE|yI=jfq(bcSQCau<3V znyAJ4z94*U^Y9ELoE3v_r!jA0>R4w_L@2G6_F} zM=QjU=|spPgeXXCz8MD9oKzn54_$=t@)MgQo)roT5S!ls2O#nFYZHu-(KeoV^zsRD zB!MzBa~&f*hp>k$L=%%lFa>kXd1L-jWBw*l$vg%ic}=Kwho0x&6DE-N{CnY$dJBTQ z>9YI|L0$*vM_5ll*`+keZXN$;2b6!E;X{jyeVbBh_v17kew<)`a_0Mk(-&{e=-(1b zMBYmIo+_$+<>3>yo#LGb;O9aAK0YMXQcBx8YRGrD=&>7a*k=?sd$i=D_N&2Z#pe#*sx&%3OB5TjA)DaxPJ3*MtC`R5!4-(*x70$(_igOhi(Fn?WJ>GF`KuwT<`qqnElCmcx%6L|kY<^zUzld`4+kwTEl< zku);vBT1IvVdT*MW7=cTFl`XhGfFcwZa};ssN}I27;}2kK&L1V^H>Z=?{ANo?~eFy zkLckUx8-l+|Ey>*g}OzrAd<%X&;9GOUMCZ;!WCkOtnkWL#4GU1XrchTa{X=LYI@=7 zeDjII}8j2|5za_aYC27`WW{tPlJreHFtjmy{;ua z(8If|vYDJE$`GFjVg(0=x08}#fU%I#w67vRYaHuS=Kv8q`w--3&=6Y&kl>v2 z`(o0a!8Trv1K7*9tYVVO3R3+57SV>iwH?whM!7}~k%!n57x$UrI1Y?jC&h>yq71<^ zVwyTB-og`81Q9H^cV88tg*gX4iL4yua*1^ z6f(mJ;%x7WjB87lr9tOcXp#res5X=LB;^&F+yRugn8=$^X#bL!HNVdd!c=uoR>_CV z5cC<0PX`4{KIDL)vD%vG((OYiB%A?b-$}6`A6|omFOm=CA@q;ihb?3N(&MUFeh}zN zXb6G4sT2~z2r2?P5%Q*bNXR?#VL>g4n$)KCmXy3gyKr!v(1w0XsuBx6*7>t<0zYOe zWCFG#A}TH-RC_5xPa&9sL}GLNCWPb!!Pq4d5fF_luaQH)xs{ZIL)TyT2fn5 z8|@wGcm>IDAQIcg@{ZIoX3?S+z5ccZkK=oaYE|llBNr8mT9wWtB^Z&;7k7J~tR*T< z3FNw*{AP<ma+v%*zLgNF&NdHdC9X^FgD_Y7(a_^X)&Cgo%Kfl8J)Q{ta&f+7&SaIphld{Dpx0#A4%O7 ze{i)E>XsMF-2dQL$8t2rS4LL;^ zcvH&ShBd~UWKn%4A-Da^M|5`RS*fM1l`j3(EF(Fo8XlvmGy49Ggwfm>!;NCZD?(+i zp25aPL^@$(kdO8!V&+0KubAD*fRM@vY-a-h`ezihs=Govv6?C zhd`hFW%&2N(h6LG$R}LQ_4ft!E<*3Mhh}GI2jTQ}aRVYanYjX1ocmk>2abQP064l3 z3fAWfm~hQ=1uVGzIXebi6f^FQF0MxeCpBlsigTH>nhu)JqsHfK>S z38)rL6tcaA7e#At0ijshk%~p30o_x2dO!5~zU%er9IQwltXw=;Q8`$-w*6yu<-OW> zJ)h!aT%12>KO_vhLeU`a+wC3lha3w*!%q~UxAzXYLyo6cC}7W;g4jhW>^S= z7W5Se)RCM#-zQC8G-D!7>f(GLDEv#R1{s)H32LWFz{3YiF=&C%V|FN=qlkWbb055S zs1|a}0;RJRIrC~w5>N8(*|wj8N`Kos5WT{OBFUruPcIEpORo6gC)}48OLo zrvkxrwxE`Jwwbo?(=%=TfSXwwN%PMiNxP*mljd(Xr|-xMf6#rZ@Z$3b=^ooT{Zx^g zzzYgK#85DND541hmwiEnkPA6+Z0VDKcY53$IVlI{dEud-*-&lw=vu99ou^>-e;BK( z{30eTTH04V=XM&%2RGoMq4}+i8$Pwq!eyPpecF#7u}4eismN5UpQJ@XW*W9=)H}G5~S=0HcU!cW!Q0n`6<$9+HRUNb94rtWQkT7B`Ds|)svy5_@s(547Zkhz-M%`5hw9?mL~vnq>zp{f z4jLaE#6r5jj4Mq*xr^We$Q&m~_sJYgKFn}scGR>kZe9d;Zcg|N&U7wR0QJ5@Ll+UM zd2Mvuj9p?rG+iS8vn8l}b@7MUh3{tLKg^WBn<@V=!ytnHBDN7>NIUK28|ocSlHpt^KdP=>LlEWPuAx?>+0Z^^#`eRk z>TM}c)b_;r?TH856IZt<{I(}pwNeZXT*Y=)g=6I(;}B_;0RvF~cc14P&UJbKhdm4u8lJ#G)v zEt+kuwmeRebfrii8Az_=rzc2{$WNI_f#eM?+y~2T^Flm?H_rg5g$j;%dogqr zILHA9RUA?1!n%LuCUjEeMv*6f0Y)!(pPXapJDbRj}eb<|;UF0-a?$&4FjuOreuXIO4ZnTF9%JA}GiOh1p45##8Xq_=m6$)l)`KrH-$=d>?MPpRn+qYW6$To_DG>@2b7N^q7vGI@mV)mfW@H z-HG3a{rY&fJgDd2tX{-Us_`AG{%tf-5wNW#tSBhzf~)Tg!kJyzN1vnqyoT@o{NY+< zQcX_(ZNpIEu=wrKP^NQVkoCg~_PVONke#H@muC*VKKd~9sxIz#IhEuvuzhuFe)9cT z`nxKV|KUq1AMJEV@A(u8aa?L9&vq=vjRpD7OHJ{at~)(_ zTq-%E$S$S2W-aGrA5Mb~`vBQ9D6WD3Q0JV34zB^Sy)Hsz?ltnJRMi3`YMN+UJ>8As zX##(?61fG7%1yXkspRF9vNZB~igknE<_3DFbp5E#w)KIZSD9;L0c{TH%Z%0sK_;XxUab$HT+$b_&jqx-i4|lw za8yxWBg!E093dL6Z8W7|$i%11!k)`^r*ftuL`zXwy><h|f4}ODSHv-FFqOm|GHdFNWc!Lwb zG6DHE6uk@H5ILy91%q*JT+L5|Zv{pP#58YCV?HQ(3n2s66tpy5MPCft8HsQW+F2Bq zIqWIX*>m~1LexJOFqnacEXc5hLUabeG>9bC;3-5L;F$_pOEtx3#_&q!z(1+bxhKDZ zdG$~!LUmz8*>Sw#LMjr{l3vvZLc`-%NF{vYbu&#Xjm zgGDQhM2{qW=Ay5XJ|j_~q;GE^N41iwbXv*DiY_^T29K{~pO!tm%313_vZqI#RAMV0kTOU4)`^@gE)KB3&j@u2_ec2<@qVJk8xMtnRg#N zCvVsncG2}nQm*{YzOYNKza-_zrTe-rUU~8&L^-v5=qvw}L6fx6L>VEcwxa>wJeJWH z>pPAcJ)6gMI}^qS58*U_Y@}q`|AgEp-voP(a!k3^5g*u_Sh9Ap z`ZxWRK$f70A0rf-D!pguT(b37f>=wpJm>3%JI|*)%1xT}s4}T|=%MHb+LQOY9}|xa zL7!+|N}0GT?b`u+jLr^+-PXVV5>?#!P_bft-xn-*{Gq~q{cfpu=%BY)Ry`%fT3S6d zrK};rYvShlt*2aXx}&Gpe>-jd?es4{xwZwmwrzCX_k*4L)$F~mnvVA$w)ysWT_g4R z3g}K0)zt|P9rkEz!WU#~eC(`GyE^=X|8ZA=cyTa)8zIFmRcsS~45>o4$;$06PM(EEQ;j6)XXF>`)U0fnn%~2B^QoI}B#3LQvWg$rGgW(?- zuBZMQ%DYn+@nz|ekitygq;&)Dd~fZBum{lX-B3(Ou>pRG&@CsTtoV5i@aIR^oo>*(_qTR;9SVtb zUR72hz#_{@UjkbnNxaT+u&aYX_0j(b{@VlVoDXY5g)E zR%??+CYdl>40$g1Wo>VG+ZPp;AJwJPP3TMYSvqPqGQ!|}X zIBDWIsmfQ)tjjIn-|e4>J*~I$VXe(XyBajkl8No7^$tEP=K{V-o7fD318$-BMA?b@ zx@`0w->=EXFa^(=3h<4==nN) z3Z#E+2y=cYsd*|K5x&esh3|ccFXjq@$TGG3@H`wLM^=*82ww^2`%xzp)A+UZa0OE9 zJfX1V)6Yk*08I`euFdEM8AbHQ2e3GY;7##%W?)l2dK#H$0tBT(yax2uRP^E3gn}ym zh#V%$VL3K^16Z@##aoo*dE)IFcNKMntI zi|fAmcI8*I*S=~x*nimN+he`|>n8s9T<6xVq{~zBw;p5;xA-OL)jknwUv1jC; zeNC~24tZWPBbdh2*B1#ciCZ1r;?hVpAV0;QxkVQDd6HD#nKzbQ41V=K zwBp7qgPUjAvBGUFxmh)rQRP4J#%0cTpa6Fu9EX5H>LkGHVh zZziv#-S1PoU-L)5b?tt(Jee^3yvR~scwV&iQ~2(RKuU6qj#0%BnGS7FieD18^`Uo{ zw(OOTx*zNseNZLZ1RYyd{f=7K`Yb8x2a-#nCe$<;LF{@>$!Yzf0)I0ov`Mqt2m%{5?txIHQz1Y0 zGS5T z4K(>)ZQ?AHESZS(VcE5bv0ymK#AY9Ze7YZIE%SkJ76p!5M%w(-pirsCkD_-4Sg8=s z1Yo5@{2ajGMI-)=)_(sc&v@?A-mQ|IuM6O zv{Av&g{p`qD!8^##mGbf_Sq4DeMW?CZ5z-WjYAn(m;x7v?i9Y%-tXtKU$<%R|HEbf zfeiy(_LnSCNe)k7N@E8ktWdgUi)2E&F)j36R5`TUw%rxd?4b~CfKc|xzijj~spcew zXaNk>lOib<x~$`wYUyrcs#U}A=Z|9dYfA3P zIX<474Pebo=<{A5&wMHOZ_eph9QMC=Nr?}dM)>Be#Li1Zfi4q-BG8W>+rl7ZgqA&&{ zr8UlYayI0O^v(k44J3HcXs4q4+ehTTu0T%UWeJZpOVN?rILLj(s8gbQS;wlqj zm1Lna@r-1lBXPVz@F+{v&@7stHaQndRLM$Fn#fN`4@(EKod|XrkTJ#8RYqNeXQx9# zgyD(Dgn=gr-WCuneE@ALfh-aH3?Qx%{gDFLfF$Ed@o-fM^f?ebF^#xnF0nqx6}2F^gORB0yn+g9djGfImpYAytQsqvC-*aBmKDQml!aI7 zR=1Pyjpev>g$WW}jQb4!8&$_C2|)z^ZEay)`0z6}m~dl}d$as{+d#|1rvsX6wZBIF zP*Xl|?pp1!s6{ok11~Y}Yt(|8vVqcT^kag8FbvR75~#=8s4P~i#SeB{Tr<%OFOd3~ zF=jJDUE4u=b2lueHUHQ6>|T2`#7%!}BGnz!VxNw^Vl0OM+xtAV{q zbz28ktc61^=>2|O9Cl(Nly|3z2yc7otFfr9N=Y zc@&rxDODEqp9HRBll$HG$sa-zk&Z!xyhI`JW<9J~gU#(1PpL$~=eBSEEPUC`@NxXQ z5S!CS+O*3QT=qF(%6_*WX6cF#D&crk2*0-k1T>m<#dyA(fPWy!fJ={ z4{c=-Ef5^V~!%n6)JdcFM08 z>UizdWFkSenx?P=O(fJqnNS15u)vEgL2?7yhZRIXb|d=Oc&vbgJ3iRudd=h6NcVee zLs?Z>u9>T5I1o7*AY?)edd&p}92a$UP2B4@|J{Fm+X{}$+R>kXIryja;hKEu@Sj}j zbAencO3l_vq$!j+wss38QX>kbU80&1BMvfQ;x>x~LY1YGIg`oRBrdaIMz0xTy0xof zl}s~cbbz?4U6rI{Hnpo(#E7d+nBt9MvQR}(GI31*4Pv`z3Fn^6nG=bJaCX;E_zWym zPAv7Hg|e2T^KaR`*Tj7kb7EMARH%tfAx>mMO&FMN!rYIt94$RPk!3jbTpT?IR^_E> zb@mEX*K@I0lES*A)ww8Cs;oM`lUDB_*ZPfL*(4Uq{mhwyV)!{j0bgj==`6-noR4Bw zz%a~u%wKw#722!^(scxTE!}BMb#@q@YsTeo*2g*N49n8uqEh=7t_A%VGk~G(;kNXT56nV?#S%paSYyH&70s-CZ=~VYw|``*LP0|+doz+ahj^tvC?qY0_)m-| zDE&@CaI4y&J)>XtFA(ocI{hwaPWH&=Z3!`3rYdaHrrtDFO|{(l5HlYwv%kOV;IG>v z(_U2Xz=ZZcqwZUux)b$@_idH->_GK2c)Q_w>qHiOa?B&Nk$G(so&V)ySsnBE$EEXZ z&+R(uT)R6~&|SF1Poyxfnl&7fS2#zcO}WbY@(*vQ#nn^XLyqrHY8hK;3yq9DIL3KD z*7EYi(pS3KbpO!gKl(IPo&9gGe_g$^t>bI=qHde7z>l?8`*t7o{)_&{@RHjpTpoy7`ik9#`O3=OQh+UR+&U<=xqte@=8#IZ#w>L8BK}hur{3xd1Bh#Q|D#%D+?f2fST6Hd+6h zp>sy@5rb4yJUjFM>hnrUMLN`U1F#FD0maD9BIQo`$WBw-OT^2H7%VB7O$>CWmFMze z@Vpq|_j=jSh?iZYYRB9}ca+%fytD!Bp8{giyAwV%8=8yYX8~~y=t&ANs|0|S6Tl2e zgD`%?d!|7$iH5?4W=S+>OQFxfpu0WMVHxvBrFy?9E~rtk6G>ddm}i2!WY1f=oSsLc z<=s&&QUaGnyW8o@X`z=o(7D(>63x#PqI*5M{Qt6D)U|ky1qd~vW?o-3n@ay(Yojc{ zum%EfMeusgR!uUTg!Z>QNrTz~RMqpj|zhflTbUOiS56sF^`YnGJ9< zAV{h)qofFBn#Giq@Ij4BDYU{0$97}l6(b|247?>Sv_a5`j7($T%jL`i-P(&~s=dm( zEK!$GYfckyfx~ywQo;tQ3-Jl*&|4z_GZd_&q}T!CY{*Wc!8pUIfd7@9AZHl?a|dDa zL^wrn3-Gg{LRZkg9)*KJ)-r-YYh>kei|vAWgs2RLEiSrVkcW)eGZ;2F@iM&O{;;m4 zv(}ndE7Y#0u{Oe$a@`8-zU2grL!?VI@Dy+@X8q~(0iR(*j}MrH4P8E<1!mR(E^G%a zoC~4Hi9k*wusa7W_@w|cZ>ENLH+*;T1^K;e`!8xC_mipH{U6 zF=dQJ&d|aDVb4$9Js&%JOnKXdJ=1t^g+0c+6{TTAHE&ZsW#FsVwqf`lU!BJZ1zn^y zv+(3B$OGxM2Ubfa3sLq?@U|=HzNrCtD)Ds&Q0adTHrL4w>23!pt%G!-G3ZK1kR6*1 zAVO;*ttkkneszwG4}dqs!aszJO7$h(EC%sQUvb=yphz* z1KcGwGl6nR%{c4Ze=+>6dEf0r*|^!u-bO`i%X!hU>4DMOi`(u{Omk}IZ~e`5>n22^ z*!A5uL?-k6d~d6SRPUy4*3DM#ZE*p!R{NQ&EnGcB1@hu5$D`gx6VIge)5ex>Axw0A zi2D5P;DJ}@^2K4@z1tMWeytSkias>NTvYkE=6ZkbI`U2K>j95zVLgoX#Io{tT_0)D zEhkPXmQwTI>J~@GlNNHTjn0JDK;Crlr-{&#yZYKk>}CVO9L@>2a=pu7`TpIfo)c4| zaQn3>+VLOWS!}C#9Om{V_6+OfuL+|0yVy@h?_86ea$VwU$@@9bb9eijJwcwGCz;Rt zCk&$xpY+d&I?b`dT3nVekAL~9BY3@Xkwvd6!b^~NbJzii-;2bDeN&u96sE8T zqA-VDkti$Cn@sPCgYCeJ;wuFEKiL(36JJU4-8|lmdlPH`d2D7X6lIrj1+4k z--aVj1L5_I6gwiTLaDJX1;xuJC|d^wZ*2Xe(r}fH>@JC52$9*SNA9Jon2TWxTajIZ zb_T`Y99}BX&E|3fn944e zW!SsF?)oSpdmoS)BXhsFz2iY$S=y-^6P zY+gdS;(Bz#*C}Sg_tR@N>Ca~)(67!iQ1}=2iN99s=Y9S4EJ^uONq&i-7@Go<8Lf z6!gBqwO=D_R!z*2(Ni8WrV{)`YJf8Z49$eFz3RGDv4zSlGHF=?Z2kpa2R3vOyGUlT@(3 z6epXPayc6}OCs2!_OeV_)W}|BmXLMLyR#wR43ne>QoS9yRLNU*JJb@)DXWJbAk>4Y z;7g>&lo*-~u9l!btMS&vyhf->_YUd~=0NpO4MLs4h?>Tkl!a_Lc@0ofFsI9%DJn){ zfDZPVY@9t(GBc$$8@CsUF`C$aU-D?*HxDvWF$E4rDvaUdNQDvnX)04xq@*sy7&DHy zg_>(mOvu1?C)8HWokfJx!CEQmI->Faw=R62^xONrSY7zW>iiqR*{MekIqotxb~vAr z`9oy-+3Mgqhvr)?|Jb*2aw+v*ZXSE-W$jZ>l51Q_oIs_Q^HY0TJ#uLsl-a^>(QW@v-d7YNI>&erhKH(YfE2J`bbwo5vfiDx`7Uq$p_-cTi zi*jEGTH4C!+~J8AOaJclFZq+OGkIg*^=Z7-mwBsAcu(8?oOz^nKSv(g?iX#cD@MqP z>D-_#p7!aD?AcqT{zy&4M%B!2`y|izxNAYcKH6UqZ3l;<=GW#Za;tj2L@ll@RJ^b1 z8H!q1o1u7C<@Y6OY3=S-1M6o8a46?LZo>@w?NjaWFm|wm1sFY-z{0RLuR*Y+g#FeC z7cPl$XPnGne?^{{5R;u~DrdT#Db21}HJxTxqMAx$7pvZw5^$?&dUJq(4uTipaoNx; z%()GOHlW8SdLw|9330ByL%~20%a*J}3dW2I(1I2!=!UUtU;rIU`G|u~0wkY&i0h#n z=Bw3j1Cggvz$BCcb-)5EUNaREy5RmwM+AZHpv z5b<1nZ9S`Nk&Z5Ut5$LS@TycOWs;f0r9nX^04@XC7zlzG&$d=AKc*DAOG>;M_^CL% z20;@dv>=W<(Qw{lwo{e1Ti{u8=1gAb9n~=<@p=)|fZc|9RuTN7M${UaSb*o7f=v>t z51u~_tgJ`Nw|>#A#g1i?YB2SBI^drUv89^psThAteJDhIN}v{VT!IsmYmbbqV{lDy zaHD{Zj1U=&Lvmf~M=iBTWv#rj0scvOWfT0X^2*kBl=2_dw={qP82>+DVtCOgULdD> z;4v`q8Q~fOVU6e?snC0b`%+FV7or{+Y)v4}+L-9jC|IE0KMl7{6641Baka9-YplXX zS+N$BTux4w0)5#Z;#oEuUXhbat7|HFB?j#226<0v_#Z^@XKmMO~}5&=>7?&e=i> zT5$C!eQ|er=v`&*k;=M{x_ zp(lN#V?a`D)3?Lt|{=oSa@A1oUBxAz_>ESCOBTHxGGW_ zM(?#K;A7&jK)UmU*yxNQg}ynw+hRC=skR93FNn(M|FI=S-B5M?tLuW=g1*hMdDZk= z!?SC%--JA)XAWB>vu_msqFQ$BGA}TO-QaqO;PFpNnJkfLL|-trsMmik^dxK;JEsjU zFX;^vCMPvg4N%RUM$#`u=nR`irfC{_*ce*qewtWi0xev6ns~;Zmz&Gm zi|6eXhTHJo3&Tx#YlY$4T-T-OImOcuX1uau)t^4tnFln5DOf1gT%L|`=NL{^n1g-N8VkHC z6N*B5{WcO*J824QP$!|T#M`AocMyE544YG-J7~atB_pjdh*ioqa>d0p2sWsFoQZ8| zY?3tQw_%d3~LJEsA@t@<^#BNC|mk3@Woac zfmCBjNm;d#;9si5Y;OK0U}YnE0z2p!4}O~@?qPQVt4KNVpi%HN7za`rcsrbDz2Fiu zGLylbhO1mg6Ym(S8ysX>^Abu_F3P$~B2~NJ(hv~0oWL>#aZTvb`G9{01WGm56#Yzq zpAJ<@HO>_Mx{U;IFAcB&#SQ2tN|Y&h39ID<*j6-A)`2cBg+{G#Vt3|*WMpI^qcxjt zhK$T&OiaV^m(lVthJi}UD^YnX^;bmp^2iG!|9_O+gM(C?@A|;}|BpJL@ucXTf$Dnn zgXt)D`yka152r#V2xB@B;}00{OK+bBTbikDE7ya!10mm@8-U9dc408C7EerW61b|> z7R0ee0a5+25{YP&)86DGqS-Rq?wp}VhawVwPvqI>3~kSY!-jkh2GVaq^*&&;4|w1k zgVyHNMyf~z(938+LIGrqwaj3>GS?CT_x!(=5ijNVFbpoQmEpU*+ejudymuxP=nCdY zYxWP;Y#FS1)<{Y!Wjndz)=Enp81J&!>ye#~#4p&MvW%Wj!*-VHsgv+~6V2{FDc9`h z!Z55b+t!sFd5-=i9IEImT3=M>v};-X+TLfzdzOBUSpP4;6|W+b3Es?n^hb?tH~o67 zYDu&jLLwC=z0p$>@9bDMf1Z_1HBL61`zyI$*cHX|Zr$NYAH5p6fYU<}g#zBq#7ckc zP>b?x-iID{OK?T5R`5xCJ(m5{F91s()omPGe*Nhp`aTc8ZiQ91TXNWI;1D@?_(F2n z8{jB8XSgM~>ostMT(~CCb@Zdn$DEJbs}_O@%~b1T_he^9f`HoZ)f)9cO)YI=;A6k=P!W8=CDf1p?NU8s8c)%9GZ@4+_GF!joC$7w|S zLst}44Sf5or;h238RB!4_!-Gh7O$J-Cx7vVpHK?2KkE-9&nd9Gfp(8E z9uM!S&3+Z~lzx9$iDZd)9*wIP%nL}UsPYCo^VuR}r9(0H8-FQZaiIfcltN|*cRJu` z_WyLqoP%D>8I4G&?MMXX*SgOh<{AOcQmPx?GXt`vD3laMI%JXy*zKYb_ee{&4wiJw zO3a7{r6o4RPtq7K#*aId9${k@h_Ye}yj)ok2s`Q^lDlt^>Vn5j1GBM)nQ4Gs zHndQp`H4cbn(Y0Hkx-eJX~cbl8lTD44@`wtOEo`Ih&?jRJWAc3LCvaCsN9|yvSZvw zD3dKx`^+VVq_KBPWoy(vkwSV!l?opUYvjBsJjY_y0%g=?(Y9hGqoxD3M;MFo(e@IJ z(|?}YAt}~1Q#S*^_^teycPK_ZVI0>fgyE0(p90!7qMKboyC!sXFbFOu@b4mtwH*Q% zR~)%f5Q!vuGkQ&Mszw3xqA2JFk4>ZDHp4PG)0h`pta4KlF|rN10dTS*M~UX;6wtE? zb;nMJ$Mem>$|e*8-b?WOQGdGY46Ct;WN#o$#>nY4g!p{a)Ji3WYH@}^B{f*94Kwxp zbVDUU&rdT%=jvIz$HnR_gEv6jK^t$E4KAdN&jE;OWuel+)s*oFsUbWTCIcc^s5POn zw!oos-CQ1j%bHki06eDliii^IigeTwJT`V*FEo#a$~%|ZUo4y+R(OUswg0e1CTSI zJ`4{~M6&=@I&>A`dgEb?q@8sGm?fpo#$(->rW9Z*cpVQcZ9-3$LVHS~pU<&{!MGSa zvAI#;qn=}j(>4apWGr&0l`W%}(P(9N$o|TZAb6UxZ43Nx8KKOLP}W2;$Agwgff-1W zVmuv5;_LV?C2f7=-TzQ-Bwu`3J!vsMjEWCyB3 znk0r}FN&OE6CRaS+ww-`r#2)kq~*8w%qxY~l|spssA=FfSBE5 zI2&)U`Ch4Y{f9VlQ_pYvI^RCy$~ZY2)H82kz#VPUeFA_}anVuc5xt zqphv3je5%$OSm(1_uckG3!lcRh@@_CCI9ZSi>rc;MH7z3RaF8$p}OTKqjO{9o>eYC zQ^`6qd+$r?+HU4rbmU3ovnQ;4N2}!8ZP%BX3);CvUt%r&Tf;5lbeSFzv*f&9E+zu1DXRt}(bcTYQRZ{?#*^b83Mqu3PW}I= zec1P#p8B=CwBYU2xJO69>e^?+X35o8dF_h7svNufLdK5N_PmKYLbmAM_Ej;bhA#;D zSooy&5ILt;e9XImEC{*i(aQP~2c!HSvsfJTd(H0Mh%TXsrh(zclgu`;6w+by+@0}o z&-i|O)LPQ~1K>EhZXPfC??KI<9sko&H^RVRa0UcR zH5L^8j7f9KQ)Gf{h{U+r`p zAFD)WAR|i|6J|J8lfWMt@nmedC^{L~MSn7)`o+6KHB&~Lb$RIR;fRC~8I80RYZ*Us zIhhj|Qvh+X`eG>@3YuYje7g^L?lQ`FkO+8Ut+a=+SBx)!+kDUd3!shbP z1@eS`=%50+pXu?+cFe&J2x zU*%5aSlHMS3z|id>cAxO{XuCP2><3o!1OOyBXFUVdP9KDp}1OuGKsGlAZYq;QCxK& zOC#=DlI+1n!(6#>gO$8vZt@{l6#Xwch;K`n>t4O;atmCeK+Tf_qXZ%~rBNd+1oHr(!USn&gQ>TAB)IZ-+Pg*}4J^ZTa zYS1CwPpy}p@=xSyYi+f)uG-r9M_At2+hLY>3=8Yssy@Q1KFq3)VUcej`evfRroVfm zpkx1;i&}PAUPSX}r)#?-E8J=xzIpbz>sc%?FtB}59;xO*|Gd2Xt;Du@)QYXIMq}TO z#BaAi9FnD$fnDeJZfEeSc6Yni8uO~0c~us?Do0+G9j^+EfmWQtCtMrhwk$~zoh^~QT`A;#ZpgP3{fPXM(Usb@oI=XwVu#P!H-uYqa~tw4 zL^1XBhsbd{^7n#|B{XD_jE)?Y(H~<00CZ$F_FxZot--Fd*pt7H5GYyLbq~94x^=r= zF5GIf25EIIYC|I|#$ zDJ#)0l2f)K2gxZ*(LO8DhhWheUB^GrM~CME#1ex-R!=0cAtX*xE4vWUy?z&GiHn7(r-5!kflVhxneYaB3%B6L;U7TFlQ(q0H4G zR^!t58~nKg178>M6N>44=B7WjxMhZQ<9iZCp>Cjdu%7Clfu=Y>x_NC{YJtky2X?gQ zVlzNI6{)inRo83RQN%`Yt%O;5OQp(wt;Mt=F;1q}FZxHXpQchl&-wg%oo=xLt~||R z3}*uXbX<=z!q#c!UJQm=92d`&YOcU>3707u`C=WWsMTU z9*dxhAGDK=DDFMKa?ppWnu}QL$@?#iihD>6_r2!ou@c>@DiQnSkZ$D%?cqnNg#w!Y z8Ck#X-=4j9NvCgw&2E<3m<1=k3OHEc;5PmI{H>3tJI*}6;G9Fc-=FQf8t&}*^})`6 zQSv#fBr+}e%q`fv5MEWF%N}kmq(Z}eePmcck}bIUQ?~l2yT|U12{-IpePHzHshjWT zp$=9598J2RTj7;ZiiWIWcl91f@9YgYeLb8xxQ(1UlOMk6D`xFGC~V%yEA zfLo3yqCCop1B+ky2aM$%$3)nD=*kvLtnoVJ9e&f9YXeuWT^|A5)`K^ww+9;4h+$*R zLn}sEa9{KyZ8^d#ANiE{N;azT8m9*t#1jRN4Iej@us6EmGNdt68Fw3k)-#UQ3wCT4 z?`*C+0MvEM^E2vd_7_Tg3*IBod=Z||_6ry(m!R!Wf7bVK!AI;QBKoQi4?nD@C@Hmr6Y!T}+%6%=z zEGLy|lSY;;lm5}A)X6NHxVZ$*DU8Ky5F9LFC%I0Ru_lap);MRW%t!4bY9~K^0=ofq zm`C%N9P2*^((1z7RjqRfoERm;Qq4?C-E05@{coh2i|fB=f=i%s ziRL(^&J0L62lYra$!y3^qS;siWnTtx-sOi~Vw# z@HZvTnF((c(}gOcl80mB&I{3|!0*8n$i)8h5XNtBrKDH^oGd6#qB%fG!2+2oOMvK= zw3Hc>$rII5jSD5k5fG!46dX{EiAeFviDwOhH-WfH3WIBft8BoelR*Aka7cRc0L zu=Y+F938m~AB$RfX<%RK6!&iacwF_I8*7;WhQ76FLSh z8MBu(n*lv9>Pdc%lz7+})V`=kQ?O?nz8(ODs4dznJVzJJu~hZ8m;rvZ^(0Svn#S2Mo&L?HR@U@T|cWLs3GZtYqASL zn>5~wAFSGl?rJ&UBRE;;d7XM?AQ#I>{3Wbu*ooc!Y!&#P8*&C1*nSONo1o!Di^)3u}9&|C0eYu&iE1iD#U3+!M$LiOe)dvUuGedVx zx?<)uORdd4$ zvE2pH$!MG5z3_%MBz5-oWgl^StAB2#&Rr`QFk z3A1IYl}`L@ud5kwc=2%fm%;F?x)>qW?{g(cY$*?~kcZzH_UrB>TaE84#vpfLR$Zr% zoK+0}94p2ay1jBgXC_nxM<@%k>(J5!B~PJNxPH@b(x!wyR9%ZWT)BQfyh7z!rBYqx zejKQ~*7dP>-?xMLJzJyVNc5JWQ;Jl0c-fHiFwMWkZ=sa*kk2zWZR_7q!^-2ac1U_{ zo8zwkcKx$XcM+=IqM5i!1H`NF{LhpWj2YYakLFP$8vaOLyR(~oy$t?E*_U32W$QSP z#|MdBynvwETuA6z5JXRO{c7!tIa{b_E!s-_5?%Ywq4M~GAe99F!VwZO6NzjF0Ef|1 zrU1B1s7#_cHVMEuqm#=>H1;$WBNKU!jqTa4V`_>i(e)f#Adw}iDaJ%#kCGYHtuhN0 zI|@~cmCU)!=#Anqq3YQj0{?+>!U506bc4+QzyB=@3YBO&edr$)aNKL1Zk|?aHl}*> zn@(q?)vg^=IS<3tAI0!vzBq=(s@Lo1K)O@*ncy1^9twc%5OiX$chCuE?;yL?QqrGS5=nnP5xy0gVlI>m1NEO8T1&+@NP}cBV%&r@7}{FO zUzw+Gju^Kf4MxA5_vpk~=Fn}VF59`Qx-OB)URi*N$si#CBZY$P$ih2&Y|@qywM-?uft8vwZx^`MAc{-Ju};S5N(?%xRe*7x5F#;g&~ z`8%8<#^Sg2$WO+# zP7WK6e=c@`YH%UI@fX&wcSpiDH!GZcDj(G5;Scy!ma4K}={~*4eqB*QFBtyzLhz=d zh@L)t@x{{D6`3&g3J`h?eeojhjYp>6xumY^WyF+w<}}uo-h}g<+8I$jb80W7Fb^+) zA5xT{s-@YZn4I0xSM1|?5AF<$HmInUJpTwq-rrO=0&YGOdzO78a-V8hw`E_+EGny{ zmk^k|OSOM9d^85Wv0;*c+zg*pwrzlaR zZ=bbNx9v@51nAImz`E~JZ1p?dmgFmnQiMAV$ZJBaC{efX0bz3q*#GKUgli9AO%BNv z(G1Mt1+ctm`uB28W%L%MnDKD!_&D~YlR&5!#pBCK;>8*Y?q#8BXCoE27#m(wai!SM z+)jV~q&lKVHC5?)K~&OCUqfSWgr9uEno2eiza|2qXD9p5=)?nJ4iI_{>cp(m6ru@$ z{ZD^G7!G)j&Y$k#_>x}n8ygb&z$Gg87ZfPBpKH-Z|Dvgxj7^L-Hsm!LVi6X#-e8YJ zH_7?;ge;egGBgM9m`Zsu9a!G9+n(}=Rj6Y_=gTaSI~Hl4n8{A*@msuQLdY^3}d6W&>dCCA1M+y^5D>gq{tC%l1lf)Z~6o-zS? z8c5_4sOK_3cVhG&RVI?^1uKw5cgC7*wgV!ZNjx)+_ce#-V$5?9_E_=?g*|4xNMX;4 z0I=GbAT|QYjU@IQkSEc2OeV0vX%JmnMR`K46)k$Z5Ood& z6R`adnMl42k);~KWUcF;3fW0D3n}_JfdAIrAjgToG6y+Ls2wt~5N|LAb;gq`h?GR*TyG>OcCeZ1ldp!LQg(2=%4`-&4b8;61aT#RzweggO^r=}p7B^tkUOF*k*R z;Z(LS;^j!hk^vd&{Znw(HoP}EJa=QByRg=ZS1znI=baGNdIW&Z|A(zN0f*{;|NqIF zwNfNy+C&j)LuLjQN{h6qY?Y+dWXbIIRHA7^ii0GrM2j@WT2$ho1z~1nIfG$_GmNp# z??t^o@6YG|{kyKNGvjg@G3Ry8>%Je)#|?n6=_2Et_WzU^wIE_C>PKSB!PIZxQG5n6 zA*9Jb>u#|FPu5dSZ-}5*x1__gS<_7vu$CQgoF6@)<+S-QxeO zEqh*?=VQAaJ5=XA28|SIdjE`z#E;A*S_*wrU_u*HDmvMvMo3^4z{@4O=0q&srWScL zYQmxvuN!QrumN**czXh_9-qPAw*!w^Ene3*VIJT)AvshSyl|K#kruw}GFdhv7<+g$ z>r3kk1-l#3Xb?Gd!{BHrysmR{Bh^L~X$mN6g^(}oV?>Cb5{y)_eTd=w*5If-IeWt1 z$GtDK9K{dsk{8$d?L@;X>U;iZFnpu6q(3Q7?-$PaLNVi2E^-w9 z2`kcS+H#6@#BIi&$PH~SVupy_#uO&}ohtRuvm8hRH*O*9i* zfA()~>f`q>WwKiB^Q;>^Vsj2JMF9BztUk~p6H&Ruc;tks#^UdlJF1SHnu&SA&DcPD z?IO}%MYSeVtTXaeDc5SQZJH+%q}5S zTuA@}0bvn`OyvF@h~PS6>D=8;V=z>??Vzow2{e!GOGn-vs-tG+iB~xbe(+d|tcC~T zO(IVQTkp7t_NpE*e>7t(NBbWQR0P6oljxI*bRck*ACvmRKWvoZnw7Z2cJJsaeyP#T zzTDx%jAn#Se!@qNjcmwlYlx5L%oNv@Z*kJpq++o%G#O>(-a?@z7AvdiylT8CjZd%p zHa3UiYj6G{cmvqLzSIAX4tJ~AN_ViUz-aK+vutqZe48Tm$1 z{m>Z=sbxdN3llhZsZ4_n#a$|26>7YiaNr0#Q#g=RUy11dPx_;zGCzi$8qX>wQ9|tn z1m46VR%n{oSu{B>13B*mh+VQ0RuC&J)Pn#`VmKcuNbrZm06{qqo-IJEK7YspDMiGp z34}sG_5<{!+}p8;E@H*mN;L)6Sgj1S#z*Lq&Fg!{@6)Lp0|mV)3)i3hYxIDg3J@GFx%}RE^)$sN8#avr#O^IX>}C#*v-t65zAJ~H+YT=WG+)*)kLA|Y{l}ZS zgA+eN=ZH`EY9L_d`^&>L?q-e(--*A9f2QeXCH#S`9=tkuQGX7gV2lTUF)DlGjl@1p z*~^m+tNij@smUNr_Ns4UC0OTn$9o(V+csSa*1Y9$LVUF8W3Xl^yl@p_FpS+5yleBw z*kat^uiwNkH^$EPO(c!5UI`n|@fS)a7fPhpH7Ccg#{{`88`<6imI6~T(lkcp7G@>g2t!B^Xei)w;#8lUyj-`zYC$!5ul)`U6-X{K60i zl3xTu7Gg1wP6=8zf2ifTsAUEWShndJ+Z$nFO*_b7r9KzYV(QT(70k7Gd;*DPa*5$1 z%w32-SW@XUawwD6n#OPCb)UBvtPuG*2(+h{4gjG%tw&D_X`8UAvwu$!E&s=l1RxZ9 zCs?N(HJG-#0#>*jRo9=gx_SVOt1-?dP3ZrmzS2h@lUQCkPv~zzb63E)mRD|wVc);Q zvY<}q#CR-qR(^(9L&Vn2M5uQl!6jsjE18@%O|%Hd*I;dCz>G4~TR3iswaJacX)2fD zY?`8xlgas?CY%kTtV4f67TiLYn$&QqZ<}<(Na&(TPMFjJH_3^RGU6v~Tt=mP+q$hX zvk)BQ8J4Bf)@?wd=t7?1S+4U~1Y;^^;14o4hNsxr3NG^|jKGkDRTH6#($sRP&XQ@S zrA?|gBGsNOj+6@8q)H=Fa|bCTeK<~?T!)p;fc-1Te!j^_AFwX7qp1BylMxa)pIdn# zDC`DLG8kU*_z-ktWD$NcjA7H(ZZyP)jNyVXh91uZ|fjsVs_Nhks#5;y@yi zIE$i`K~$z(e(*P&NL!B8j6~X&K#T|^qwO!?8Hu#FP3Z<=T;Pm&sImk-MA{vWY!@c0 zz^C=$ZXwpboBR}n$pG$>$2K(qi<#>W?(gozlig7ep zeY~M8RBIfL1Z|Y!lJ?Lg<2idqy`G4Qceg#+-Tj2!ep(w_9i3$*T(1Ky;68DwYktl@ zKOi#QEI2MQwG-?WnQjpb8cpQv9raR|p5=y~zakwH7Rydrl!Y3P6C$M5!s3tpq5rIO ze^M8Kfl;k*(`RZKn3VW!zF~UJbCX($3{x(?e|L9(zr)O2u-1vE_?Kj>sldf6<~rg? zO`CgvpdbZab3cChc05__)6QEOgT9l?$Fi0M8}e%!J%X|z&OD^`CDU76GBL%)+_~+j z-m1{)vQMCXC;NzH&I=|3tHLe3&c-Yk_x9+UFrj|)JY$}|G4nycf1Yu-z8Q1vWc4Zv z-ma#%7hrF*`se;^wbfT2fEIL5Bn1?kvx!>R{FTA$CdSA~O}-y*NsD$X2G3?$Z|&Fq zD7iVhX<|qsg>)LmwseNfOiuic9t-e1BEHZBHlR1a2K3WczQE{><7d+x>g#mkgIwa? zhs3p%tTf`PDSBxW#p@?KcKJANBjYvvC7rbjYThh>6UKf7!8biT#P0Noy@RKo_@bT9 z#S}bNQQ;$WhW$LhU9(I$9>rhz|UK!3& zz!q!3gc9_=@NY$|1Z4`xJ@tpii|SBdl3RieRREbS)IvCZ{sT%Bjx*~}i~}rjA8wKk z4BV`%telNWEvd{B4(R?92UUbQdeqP>qRA`l)Y^Yzpu6DE1yeE5(DJ|s95Wn3oZiKn zato0Nu)FOjM9Ndd?u}&F@mHzLaX|>6$L-xk%}pnyx1gRjI2w3$yBLsH@rwv+}?JDa;y- zW_tsPiamwlD45B^&1M;na$zC#3mhVm>O#$mQ6Lz)7da1*2;vm9$N;X004}L2jXJZbu zWh|iWzs%UdZQncc?rSYIE?4|(o8TgkrO&cR%U7hFeUN|f9@IM@*Ki5Y(*>R-fpR22 zWjKyo0JP=d$RlBk8gw6Vfmg>uglNQ#`v*}mA@$E10F;Vg4W;NCuYdsrC=Qr>ds>SI zW_4S}JlgAM#ztY?&)VkCjm=i|e|Eg;tk$|_ITr4lh?ZCfYzi%^5EW!ru$NHg|!=&=lBnJ{s#>T^h&}_nkK7)84B}i*Rz2zGc#-BVKA#l7iD8q-#gK2%_Rr zUg)#ZZzdU8O|zW?xu;G4l@u(XBaoGvhu{4^7AReekHe3`iY!wd5-e};O8FEpVo`fZbDI`gD@S8*!T^~3X< z>~k>JQ2)mETtn{YRZFwc#7_MeoduoQnQ_Uk7Z`5?ipo;*Z?o$99P%s*TDK0L%)kGI z{X2Nwcyd=j(T|k;L{@d5MqX8tQIC=J$G#ZS`K7_e1uJaKVpImGqB|()#i$maB^18Z z4E7=y)q13A_l<>oZd@7AN^7_mgRUCX|CaH)K}z&IknP3I&WT2Q0*Y!=d_Q@11V7?` zEchr+KV{}`?KZqOKk$TE)#^#ILAS>fz6Su@7w@nx z%CUxO-7qXN?|c|Lnups)xt%dG)@W86!V3Ynw`a$yhAtQMx_!d8^d;mmZit@vZ!gzj|G(pJG zo@_1+rH%+@2|2STnJXuVuA_n%!k~!yZ&ziV4NJd$76z$c-$Z2n6n=N8Yu?_}Y*jmb z_5wEnTIUwV{^rzOe7PQ6$Hh@nPxHyKl2ES^fs%BhO&T;}BR2_0NndHals+h?Cre+6 z+ihwjG9<7c&*1(o1IYs1Y^vTpHxqfHf{DC?S5%^@g)`EH=4$xp@=E2A`A>L@a`-8; zrc7mlwNz6IyahnlDf_|gs}asi8P+L9Kbk{ej|^^QS56sbKy~yFfPKIL=k-EFQ^$I# z{^hN$v7FgLnjzNap=kVNJ*uUGX#hzOjL=_>)}oBDD6Om(nlHlpxro@Ae3o@BRg)sH z7tnbu3`;XjT)LMMvb9^{LJCoXFpPomu(qpCjN(Q9DfK`B}_ zJ)=PNe?UyHmAKFx;Xq7%Hpj3v<5?I5ij9N7kT)@xm6|RN6ot4r!CoLj zA_sHIP@?&?9;{7bNSf4zLc!%mSqB?^u}`5V#D090)-4^ycCx4~~w2 zBB0mEU0KY!Hg9d(*Jy@S4BP$-`(rrUfaejz_ThO9y{>X5M=BouxhHH?#^WgKKenf$=d`Myd8PI96xMC-?|Yf zQikwf4hu30hwyV=h+Rr4n0fP9PYyP?8Pwj7WUWBTRDc%5pQZ8c#XX*m za~(0KZ$0{eJKwbNjive=x#RMxbCmteTUP(rf9vhdN6`DJz3tRT)!LRC>m+j31&PvK zayi4NSW?r{8fb=D0wKFJ(L&`h+z0&ZjgC&&Ut4|Y9qI8+J$0Co*K2jF{ail-C$}8= zWeDTx9SE(-rlH^L#?Wx8>cFq19mgef+M&u{vk1N7nfCfdRKrGArXZY3N{3>HL&plZIIH>)!OqX#uYB^yA%gTw4t-Tm z{ED%96W2{Y*DcSZV)hd5uJOnN-!bz?&fx)nQ4{2u+bzGz;$~pK2Bj zCtA{q=Hk7wL=s9SoNqL4xv#tOu!c=dGzKXF`7|&%rJXk7A08oIYar;<0Ei#efRr;s z@Po@zENlq=hUneFbCgpF5ikgc(~N0F>UfSusvrzh_Yo!+-0VmoPcEt`Y0XOTx!oZ+ zx7&7+md^y02`!gsz8f`kpHR)7?7J|8VL~PnulxI!YpxkauXMDX?0w~nxtfT3w(}+I z1WU|SAVhc3X0SYm+J*mA~Z(FMyyECzVe-B#2PKPF5X#M6K- z-;0Zo0G3r^x|Np1mu!F(QWs2`A;*sikA8q)-I`fji+*+N-;WaAjs!pEr$t zJ{E3n7%7|p2hK=g^Sx};FRMfSqEJI#uvn;}2rg9`3W7Cl7bh0s%ibaTYq1MXkCWGb z89_hI57qBGF;0H{Y5=JtX<-?`=9Aca$Ai#QPXqiMjcN$52gfTcYX~MagoQN(YBEQ| zvUrhy$T1bRM|>gEibPZr=yOwK*jKqJ^6bxL&r%$}Z91lT&#|o{)sea&RDV~Z7{SJ@ zpTx$j1^+gJ?|lrs@V624R04RxbM0`3)gxcTh02PgUGM(jJK3t+5p2?OJ+k@g1?!o9 zhUI;8FE?Ln3w~SQw=lE$(xbD`*8`NbaNB1ZDNhD6i834zo|ui@zK4|Zv}0GG@KL0N zT;YzAX(raR?@>d6Qx3|#h%Yo%7QR>Z)G6k zxLqARsPH{sap;9Ty>}0X@;zU6==@gt{XLv6{p_4xlyWVD@K$QGmWNWF&FoJK2_FP8r*M3u)MO^??y?b})XEJfEH1@fZZ-`U@dCdG~TT6|{M@FvoEC6>*B{)Qj8UBS54Z$lGRRo`6T zlV1)Swie`B_d*8DYyC}m%pPbN^L~Fp9%-oNSqNy+PMFC(#Pd*M~c>=vq)?As$bZbf(s z49Gc`q!)$7`jZy&f z!`Z8OtubutTBbUyxsJKaPD<3B;HXQ*B~q68zZ;3RP|P@B=QT^Dk&ca_Y#3i7-J&qU z2%Ma*%_+70rB>9ZsTB)KNI6g95y^0j!|SV#G-_g${y|ov7+Gp8SdZ$ZEGoLfPOKeU zOYyQ30GZQjJD9KlSF8XN%28``h!cs3+az-TX5+O;lk2zRLQjgut+1i8z^Z~e3&%m_ zZH^ESZ;mxxRv(+NIu|9r(#pz22aK1(w66(N?1cl1Xf#cX&3vr%B!2=|JElaDZWVa( zCiGa+G%-gWs1G*6j-W675{0hu1c}f!@c12Ymj<%~pQ6wXpg?>G4&alockG6JlB)v` z1My)XJMaL4!ytu7dx|)@>o?9C!KM0%Xwh|n7eNO}VLa}mt_sG9{ay7i^ zWrndDt6>2(M|G+(^H0MdmaR8OM9ZiPTsNKLK92p95>bSj%L1)QewtuxoaE8+A=<0D zKTRB9MS%WpszLX7i37YP4!W#IYdI;ZGv{V#(So8Groz9?f-M9uZ$hyxAylMcE3g$k z%9tuE8uF~lc~)9LJVibfi_8{c=lmg9Ky&L9NnZ~3zWsg5dN93r_ALtpo&qrGP!9p`0L`@Ny9^Z;B6c z{t25cb>4@&ztp!n$T_~%UA(?&b&zvn>t3;1(~BVZPU{h|Nz?ftIHC2Ro>oq9V_&ZI zQR4R$QmA1vv7$esb)J~nh8=Jk?|a4-95^7TzL|Z-GAEmvh1IppNf#quChomQK4)iA z3;6Z#T|b#-P&4^??_EEeUgjM3gk7u1=Ud(KGNhV4pZ4hhvo@QvO5EE{wJ4$L9k-}Y z6|5b(OAzHQ=Kj;#{7VsS5iIZ){IV5n5@kCI6h(epry3Qz>(PxFNT0A!4k7{*tvXP! z{e_68TJf4?X!_hCS|d-QjKy3+_5lM*B^l1zB(SOiZWVx=9Ixprcn8F#<(+m7JU_l9EX9|6oN zfJUL+Lm}q|I15<^9wz{GDOf$;PO~iSfIR^(ioE|WqCv07rk#Zd3ckh)>m>{Oa0||r z1X_`@Pl#wKb%8#S4Aoe?soKapWxQ$he@5*Zb?$Uu6ESc?ecqytw^Y-%mlj3U?~nBdW6Si5eETFQ6@2Gc9W z?EhLP3YKAs5lD@&#lRj%+&}@w2JmZd7mmwgZ9rRb29z3s=)^)^>nS1C-1a3IjDA@R zj@y20ie;pfRb~hW?xyGG=jJ=70ddN(J($`@*Ji=#V##t`F{sl4+;Rq-<3Q?H`ZtBF z08g}$Ww4q%U0{M9u2>Ehl%c-DKi35>#i??xjouUrjs4DT$7L|Ya(H|gL$j@Y*~rLz zJU*P^tj_Y%qZZE;gsif(dv-CyUzGA!u0`v?mcLarr$CChE(T`?3- z;7-q(#|LEzD9++{RLL8SmfX4#s@vHay#86LR_p?Tui+TIT*SYljNV2#06nYM?kiOo7fE&8E#WwcA*E#!q z@`sr_gY}B5d=f`JmM~v%;(IvHZ=u1Hw0r#QkgTWHr}MJLe4|I91sx$4p~WtA&blAI zzE5y&lSLK}e4B2D78`o>sTJJs6`XvEnvmgxl5rcvD!>Njzy}a=03?7_Pw0$z7%^)F zOPlPkOvc^|&gB^7?fAo69Tx@fXYFC_9tz&eN;yE#>E6YN3cVh9{56sB&GQA`+O=OS z6rVjI7BLS7n~_69qM)%bsLB?m+rbmIaAz8#QX6Q%D^U5|U0`z#QVN5VfXq7*j6r}L zBOu2meDZo;f&NCgxx9WJN8?6lf*|QlLQU z6ezMogw@#yTSq{|88|aVoS7`nOaW)Mr4bFNMg3lq*^4&9_h;dDe5kB>DQQ$VhG9nF zyTb8Zk$CMeymka$TbJTGpXyq{^T?#QK4WiqN_^4dkwt0Pk@Ex9_y4s85(86^432O| zd={pLLt;goK#s!J5f$o+3Kc|!7#=xvc@`pf6s0ZZNfy_lb!mvVEnFD^1%MkRC;(U;m z^_acyfZ#OvEznLT58psu*}}e&5PTE-5J)%#E8)CkC`GeGwAnn#@mka%4cT!s83O<5 zzRpQnI|HXIweF=G;VV18yfg>LOPD+Nfc_)`)NqNElh}nIChOF zGYx@{qT^QQpkh0b$!v^SSy#J36unSwl%yaUSjB7KP+QrX#;{Oh33RC(5XBDfnb-rS z08wlXvQi(joiiJHB-bqamcU*SVA2RKbhV%XDptUSDp4l&MdNZjiDND5oQ9;@!NrTM za8i}~2*(yKj)dGSDZBke$vwP+OjYXcKv6P~lA$Tpfmg3V2EW@i8)@TLUowhqF`<$8 zrPuNItVU1u^SrIM5R83$cM;pzYL)Drm28tA_g_!~_Y<;3M{qhHPHU1)gGBBfyn;jQ z99({|sHLJV@JR;p_BzyTMe!5x3L-O*>!wz?@+PdcBb>4jCq4*`8NohZ0y*=cv6XOS z90Z2VUDl-qZ5-vzDR*@3%(y>T=ON*x(?t966kQ4c`R18Zj1Lgvd-`%HN{`v$Pl>gm zB6n|*`!lSj3z)i!)pUg%jo@YRh|3rBR3|xh5POiUF9t+tTojJMXeYng#91mfeD@OF zq%%pU-Wv4E8MiQ!#)T06>~R7AGVN#vT2uA@)tQ-x({}4UoUz~NfXR{>TWjB`CdhBU z5R;&N_KDr}7T1NCqOwPvunV2mH0!bft@5>+c6j)m@Aa{rUB4q1pE`l@_Kr+r029iX z;*ia*zKqo5tR{4MQ&O-+c}f=$N-g_{Ur?3mST$in4UJ8fiYX+&Rl)bh=^^JP4)=1U zIa-meoBOZ7Cc6DDj4!M?L!Qh=HwM_S*@SCoZ~$}^w*I8=Lv(Dq8ce*Ea)RjF^f{P# zGvxtqm+SCJ5~VVoh@}{&5tmX7(}{Va3i&oEqZ=CLEB;dA7U%}pRI)Kf)(!o3d1%K_ zbHkfYhr@AIcRWrJ6ZlJ+uY7cxQm1YZPL%Ht zJQ9Ph_o?s2Ax7++V*xp3!RnO~<)$CQb@IpnbJBxqV>i5?sWoL$$md%H zSANb8M~*OnX|ZsBH#w;uwNk-+yMup3rF{)!IE_4xV4NAbI}`J2E(^WGLUAnBTIMX) zwOZzU){a_ga1@jXXgRPC5EicbfSw`Ybs#wM?>O&LltN<9%7kE73UJI@{M+ty!$LX0 zuM!UtfWR17S^z$O4f~&4vT5?UeXYIV#~1cl?7z%gEp-`%5L1i308W-EPdv@>3aHOX z{76Mge}R?|(p1PJb}y{C5@$0#+4z-kd?D6G6E-7Zi6ix+eFRn&N0FfeUi2Qr*c=plrcShDJ&q9FXGN zIti!wdureHEJ8d~gpz(KIybkSR>IOXoo!0KF;t|*##E_LGTsvk#k=g;1sd~r6 zk5Nt)Z`{JXCUjr>xW(;;ENNE-n3-ZJHLs8mjwMSIz`-Y3`V$NO9Cg}h{Iki7 ziCDDmKppi)p2g2^XKSZgz;(^4ETs(b4P_iATSSw`V!&PK7A!^`_7}D&0nI_6&6L&~ zU@N&UJrYYWHhcPBa%%FmWIYMr+AdKe?FOJ{rU-ka%{#5WaxsIU#ckg@VmTAPJDO1{ z^pANU-svMa46)OBi=x?WJkSKZ$%|vu20o|{oP#wi4|KYMmv;Ye*xLCb41*iDJ)i-Y$%Z)8Szq*_TnZjN~9|?rPWSSx4BS)G46$sbY!OUvk%{P z|7n2yym%wt2Ml~C&YqR%XK&x?xKQoROPP7+wkteb{oYMMZ4ZCB$%1L|%jz$i?dCG$ z124B@IsWX+11+J$>?Go_g>NcVoDcJnuaE3qzFRDdQK@QJPafTF`kwBSZpI?q~- zemO&++;@L6wa99{g-Q^He6PQAfL%cexs#le2D%?H_bPd?*V1oHKV_8(Q{3&+j&TN56HBx8C#JmYqpX@7Q}!XS?YOaxR#8oVd;O z8f=n%EcoHJnlK z&!qM(9G{A!Dml7qn!riqajEE89Z`KWdsjWGn1O(T#Y_kclwkvBIron{Ek#(U3K7du zXzoy91CNZs7Hh)5CI^aSb0HgGcv}b+gXqRja6yk`XvX64Y9k}ccziTtLg+7p*C?x8 zvV~(7OJ~TBhFmT3N*B0@aM49x8G?c3xYRY2NsTEdI_CHkp>I=;noU*Mq>6BHIf@aE z`^Hcvt9TLuX%YkVTz_@%z+&92|{6aMT< zU9h9>DP)`j2QU$2ojN^GZ>(#ksQOxwq}IY_RNIyl!E@U-2JQ@SyTq2TueCt35F|vt z0g*WZ(jqkQ7~nJtHPoV7GOS}IumV$tYJ9Sh<1U5BHIK$Xv#-=%$sAL*#9*!9I$1L% z5l}9fHDhL~(oU}Q%t-MHE_mbToDg|6@ub0#Syi!+sV3?D49KbUTf8u69yUHYYi)E< zgYK9ohUcbFH%=qii&(OB!dA}xTcXfcbwB|Fs4$LpyHsNY02YD>=_;Yuyvb*!p%+JT zZhoG8A*M10Le92@oNW*3{m?@2Xd&QQ2=o?$Tnk}K3t?Fc!MjC3Pofp4OB4Gw`3(zP z#`WnkV}o}5s-KOC=UeS~={zj-T4q zXtVld=#k^n*K0+6NBPa>wfS13!44c#Uh_OUGhI-=y}zp80mg9)KwnzBeM%@eXKLyY z;cqw@FC5<)LkR)z3M*2G{(qK2xfu{A3<0U_@>s}m0j=<;XyABBNh&42K`kCaRm^Zu)+99?uRmad~TYHG*H8kGNIlCw z#yUvQ(aT?#@=CX8tbw)8w=1QZ-C{Us9QVMe8n^D*gU36EP4cUJ;9%xvK))FKz!$9t zR$XvDI260K^>$>6F%chci_baoZoSKwUMwz9scK`oVaB zDTv^>x)$VrzId^mOl-on+zv;ffY4V=&W>U2d}>wA8kg@5!H=5H`}h{L?hZbm-`q|O zzJZ=2vK@nSuS#ury->(V(rDGh9AcR8~IF9ZPoGf|66 zw?yU=V^yZ6mhf0xh63$%6yu<HZ* zCM39wD9xA-Bm*VjK}v{STl>LGM)M53-(`k1w|)1>J5_vtG=n;qrMZ%d(GcMy*p78$ z^C=j|DG&16?J#VFvr(N^Ae%#8QAi?J;zJ5ifV?gt4P41ZQphs(D=!DP-rB=X_IJ@Cbb|W^D!cEno6xMnQjaS$2GAz05?^K z-R?m7t8iIOJ+D#*a<_GR`TUckO7^}81-=j``?8RLUYsj{QtB!2#q)&-1#l;R z7olg*YXXfgA+%?x%h7iF+#`aFPZZ3@pJPV3Y{w@6dzs4`if5_MV5!$NE3@M2{!IVa zNqGb9QU?*o7ekO6_?F;L`?H_#HNC9y6N%>z`po}mrhLVRV395Op?v8rSLQ>wT-DRq zwJ~xkcMcp}WN(zA5pCJ?;gXi?TqTW`8M_x+UiiR@qejGxoi4guXmfk)=a?vU;|H^X zZcwKZLl#~kh7y$wqo>Onik=uP$ao*g%YAAcqo1{DU(n5--480C^_x&4dQ9rHIti^t z6G`$o-S_h;F+E?#vdU5waf>L5g9buloAaGt4tRKFpWY;=(zm5 zrTl{60&g}*PwxM9cEQ9LPPaC0ee;35xHgMA@qXTf+xW?Q9OuF6w){Pzp#yGD@U}r` ze<;QHWxRJ=HL>VGPyd7FC;i8G)VsNa99vF#9Y~Sl=Fl0NIcy&F^>Fo--^G;?w&J1# zL4s(iLTrA* zAQt|F(f}>h*-1eW}7+J>cqFs4APQrB0$^@pkjssZEd@lLAdte*xoA zY+i6%NF6%xHDCy%#{anGH}Sy4nz!xS+k>$_E!UB~pDo>wbqI%LE)&DbtxMZHxEBm8 z3-uPVy&K~kW9b-m5nYY$ngNuo9@mN(83L^zEpb_K%mKAv??u7wO?O*K`pkhD!QQyw zc6)xsj>fpeT)mv578}3Uw~~Im)5}o^ZXYV~E1caJXOXK%IA(#b@S{bvj?85a96oA+ z*W_2|G{%|b>e=WLy)*nRHX63X<;N{7(&7p|E{y0~(l84{WHfB#FJp9r+l{?BIdb%3 zI}V{vY%QA5r-#~dFwY9~?#D6*)&;lg@GEl6nFD&k?L>YBrZLVYS1&|($)t+jEd-@)p2w;h0(VToQ=F@ZF+OMV3@~@9DXxc7&xyL zjNAQ4hKLs-WOy`Wu#kyj1#MWEx(P--YtZBX$QJ?6A`$wTyS`A4TusAlr0RoYQyVSC zzsMxnOb@Ag(uPh*n>OL&Ip^W10?(O&EV&TBSg#*}gRzqFsDc^ofsVSUeFZJo-0RjF z*U{7`LD?q9va!ef?8;hhMHR%z7rYxwSb$c=N;)4ov?0&8-E~V^lfQ~d)A>`C!LcgPMH0=zcOR^bpJYC5LydAqLshPHYuhSD~lxI*S!Pm)KrUUixYK z&Er7^Jg0Th@I*Vkl$Zc;d@-lR`l>lpdPx6-mg8sC114_AEZ>fXfsj1H5bdb zr?5YBJ)sK7w=TtzIJ0$LkVS3l)`m;{`tKciltEGG10A@xYLFRn6(vNDZ44`j6*$N58;bn{rg83b_H}^R1mb` z*#hq%91nUxjqX=?Z^0X_V>yatTPv~rEvt}qkl3I~a8wPc1V2`I!EN57+Um3&HS1ij zWGlPB_lhdmQM-Ce{*2ZIL7lu+bq6w@+2`xGo(yWP>(l5j5BZ9_(!b_?Mk!Q%mpY?$ zWsq+KuGw5XNtkkYgG)|^Cnb@5~A8wNm(tE8lYOY+97|ghwl4$-cLnA){MYswLj9H zZONbAdN9bkuFu|;kuB@7?EQ+M>Qeft(w2ik=Xt*(ac0N+eS#WlFDg>m6)jAj{)1kP zVOm51i#J-!(irB$Twjiyu+T1O3oknGUGblbW=*b2*_ycyZ4X7-v%l|hcNZDZEtlg3Qj}#TDp%=wB6Vk;}Z+x`huN7tdiHJ>q*j ze=akwc31WJ(B$T8*^%@jhE`y2Prh^h4x-B_?Rnw-L9gedfj@HGIR*G)Vmrbme#{eq zS(q(Fyptxcz4XUN2HGnb7@Ls){|C~nKX%^Z-baseWsZ9)Dj&Tx*c5hmc8qQsZKg76 zs&#MSl`gsCs*g9_2wAZnonI$#xGxp(<}wl74dWiEe#IFNp1bnOY-hh`n54_!7L0f%M2IM;kO z+r8RpwS0HZ;xx{@T{c&8Fe=|YpL^Z8ee=-XTd7%sTdD5%?%#9W`&`gF|93m@p+J9O zn%*5R_ve^BcTzp?-0e+Bx_#uim-}J&8@Ijo-a7IyF(IkO)_r_UMkD<7Mrwj$U1hX& z$iiBY|JubX7YrVa#6{s{GM#O^Rridl+$oaH6xenv?HQeYCuBxus$I9vp3!-CLgX?z zcHNqhu_2ecYFtlElA^nu?-s9A$Y^8qnC>mdXluN@5PnI^q~&Ovva0JL%kr|6y=xXs z&Z4B1g>q#cvo9Pi@#0)CPy0z+jDPTZ^W81MtdHSL_MEWecPOfC;R2p$qZ6Y(Lu7=T zI;_W?76q%m9Z>G@SKGt13zJpcQ(bB?S@I>!YI5<6W9&O?-j&pZB+nyv&RjWW_V&UFTUAG=iS3gk9EDSbxt6x46pU8ez42eZ?D2$LyG>A< z@=)r6ALG7iKel9Bm$sK1H!qyeUN}Gv{O~~*8$vr36M6FRElSginmYeOn|R9%*S459v6&3M|n`N$m_paQP!)b%h_u!Y!T4#6qOt-3SePy&g zM)ekc_u_*xzX?6D$GeB@hkIQo7+;e`jUhkdE7*&mz&=-b_BZmUygL08*-Ezx3Qu+A z*;Pj+ss7$!dzYAWqvLB@|B4g(#@guC8($-3Pa5soNixrf(pk493&))c>%WC@Yv(Fe=Pe(~b4$@!9JpHf zZq=2Orb=>ZpY}ZVf{!g8tU5Kh^;6Qi#e>MH(FIoBXZ>{AuTqVT`C?G^!^5&lfznsbhn(Mtd`iQ%d3_qVQXTqS?bBqWFk{ihh2FZK#K`(JjVH}!D7p4wfX(v9eq5X1+ z`Xak=E`3(W_A~ZZbK6c$E>M%4u*O!fqNw12TH#!B)iZT(8a zbxE5>x9>t$Uhl{Xv|3}CFRi$^=4FmdBxd-=py1aj>v*Gyj3J{J^*Xtok8$Ovtba5f zT_36*O5%W&)e#Hvq;|e z=Y}2Q&%f?l!)i^rXjqwa40-W>Nn7SN-qAgmql}z?KG9em^i-MPf!nrtThL5wkg)az zyE&;Y|J5?4wRK2dD5+3VoFXMiIqRgdw#yhru5F#=&(v}P3Y|pg-V|cD_`L{S@b&Y} zZFT{PuRg_Rem;%;o#oOTzmr~N(joiCbx*K{?@eR#&*X4B&*7gHgWQU|vNMHV&A!yb zuW$$7Rjj>Gm4BgE&d6@rvP1E*~cWJg)b==HcCW8y%ufvN*@#wcU{FXH_^hb@p zr^p+x(K5F~!YwLuRzxWkiZ{)j^)gkw=uLLk=aOnO{?4%`?EwWKEz0e!8(97=u%@|S zP4OK{@#xmJ_dDMO`RPptJ=h&qWPLL=6f5a=Ms6MsMWyklXS?lSSx^SQy>dVf7p_=5 z=h&JRRoliqI_J%g+;&|yGVw;3-rJgpZSE>d>=ND?-6>m|Iy>|kc9UE^dPTT8#J=>Z z^2~%^Yq^+iG0{K&7wv^kWc41GfF9%Q_3k>Sa)sWe0nbe<-=k>z%#`9Sl8-_y+nJY? z*4xXQPaJi+9`{T|?R?7anMSL&EiAaXZ*k0w8pbMWsA~iN=5?nw{qJR#WW+uW2Xv>R&IHI+QjrmtIWA`ugAtO-!d^+ z(edtSs!qL4%40G9rH7!2|72sg9qGF2=6K|7S?aEwy{fD;D_JrZ{Tfea6`K}*5cQj@ z?&U1{)s(CJhyXWLd_FqS!6^7myo|fi`~rEPMdoO}Ew;A2nKLHA-Kbvbs!-pXAna!4 z9P(94_q={QMLn!L7ygF2XZ0(my|W z?MXtphBZ0#fXc;|34D1=2yXP4&&to(vG)b0cpALZl_>Q30D z>xZa?@1R**U{Z1A1>HbWURT+>$EaTMc`;)%B9KmBPxyyDz)3x~hJI*&M& z_+c3(f>)_N<4zu1ASDW_0o8hGu|-d+es3sw#AfNPi+L7UFWW)SFM-d#F6Rqy8=KIn zfce1gg_vXwwhfK8e07pVeS<;al=FN6qw-EfAK0>d@iXV9?7`-J_e^H@3=4PPPzU_g zFyk+eFbyZh_owc=Pc?_EsThy!_l6;b&5=Fk5N;2g+)%3;L7s4r>du^geJsk$yYGP+@v-TR%`Yajp|HU?V37E203M`3SfGWM$nxr zzX%CxEvq_KW+kZ{;1AF@=eZBKWOI(mBc(?l+HFMS27Y<8RG`O(`9kmqtpQWdWv~hD zeqE7Uouz`iMz@oR36Bmvxibz6{N(l1@pD%=Sd+?Soj;$Je@Sp;8+H56C;HD~3@yIs z!T1#?1a#h9Q}2B+6&(9@&M&y1EUm#`%v$-5rX;+ANWJW88C_D^d5QBJM3$AnI!^+< zAUC2lqm#7O_c47^{IN+%B;BNNf&FNs%xB(dO@nb4xR~c`wHllQA~E;a2v|l>TyYC78q-Oa1+?2 z>hoYG;{3Ir`3I&>FU!^ukGC*8cHdPUH&H$Gwo~Hy;U%8K;fF29w*=-yaYeoo&2Kw5 zG;C5VL?9?3rYey1aRS9a4oE%*mriSA>!Y!Im4(=Cjr4DDmBXl>L@L$0*Q2L-$m}$j z$xuN;@a0Oat#|n+y{ShlTYL>9+*y;TrF?pg+mHPlNIjgFx~zQX-mW@iT7kJ&o`1t@ zWe5jJh97h{veWnaMBIA}`w}FmxGx^o%uX$q1xI=5^YxuFU58_P znH^L}(DLIp2@|aZv@7R5vVM4BeczhBZtA%ftb95jB;fZE`VFRE;UHXI_0-qb@T1zh z-Wk$DH^JJ0>MQ2h)88jnLkT#sM1EVFMFB>S7R4;Y#0j6VP(wg$qrn{bwSO?e1zk?@q$ts$65AKV4UJ{4zRnASn71X&KR(#- zYEtmVOXvndj)Pc8eDG+<`9wwW*4pX}pr)J{>~3Kl(Vq4s;D<4?R0QxX{p#_BYOU_Q8NZU5@N@%t(yg0qEV?RUMM>Eoh#{!T?9WDWf4Y& z4MESl5=~m^x9S1j$h@fUWS;AG(TV7j-?P=n{ZgPY&R+SbjY9y*Gj#AIXC)-YnOwNH zRzi=pMCrM19nSZ~#4hnG&FS*|I>Ftl?Z_AU+k)^(W6wq9WM9q@7I7K3kLFdly2wf< zd~jTe&BBbo*LvaPKkxg|^HA6^)Cc)W1&3zcZPCq@$LYE_BaQ&v)@$IFzP*~p4bx6!=s zyq7F;m*7TSNXnCLyzMZ*6=*$R?g#5+>=|{bY3k3v!Xs{`sj`neKH(IZ2}2&AbW=;e z*_n21z9bw-?DW-;Tdjx7s;5F}mMr_61S?FDO6k9Tl5KCsu>x97XIIwC{d$tvxG`#DzC{q|st$>+yL?|v z=TiLD_7)q-2HG9h{b^(VQ zGF(81qlb<|qO*AmcSM>n^(=&Ev5M=AJn%Rc!&uCh5y1AygAdy5I2Xfx@Yih4ob|w$U37*~)nDbAPAaw!g!;_Yv%Ph5{F_BLa(`M>{|Bc8`H zoqVZxKC6t>*%i=hN@}i=$b#ScUQALz_tEp{<2XRZ*Q}~%?7&# zxK^yP?ECHHIc5XS8m{Kf?QGb%|5N^r+rk%C5_LvCN;GUxhRV;{YpWWs3>vQ-Ia^FB zJWjV9A(x&@v*l%jw}Sh-<8#+jVXUsUVjy7@+*y#2;_}r}bg8!AnXuEY@%$K%lTy0U z?CHaYX1g4)$m@kyYw|<9gRO*lW{UV@V0jy?tRjus%%k;# z!0&Nyczzy1BSScNA!K1nOE}1D(LQ(xGX{1m+A1dkJ6;kJ{2k*K8}N$$AGwh?F&cyv zvmdHrJ+{Z)jJsZ45-OsbnifB)5V2=^^QvI-g;!iXxis`JKm8jLH=fy(Fjn|ibEe`6 z@82|J#(8|u?86h|z(PvP<6>XzjKbCL!#KCJ#NVi*%#FSOoZ^i^g0_m0k)*F+e+KHk zzfePugzlqYDmZ*+mQ!W@GPd!PD&zpZ0v=0&80|O~S{^W9ppFrCH5On(j+f!Fe$b8P z%*~pFmG6WbDc6qc#GxjRJ3^cbz5mR!3lY;|o_kyUDQVo1q=KL5VN3+*^HR&hut{RJ zZyK*}@Qg*HS+VCi%c(!pv$A*5aI;i$6;tQZx3uz9`ZpeOvzOyOp2beYj6Xj*LB^oW zM0P^1zv%AaL3}I2m)*;F@GWJdrF!h-CMgMc{y!9i#U{p29x<{Sb53gYC<&XCBaIHpET#=7`Z?z;Ia zdIs6P{Av+QrZwrE*w`91F~e%|x9S&EHKaCXz`x8$i-MN7#VLgt-&nmOdIOLb!vas( zrW8BLZ_6+Wc1D5EG+iz|M_h?5W^C%cxqUrmFR-?-bjww$7kxq*G`ddpegkV7ZU`Me(u@|EUkp$4g*KXM2EMarj_dSaZWRh}@&&avaE_!>D;{0zcKh3~0_X@; z)O4&t4@Eotsz9Ex<9AIOl6H<%~WKUwD;!kaON3$JaqU zPk7LYFs46cZfz##GDM_}?_JNWW6VWAYpstn?mZ_fb17v5lDxaWdG;QOz2b5Fp0x~H zF@M+X0~F|}q2lKyaQglulDRB_kQV3oOPku+*okY^pa}d2?3Sm3+)v4kPAjDs(*;vo zVC%@MpY=70gk$uR)=GF%lfvu0zKsHl_wsK#ynxnbPhjIrUaZA+DSEoMfI%f`d4}>+cx!#UFQ0W%9K?W$$CuA23$Fnm&?mf?dK!ViR!G^U!#kE%Rfl7NyU zA4frJ5_aQ^xir2*HRv>1(*k)}FJa@XcJcZU?OU#y>%CA16e=POr+3WKC=^Hv(Vl8O z6-G}T5YWVNIXa^I5!0YAQs~~dJ%|OlU4Q6>5?1EXhu23XsUL6o4#Yc-UXsO?pSCPY z?dJqY?~9b^uDu%<1S9CI2}!UK-g9b`1f%=@H1=<6=~$17;^)lnbn3hnPZlmoe)l1= z^9Q=B%Eagc*6)$kjEojpv)S8Ui)6C;YEH0F5OJQfRHOYM6x)B*CcK_$LC{8c@EjlC zr#x)o%K%pot$=N&GYRV$8BvjW25dExb4?yJGt=s^k>1{Oc(0PcN+}L#peaPb6%} zWJ$;jzd?$ZRgG&+V}HFKA&JtilaJIEM$HM5?vL0Z5(~tn9D# zDtTjyV`JKVbpX>*7=QrJ8|-oc>6?+mPhv%<}27K#1Gzi+<*2vzU->;619dg~vhbt;> zC@ywIwG6MJ8xNi^q~brbeP&o!Mqc*_bG-E1XY`|a+OyJPHv29Xj0ww@v@6-kTDx&! zjO zK<~&wbc>oQ;>YT^7GuynHglOa8%Z4%B`@RQxIeL&uq9ivW91GzQn)(zadch#F?dj= z;pW#X)J!tCvthg0a%Bkh_Te2oMpg-h<2_vphTe8{U!8qf9)zvUYnbkS_ky}T;t2-L3$+&$$(~?q+Yy(H^|)8W{dzW1 z0@EjvO#<4$LwX(5u**atfmrwGyDoK%@729&R>2nDkDsSQU**MRdB|lUq zc?HqRpdaE1UPWv?9M=Ly4nI~oW+UpE^R&&sT?^{HoYda!Ol_7k7K+p#^t&9G`r3MQ z#iINJW-4T`-ZF9g+NX1GsH*-`&i!YDW;d!rm+i(v1-jnpJ5qyIK`6$2!4R$=pBg4Y z@wuu(TpMaFVLWqOR3339=Ww#=u3Rsl9S)pdwH$fv+bm?^`MO{If@UUwW<}qR48aub zLxPZs_8}0M2Okm#q@l}p90i=^crc`!rZc<^=R)LRlHhcZfaHri7lhRJJ&b?@vI#c`%5uDH|2O%Gn44Al0PxjZyWGLut3A^_- z&tB`#HJ&!rCSt=G(hX65f7@B%^X!y}Dfwv!c>Fy7PPCc3p%get+2WoW24Tbh`hVuDNOcXj>T`-WBJ(*K9ABmlN|$=uXKniime@z?1RV6qW5|Ky z=4QT)!cJ9#X05W|S>vm7o11Ny*N;@BFfu<Vcp(#KZIfnr z54SJ?7nM+m+$!^R*LMbKX(t0^z^#mXmQ`o!TckesZ@^C0kie0h)jb~S z4mfw88iET`fs;v+3XioPMX))sMyL0jSWtgA+v9<i$aIPE?Bd^~1MCkWFU(>xIB3MpGd^J5TDiZZQ->vh91t#UQ z7U74%TEndKdVR?!4&`iEyh>8Hdcg|wqJl96?5bZeAZ$g+T+fr(i8=ICSO(YB1o1tt zjZ+)^pS_ra$f(YcK3sTfAsD*?5w+O{ve*3eY(16|B7Yta&5(_w=%dP)g}GkWmTt3#Y;6s7C{PdQjwO%2BC zuK8tlcnp{wN_g*iS0Ha-QRadX6~ujk<#lgkZ9&k%zcWx~e0%a!#@c5r^pBc<9|sc6cyG;_u%GjD{co)r$Z|B=?EJ z2&)U;03D#qCOUE?mKJ~?ZdhTx5USts`yo%MISFlr`_ME;%I+Yo1PYW;Bjx&*F#65b zCFX~L^LHu5#_N)tUO|Ujr^^WcbSFHG=E~C&0r$$=9@oozas`%-Otq?IH~iiHP1%5_ zBM_rxgA9T-Ak8eTZa*O1Cx@)s3XB7YWaz(Irc?k+t!w@FkF4XoEg0MMWa9?4RoZp8?RqqW)9?GH9fAZt>q7|_t1u@k z4JThEb&Ca8OIwE}SBnZ~3z@m-N-eQ8RK>W_gRSruw8$;hVI4^JT6FQj%KH9}LEk1R zIvsLFK2p_?gL(Clec&tmSOK8Fx^w>+`NO@uI}4K37&zu)i!k^~Wb7)ju`0tM){sJd zxZcw~CK;AqxjqLO1v%z^22}c9)_nzL|1@*|EbE+e4PlF!!N8V^dKDgTG*~AYH$pwqRl8-~wN}m@{Ht z(R)ijA(*G25hvkfb{0nWhHQxVwI?Q|5JZc#;@k=xEh*g#V&;qWc>SRfLgu|k#jF;d zP2b*7yFJ{rwR)=o_>mNE29)Fqq$%(Phg8+*e%SwsvzaunH$w&zR`Ljz;gW(1+^=5SP8ruyge_8bMbw=0{G^ zsd6AXf$-eclmn0wQBEON*|26_QlKh2qh(=DWs)}Q?vHoXXYaHrj&SLEpn21?Gy<0W z&plOC#GV%_i(wNKqUA4;Ur<{Le*2Zjnw6Lc}yT5gCTZD5S z?00ic!C46pm%+AboDsu7NYA3Q%918Kno~`cZ1(`T5|^?i0oKMAt1X^ijVTK^v7f~m z-bk9=ND3F+jq)+4T?=o48UG2ET#?5#^`3-vwV*<*v%_&qo7O1bLn(KLZDQQ zgzEv0?bLn8Ry=zT$~}j32_wyi@gw3rJxY{xsR?TSrKC}_A%mlOno~b|i*S)&X8XRR zL@Vta)a2zn#kmxl^8P`jA=&cXJK`i#b=B#+Z2x`33?y0+#j10&*E8S&9v=F}PXA&b zsgZFEk_I$_wtvh|LuXVqz-xh`9@^^#+Hs`A#{=M{DwDn@BS4$oIpU>pk@(wx&V|J}Phz z(75a}(#tS(mOZB%M|g)f!A?N>ehJ~n!K6b?uU+1D{v>K{7zDoIJh0I>R}Et)fo7eU zYzHG>RM|d0_z7x0obs_}l8MMH(j~6`35)Y5f`I$G*;&Zyj$~&N z67KY2;)Qw`-!|Q8J^G^r50D@*$g>qwW1%PQx)Ma;UmKH3Vn!|q*N=$IhMSND1?$;P z&M#=7a%1(U;D~}g7U*g|UubBWT59U}$=;rM!le3_+aXt$qHVMihkjwpc?|^Q$wTBV zW1p?;4;%}s7ayZvo1J84K5E{Kow+P(7vfaAmF2dbf9ILGTFz$$9uQJHI_GGwl(7%y z&uWi_dWR*Vc7L6m$7a1X%4z}~@MdniT|c|H_8)cY)K?pDl_@X(+;TH8GdKPD;A+|C z^++XRf7iedrE|Ayp2Yd%J+Tu#u+R9`f!WzuZiBGit;kT2&Ytjtg-wF3_ommvGrMHw zWMsBpUGG7Y7u=|I&I3C~?<8m^-c=()R-AN@S0iY((;~O0!c_;BuHKSjg2Ki5e%JSYnNtl74c{1H zFWfW2L?Zg`v;ay#0$P3o^MKw8@pDQadFcy8|3<*N8j@GY3MWHB^1z4LVzB@Y5~=&8 z)43pLLgQXvR%YE{bd%IefHGig`6^Crg;!Q@}J+8Z-PM?QD?*szn`Uwa8rcx%rI6F4~_LD z^CC?kzCMQZ5(dUf7ZZ_*Gao(aG2q`FY=x)7#>yi>XghBU^amCjCSn9%0LA|EFjM{c z0UwA;MD=kKhlHi$q1#VCtRTudo&?~BCDeG(MMnpv?jlTvcA7)qn$XgvtPn;+Yun=N zLX3UA+WfoiIOF<^#W}Hr$h87KLjSo6nca|;9Qjc;LM_}CDuV9Q&jgZ^HD5<+Wg9Q9 zz`Yzbd`h_yyX_tIC%nUAz2gb4&S3wt_EVN$DfGQJ5oI+9lS%FN_Phik#q|f(2kH7e za6e+_pj>)Tgau)xSLp4LFN*P1UGAs(?7!r=_q*ClPIpqWX)9q(Ii}xXocgPfSJiqL zwuFU+529)!ku{o$W6pP2Iw)-j)flcjraCd+<@%2h*$_%}I=l^a104{TL=dQ4_XKpm;m7 zBjJ|1ipY{=g$XDFSF|zKyb`-xRk2Bo>PorF9PbPyTH{p z0m&;K6!DH>m!UO~kW)1ojuhrRnJ) zOSy0okG-&T*f)J5I5r*ihMMzIfY;jt$-Bti&%54ibLSf8k>ktyrp+t0Mc|Irtq}CR zH}Bm}w%wl|$#*~4i&5}yEdNYFmrdmOl}u#K*!&&Cn&DW%NonN?tp!$?>-;?G?9DgG zw`nc-GxrHi%4T?If}2=txdAqjr|r2mbKTppa^0;BbF*5F1MT(;@6A%2NP;&(TK377 zygIcP%qrp;)L*v)7uM33DMSVv`>I$CpAJ58^sdh$e94i0^6=9>dtvFU9z7-zMc-0+ zaMWcgbYgb@gppUf$*<1So6eheV&22)ig$)b9_b?wtIW)5b_;RF_}X}Rt4Pbm+PL!- zDw~^b8C*-3df9ba1e3XeuiT1Iyd@QQT`q*R!4pr3NM__xFuS>C>&I@Qo}W)s`eEIi zH^{f?U`v7DH>m?z*In3^)T=2>qKi=f!|lcJ`Q%`E;-|VWGm_D3f0q}DHvEPAytX01GMgvh$fd~B7{b*f z{@;yEUY>#w3f$an!rZ1C|zw1Y1kc<%N|7G)Fu|976`att%@jCua?eG7lhT2 zydz7sFGS1Zd2Q0AGl+N8EAuz0u9dlPUcyyv$)ud?I-aL)zWh*x`hzhvzt{wI{F`|< zhwJ00&F&jBD$pMJLSi^e( zgt38VRq5Yp7qYRGU_f`9%M!aM{a%mc|Cm~;5$zW>?rD)X8Ag*<&6 zO2L}po2H-Ui*10=-UxIer&#aEP4wXsJYH+gbOf4^(_u5g9sK73i1izY*^|c^^ej`j^BwhdrLWXWTa)vx}dwVBEgIs-|z+s1ncx}=EQtx&4q z%Al=vd@uBQn2_@^WEQgGCWbV6gt>%lPW_;ek=GoU#3*KThnl8{u1bwCF=t6idg{%N zuD2ZZfiAzPJkQoCYO3^mMcljAVjFrL(7}KN#&A_-Y5KGvUA_*jG-6k}*CR+|_><=L z6w3UQwIEi8k%awfuTcBU4>q2kzeU8K6v+^gg3*13(J`sskSZ8Frt=wk-_#zG)GW<% z8Ym0vKAF$nJoRds_j=uOQ`()wr_i-ye$T`5Nw#B;eveZ^#9AQ}(M^Zh6V8l!QsO@PivhLZ|AR3HT@2m%SR5g~JA9n4h4^_4UZ3%E+4= zQhvNuiaokLCTF7@2_lpK*?3nNp|Me_XOrGsAqRR^{n6;5cT?OZla(Zs*ZJQQ09|)k zS0)z}EDr=3&!msKJIS!**3DevZMp4NLqYEK#T-*l$jgc?Kg5!6B+odey8)%r=8saT zepf1^?Y`GUmL}f3+F3$h@E@`N)i!Cf({#(Jjr9b;-+S0cdgh-5k6i`N4m9>`qHs(} zgD4Pr<%jp~{RB=(vPX!N8^#^^v4}DhK)|srAQ{{Q`EyKA{41NvGBWNq2DTejW+*U( zLJv&J{A=PT44u^sAC^Xp3uA1%V2(Rte>D`k&H6I8=fA*(Sl^di*Obj_ioT9dLFXGy zdadCSm8L;Hhdo6xqJv;K!~e~z+eXgw-lQzS57^vV*278Bk46Kpm5 z<)5s8|2gIXcEh9Z@IqG=>5Fj1kW%ZBJLq;3HU+;35?#<{i4?r)pDRe zb(jEuVc$C)#zE3i(%VemOvW3x?io?PdBr|)zximNdAs!aYlH+3NHwARKPoVA+=F+h zL2&kO8jMX#{##J|(8-p?W%9G@iK%ki^XEOK7)hyK0iTJj&%DZGY7BaSPQCnBrydbo zV~}_3{_yX<5jUvjT2`w;!xA1bH?RZE&`Eu@urvspm$!pVa=LtCBw)qj(goxKoZdwJ@&qMRXJ$|D~Wq#FxQyp z=8Tl@RgS`BC{3yfbglC)o2(etbX9a# z34*KygU&8u5D{C$6z`?0{~j5{r!X-wv`8sT)l?RJ(QNvRJvCm8LXH==U=aQtYfyN# zJ^q_RiTHNJ2Z|Up$%v&G-IOex$am{w?wBk?L;6A1-X~9_Z2!Z^kr($#xj3#8KdC0lIjeqC1;|WXIb7~Y zrbu+hLpgxiBu8pW-9w26&a z%7ES6K-;dFeKahOT^69xR749A!Mu0X5e}um7GY--BHfk^vQ;I!- z7@7tWwS(qa+_EAYiiPvP;iH`>Y3I_3;+C_+ABn`)9dT$L-G6pL^>m(*O?*b7?5G#x zZ8$2cS<=3dS@#`X1_r_VG~N-E?&)9@W_cn>*rZ`MYX>`+foio1RT|2kmmW$U`$1Hr zW0>Wi(&n`&%sCd(T|xCAs~Tb?I!wlWeXuHmLNB1qL`Dyf>Wb8N_#pEZLZrNWA9C6U zda4flA4q1^>DaR)t%aekZvQZyw7>9@rSTtEh#zhCDBM<=A++^AMMg5*IfjOXOL#uS zCe2vN)k-PUcYW_veUl#~?6|Zu_)fmrY0GZ%-!+lRR>!Gms@JQct$s7VIOdPcPh|Sl z_wT*rGdvh_Mneb3$17Hm6X>*L`+U1`e4(trgPKhCX&QmT~R=1Xz2&0 z6dx}4RmH&tMvwt@~-xVl)Jd4X(N*0RP2e4B5U1=a)cKi}dCUec&`w$Oke#zrg zqJi1)ONu72igP85PCx8sbA1^r6@8-^IV)`=OGOz`72g0mBX|eEBWXm=DPg2fqX|Y# z5T<3mh`a7Y<04L1vh!<&`{cpq7WaM-Ay!xt>Df#>U<~++39-KL0boM3d)YF7c|B+B zmBQN+RLo5=p@e=otjoWe(1b>RtN71cwD@^QGCb#e*w2E4LyL)kzq;oy`DeZPcPunW zRS`4zcf_IM|6it959vTkV z_*tH0^L=0MXw+Wiue?C&{noTH6~%qkqybRKCL0uG8kWh;VJu24Ks}4|6ukd;UnEDm zqwzZk|4y)Y^-r9;bPiS+nSa{-cK|x~@Ro+6ik^2ScOImBq|+Q&-ql^~N;qn#iHbA; zU}N6lomT(A4t#*kVWd+aySYXVys$@(l@Se~c>oL--$$v7MeX#F$2j-EK8<@H>+NS4 z$Vz$p*SP(enNol0bXs=_D@-81zvDmaV*d&r<&giKW0rY;-PlAF!Xi%*W}uvrl$b70 zc8!BkH$p%NGHV$2XKUMtAYd$pr*;mQKnd#)(9FTfr!cv>hcvvDTC}R*sp4x1e+=6Q z?KFGeUmzah?EwqvU5)Oy@Zi**iz@+>0n__nT(yLF?F4C8Pw?KlSC8?Y_$6Z7DyzOO zpS7Ju6NhTOP5pI%&La$x{-P;7*}V!!%)bL#jx&6~W`Pf{oebTbAbb5dc%esJl)PM> zVpYsCP1`SvL7r!?I8$-@b)R|00iDU5f0CUtPp9>K4(XLyfg>JeF{wI1J`lcO^=JkVD$Oztj)*zFbeqXSo z&UIZ_1WS_c{Z^lCu0fejUl8{_6R){bl(D1@DZa z^nT+D;UVY1_>n3(T?z!`nJ50QwD;<7X)o|+U%0x)&Ia^_clk}dOFXa{j@k!U*icEi zu?#G1pv?LGIK6&<+V=f24N1mYmfHVf0f(6YIP`z?fSbtv|MY-w@hKR-?fny;s+2;YHweg&b7_B$D?Q7pR>ik0X2~L!^NW z!#8IaGm>e|8g*yg7SWFV39w_309&{m28$GI+_0OjgWWF}qurH}2KXNXp<@(#`+dlD z6Bt87kU3W?B0T3> z;a+rIgFaN&VDK@1MuftqJh0WmNA~^E^Vc33TvPfi>|7-M20@R&KrK!dB$|GY4`d`m zXKx_vivI{Zsjc*QwZS9^lbMIlyw!Y*z_Ntgrv4?%Kp-;JhuVoQ*f_y@wy#)44*YK{ z^-I_=1R4F@5tE?H9|w1E?mq$dF6M6g#)W2{cN!m?Hk@qG-}mSLjS%{$jTixG`-T7^ zgmp&)k2*yp{^?QRqnOR3jREiXEGSjC(X#h`&ku3LuZ22&*34({RdZIDp?qS}iw zm;Lipx)UdH9fK#IC+%7mjFlStmlIFWkgGm8q)S(cOQiA`Z`}uP_lay7M2I3bGf03o@0t;WojlQroBi48z963 zTWzG7WdXcpztP^j$Tc0Ucga){CgC0G8Pv&fFpaY=imATuM4l zJ{*&mmCfbGVX*~j-f{5(d0GkjMq=Q@>vVsnYxd3v~$ikUdM|_Z@>+M z4=FF{W2KiFkX9H_>@8;_?Kcm4)Pm9Fof4WfNP7oazXbj>WQB~?aw(l^`UkF26DU0j zf|qd{Jwm3&D&+;5z7^0vH+^IO##vN4T%K196c-(@$bS@{5L`7%3jFAgM{cv0ybirK zwJwDQuXp9L=gmdzs=>ljN)$WAu_q%AX&}%c`16b|0F=Qm zmsmg=qHGY{Pf8Z7=B?zbBxK#PRzL4k3cK81^VycE_3$3nUtDNQva~jvg29iui}r)k zJ0i`Vkc`Tw)&J4ge+-a19lHkGCit$zqN=%vF71%l72Y^+eOS+r)astFD zk~;^AN_tj&Mpkx`!7CIuH@E~o$XCLD^=^Lc!HFbozVkTW!L1w+`(iJ|pH%n`x8m81vT+w~?e`rVfZyGa?RU4ou19{eq%X|J;6ER){kM1rlU3SZ> z11*nGSn#!^y+`eUZ~@qD>3RLgiAS(fjQnn~&KnKov4Ymh7G6CC-5Fa9kQFYv5J@qlrYkKr@~o=K z1g2t4iOyWN8zxEa@43CMHGtcxC5);umihh%7Z>v*CfD@?t?Wd#eW&)I~Pv4syMwy zAk4>6Z&xGKt&2tN!-vJWReRfQ8lHf8PeN4dJPL@x}B^3$k)IXcGr9rx8FA#MvO)^wOoW@R;X&Qdwi&UH!svn*M8wz*=p)EWgh{lkCbVi&B6;o| ztG2SeO)gbD59jtKYypw+SJgm#mf{7eK{wnbF4K5qSUC26rHIw&+t3NlXbgckAhQQ; z9VFyKn5!ea0bgDFFJGMthM_=;?FIz^47&p1WIfkOZMtG=jERvxl6^VET#L%hPF=h{ z<-)z(E7;M*Ci>mMN_mB-0MhYq3i-JyN3X@`-{j@3=e@tw<;$^OJn=F@!Olx;Q5j^P zf}I~ju1p=RwK}h^k39;O%Y)ttBmT-nCIDJMFp@+pP);VeI`#;Rn<{S)w1{AWVDq11M7-lfJXt(IKY-HPeHa6N$F4vqB%S#l**n zmuAyJeaE64sf7KyPfOC-oWy?Zs!N!8CK>hxHN7jMQxJz5X6XO#Os53N9;Gxr#HBrx zGUo&#D_#F%Ug{7nyd3fliOYQRvp#gaF(daB{Dh#_kG>kTo&{M-sDNbkCB;FUkxD!; z@3lulH^>R?*+}D@fiVWr!#H3Tb-2ysC)}L-)q^zt`yQkg=s_^nSJBuvaQ-VHL_cR= zpPA)+bBRBnIInj4FU}i|)*Q|>rhmP8wQ#V1yee2V17Itpilfh5->apqS$uI(UQJz0 z8!Wf>EM=6j#d{KvD{-q?ErTQ~XR_ zTB=ED!6mIyFk)tJNf4t=`fP0TWN19p026= zsn93z*YkG%EuAmdHObBOT5YvE#g%JN^BYaBDPQ0^=YwO$-+}a>m%VKS{P>4B`fs0a zg2nOM^ZfS|9y-yZ|FrFm8D-u0&fP+{wzfh@oIs&u_#JzBp;BeSb9t5RPNG8-cdF*i z{eqrZ-@Vw2N)QSM3^H%=VZ6QDLpCm6_}@pFHSb25)3BsHfpkN48|4297-ROsi8C~B zWj3fhSBiq?ZWjGF%I#tAIHXZF%2`65|L>~TW4d|#za^T-UuO%)Kor|O{d9VRXZjp8eCNBzV4v+?dqvIQpMN(h*Jc$V@I7cHVFF23LIJe?cZMM2& zWp{Kui=1>965l?U_M__ntY+GcVVB2h?vOs6;SGf}t~H?>Ba)L?BY zZTHs%BB8NP-!91Cc3s&Zj}5PGz8V#A05D1-Jhwr>*}#D9^Kgdr^N<(zf1-ZtxZmsd zBK3C?K7&S|1VrPNd_HRMGc&kPLB~dJvit=INPtw1_%Dy7DYRzd)O0qSMg z8!`WXw*>RoNIoUD@GlqGAMZuOdc)wqAhFQ*@Z&sburZ`U@3H@Au_x;Orjb+#GtkRtnx|NGbQgU4(s@;oE|dT-pP%u$ z0-3OuRpqrC2aw<-V*paT`<60yTeQr59))@Wn73C0=Itd8DBkR)Yb0nVrKT+>WTa?j zsNpIn87yRKit0Dg{j7|SA%!CUYh|o;vun`M{o+BU-%O07)r_Mv*fGPY?I+$U{a&O; z;VvubNZNnlGOgC*r$6kn@6*shR{4^Y;EZXV`jIbtaLjECW$wu}+ticJhkMhK({BrQ zRJpFZHwc9E9(BQkUSuP@K~>bK;MGH>ehNBJl?)?~tH&cM(fP=Wy-!D%AtL5&ZeE)Y zN$T^KDBLeHySakz%{jR#SjEuht1_<6B4#m{9vzIiqpJr7nR-}R+P^Dld%=K)@cg;S zqtN#uBjT5qS*#zbnm^Lh~{ai5B7!fpz7Jjl?1ag%BafMz{YUVGZR2#9tNc zi~`f@CM9GaP&|;WW8FA0!MEZC6_BEJq^ss{}V8DI1 z5@I*h`Tux(%djfjz1y4aQd&|$LK>7#X%LW>?o{dS5Rgvkk`C!^5D+9K1nCCp?s~6D zShs7fXFc!U`^$YCc)+}!&WrQ>#~8nX*zB?YN{6J3d6f<9(YG`6qUL)iG3rzUTPs4W z6OxFy>|py_Lagd_yEvD8>zYP{{P89=!hkfBK+W&)+hx8$Wv}`R*K)`)DfNQ!vuf4d zl5M2~3VVVSCO-tkw*m9WoJd6tc7kdS(qQ}AzATN~5A^KLYL%(=2rq#Igiot%E`uF- zN61oOt1nl#C_X{M8(GkwiLEZSZCcp(6v)O=p=ijK4Sik)y?bS&6dfZ!(H0-*$*}8_Q{=PQG z(Avd@ky^PIgA`88zM1%7DZ@jH@Gc1|{s(jkMKn)dn(vH#NL&eC4ltB>2cIqMD~Kw0 zgJxTZKPk*U&Cw(Ch86BbO%&7M98KaR+vf{#UMQLF$K*|UhJU^#@Com&9Clj*lE&=p zYzutI0|hYC9Pe?uj6kQJmgg7yHp(PQ5>f+n84RRKjc3&wTHHD0^%!w0GcHBsj(pWQ z?WFmt6_E^(@M}-}$%J5vn7b2A1bxExWpTTy1Mf1Q ze0|x1a8YJ|mWs3Dtsc*aK<22?TaPC&(TlihJq5?3+;LPCw+m^uNl+Ji8XQA4`(->I z-IC~2%Uvw;wW9ru7gH_`6_PF*vL}^!Usz7qP(9msp_>jkvYY~oiz4g$o`0>j(}q@u zH5;aE#TC8(yyuaHB%=vwGy5st%7Vs+k|@=LiN(FMJO% zOXvDzWEE#z6Z!A?-6saHy|xkwCkH&MGKa&K<~o-?B~GY`bDdupX=}Y^*e~ojr(ILY z_F6JZ-Ra!qJ~`o8QL(MGW2Q}*N?nDudto5y^pPF0xM%Wlk?Cu@NmG5TDY5Q%u;N-% z_YU%skDXU_wn#^wlwlm?J=u=4O}w}k@Lp4qZ=6;)T~0_;Qd?sqtS%lH10L=PM95x| zR$rS(S}^)sOgGk@G{tWjqEhSFjMU5+om^T!EBNb1@b%Ag`?sB8Chos2I6$UQVW8m1 zBu$Sb6(Tc8BQqdhP{au%(D-ZR;nr0~tVwHeWbw51KJS&0BqD7JFlNy&l`vh4KmOhP zeCgWzX$}tC{M&FN9vYC(L@&@VU-~j615fI|I@j&vq7^^8spq4G|L3jHn_1+j8cNDd zRTrUq#@y`u7WTrgIKUPY`%W+*gp{4dOhD|DI-nY*5e>k3U4fEuWe#g?`eu@@P~8SC zG?qu~7KTC_SgryTm`ISrCS0L?y&T)KT&Ha8mm3wI@rz(B7bJtrRYZXadeZd-U7dh$ zU4a`=$Z%(!pzz5}r5+;@a;F{##2&AWf|aWnC2oM|EL3pGX`ZV;yBg=o?ttpM)*oG( zzT2%PXGvX8Le~`QOb2)|c*rFTedGj*Tio2h2ZeG*y}{)nKBHJs$WT3!dvx!k1sBz`(5Lnr7~#GQH>S0*=wTBYUV|((`=(d~$XQme%%%&hyncRfL>Dvqdts3Ca$~ ziAhK1JcsNRA9+r!EjRX}GHdOv&p%J7pxSwG^h{@PR*L#9Pv5;rKCi^m8Je^xpA6i( z%WZdx%jq*~g`!Ng<|U@f5O3Ju1H2pV6a4Mmka~#hh!Py1}^AP6yUQsw#RrYbc)ByVLgP(T&QP6jJ)g z%7!q;##;A!!2QS{7b>>R)f2+Uy!Nf3Kh#?K!f^istDTSQfm`1G5QtqjX8MLFlceec z|LbQ8nu7eYdd=}~^k42{t;kR3QSr@&E?n+&<7;o@b1A>WJNL(jWp-X|zccyaZR{g2 zlBssn{XLV+$-wi(?lc}A)9Oj+bx3^Yl-Yw!b?~K4qLZ*s(ApPuNu-qwH|t;rd;cj)Z3sj2X zJJE3UrnlH-td&x!pFgU8Bgfy1{a*dcJdJff-9`|Y?f4xR)|auYX7`(ly~#@k&_|e# z5y^!Z$y@Im#=6hOSk72zerpTjn}>SDa_?nNkRzpQXpz4Txm!*K(hC{6?sM%XiYRJy zF+5XjIXSs~&SQGhr*cqo1&+uEsdj7PcH(T@50Ef={S|fLkvoP9@et9PO6AL*b@Nsl zqU?3DV{B_+%H=Zq$KHRpWAHx1_xYoJRFgY|@wr*LHkt#=n$Cc4pXVe0#FyM%q1Kem zvFsYH`E&M)n8SoGB-NSdejBLk@jhBD$BHJ0;{&pd37K!m4>1?3?=FmZJEw3WGWFJ* zkJ(CX+KmsBBsrd3qvEvxyZt20xEtiN99Fl#cmI|^Zw+QnUThCc_`GL%;Qj^ZsS+3_ zF$Bll2S@=QdLcxK(6OA`FSMa!1Ag818Mq4*kw88$(K_Kh^XN~D@6uiQPL5$(IW8f| z9?ZFnS#H!X>$r_R;jbR6QIxb>L_V>&EqdzlkzAPUu)CZ*qDKjrexM5OjXidxjpl4b zB|6eQZG28<1QpX-{6(-u4go&HAS~EDvo?L&Vh%RkkO6nVQL&FtL7C+3cilv#764u7 zHE3ZzBK2ytN+Rcikn-JgOP0|e@#zktSQwK`cuDvU6%w%ciJbzJo@KjZFRw?2+M|g7 z*o^{8&vV|2+esE)*ZMb>)b($DHq^k_Mkj8vr@or_b@{Jc;e;Wa@{6BsOPU-vf26(=Xm;87L-u(Z32w>7w@emd$ zK#OCGJ#s+VJSbKG%s}HU9`n!yK5#~X+JjI2?m3-S+!b=>5jGz%IKP&5hS1#S1cR8= z=Oonabbv^iBms2V(KZl&;iQ3V)3KS3)YHwb#Dzq!D;Sg0J*R$NbUfr8LOjU!z@7V0 z{PJdz$aZ2{I&qI})Pz9wSdVqFXf7|slE;6j>g%>b$`Ja)IPC&0)5hd>J$m#{XbA^ctcs{?KE4VQRB zfEg7KfiI91lpb60Wtsuw;_H98JmhKQ-y37VdxQ z)I!m$=f`-nXlTxhY72_Z2oDEnETDt{Q{IlU_s@f_r*~}8#D5$Qz~)5?OppkQgQLdl zdENzKw*gSrfID)}30#eBNiq@||J|e#D6oKM0W!bOX4SCfo!0bNo{1jfWp*Yv!Rrc; zDuw$RMYjNaDHK$$0;}i(NL>O*Y5;L5;oTW!Ap6Jz2XAzoWs!wLmfBe$!hc32EV z(7^zhvKI@9W10aSA5vwL&n2&>>31;3VX)7tuQqg^niHY(yAVP`K0L`$*BA1V*xWeiV9i}xd8yfNN^f1k)MbB zJ8hjrN6qHk-wt`{7~so7!eHQ&S;1|G(0M+8>UE`Rf7Qf** zvk$yBHDGOfbRF0*3#_7E1PcR8EL<3kD;+0%9s%Ojv$3Wm@e*XEc6yxQGc<~|O{`ov z3e{gK9pdrPWEGa?1=8JB*r)8GHgRQR6AT<<%y!w|MO%7P)%OPD_J)Y2n^K}u;0Tpl zf<55`FWostCTwhKti!Ez?$~NF+UxIf+8-tyCODJ(f`O$dqe9d@0WA5}&fG}KNY8}s zJhDUbdwL&|ynSCG5A`LN_Es~B13`p(oO`CdJ33;N-kV)PTArA21KGwwaao5uuyyq5 z!yoo(r~AKQh+CbitsyC|AwekhuV+UsEjSBM6-<1Xn4)2xfGf-=YC7GkpyFE@y^p*G z@ilKsT~m$6LzuMd9VtcPqFt6Bt6Eqeg}~QiD&0OraEf36t zE0SXNDxNu**eBkv_Kz@W%n)xYUgn|Ofxt<{-aev~i#sp9Tt66Vpi3$Ef-uwVZCp~) z-S}ZBlNd`YpS1HuL%tbYByps8BhdeoNjt@0dNm6Nw zcAsX8xKHLp2$pFH#-|uN=pZv_DGcp>&MbpwAF>-aERRC7j)Zz4GtUOYmS6{6MiLk; z3Cfp1Y=PC50M%GIw622Q9=J*h5v83bYL7}dq#DBN@!rbr1}Lht85d>+&ZL^21#^$M zp~xaIh5#x(Xd|QC*A7L5J22T|44K*=^1f42__0MNt%<%$c}OPb9+08QDY>Stwq{&D zB1j*ho6Y$!*N>qg;k@79iRbQk`=QXczIjbyayRt76ZR=^9ua~XPE9er% zeFg`gvP}cY>e7Vn$kWLN2^S0Dl>*oIlevp*-v#3jp{#4_{DwmqhGaKCb2iWru6`Ut z{$MXwXk8$FY+t@{ZRf*zXRv2E=5NWoI$Pk~R>!}3&wiY%zvpP_r3!w_`EHqOJxp0b zK}B&*BCD&K)0Z7X`*&5=j+EvL-yAa_P;0fm1Qrw|j=Qc@PaRuR8C~p_N^i@rbH^S9 zuM8<5O0_}r@!_tJTk!NgyF9XA)Jxpo(3}|Es+`I>zC;Yw_w`KEs5r5v`c_qKE#Yi$ zxzP4#*YZNAe7zrbaiqWzoxFki*!rb})8W#x>Gf}%VmAn0n6y^@((#*&bc?43Y&uP3 zxypMiWl;sLQq3ZfJR-PN(m1QRjL(%ZWwh!JTi?mmp}6e!$m-tOVGX9jr9>Rapn4Fm z6A`nP#FU0xt!C6@=e;IG3fCy!tS|*QPm6(IU~fb3g9$6c7e512Zns3mg=dUyH`JWM z!^J8OnWV^!%1Rz?Tz(R6{w6@9Rnd0QrN`f&u0cJdds+|(48{noRz zT7G=f{DrdW;=B3IFb|KYP^cwx#iepmhG+XM z%@iv7Fdt?AyV04za7dyg4ziY4hNM|{RiDlv)g{dp1`eZ}*S{(`O%HU?$ zMW)k8ko{2S!U#za-QwKtrVdFF`)B$DWWzag!|x*utl&6Fa;+M8goiJEBSs@C5iJQM zQ3&3B^z%fAT7$@4eVx9)4ms(ZYWJ+qO#w zg8VI~e1fu-{Yyb9Fe=B@73l!K;`dZD-xbFy%GUB9_VCOTk`cMaVq<$xP4OI^ucY9EJrR$b~KX|40;(^XxZO9Jj&W}B|DuRVzMe<;@%taTAqaMTR?Vl{9gpT;L%mz5kY(>#*7v@k_ayEC z*B>5uwA$x%k^XHcXkTQ#YIg@&zA0garZ`aPt(K2kaj2G-%;T{!IrNVCg7!P=iF(a4 zJ26aO=ykK^$JiAqZ6z_R*=tG(2%1j3^^=@2_y-up!xj4UH&?HEUEWs@H(5RgeNU8p zSj{tNN$7oN$&=%IVj|QeXL|IcV&$q>ghA(p?+$erCr6p@;a*_C=}niT*@(h@1`FZH z4L{ke5riy$O~{u3eZR@{=*{(ULIZaeXO1o@Nnd!~&Mx}!hV@#tbp zACRJ#RiQrCB8qd+n~ROZ|5b+JP^oiExVaikLdxVLds#&E17bzCm3F9GZ$T!0_pj!h zGf=B@+vo6m_c<}+>~xxS8A#qb+0ZqYu>_V#v7+8QT-42YLz=ApuV4ZDo9( ziHJ`=%#HtBWxP)a{5a4OU023k2EdPRXEIcvaq3T$JNNMFBd5)r(EnnD;+{(SV4 zCkBR%PC9U$4k-)1v9c){`w-KUKO$;u!u6JX86?z{5-+^ zp*GglPp!fOOo#;8VUjT?k($LTDuW15HyIoWfIlTmjv8evVoNlw>nLmf)* z3$ET^eS00(>4%L&lMbASc$mO0hV#tf6svW!kkjBWdl=hC;{6Cap*{+T=t=vXGNYF+FOi}Fsx`Xr#NMwGXP?g*>dGx(7tHDuh|O`2#(zHFKj z=isO{*;bGVJRVun4h?!Jf)>$HEg8Ql(dworvd6eZPj*is1kqi&iLuWrp6;nCZ%4T$ zBlTtwnCqmH9jO7%WApdvdO^>Y7JC+Y<_)9*^rgg_ztBHeu>6=A2S#$=Jm4d`+T@Gk zBGwJ-?T2Kv>hWONxCojOUqddNiq&ajU?N<3)P_W)o9$PLc40^br%(2?dK?CMooHU= zv=+l29N*vWrn-eQ`ByE7ifOp3pqZfb)~1(svW`nZ%8SkPJGHk zeXyuvpEwqKdIq^_6I?n#UMS&c6AVZ0`7LvsE{q4JZWx5ASWltwRP&#G>pcRGUP@FS zIB)BCVs2qQmHqW_Hzlw&w`bf^{MC9b&)@^sN)qSshA%8aRj70AyNIG~o0U6H7J9n( z0;_Y%ThLdxY#?0|lwaf+TS$kBhq*AV9(S(>3@eRWGj|S-I1AB$d-Bk*9yEc<0e93ejax<0wotoXQvlhSI(6oKqsY2(G z^JxB=pF>d3C2+NTYO~xrI%>gpbl+v)oo!yF?qRPPZ>ld_w{Hmdtu=*q=dApAsxVpM z(Q}xG{&k7x1)5K8clE;2(0{n`uLE@UalkG`HCyw&%#3_hc4?Fcsy>3+ zoL8$VO(#^3cX$?Y$DN#CTA6Q>m`|+`!ODzRd~&9Gn_-%F?pjDO7)wr$Jz3hteM-z} zcX+bhyrki!l;m*yW=_J+?pW1q=#HQ|8@Jzs#D?^olB6k~g7eAE^gMz@gUV$&Ya8aV zYLPZ5QuYWx9Q4(yY@9+kcv=WyVF7+WlU!b!`!R+%dOK)()_U>@d;T@&jRdyOHdmOC z?p21E$Efi;lVqL*>Gj~RY_L&VKW&D?=!M5Ng|Iq4Vt|t@HLv@;a#lGo)NA2leg-8n z@*IpVC!@yn*^GA61J-(ixayMdmul6I6 z;w-1ifmFPK^rDgpWbg7Sr~<{gh`+$Qwm<$hT)7r(-mWrXfmNm)0SG@Na>DBV!X2Dt z8Z7(~pv%1>2qPPlb*bKR9-_eK3z>MweP0m*i@^6ss2~3&WRJIz^M7Te|2Z{5$33q_ zr<*MKF*SkyKQu_|b&s}dmgh#syw+9-m;7UJayv_lO4rL+OnXCmyK@ctiJim0HV|r$ z!vAB^?iTy|7S*$AB9;Rfp8^v$B&QmAzd-v9cjN+KAPVvhN?myeg%N=-8&5baN+&w# z?XKz@FVEr$v2?3oM4+bN1A9n-al7Z7GFf-FF$ZvY!+@x+crW-?lLrV|6g1BX7(kLe z&Z|jnG2e(ux(u)?-6~bNSy{%Y8Dc16v~6yXF@&ZCDx^I(q9K*Q@)S)YdXK3ugDIO$ zgfZv&c7UUXsV1DjfQ-YoBwt?p{B4$C-s^`#e2DdM^>8q0bb`L6m;(OL4LNWJP5sF< z&RKL`i8V|*8T1T``WmRgUD@0&wz>;KYW9rC&YMU&7UawY}zj zcV35Z>Y#V0`bj|kqu_jxzOP`reJy$Hrz4HB4Qc^X>`_yX#xm!kM(I?1Y(2Zm9^){D zV3M!WP3?Af+jDnb@RG>LG_S~rexiK$L3HJl*eeVc_4oL$_urH~Qy6ag?qP4WW-0Gs zFqF8lWOi@0*Edy8t*zlZgyAa_0)n!@h^$9T!lf>b2c%JhCw_eKNaB+n69#WgyXd-l}~gB_%lhq)kT6Yl28~NM>pb%p-0BIcVNy7sZ4?2^Y?HU z#UC+8#fyzq&+o~>SaE%ZT};EJbFfVM}o{-?)s35_Wu zew)fDg>Mvt+;cca|%RN79xNLd#52sVHMIcq&rQE?adCcIB5O5$Q!7|-U-AvuZ8}+6iZK0bX zR>E?Exj++wyFy60HMkRZYb0YuLw7-|gD*k`HbNvL+acOvPrK_iB4|GOg8Ts%iWp%J zjGfmFX}`0p)2bkxNo`l)^@#;(^xZq7ZL>QT&dYh{>{bhbY8ULw%H*f#*8LjfY9}%~ z*54^g2Ov4`5hy)j-ytIkf3J2HhI;5L;aqWea=K&mTbpw6- zdRA7<#24$pv7_^6>9Sl)BlS+OC3J_otH+-Un0yY))(G(zgDwu{GhBAz4B}B(4l)bO z4_PQ|2@jAQBQ-dZQX2{e7rs-EiL4Z*>Bhp8Ul={_IX^$yTP=C+d;x$}0k8ZuN{E?Q z|BW^b#SPzQ7-HV-$cYypOdfUs6#~dt7NJ25v%ivS-|z^$S%lC23B3gtH6S$#fce2k zq6hIyK!|zLbLtm+O!t?uL5gtV83wt%P;}FW+kQ&wQx&5c4b=S`E@s}&=!lsier?dF zmFTK5L2N2(e2Wg(ZE(?YE+(b(3{x!O8YYGXAb>{SQ(gAJ#6kG;K=z3N z&f_zC+>mCXk8~6rQgmW80BfU5yjzQyhuh4ZfUeo|-~R$JoM$^lhYdH-HU>ySYy{=LA7)5P4rV)A!p}= zB@NlUixq*K2Dsy3cW}pgoGW#!NkaR%p3%sYQ+&q)*oqVK5g$EoSo(C%BB_Q$Zi^w? zmGn;9d*!(zd6z%TZ9G5CZQ_h#mf<^hnJoP%f6{+9`ds#tMai3s)cTnMPQJE8ZVs*m z8~cya2FCR>^-3mUz7x=m;!%mi7sw&H{5S$SDbjKH5=Mj(D&i7AQHWcx~RUoF-k;d zh(c_XYFJDXc2a0`R9LuQC{JNJhds=o73}OP2NuRWfLQeCdNg!sjkIlU<%i11NdH*8 zU!0nP_z@RVN_1y?a_~cZ-@YZVuLey5%B%=akKc>TKp>KPhjnXc}f*(i&R%51vjArLa&)0mgXjh1>jn zOjzS|Ph4IUAnV-T|2pd&2Ji-f#~J^{XAbgs$Sn_l831xB^6CWtGzEdzP!0C+M4T+w z+?_?*Gr;$WifR)&T}}mz7%nGexi58{vyuxZm8=r1h#)u&s> z)dpe>ej0WZt_(XX0w7ol65N%u0Ls%%<`?BNavz#%)JnL8piY0;Wq-tLlzXs4%guu_(d8SZCl^q9YcXVD*R9F zj2=lA0TsyX20J_lc$N&m9vQlL`V0X3TYVQ5ZnyOp)#Mt#XsEH|O=dG3X{ zOc&4)UkbAH{UXqsU=J8A0#rfUphZ8`qws`}oOj+G{dDb(d0*R^0}paVL34V78 zF42L`nBsw-hfd>J_yGjn;zsNc=h#mQz|-zGF^JcJ7Ehs=#<}LJ(f@jR{6mcQ)|Umq z?*pe!doKxXJ*+=SmseQp5q}$mboygz@Ou&xV4no(i(LfMWupx&gp4h0WL&(qe;mS) z|9cHKJ`^BfqVH6Bb&;y?h^kT*6RqgmxAB0C>%s2wIw}sZ&5%);tgA1UU+jrnKWHNj zb3_VG0PQ%^e(X577(GVw&H&^YaP5IiqXN*}KO=yGP&8}afozMw&j6-Tc2?%Ap+#6$ z5+*?1*^EyL*J$B&ad0hJE}h(930_-A;8DwR7&0wjpwf}f9Hnur={++wak@6{T^iP1 zV<;RfaLP13QwoRiEx0jcI2N^{LjnlBCLnc!PI&iW+3o^mn$rkCr+hM66S0V%Q(=i3 zje2ZjGVhA^JVTk|aF6)q(zU4_bQTrfaPY{ko$aCY0`bsZy|68WA}30P-?8~+=>FC7 z#@ofzs6%)g>j{Dsz3I5W`ZL6XD5*y41g01~aj%89=2q&63=<~dnCl?GoO|JtImsHDzrBG`P7mHJ>5Yr^DmSB$b=FvQ#%?-YK z2*M)n>ET~+seP_eWb2+$P>UE}(NRDFe^@bkL9}C@Onr83NPbq!#6aA}0TM2mFYDc0 zZ!dpbZ?=hlyWZ6Ht61*^FH+gr1uRk-FXkeO9OnRikoG9%pDhr;`J~g34(lNj=^(;P zYF=ohZxXP6G6(JG88}p+(h$x1JulRVZO)LDcsT&ybs8e{l8<-9U3uH(4se1cyE>w& zfDBvOrNKgDWzid%)-{p$mRIo61-Jy4d6EZzO4nTYAHTse#LX-Co*W!+M`hvEN*-U{ zq`ndx+Q>3RelYW-BWC8_(mIvP<+J(Y!a(EwuX<@Ge&a6R46E_kmc!(!AG{B>jycbH z)k(mzpY%-%{+em#Ea<&%aKXZn6-irwlzQO{aQot~8U|Y%8!EA9pSxHxJZgk@mkck` zY%Xg3B6xsgfOb)hJ>w`BHwtr^ZLD?%UswXn{L+7szG6E;?TNL~qO! zn$v4wIiuBKrr_o%#(2%Vjlt#P~?al0RSiE z-7f-)#4_zGXxHDtLTI~4aM5l5L+D!;e(^8tKY$BFYYY1;>J-d;n8}5ys^oNCqkdW4 ze0|aS6h4og(r=t@J+NuIn9IQl6w}+`7SkgLR9c0lkm#8$3G#?o1k_)m%#RMO9xkab zJoZtsmbS}P;8~&@B>rIC=8f;7ERS4X*HreWH)T|+A zY{B#lLu^4-Ou@$egAf2o~oodiYM+n|w#+DqfjAA{_J60QOlu;6;I#;vF4 zeKyO6H5d{+77l_^itXl&VDgz@S{?(K)RF~|Y_@Jkz%z&1J`RsGNTY}kcNC7^okUz; zQlcWQEv8@3AY&)Xd1=VzsnElTPh%j|i3`|{Q$gt?ySrjL;{Nn|;X{*Wno=e% zM&UhU+l8;o>eOa35#@VN)`8Pfl=P6ZwBoeua`BUopl1dV@?VONPD95eloOZ-01k|h z2UqCa@aX~^EO1Hk;K~Hy1TWIPs0>)7GhQsn6gkelqBl6gQrFEvz;+3b)fjGHzACNb z7@gEh?s4knEw!xCuS!&lIQVjrw4763KZU&}1tu=qtV6yAt=={9B+s51xc5XBfk0&c zcx=s!WTAQwuRBlrcMqC2<;p50^1c= zVtzO;IuRnECOu*V)ucgDO#m&?ZZ&qn!A5$N|I{@jcl5+Xqmbu*=(vvE+MBvY|Eijd zC%xsF3hb_}KeP~Jwb9Za{bTOmYQMJ`k{4yscpg%gkuuy?s&+qevtC~BB>qhwgQhrj z<;+L%h78*P)UhIjGUmw&>~@gATIV-73SnV(>T_MxV1}c}B$i$6>u4K}^@3 zE=xG_asgJ=LEn1l;?2##=x4bKp#DKeHUcPFT_gc;jzq!V=`uSESp{&n6xLhcC|=cV zTSP-fPoW{dhgQb_(o6v01vch&c_m>%L2MxKZ8QMB4ZH&19uZQ54ydLb1dH1swsT#N z8&vc^lh{D9N|d4i((cYJ730${wm57V?*B;^8|YJNYyyyb00$TRGe3ab6N7DV2Nc#_ zJCQ@{T(1`N0j`cvjeqpsHCGS#M8(wEdE~>YJ1Gt_>fZS!t~Y-oIWV{#9e_Spj~^z2 zy(u{3ikB#1#&l({d~DXl+YWA`kE4- z;lOhom)F%MnCu*6jC@}_i!s}(CCMOBKU?`^;{`Ef63eLf>jrkKKiyqfd!1}|cb{GW zEf~Q8%_clS(3==;pc$pcZnQ5KPFp?PicYCq|FwQw7iw@6kNs2<&*kaG;iS|k7#M+& z|MNf*ytiz7lBt1sG$w(;Uq8K`36`CcjdX$5DteR5NG4YJVLCf3N8)LBDNCh4mx`fd zIZ@!O(8>{!?abT!clLr<9!;Bz6@j}uj(#6oxy%?4qUcABQk_4|c6>>&F4s99_Wkw^ z`#>jni}lp#oy6;UW&4ZihpUObX`Lo`W;^Zy9Qx`e0u>)scQd7Vav9|pKSkBh(H3-D z$UASBk7N>BY*adqq@OG2Y}VNLb@@mC$-HL?u| z0+wx`JL!Fxl&ZxMuEj|flaXc3N68;>XR=mr*@}FQ=JlXpl80zQWrI`1#Z~&a@}b+29hX!EtZ?P_cJ^2U3q^wpe`0 zAf94;~YK#?(kz?H}RGFEC4JphBqBs5N+|L#Q1+L{*)U_3g#uQwKpP z`#E`grGkUn6ol4sy(|h&48OYbvBq;ty_mi75v$Rus{1oL!Qaucvlt5^tycl*j|rN6 zl5Y8q3(pzcs?`In^DkX4I8ePDm#OSr@bUIyRx$<87sR3s%8uUHW9cRmyw*yn->jVy z{m7p1))O|nP!e_3>Pz*dxcGqLKtYsCVN6A{RLO9CQSQuTx*5*|_%MRYv6^rVYF||u zkjlN#7;~a=b^VKdrly7a{0n+b-wlkL80G35b_3wd2n$RQ42VEEAW5v?R*d_%NpDCM z7F3s)R&*6Uy(KQFfr1?}b-PNnAR|48;8k}aB<1w>13=iX#X_PM`zeFh_7!6f@EkOX z{&C;_TmTr(pv;N`c;uLnd4cHr8^BHpDBsAa0n1SE-)4fm-TXF0Aupmn>waGXRuYP(-$T8w4o5gxoC!)g!!vk^dLp zV*uYG6yO2!ZpFtUwFHza;2rvZyDE7XmC@+2y|orC8oTsBggL?&4dCuuT2JALK*MBE z{uWS}#oe7xud?bOaV(fHuzKgPF_IJ_vcbS<^D%Me&lxszsTu4o?z^K44Nxas-H%v6 zwnQ6()sz2Zx?}kb3FVGJPw-Pw^Y5(ns&?yYElV0B{WgVw7vwAk#$Cut~Z)X!$Uf2ZTOM{w(Cq-({S8PfGo+ zhe3v|oVZ5MY3qW(PgnFen7`}DO4eFJPOnRH)1!zAl>rwkSO444pprOBX3J8uqhxeT)1a)e-*PYrgI6Hns+grVq zK?{;OOM5LSOF#?cO$M?A{xLoN1zdO~6aO8&fCD)I&H>qy(7vd3MK1oA)UXyWYzNRt z@V})m^g~0{_XOLES=hJzF)+}iS5871If)nt3ABy9<&v&r-o!?etW16}0d_h4Fag?7 z9aw3CKJ#m-(-R|Q@3H(9gWq*ZL%@Rr7=l-)J3vtjBS`f&RQvs0Sb*oWH4)_%FoFiY z{qcE3gbI@TrIfcqJ^pLgt3=K;c~Itw6^`z@)b+6eD&PMIM0StH1(olBwk`4#fa!1q zV1WU^{)A4v^I5kj{I8b|Oy}6lhlXOLU*5u6HG#?j#cFZge3?&##c2YyZz|mf+E2@3p;ua0r{=qY1y^zV!#C z86W+tG-H6;zPH1|P!I-Q=X9S;?Rs3ydy|0sm#~Sefs?GvhSEl5wrkod=H~@MDoA~H zY+x<(u^;7G{9Rj*Cc`>*-Bo#u0qmlMEGn5gu|QC|1~BH;T7Pj;;YyON5*)l((RcRA zjjN#wxxa(mOd41sB3RT)ZLKP0 zG%!wj>Nn#~H(OnaMiKGjUG#>wF{dp|0V`;L;o^f#y%$H)BpUR*M#gDvuvaVjv%Z^^ z{D#M#{Qr6-FWsXh&awl9YM`_X+fq}2k<|)>D7Bu{2i@lmlHBGKg7MZDb?}9T7DyKs z!mz}}-79)S!f=AGc@iyxD9lHUd{rZ91K313=-C^VFDDERMK-mF9xseh3|kh&!m;2; zE41%tv%c%77`u>fpkiT$d{~`kTg$!!ZUp4w6Krq3$V$Bi4q(Cjwwe_M?&-JuHgLVv& zLW5G}+=97j#{@Jdx$SKYzuz{^SICH4UPOTKZOn}q^3B4>kRI@|q@;Up-FjR`^RD-6 z76a<9SDBhidtM&+TR#9Cad$EE$|@mi`h$W<+lEs$}AW z%1gjm$nyDcXJ^roY1alCj5mxK{99Pcy~oDMKI*~!LwsZRNALEW+X!P<>IYZYTX_@B zZM_CR(n&lVJ(2g!!h}qr%7Mv!`%LZ`CrZ(4Q$twC{H+63o&!I;32<`OLp%Hdb9tfa zyT~r&4S+Ug3LQV61Z?=zOtm40=$KEiS6L{LMr#l5<0$ou2lcD+Sl&^S{@Gh|<2t^$>#AQ`!L#jkn-TkOk;b{2>iN1SPU2`vvk#-mpgB<#Z}>moeh;(!+N3*{*K+@ zigcSUJrN2m*uk_Hs#WI_st7OWG%RhPlhnAe$2Z?TC>X~PY+5SQb-vi$T{@h)tVeP5 zR>U>oR!T~u6pk{C^M>N9(vEGZH_gUTAZDOy{ED1{_sBvnSsvNzdqybLQf{ zo04F3o6+3StoYYsH=lzNLC$rUI;}pE;Pd7lb-W4*a zQF}j1&P#U?mp#y4L~}Gp2`A6iGIw`NA|kq+RJbe^8^$pPKp+52h~i^q00uV_4S<*S;Q$8*C?p% zOL6Pzx${z`GlZI;NR)3?`z+U215ot z`JJFYxg46M+yuqfF%1@viL$xVg&g#}`)`RnfK32Z_?+M;8pY$cCWmk4N0T#zryjPX zAIbH*WsnB+WIKD+uIwzP>a$PCA($qb-mT5CGq5rG$R#Cf|N^wMmL(FfLri+;DtyX zk0bU7Q3f}JPgx%&hu7Xk+Qytun^CotvxJm{iHSzW6p|v z^_c%DJdBK03=4Y^mZhYsq#6>g0VMIHy-$pdijD}smlURilo4*R6J9cxfNp6Kb~n7_ zt2O=O)wC#m55wr9*jOYaC*B%-K!Fl`%Gx&$J4?Q}uq3~@7=^{(%D0F!%>WC8L%T2U z0;ymA8NtXous}BS4Qf@Mk>60c>Q_x79T*@#X0@m+29V_lve41@|0Y_x#*o*9qqk07 z&+IYkfgJFg4nmk!9VQ$!u{!r_r(#zcUemLl;vBEv3_WM~v(W^K8q9xP)HGj7{{YkM zt!Gvz8d!~w0144H+_^$mESP_nxNW{q1FCJVIXfu75%giAQEv1n=r_NJsNdu|#k++R1&AibxGfd z9u(CAcHAFfCTz+)fN(&;4SpPyZ8f6?c z2?Tx*QSw1JL8aB{mlZN}K;|XTb*?QZzm6`ywaO@6GY}+3zk0mG6m&q_OD^^5mkROl zNmCGq_Lm=hKtUb;su<5U_D%Pz)!B4SI+tY3G=y2AK9%)8&%tm%*zGU5Ln^3~t6gLx zlEp=FHYFxS_Vmxx!=^gpSQ=QEf=R)_ghgM1mzT0Tc$5xEN?!|H85#Uttm zoJ#av@P-g(@tmvVG{@ME`Gp5rgPwSk&{1ZIMXWh-f`GU7@zKN?@QdUk#aO8emhaV6 z7HShzDwR|c$KTL^*l%I-YP|_{#@Xl0YPz`^jCm@bhR2EIdCgqFgiX?fLR-emsCwIu z`tfO-kE+`S4K9&-#S}pW@wKHp))h_-9oWfUiKgt}4tCCG)Gtg__wibzbR_?kxS*P3LD9##s)?bOa2r&Uyt6%_2M~ELYln^>)ly|^P34JTx1WQ>Q>^f&aEEx9wbs3Cc; zAAIDMwZmRuUBhRm6KeG&e*-JbyYDdeeOLWUHT=HJ*D5L`BBgVU;O2Kn*MQ3y*YIW=c92Jvf3Wb~*y3F`Opn4;OhjTwN~Dr^H8@ zYWd6&&nC~Fu~mzVQn$c~K{q!ZSc)@fforFNsj9Wb<`WA;8%swO>3?6wA7m2ARwnnf zv&FKr7v8VGGeFwnH5mDog@Mu9dEVk=Nb|B$FdI8opMsm5(*`}6jyOomEX5OV@c^q0 zJ&3!zr8N+}@u4jEhpc-$lhG^)_MLAm7B*_VEn^ci=rSbUS~hO4S_f`t)gQ@B$k6Ti zt5xCka|wRp>cEfrgw#?v_DG40kzVO>4Lc@**gSxDeRK%mU7Z{-9+2{}O^wJxZ+ylA z#8mn;1(!`GO8ofwV7=Fek1_ODcnaRIK4M)@fW< z6vEn7q}SHU)oUgd2+{VRbx*2K>+0=y>xjU??zP`-d{?JSu%D<^Nr6mD@Lj`!hwSzD zlHu{X{m9bbSI)XmLcgx9%iZHr(~LB&7^y(?S#7a3nXbWc;)mjHomTPHj{&QJXHmV+ zEq!=!Fwx?$87zN?_R@(-`GmUumF$L9K`oZnd7uAr6?Et*f$m!Qn>A*yS;>9oLvxze zGaI_~6N&W+y|wfQXS(Z8?iQ$UCTzf1Y~e8Ojl;!)^(M;QSI={|t9q$CAWy=QGB2+u zR&KKQDR3(Cfwd{(W*DbW9DiF{njO8AT_LP0kCLPG5(iY1W9kVsdM-3N?vgw*CNigL z;o5y&MeG8rM)i9kN*-ov+1|k)E(&^Q5MTBllF;UxBF2NcZVa_aPtbOF=aYICSeY)I zzMV>jg8a^1PJj*E$;?_Jdy6Yt2=ors# zY^1ElnhlZfbV(?c;kwH?XAje7e_$rulLxJzRLxnDsg`$d9jdy%VLr7PQQhhd6;MBB5cB9=T^>C% z*rZ!?J#v)TKrWCTe^t%QbIwj1YE7U8`5EAjY-|P@r$T&G0C$>bsm{Kah@jjjS7;J5 z!pUgqU7al{^#9TJmtj?I3)nUck_ytLbc!O~4bsvGf~0gx3euAX=?0~{yQRB9y1To( z-g{y!*WPRIXFtz(e7~0Khs?vtxW_%>y3X@p7akgTTzgzTpf8dbb$22@_E*JYi>e(Q z8gWwI6)ac7Oz?D3gJeLp$c24oS6L_j!D4!EBSk{>nhla>;zeQdhVXu?ze2R7N$RyT zXUbBIson-*2}_gRK0sq$;8LcnlmAq@q$cNZ8_JdSqEaA^Vk}w!C+_3xzz<5%7`>IcpUaR5ilW@Xq(Rd;4<5Ut*5iaR8X~r}1mmQb zeXFLc;I<#zl9TurcFk~RvsdeMblcNAV^~aNgp$X$>~aV3`_GI+vWp!`tjGCCq`K^5S#e!YwkzGs zmNrKi?Zvt6TLS}gL{=hByKyyFXN!Ee=cssni_Z@zm*BMWt53f^aoDwH$@jx?U`jVu zCGCA)ce_nmre8nTDBU?zFm5GAE4?$iT-beCMW#KIvzn>Vx8_SbfV0JP+UNR zRAgrQ!YUx2o%ng9s`%Xj(6cHksZgsnmc1N=Qjd`D>OLLA9Cvy!|$`tUET zFId+Fr8bqOUQ)58g{-D(vS^hQ-e7I1byOEDzX{6an%goLDL;CfWY5gF?)g1#`kTEx z%bVo%*SG6Y9=qy_{Ye|vCt)|1+4@_4bP|p(*No=9p!rS85;wi!8!offe5Q#JEb7ZI@VL9@D{HrM*JtTl)i3Pbod!#! z17WXp3Z?Cj5wgY>h;g2&uMI4(q<41XUa-KljomoD%TSuUSi)_rawIr@)ETqCS*;BU z2(p6X5ue_UsGoN>&CC`ej9v0rx#~GI8>)-zmZo1jRNWGwbkKmdt}@@W+^%KSc5+{u zHqIMeh(k}X!X3ij6P)U^ifK!G7IV8_K+}%(eUE`LzB+qt_tWC2W)1+fDs!b55t@t=GnEjcP_39(CrLVxTh1|Z#? z#91uR&`Ce5zI&EUV;txc9!`Tg^4$}9bm=Qs9&ho;j8XWzPxAShjFRU~URl&R$wm3P z;xm3t<(pmE`mL5GU+qS$D4R{;6?8sp^VrvWZqaXR~-cW3XzMl;I=#nqB6*&qZ6>8}8I)flVk$hB$g!K5G-J_ogknEUTp6#? z^c`DX9C?QqBeJi4wA4;{GDF&?N|h#(=S@)koExIdtQ$9NdE%;6&6v`zC7oUc-n()E z2nejrJ*!fv`Piq5OJgOt>k_1@+%Mc-b@l;RCSOcM?I*jGn_*=7)@zib7vR-9br>RK zQE7}jpj*xD5;`>AM#tb88-se=BBO>X2&OgNeUI$ghB-5Bb#u#b9O#i8==ma2B@fsL z)fvrKpEs7kC^Wwk#wf1gm;wSPHXTt$Jtgh(@oFi{LTZQ8&biE`rp0vcP=_thNZ7fN zGF-@mj*1jpmu9tF(8f5?@(!p!R}=MXuFAk+%j3Pov5-L?9aAYd+JTg+M~#&!jDADJ zLHwF7Xx~6;L^$!SdadVcNB|2(e;~S4?}X%FTWc24jXUmw4GD5IK7t=TGd>%M1FWrrp{>u7!0P+ew!F_fZCBWFoUQ}vN%d<~wYzyuctwVz7D@N($ZYHQC~ zJ#J$m$m7%J=aT(c2v%*eUO4e$TD?n=FoxKv7S1$Fp|RxlyEvqQW1$OBre ztp}-gCtVqL;dgO|nMlovL(A3h1UJ$WY3sx$WWu>D z&b&IYh;_Pw8RQUzdb%-dvHx;=sF?>JdMG0beeJUGlC*yH?RZ*225(udQ^zQdf#vpN zKN?48yQNLFIeYB7icr+qj0oQXt*!N=7xrc+Ks_8O{&Vl$gm>t}HD>j)i_?2@#y?&$ z-uupe;4@e~{>5==QAAUHu{Vl+3KxGh6U9;A7Z20n2hXLO@aBBEW4UhP^q;vJ6;V$X zO@r+igL|}_!1iz@*Zft_L;jCaS{7nTT2gwiMYTAfhPiakG!bZt!}r~Qrq2;TfCkDw zVLvI*{zQk%UZm>t@7L+%2cc*h07f#np>_&61jPwuaR8Ryf&P>9?vENXU?Ybz+(7$Z zty6V&v(l%p;6FjmZ$FX~|DJs?a1D!`F>o#1du?OzccoqP0)U(b z!YG>alSNpZrkjKt_JTHdPT;QGFXZTY(SVH!|HD=D;lEmSoIE&FMZ;3R&3Mh9fBl%L zq8L3hrkc5;nOnHhyLfOWhW~da#@-&fOxvO_ClZ5PPu5C3;?c#gYdjYSDWcW)E|5ZRj^9Cp;9Z2j5w@H_(M2!=S(uVwLX8LU?Wj#$1Yg zBbYGzT05}s+-`G4n1|{rcld0F@lgWamuc2NT26l)xpFq&M-IS+wf_=1ASk{n^o&Az zZOea-8F2waPA>HM-LLegFp8aJGb-)B#F?7ky|;h=e{8eS0DXb2pEpvqF7gFG@(Pw+1NY`YaOF4X-W(`l^XN!Weh~<{V*PYKko*X_ zGEWx#Qnvvi7jOrvlIeGv0drL2PCyIf^yd}Z`UvW<=?Yi}1{6%wB8dXH1O7t97()T3 z3ZQTMt8kb9t8h1FIzyYdbE0%XSCi1k!!gUDoUr&EFjs?--=jWe70HO4vfK%fKaTs~ zLp%Uj@jOJjz~~{O`ANin2>3jI$_)Q4`Ucf3Gl# zxwSpf3#t%?jxX+i{u4(XTty(d3JxE8VeS5seeSXV2aH5VfCshRqZP=W6#Zw<9Wr?h z&?bAGLD&E5z>)N@8To$n{Heaf|Ns9v{)b=BNkYS*)a%<+C)kh`{C^ED{M*Q}2afnl ze*xEd^66 z&{pL2YCLFjFwt<$x%Eaggh1-*mjMm#;rN-DduA@K{r`(^qQ+MGel8U85d-}n=R%{@oTwg@ z6O1&FH{KtecsQ`ewA;W*2o6X+OqEgx%rJ5(PQ_&PZ@s8+)H3UIv>v2bLO6ZErAWPt z@gYOm=>#dOj%1k^7Iyo>gh?$h_G6Xf%n+R6752DQZDHRf#cfL+g{Ps}{)zZ0tXlW3 z2IY)c*~bfl=W2_8QdKB2cz%;O|D|r1{8!!X+U1YBog?0T-ELm0V=pI9#Wa{piqFIe z8Y~dR!}oq_dk@^|9?*^ z=Nwk)6)(P(>UgkQt~hkAc=zKpO-UT|6&_$sUP~QcT&@%*Ty7ilRmAM$r=4FLZl_*6 zV#?9S;g}%LT(qJ5Jisyz>B0!A`m$CZ7RTyU$!xrtPToJw)t(RZag-_+ZzZjqQNQn` zUJS++^jPw!%~5I-6AKu|p}31ZG?OGs!+cTIir+QUFe?(f3^c?~*d>xKBseWwnXe(& zpz5`Z7k%={*u|D-8iy{7`l&cz8_s9ZZWtmI^&~_}{g5Xw@xIf0oFST56cj$`duPJ= zY#`<<3)y>lLCvl?(^37`>ShO*{(1fW4o+=bjPDlxOl*@`iJzqCXrb{`+gXKomZ_`P zf~pRcrkK;eE$>`rXg`ZCY1NK7-_2zklq=+;7PCNQ=&7N=_tiRKXId4hTbRM+g`Hyj9SEA!N zv_rJ&PF3$TmKXG#PGlWTduoRw_v*uv6lQCT{pxAgd#iyzwCelDpjT%Y^$D?(IvwTL zX$nh&90ztmUH)gg)8+3EpoAyxPH(H;V85yPM5&$-FgA$5zslZhp}}m!dU)YP#Cf%G zKCx55TObp(Z@zgq%x7a0`II9kkH&|*gB+#laxFWt0lI|}QbMgQ`K74WBQ3En?IfY3 z7L+37nsNyeQJ?%=nfH9uhcYRZ7hg4{jh3>MmoeoBm>`dhj#!Pz$l|S(^fzrmF&kd5 zL$^Pzgaz3+$9`Dnq^ys2eo(1`3PDXTTRh9=gBF+l;3DA@vM(D=7wTcF&jSlQ92>O` z^Z4lAdO=0)ZsQ5xb1c(@hNTw^E?8}pEroJBZ!sTg<{7>XM_^bk6%i6*F0(>gGH-jq?TH?r?2v_f`aJ&b%C* zk!L!N+~)6&)cf=rdZ9--$nC??>6Vus%ylLSEPyKdoPWP*e)PV7wgX5sQRY2-1zh3* zPYe^^V85FXFM6mmBoQs|zeqGMfCZ&s6i?~h_qz)toFSnr-k%F-g#WgH*4B0f=Q01x zEc`$3BeeX#QjqUq ze?PU)y&kW#kL;vs%qJy_`t)y1W+e7MKpM!u97NCZc*2upe#>6EJb&eU|8?CAH#SG? z^XJ8@1@hl{0rNnd0ayY(fvuZ)dc#DPxUdN9o~Xbx_M7_|TlRLq##l@XoG7QePn1K$ z{#!ZE?XTNg(DVvY^tO%7-wJ;6I;Atpp*ZyBJ8yriLw{?1*gF!bxr zgi_jHww8ZdU`U0-fVb=D|8;>e%mw#gp*09i9mV;zoROH8;4c^i>coOKHrOZrhn}7f z(SZGbjd?Tr+Vvp*-!=haKlbU};wm-G6c@zn9=vbKIq@YzRW{|YD~Lt;YJrf@+8|z{a~d*{LO$7GBq_ODr)xk!TiXX z52)0~!MXOC?+r)FF!&?IST@??^xAYrzhQ6i1F@8Oq2mHd;5L%d7WFy2uiN)9lEqE| zRDNW=uc>jVQ>HdClP~O0^y?EUla7vbB{DJ?TA2G+ zN0+i6mE%oN@YZ(qTVCrtc8*>8qzu0WaV=ic$#E-od2JQW{poUSX2Xxr^Y)A9z%z95 zCTRrxT|4q{Q%C2E`CDz*4g96!@~h+W%j>><;;S{w*y^#E(jC1^EHxo80s$ISiI!DH!@lu_=WXGEp7o){0z|>+syH zpczv=!C0iECWP9SzOb%>CP-5*B$&dxxuC*~f7^81VPDOFMLNIMx#;87xI@yn&#w2KMmG`s#MAVF5=-HlqGk|H`^ycpODD0#D`6e@G#Azi&T zs|$oGMo;nPiKI7jPtnjQ4UQt+KIRZ76MvukF=xQ3(TD@ZlDb!C|$4>1ZF?8 zn}ka~SSg!e4~S%{Z6J7wA}Zccw51t$lF4(&V3O_h&LWYCSWQufBXhd6ya@ie#21Ay zB8fZ!t3-`~B%Rvq%r7}99)+qjv7Yc^GBjt%rbNhn@=Pq>jNW9uw-$)$=kZDkJlTAi zAKiCt(>FtR=uA``*yJc0p&aiB}% z#rj+xXG+5@9B=ft*lka&Aj4je_3(0B)swRgvWA)P8kgR%r|hH>A&cMLf{r|q88{QcaSG-{ z0nEt%cY2slJ?pu>Y@_zorzhJVMM_OX(47FzyXxFh*Yc<^3}@Jbn?j6 zaA=Gb>~jjNV8vSsFm|Q+_d!}=*;dC0E80{M3(F%bclBv-rw*`l0q0&|S!x;ZzgU6* zKnhM5tWfH;L@C$KioXRr3|<0CQ#e4|^y5%;s_4i0G{~$JUmS3?*+<;F+Jyi;%9(s25fhF3)r3DPJ#c1UjIC> z`XP0E&-a@r2jMf3xTz%i{XPNqcbwe$^y4A#-Wf>I%kjc>ZT`V_!01JEJ3GH61QWEA zQL$mA_m-#dZs;j0B{^u2CuzSkq|>Qn=Qj$JYFHw=ipZJ-3~dyoYn~Cv=WJ{sZvTr% zbL&b8-#f7ALa;mDBV_aJ8I&c*|285%|MQ3dUUR>`n-JjC^!JJBUq^{OPk!k4{)Ykq z&HVenWnH1L6IcFc$?m_CpLVQ5xT|a?oBzJ%Is?{REx$W_Tt7Q}zYtIRKoIWdlCA3$ z^yTuh<{9v-`~xb@Ls~Pl30T;G(A>`=-yHv_X_^sGP$-VwxNpioZ3U0Scxaz0zlXr#z@Zq7nh6ytNdbxrLhL#6&fIG41B+(1I z#A9*q=YyC2>UG`m{i9>=KQV89gP5>89{lo@{41LS>}3R35Ig?hNv8beWyJEh2eGw# z=n>d+760e+R4{-GeDwau;VD1ecS|rx0SizU0w}r1EoWpUwcdHt5bm&}U^N8RtNp+n7>omy0|2SOQF%`}SO7x~0EOc(W&$u}{L-UHUfw(E zy8kwc2G%u)P09a@P0o-1-X;f34c6aNe|L$AZKBJxf6NMikN&>)akDW=lEYoNOl+#wP6mY^m5b5`n}6TnU{Pqj(T~*+P8#!I zFOdkIfSYZIY=^9RM=xeLGW6c%psqf9HQOzY0P)@@7x7(yPMRzAX#~?0%P(=U$wuYVOEBbmvrWzVk;GvDSH*O(N{B(QAgS*t_@A zy<5I9?TIS-JGiXd%R@LQr-ey|tY=oV&gLMq05ub1Q1?m!$mwW)Ry%M~_h@3fWNLo= z9{vS=L#L|Maf%UY){3Dq=`}Vl0A_NA*bE1wXCztHx>nYK%Vj;kf%gJn`?&a zR6#4W6MvwF5V_auHU;loRn~N9T<=sFtdqYobl>q<+2&u2IBcPU`S=dWGiQWXg_{lN z>|%;htB#;z`GqQ>9e;5pzgx2R+oImIcbBN;*4id_I=!|tAyQ}MN_nSu)~m>>QZ&0P$=)v9a~DAtubpLk zPDjvRbbyDj8KXT!;P_NW0ly$(jn=B-jOU8Ge}#8;!fAP%cDMg@B11&ld9`>>xR`Y{ zf%ddk(SOFHA3%V!I?E2jn4eOfpFdYfxHGxFxxGq=Dq<|NCtnh2H)JwS@fZA zvJ9vgQGHTWm6-)d7cYf3$DD=wZ^;y0*d$e*2lbNy}&UUl8w9sYvC zK*8hrxP8Z?Msnoq0@$s5s+5nxh;C9e0HN@cpZb5;1)Bx#p{QLRBs(?L(h#dvd^**r zWTjy!a?l~%zu(6{`p08-8t?zRT`<3tv)J#7VLW&jj6i8CC3k>PO!&9ijs`s2`EZ8x zHm`zft+xNA*7{2^@#K3qrq&?o55B6-(feH@#RM1vCx1krO3#hIAb$xmH4B!k>>D*D zbNc)jIVz`*OC;1E+Nc%jGv3WSMYZj!OZ>6Kco_N5$0sQ#8^PJq&m}clB2!>QPoDqn zdKw@ZJ2`^cis3zrZoidPz$@UVvC8w;eGwiaa7|>ek!bLH8*8k5oOU(&tYG5qL8J}% ziWeQ&0h9fO;uHt|0?c0-_uU?%2|9k9?J3FvAB0f)<7J!CT?1n3>+mw~TZWv)i}Mc1NqVU(P}yAcjK-h`CJz zN=L$+8|-1Z7QI)`2)=-r`wF@c)_RI|Ddt4IAP2*+qzB!|aMY`(YOGmk4f4?DYJK-~ z_bree!y8#q#oj=Ui&YMwogPe9aGrS)_5&<6^*-m>Bi#$?Gb_`@kK$8SyVtD+{RGoa zEwZ!3UKNe4F&`)5x~_WLTPcsGRw}btSE~E>g}9G(F3<$GV8zo(-Czm4MLYc)#oiwr zkZ+Hy7e+nT#}G(BDG7~6FBQLum@+FVKlEeDHxs|6>9CHb|LB9q{2d0*BqAhBc!PZiXyIorlYNk5tO z@rw$8alq$qiTIF0bbaBF%XKqx1J3?v3{Ecy`Njl9Wax*HAEiq3`zHpEF`3+&igNS_ zwM;;$s~Ep#2n{o1S^KyCq`Ru3?)^cV%eXVkKXPX-o5_h2_7y1*H@mQ zxv5V|>t5e>yAw!}X5rTl3R4L2%obpiS0*ef$P;w$vp>l+kma3^ETwu3E@G1eEI!x> zH@*{+9O6y4_9+3fKboIUI%uxsCW5CNF8a2gFSwB{(ina<(T3HEX7Ke2WRgJY?L!jt zd|-!J)ubo_X{bfxgh)chM?W@D206|APG;R;C|&OM(91r`S>7u<9V?^MO|w_gY8Mvu zY;1AMLIZ&tjliCX(H=r?b~T6X4t~oUUy=8`3fX=C=v}%qe3ORusFK)hW~ZeBTOD*h zB->JWSE;&YR|H+(=r(%WyI>0&CxorzuUEAq2wNY`cq>syH#Fmr+_HvpE@-Ouca}3E zu?f3xX`Za+m3p2T=3RI1v2&aytmQS8GGMLdO;M@ewz5^1^&XD$-8h%DdD~H$Uo`H} zndOPiUf#!qz@)v zk+~8s4`dCvE{rraPfPZypPY}ha0s0(A^3QzyKjvK~$#)Kq+>WQ|SS8Bg)0 zx9|7bXElIb^DR;wTJvI~z~uo{V(IK<-X5j-9_|qBreNn5ikghP5}yubPyoL{xT0B- z`pb=KxBZZ@yAuw)gRQ0HI%eBi@qjz2++L^8m!rk|19u-Q&H-nYl!()o!EnV}#k%cw zu9&R4I%clfE79SK%cFUV;R<0VD)N`;3i}09dRC^jsPRbWVxzs_m7v+^NuaC2$ zXxXdjgMd10Eckd!%D-v;=&Ysh8Zc&V)t@;$H};Og*|pKqcV?NqcUHl_w)6jdGA)l7 z?G3%=nzAK0gsB5KtJWC?3gi1;al40ya%{9$>&>s?4{=^0x`XSmdTa0J_W9%_%fvN+~);x$8hJ~;UQ04D$vkK#X>xP`e1Wgqi;Y=8T42Fsn8!UQ6t{?OUm{2H64a&UBZClnmrIv}yI{XPBD=q&{>K5*kG3DnFRU-T z`Kwl9zJ6C^(WiVTt}OuDSO3)@EyVK58a*8%xf5_+Q0R$_pnOgVaS(G4QLi$++mRh^ z%!neKxHI@qyTZrR)BKJP!F$5cX(lY6YW`J8J_f*u2`n|V|8vzJ861)V4nux#_UWuT z9`dTrH-m@@{|@tM{0QE_qW~Zv@4x8(|8%bN2lWZC%+m!&68z74`M4V%gf5MlV*RUn z2`8sn^eYXr|FBlU^~_^cN3w!A`cGFq90>nVXbr*!0(N`Aj^9o7&#cSD&$Y`Bd{1NS zU!VZ&Tyg7(UbCr$0-h10@x$R;)iRIa8Dr+-|V(9-^J8^Gu1C=Z|iUpmOV9aseUS*FCSb zq`sRXx=h|w)`-Ib494vJ~RhwkMd1%~?eYj2q%mPB$4I>X}=0i(jnPSNNKmgPd)- zRvrsyA1(3t(lR<1-9VemMnO;&yTw9TDf8&B%e)Ngd(M`VX?WONie!N$Q%xWr9khK& z+vw$(9JJS^j*>4%vKyk;tJ}keSRIg@MEW=;Mo%##^;M&zf-wE-S{EkzC<0gbhcZ3Z zrzXT_64)4nQ%2R*HzSYpXs+PFD;51xH~#jmiBIkwSNcW0HD(_8k_0w*@3$d(D)S0f zFWp71*9UKt(vZU(AJ*4uolsY7=H4}538ZWa^R8*4Slq@|@j{~($WD&Qu^JVtVh0s8 zOhEzcy+S(;%>pXT_=p?y)px;mr&@4(8;^q=ke|o7FL1~CkRqvjogMGTBe_*&j2+dd z?l0*b52X|++|fQ6%@b?_+rd{p5jvd^j^yni#gFLe3cdOwe}Ra6)N?8wt}X8dOsI4y{2PWS#L3Z9M!z8N0LJk%O-eHs#Hcj(#_FH zF;h82W~!&6$YuN89gerb-3|WsA(s3#-wtqA)9OxiOhH2JCUUSW!D#qwVp#Ii8x^qq zo3(RqrT6M9>%(~&^e2W4xyk+?VO%~eR|VybgoS9$jnMNn&XV7{?B%<_@o7 zCkNw@XE$9SDA)h3MJ@cw+|r;PLjjMAoOkX)*Vc#cw>D4(bCjUz2BSuo_2}$IlBQ;u zp{H(dtxvF?rWMywNpKxr&&_&^^E;`QRVrWgfr`v(4^EnAlFkq;=9Dpcc%;W()HRI` ztXa&x?%O-4G=sr?rg7WOu+!G((sY{Wv3&S zH;+GVRSLF|wZM1547Kz*sFb~j)GC2coo)D*MAG&k&wx^iH9!LC>ATd(kv@0KW_$r1YIf)Y# zF{hKHP+9eey>@Im%Y#3Q4VV}!Jf;lO(6x53hz!YEW)vZQ#UOu}hp#&y_&HfhU(v+D zp|UQiF@ta=N%Lu%ScyT&iSni?hTR=US?rl{l8B>p2F4tr5j%2<&k<|PdVC$e?NRt) zpOfy!x8jYX?H`Da?I>wc3=52QP)SaD8U-e?EXETtk42iuSFI96vVxkaNoppi2{ey6 zb2xp4KQeR*peeyoxvk5n`}$HK3_LRQTeZxC_5IeLEq8LHPpdsd$Mi9$0`e#O)I?U! zQ*zbSZ`s6*TbnuM62lQH^=A;BPKfdDl(sN!jd1&@j*xQ=80QafA)dKWL$toa3A;AH(0} z)eBmLnP-YIhpC&IVsDj6oYPw4{HbDY(rWk1t+e!Mx5CnSE<#VlMxRNZTCD_#7p;jh z7OAgEr?*`SlL}nhR%ftV9x-Z^nN?Qh?$Hp&nGhkLsmEB+^pG=dIl7no7KA$>#iV=B2_HigcCYF`7^7mD(c#~gv(weEFP^RXd={{Oih}obG4Wkws=7_i z5Ts82&up?@b)A99znma0F=nl7KdZOB9M3ebD=$5rrG2fn{~#r|JLNm1)>ixhv8b|yIc z-rDB!<(Km3>>bf=`n~t!@5&!H7akU{@<+@_=yOuz@2?f^hXLY0}rZ*FqCZ)(< z-x+Yt1US z$1y3D=5`w$>OUMR*mbp1JX#mpenZfFwSp|%t|0cES2mQ$8ja22m`SiVY@{iZ$V8tg*;@Ql$DLG%DtD63HkBBhDdhW%BaxfoIkqzywp za|2&@y?3GZ6M0f__rz&kLB=SkU5?*{g?20;QqlorOM(;N9tI^Pn-L9S<3j2EV(!-h zLDCrIjff|&|IXY;cyOr%{$9zmFv(XDfrba&a@az2{VeH90TKYp`racDB=XM?P~ZbN zY4-W9@-+*J0TUf7*hKdUFwtS&5xM|rlJ}7XKZKocS;9W~?Uf9>Lb5@7M^=T-39bOb1jcZs^Ph0MeWt@JosTZoCp4RIBzIE4la@WTE00Cd6KAOutj#z~ZUSWc8<%?*E6u0`B>JhGf5u#`!6|eJptCmS(qnOb)3ztNSYS zs{5al1z6C>Mah8pKwJ(m9pMNcjlJ)9)=Uq&5$MtY)G+^9N(X5)%Ljg_Tu;@S)pY@= zu-Wi29NAtbn+($ZsF?Hvw}8{)Y^?QK^9Uzz-?m z`ucL~%%U`oLpf+Lo!|$@ycigQ;{Jbq0Tzf&HZRCG@PQ~xhE@=$@5fk>tcMEyIUKg5 zd(ChGzQ&l%cBv7XvZxG3nXWwljF00Rg%G~tArJW1L&B0Ojh#>T`X=4=^~SwD}WfqE_L8C@9buEC+19V zb~|{~QKcKqfs|rrY1S%0b_JAG-Kf*yP2A;XGaFEw{mjSM4=x4N zj)#=Z35K4gNP@04j*&>~ES1^nC}Mce23_xjizTbCFbkgCJ#E+cf&|iK()$WGs1o?S z+h(0vH_+xHnWdxP?o~Wq>-E#e%VX7$>dFgQN70yXgUWG|(bo^Bg5NJuKi2w_bjcqZU1QLIC-1k&35FWZjc`zy%@ec(dxqWZX0`^ zd1{R>ejHI@EB;#n#`hMckbK<~(GIXi7tFq#Y33PC(|&Qobr!VNOTsHNsZ9}wPgx|J z8>irFYN$fsP3Qujd}z^xHWOPAv%^XQq^s|_{HB_J5prRiXbrKs9K~)CenSaQHyFRz~z+c1Q?6V$Um_0~z=W`yi z`Y0&c9qV{~!JD$5cKtNH!wqk%A+3;NkOc>szN(*6^|^*F=RE8KtZA4ICdgD+xd*#y)K$;{4>?(^q&RHQHLmCK%!eUJb53lWYVCv zOqa;m^<}N&iE|QZ;^dyJKhB;91Mmf}^L0}{>Cl2Z^zOF^(I)LGl+|Ks$Ex#tjaNlK z)@gchV7n`qd)`4c?Z{N|{1uuXNPQt8XnAi*;L6%;Era)w*j9J_Q#juO1k#Ffkowj7 zSyKhN)JD%u!ZqN!NIDW?H5Fcvg58!Y2t5lpUH?X+6xKCbaQSv<(&2)Cs|)VS>^AZ! zdG^hwZIvECOgc@HFtdq2UP)fp3ZN+5rfZA2s}>a|(Z6LN*6C_}AmAv=$erDNQ%=@J z=bqSN$5F547a{H)y3%KsJ6-e5vg)I@q2_^{9nz#tGRKEHKfs)=k5re!DaUQPC%xW!Dm-X6cKXb{|kPGHwnQ zw@KSEuTl}8r&#;hnYx4>Uk?S<@J4)CyW!PrpTDX!ao_uNGpP~Qb`d7Bes!M6gEI{0 zeo6F=hmz_x!ZP`?fj>CKI_^}42ruGtK8t4qcU_!;jrIu92@aUbM-Jbbc^~KueG_*U1=$s-G`H>sXBc97d zS`xWAzj*;qUl1QAjE18XMTJ8J>!+x=ZMB?M#Fq|?6?6S(oO2f^H+?7&^U=1~B*(#O z9;q&`eW2gVl;ZP1^VK{0Wx&acYbX&SO(ol0+`P;L-FX~3NsnVW@sb&lH7Ip`d1xtu zyPR#EAkaqbWg=*s%KP~!wJF3}@Q~h@U@f{S>$0DQ<1NiR9zC35DVx9}{mix^H9c*e zUb_;GSbk5&OiQfe%ZQFD)ejEOU9IF6VskAH^Ou&ts0d?CdXXcisLcjI&t^8^D(qOk z?`*|Hc(a+Z&)Mn3?dl-45I^Nd^>S6KIMFdKLFeqbCn&q^?13JszY5OmlTSnBJgzYv zT`6df9g_OF^US5kD#tcPC3W(ecChi<-LyJ$E9=H2^OrRZx@*0St)}|@Dr@t1NVF7P z>InNNrx{Ny+z}%k{b02sR5*Pe6256NY$zRVweWOMUFnkboA|;6YR8z3?m9v}LP;{6 zO(ysxzKc}Mc34FNQe6l#KBV=$4uHNbZAutjQOrRx-t2r~U;Ncx%joN>BnW}~;AqFk z7V*IGu!vHl#@G$+le&|+e&b8FWXHQC_IG`f;UMS!@M)@t(*&LlID#u*kXC5Fa;({y zx!>7ClH0G{fP`pzD{oF3X;sW@HK++{6>bezQs%JgpXiO2oH?sr@AgMjA7AuikDTx% znqOhocVCL0tli9xgPvVx+lbFz(W{#wa4yyGXrAyXMVTQwIpb=v)*~T6d_-$!YIilf z9?Qq^6fnCp->U-Y&RUlcjxaOn*#N+01V~g<<2X`j_cn{Llc>*Zq3|tK9j=h8tT-oc zlQPx{B%o-ah_c!W4xEJad9p7WQnp3p7i&5KODz>ogSQ}0iUO8(W)LjL%c@E5-hr;J zx1N8G1$}vV3Cowl^G-tmXJT3@=NvDB={ha&D)^lF@nCyih1y)YtJ%4VX_m*hf;KgW z-`35f=)BbP=`8N5w$NyG%-zX0%Z4ty<>BMhPGb^ofNF@@vY+EHx80%@d-$_(#5;$UP?O4pQ4y_S_UfMiO(7&CvTbrz? zA6q)2y=c20&X7E?qXMSSz?N;fxzICa0}w&Gc2x)Mj1L0;`K~b6sj(jDw7nm4#92WD zWbHK*WjXcbX5z`tTDonEm!D>!?9btE^ayHlz;h=k$blvP0_MZsG8|IjVyXBNxP&Z5Hh3`bY&4yY6)iOys+gLkxw>K+(rYgzVFQR>>J`-K= zWj}7U&YeR_#1hV;kzaMcvJK|$N6P7)h5?=s&fK#7*kwjibW1w(KxWa#fc)gsvdeku z@=?Le$7RB;T{fnlPEBiSXLNxn6T?v^>8-qf=6e_?6he7N8A>-E(csHPzeFcPGN*lH zj4U}{B2S+4-kn`tv)#q~3Pp4#C|;ZTi5usm-X7LDM^37uC%EDZ$>=F{T3yNH?ZQTR zHok=<^q9BFTBL86t<_xK@xc}%6}Ev`ce?RiGOnp;aUCZH%%+IVs0liF0~A=?sK#}k zYEf?Wu$61ldu@zrR_a%(wx#E6C*jc7NHcqjJpCyAh-P8Tg*xVBCzN#i+v`HV?vB!) zFU2by&fIGg2drHD509YjwTWv_+|=8~9v)Xtug%bW^osu=Ns zPg2q`M7;kI;bviPFVNsq-glZP=3LUT_eI-vZ@;e2o2YJI^b^1fXOS~{p5Ge_b0>aS_dbO9BY~DNLu-Xd*lL&IHXY>W1#CK zCC^{CwCJ|@Y}R9Yf8v|RhqqPe_OPS>lKidIEn3_nuGSLTjPb4|9qa3gEtlE@X~p*m z!XMRAQr(t%MG_i@#&oV9VSLGVU5|(jvbmDvJQrs6eZ(^t0$-Qg5T(||10&5CZJzsF z3Uz|5=J|mQL6CvI-}k;q@+ph14myloh3Lag+naHkeY2omgk~NjPy7juW;RHNl%c~>7FL^C7Q;9%=ke0^O!wla zoo(+5FRx{r3x3dKH`P*0-d5VB-O?c&@(2aPslD9>blLVzM6ca;wF) zY){TzuQPPo#3!K~d)YadC;UO(OFM)&Bzz)NJPc_dlsb$fG}0+E zVgsv-8Ds{eK7>9bFJvF2Gn6Xy^}|ZUb(cUrh%pEj2$lz?5)S$|jn@*n#?(@#uw3Ws z=d*A~Cd|#^x6luh& zy;ti;>v@!vFb_+r-|u7vtS3H9$><~({lq5i!I^)KY2^#1|?0RR8(md|g~ zFcim~uH7&3V<*IsGZGEEaa%{bu}DNjEfd_3o4SpK6GyQlG5!MnN$wo?Ctx==IHqgN zQm7EKo|@DAk+K<1bAkYH z;rA_G+A$<#3geG9zq^9JIsWUD|C_JY{}Wih{zFh-e`))d3>C~TNCG*hnLna&nWBs{ zKRkW=`t+s$Y7#vgQ^x$Lpo;>g=a?Yovn!Sp$~h|fsk8o>rGK^&{W)F$xAV7W=}TMC zWr2>D{6z!*$l|3PWFm$Pk`bE2l5i1Z9>Tne=Xry_otnQL0JE!K^60GK%yZBao=y92 z=b@YFPsedv?lyHOFQ){@o8is%yKnKD)x5MHS6{z&j5%Mi(%-kkpZ+|{-$Tov%l-qf ze*f?IE%ST7_y0Xs_K_$Eml@_Pq%#B@+YB88m5X}`pMtZHvx?qx*T za%4joC&&@dTNDTzLxMk}*?K@myIhJI(EwDLnZz1k6b1EYnsN{w%gwLn?eZS&0<)fX z0W3L{+@OIwtZ|i{(IPcNZlfQ8_4hfGllQqNH=dR26Fs(x$K>v<;Ox58HvhKw;ce*- z8gw^xZtVLXozMR%?oXZXt-rtT_*VQEgFjfozc-%mC>wY|sCo1L?Q(zWDO--=@XbW~ Kk?lL7Q%lsA6BGsj literal 129051 zcma&MWl$Z_+BAv=2(obq?iOGpL4vzGB)Ge~%SM8`y99S9xVyW%ySwg>bIyDJ-!(N= zQ}fiUA2X|0cRxL{f+{kCLL_XAOeC^`Dhwv(R>t%s3Re0~CbkaNTqFv@s*-Z-Kj=w> z9gOvzjEzWaZMaCp9Lz}s?Hov0m`Rv_a4|D+v9Xb`FfntG{Qn%qu@L_okdm^1&#RCa z2ne@~Gj&}v0#V%THSOCfiXbYBVxXw^RkxG|IKQ}hQD=;p?f!@ol2qZ)TadYgWW0(X&@1+&<$fPZ~0S5j!CZ_d7gWs~i;NorR377mQBP>ez;coeJ z86&!KLXP3`-z}vbvJ=BS$htq);bg)09*iu^^#N!B<(USuE3skKd75@|!a|H&27$RI z?-$x{TXWPe&{DcAO&>?_X5Ud}E)_|2^+5-OXP!B!wSB#OR8cFPzPuTYinC8hH3*R@ zrs%6j^zcblMLe|rr8(`DtlGS_n+}(dq&q^Yuo8_S)%xP2ps=hxrlgc#J%+KOdH0)lk%}+;(9w!I z-0j~D_j0ukdW;b1-08;hrPH6yc|o|WN?g)Ts;6jwFvXK|w=Mif_*NrKC;8K*zb(9v z>XmFa7~4zw>Krb@me$3F&c}+zN2+soruT_sW#0VFn7~NOD8p#Yh`?COIKz1DKZW2o zpMLO%BKKzc%jF|#Ji!i$_M5`%Rzv59+-B=`_u3zUg`!OgRW=t(|SoCJ{L5 zK#E&nBFZy!x47XpMW#m{Qs!5n`pWd>ue)X|q16dt$Iw&Vi{tVQT+|!Ig~9_|H|!U=wwJzF(HTpVEDZNXIuAbg1yl{tyYOs;SAtcVU)Try%)WmrrsykC8AW^SaHB6PL3!3`8u-yiq%6zMbf;=#=EZet^Rm~Rqq z!Q>~&zug&V>8ctrJT489=T4@kydLQGzQ8fsf450Z)b^XDG-BKzmb%LK*FGZA{F8#I z4snB(J=j&@MtO|^VWi(_(HQ;P0xA%jYTo`AzsC8g2S56mszLUB3)`KNOkI_15< z!|LhzeY=oW+mDz2iO2k1DXqs_ogX7M&(@)iK#%L?^R17=R3p>Peo|6hBkMR$pZE1* z5Bbs!`chTD6JEoCflAGOsPRWnuXZg$sA*nXEq_9rV#W#Ar}MILq#6sC`koSjRPmGJ zEt8wY$0}WIP1cL{+rI2ze(?CycA#+MW#)UIn!C|Xwr>2X7`M+o?Sq~A-hAja*Q?WM z@}r=sJLNU@A>H1(G|1^;G!x9pi#12?kmcr*N*_;KW4O{!`;H5LMrVFu_>rY?zMCO` z>Oz^U>bky|x?+zL(=rK|=~$>SoE{$9}`rGUYBC&$vhKyq}UogP1KI25fWk|=`j6et7&Z;&xD9=`Yw7jA>6 za@_Hf`d+d2E`tz7I_?``qgZqs^{^`o5#`MNTRLSin# zI)7a)ZoHs*`Q`XDp>{*#f%V!kcufSwHiWn%qrqv>(N7wQu(zTxXr4{IO~9s;e|-`X z9Kv!|;Bc^=)o3?qx@}{RWFAj(g2R;^k6oE7j6I<5Yi6~T;=`WhXZW%l;#F#Nl-SQ< za#hmqm+{E|Y7KtBS}m9cq44QEe@qr!7P{~D0Qni-uNs=X@8^NZVMDB3B$LI;B`Pg9 zZ@g(YvIj?h7rnBhdk?HC!modcu*6q8czh zZr)t_)4|xgF@|LY!AL}6<1jOsh$`yfwP%alvZ72P|9)k>B}zJJlig}})&41haKg2k9j^>bvp1hss*@vlvo`{u=H;WN%+2fc};4rP@A#oMtLbI{ZtN{@PF! z{>w9s$1mdUq6L1#Yg#VeQOv_iG#onY30i65hL8IU@9f%#U-iLWxEP8O7qi%%x#W<| zW_Ej0rn3%v^V74~6HfA=PEwWF4TXEhfa-VIy@V=P>$ZQ4FUX$z$LY>;As#{h`t7Lb zGY}ZEi-3~-XY7XCV@5~IG8fW==8c2i9qw+**c%B0;dkrB09E+Qj6l~)psoY8)HYGb zrsz#r2cS$BirgL%{mi<%aG>m9Nc9I_%BJTA@2SyE2TrR_r5q=%oMLnBjbMbf7_4bu z7cF@*-qxIvYNc)A$h>gpXfsv8a-rJMn-O1`VzQ}BI@S6&iPM{MgZK?SH1<<}EcFbI zpW!8{h9bY!Tl5yeiyA3z1ow-N7>+{JHdDl_Gr_9H4hwe4aScRGeuE=7c#8S zTdu_t=F};(d~NMG%Z2R(x@>uqbp`aT0YijT>>p3A?-eG-)Bv0 z?W&M-lP1N@H!sJzzoPp&7iOq$H#l5Xs=0;f1VAQ<8S&W_^sUS3%_aVX;@cI-w{Fj` z!z#GxOs?A$wd@RseibF|k0EDjMRUYK%Wce*y}mv3>F!Z=TJefdxkW?D5EfiZrq>eP z)O*##@PpWZ9D4MlkMj%8Q;^nPA);kO+0hf!M^|?q6`?>s+j$sj5!ZN9a)~HjJvIby zzQz?bKKkgqzeU#rpBGPf9|ly#Po%lT));1Vn>fyZJV_rt)beJa?ly7LV`zp~x)ueH zAf--Yy6Y$#b*6syw!Zh5cWW@t`>_5S?m%>JU$pioUKp|XQC9PvqJTbci2vO)Q>4u> z1aSwc*=ZO4F$+nrs{A!mjP@2Y?61gY;9Y_%1R(abT*#&UO2TE{cPrLfh zA23%z-kxy0IOpM{Kc4@+xP<^7h2DwUYZ>0DDeX8@NLyvZ!=Tmf)^Zin5&#f%IJ&I6x_L=J3hPfldOtwbZH-ISto1N(+y*1c}m_zsh_<;yCl*$>s8^5B0 zcM_C$hYOPlG+&x^NGL_8LpNBYfKhCj%Fe$7c@mt8b~i-r?T{$_a;!`~p4=jMv*(

Kp($-| z$-1U|^JG5sV26=egKLS2{SVrFo$zKuh@S;NJwH zCjz0nDu{%!tU*R?JNSSr1{o~ zMreA^`6DQ?j?1pV)qLCKF5vr#0HU2Lp;^uFWHeWG=M^u+-i4>YG@cw3mgY~E{dSnnW8kcGIvElYyOYUv+>)Jl}clz7g70A0A+{N1o?QqTC zbvIU{JHG8+xbJ)?z5M7ZlZQ9~Mzu=@3$s5zZ-WEC?O+h}e*lWE_c@?<{NKjf;talg z;Uigvq#JrLu7wEge>h{XQC{RewfaaLh5vUBa+?BQ$b=+4BLcLT zgp`BMH%vx{g0TF8F57wXjRrxghaN?X8r;Mm6 zU8RsNs$W>mx9K7Fax8^zSp?PLkYbieP_>j2Qj?>`s>UQm;{Zdz3Hsr&$$;xj zRu)I4Fr{rTv%79TLqS0~69+PhaA^ZcvZW6_y?+727#NdQNX6SyWpDCP+y+uCN`4!7 z)eZumd~wsXxhtrMqQ-<&>Cgog{;{oyV&=D=$fSXSB*E?bt)IZ;OA(WN%OUtrlqwGK z`dHm&mZOk_{7bC&X+1k1RiNkt!h;UL=3X8z=FN7Psp+PZ68pWE9DEva01E1!1%!|& z5i^{C)-tAPdJkz&`C}^h7lZJ_8#1A^WG`kXHZ)=wTEf!Etz=T)1?@PL*4V$+Q zAv*#oba0iE3cb^6gpIRDK~;26c#zmN_Se+iPXDE1$Z`|^jL`7wC``}gl6R9V0HVo{!E|Il&tm1p;P>$c*xFtJVIF=A)g|9wrmI zulDwrCissyKT*!*xNhB=eg%2&P&MU7B3zv8_M5@;?mS?mYB8JLbYo&#de}LuZSF+A zY?3%edajF0KlUB61$Xn;LlOD4(X+Md9_=t(Gh>j`S4w57OE!hDuVOqm5RJt-T2*U} z(FH=@5qMwbzsI)+br%N-?jzINxpxYx>s-7SA2wq;M|rtuwbR_ctfvB63nz6HqJ}I8 zJ09w4Ej!$5$-x0PE3nqHn&9#8in}bhIN!oUWaQ87DND~NP$&0CJc_1w7S0X&m2KbU z`VGMNs`3I_mIUt6M$Gz6lQxj2>P75G@%Vk132GAG6_VHxFhh({BMp9EbJKsY>%NgB z7gK#7*h8Af;aBjWQ;h=sW5d(Q5Z`uVrje1q58zP@B)&uVKSs!5c__U=ae)Y z%`pkx@#nd7qzJC|H_1xz$YAfr>&I=>Xc=x;lx5&!-L>u)umaUQp)lOSTiIGVk&owY zlJrPy9_anydU$fQ=}TDU`U6C(4oL4kG32r_e~%0ssf_Bdr^6NvI$g~Uqq&xmrY(eU zB+&_(s4zl#{euT)A5;eflRTc|e`9jr=T%M9&-Z@>aMdsZnlGCK= z%uI8mfogdwUH3@kb=G*?{icQqjOQ^7*9aPr%72**7Sky3LL;(%!G_&?a%QK<$^dqf zXf`Le#uEnio_LC2Xz!))43w9HLuf7v7!{B~FQwkXER*kyI8k+YTv zRK(S;%gmg%$3NA|rn!j=kJLXrP*QmJysg`4WTaxae!;(#1WR||9ZP@U-N-=T>Hn3AU8ylZ zAZO3iEg_549U%+jU8oU`58W?)tuyw!>K~o;I_B%QdLF-1*TMH|^0$q2Zmjc9pyqrq zkQnNJo5z18XI4I&b$`;`9`rPslxFeLLr!k6Y$PUtq2fXCd!SS8GKC>~-RVWX^+|sK zYs{8ycNIK;15#5o1`B)sl4WF01P>qf41`Q}RINZd?gUh&W1=ZEa) z&NDd-h^-cU2!QpedBM8V@?ZVrza|5gf^|XSX2{e`@-ct>bR?9peQW;2nh~WWC8W>^ z^Ko-UN?>k7q~perhSt_lX&eehsa7CYRr@8Y_F6ni6jd>Bp|(+6-$ZbeA@pgiTYGv2W!pmgAY=O=3Da*I zX-O5YaNf?UcSY+&_?+#`TBRQ5X1%;a3nN{!ohg%iwGZK|cg9HRbo>H}#3mxrQJ^E_s_)vaHqC zj%V^ZC%qh@CvxY-@}T~W>}wAixm?F@nBWTZ;Fxd5tNqv{VLBt2$}It|ATCfh+b_nI7yBPT2dR zZ~PFDbLCzPdvH4?bQ-DYU2sg=lkgGjhw#acK`$!ol-< zcE>Gz<}i`zI-d$OaQ~Ib_(Y&>=R}%^7+!=Sek#{?sH5%vbJ5v4@wMbw$ilpzf8`%T z3zN>@mYBh^6DR$dX;^Wbu}j1({zpyXtwbp|UEE3q?V;UY&MkIqd5E^BQnP`gG{ZK^+uiHIy({RA9bVVVC#S|2t&tl{!s}Iw z168qr^iH)Ma7y$7Cj}W2U7QF@XPG||mIMXt5iZ6bSl;&XM}Bwv>Tocm^xL@-}J z{1B*JhIR?exzLZS?T#!~44fA3)~Mc{iGb0)MOZ2Ua~HnxiRMnH3t;2PN3EPCIQeyS z3$t|SRhnDp*W*U4Lx*_jb$f34W$e&p+Wqt7>IbjTZ57!i@Z9b5Pt%8)HK$QFGlLC_HSLeh@Vi)4g{P?`ai@F5Oxe69Mvi^; zZ0UTWg}Y`UV2`XA4y!FhM+B9JZf89J?mib=@tPQfDuo6E5Cu+9aNDzJr#X?c{UOA4 z=}gT8+HSNx8b8iMLoiP32zxS|{~}q%Zsnx7J9A?zc4ThFn<5p@@k3WkF}l644~Ffq z0CaHqRdx4YW0)z-vpN5Wl6Pt1X@$v3gK}YT9<*dNGi=%*#Hk8A)1X`KxBFVMM8VDu zL&Wb=!~VpaT64OW`~2M6-G7$RQo{C5MHa>VsUjA{t&FHddGyVCykNLPNUR*z3dqUz zEq|U78CE)LB>AZfC7lJpnD}%8GDj3gKCW&ok%u0?_hO4tv9_f+s#8^%F7-X&BDX4Q z>{Jn+!@BwQDVM)D%y0#{m)G8-F}d=n1iZPK6~3?aLoW^%>3o0eBz&tr81~#>O!X7C zT;NvGQZbXlb;veqYs|bCF?!SG<&`vQ{?LUT^Vs&ZP*pbJv37B#A%lc&@ zm+2dX7JOoc0@tEgYcrO(dE>4+-5T@S>T_rE^4#8FTck^e|GQpHL#|WNgy$}ZVXqCD zs4bWG?74^!JlInoEojiy6v;e1!JP(cEm4ik$&SFnmZhUdVO&a|V!-tSH-k8%BbH~bL3$8VOm_o>XGAkIkg@2V9l*(e~mh_i|j|bWvjiU?fTEc$H&Ua zzH_v-D=H*v4A+y%L@*b6vGP0Y11s5cvc7440dJf7 zWhC*e%1mKq&R|N;^X7>RXObVn^x1g&4~&6hdCHjh<^kmLsDY*~D~t4oCWcg@vk`Mm z&G%FGA2mOjgOs)K5i{{^b)JDQMT#DbBB>rN95aL(kuI z65G91DaWqclWVI2y)JVE^%8eIgOjzf9yg}T;Wo*0ZZ^J4JrkwMfGl2k-Yo<>#ZL;} znZ|Bx1thw_e-Zmve%ZI6qBxOG1$t@Y{^WYrAI-xt{)-r3T#8t$ja7u$>&FPw5>thE zT((+-H_5MR;qp;9a-~-Dk;f=9s)A$GN+*XiqprQQU*~fyj^qE5@9M*@fXU2soxbR5 zXsWvLb}jSG2h?G1`RKZTc*D){@A5fcq(hAS*tC(wotOLw#O&M?ESPzfJ%=!BtU-U3D zVXAIwd>93BjBbW{TxvGlF1M-CK|W?d&-0YoALv1U|BSIckr?dczBrNU_wLkRcI4B& z(3(xP%sD~dLv&-ZQ{fyqnXh{S3yJ$CM}Z@-RIR0Rn18sD;8S|Le0jlW4*YOwe5m|C z$=QB#({@7T^ZP=AJoNMhWC34EJ~p;aMPZ}QJ+rklEq<~w*N zPx4l8&y&znlfk+F^jr7tt;}#^(vXWt!YJMsnK`68D7w`_iE|(`ib=*;`p?4%K{C~? zbYi2S(+*G?az~(-R!y&N*3u-5KRwF6kn{W`XJ=?w zDI$^(^Y)=EnyV*8ANE$v0dQ?v5_F>k3GeV$7kDoFLcM0q5Z^yJ;J+-8Drou10)x~w zk&#m~JEDjdFa->l<)SL}F>^_uG_X=XBSi5@14e1%pEO{O57-fz0l+04Rm$U}Itdvclj!?5LJQ<7HR!&Fh)Zx~g9{*B=kY)4e+h(UHj$aUp&{KzP-+ znpNesf63RZC?TxBWQs0lOVjB0AfP*{C6LoK_2K&Z1c}YRcHsuu$`wvHtE7@-K*}?I z1_$e@O7x1?y&>Bgd`$hZ*z(Zr`T9c2Ayw%H(#GdqY_r|)yq+06Y_!?9)i^Y~AH{z> z#XL}^$&O5Vt|m$oF;pY>(#RZ}EZ-VT9gG&fQkE7kcvt#6J+^Jn&mOB0G)@qm#4y1;AUK@jH$j zPKtcIF`rCu?BB>RSemC+=#kN2he1{647Hk{`i^Aj7@JuS7pb5o6|@Z8GCR3)EZuo~ zD4C@U2zF|oEdX`p2JcP7@jw|8bv?sgpIxA%LB&&P6h_t$>ZHcxflzV1+l(B`B(-FG z1w|o+Fys31SXoD-c8|u&#`vtCWA@V9lYuys*p+9xH&m+onPu77?VGn(!QUJ@Bi-M^ zuB#7mq~9u^&7y^KyJDi4B{w;YkWXUt2<4gH0;ozb(iF9gl_gz3sSCr6U_#3&jm zkVoE^f~_X%7(-&XgDLPn<*y*Eqx08T8l`};bjM1pfe^?|9)sVZcF8tegP`E$_@YM z{^biqX}P^T%4=i}`VS4ahzFwbSRZ7xSr3~|(~4+ZiSU){kkX~B*XmIC9=ySI=6o?E z%7FJN6B*6q$})+du{{_Hru$d#Be4O>@IxB4sG=FtEILh|NbCjX8C-jl%W?fq$!b%z zUNNZB1PP;5@z0*3z*RgDjMp8d|FdxDnyF*r%$xm{4(?Sdrkyx#xsANj7LWy|aQ;$6 z{K2LF>kWf-fZ z`!NimofFdV_k$Yv>hW`bwd7;w=W2W@{{*$JP6HG$C|;s4QBQCFpa@l`9M-0}W$Q%f zALE*r!;$#xx}-UX4L?O)Rr@Nrm@%YnL=J~aOWV$wv;wgTe^qYsGAlXBY=t?b zP~a#Ug#XU}G^&Loz|((f=&avzg^pQ;=u{C`b^@a^&y=wH?d(Ksx}`?LJN)$guj`v; zD{6apl~A5$_M{{~@!Jd2R;v9RzRA!#JJ(agt^REhqF1!Lxx7GbPqiPjBtHihAzq9g zv|Tw`KJ6zs6_nzaO}_T$VE^S-9SczYaQ*sh+VrY6Wx7=ii80PA@oQ{rnGu{?x!aAH zNeBn%eR~iVP1^j53KO{O&d{nj*|}dc-1Gjg?TQDIC3p2SWkSH>p^J%qrx0a-?1+hs zIX`fzF9t;tNv)0OFvL`12-tftwSjWkp=SFOMi%d~kEcBVUjhE@*f;k}CdA;(Qt=0F zAwQO&$qC-?8Uld5pSiiN{u+@inajS7rY7Q|b+NuRgQ&E{5`l< z*H;IxT&fMgL4BfnA9BlY^N2i6pZG+wmEN52u$nw6w`8`j*as(d`$4wk-WOH|Tf!ACH z!9rXLjdl(u*I9SfF4t=Xu8uQ#Cop2tlVL9t!-sG8|20?!M!pb`BnJ>Xdv9%VZ!=`% zd?c;VACG78S+3Vh_~K_PWaS3=JuT+}s96!gs0tdtbYgcJalNvL5SZ2ALxlGNaF z-l3Oe_@>W3I?*#ROakFk&dyLh9OPq2ZZljTaGZX4a*}r8`?w4p1MTpnG;jpS(6z&F zunq?mi?XcuX#PJ<<^zq|3fW8h16Y@jOBX%%#V=+oE<=UFN5IG4MAF2ENQ($v)@~~! zUR@z36%NOVo@QuRMh?c@UXorCW)&wx9hM_5<;hqWQT|gy^0NZ=6k>efpkA7%?gF0N zpGBLyjD9Dk`P&6ULOSA3jrkoT>U9x==#h%Aiy-<&7kRy7{(<~>7ZFd(ZFl6)ER|9o zzUX!u*-kZ_eFV;AKJ-0>e=aeSj=DNcMFT054z##e_~-EdwBdu^>VH&sARx_+56;~H z`kzyA8aq?IF}?RA@25lCOBzGcpPNt|6bRgk2`c&sS}01ISTGAah?&SqDbmpdVB+Lc znNl5et;~JWpD(wWP85%C z0y%ZzOaSeCsEt^H+1~l^7bw_H>JBJU7 zRVIpAiPAI5X(MQE-0_}ByfKB=h-yNLbLa~c+lP;EA=x5IOQuGMv5yFwet?l30SH~_ ziL%1=xlT+D0}V(f2zkt21mEJ`?(Q;FLJXM+rj}Tzqpmj|ln{r%eC858*{mO2|&gjZ~2|5-b68 z&hOQptKSQk@sTfGts240cxW_~pc%frtKryT?>bsKIQT$n{xp!lTi8fkZXbP0Rm2yg zwgffT*my9Bejy9zXy9j}@jqQl;CA7vd-BHR>2kZ-6}O$>jY2pA%l8B9J8M*+oI*|Z ziY(DAP~IA(-E5~UC^&&@j;D9qZQma`s%7B(adK)54 z>DflEV@_Gzpuz&UQw733dzskg$Mqp!T(ZRN2UHdRmW;jw7AonoLRtkVl|7m+5fF=Bi8 zQ{%SJ;ru&i))lsU?hpn-R!YlbnUzQ?PQfT(a+6T~>0Mvjo$Owjzr?ops*mgei$GqB z=0+rz8l6Y~3`qX1@2zDIBmCfA=_RoJZwEJaP1Tm$j*>q$U()^nhWwwzTNw4ap}00k zOiGA+JM>S$^z+otx&KEP^ZXohcibj+1xGFpK8%OCz6^kPIB%5RtPf}}j*qv-#T$3u zgke)REb!agc%9y?q8`(d=k$HCP^Zv(LLY<5Aqn;J5s}JpOIf&edIUrgk4$cYeeo!` z7xCa)pDt_rvUeVOJ8TG%PxO}7A+eUPoc}#!Sy|s^nm_y?gjqg^6A#k~-okK*zfE(% znAq=+-T&pSrKOeuLooZ~C?h67*-iBb}FpxN2=Zvc>}LLK=KoeEH*ZU`KP9QadDUqKBmNfDx?t-R#KmzJf&se$M!%s zd_IHn>QoH3Ei_h1jXtLST8jC)S`9bY%gcg(mq0|>)KeAE&mCC*e%i?Bf1g!eztr6n zb6n&mzH?m{@7XwSrMk0d@eZu*XCdyNRy%?1Bm#&3XI1PIKC&JXg8yeqRdppW1#z=^ z&!YoPZ0Cia74k`pR=~Nutogx0vK27fX{)QZREI7}>&-X*U8sV&!9-+XUp;7%{Qcp{ z{Eq-i^3Mu!fP3`V-&4{GsEVu`6Kst-7w)QN4ba4Oote)apT}*wEhdET4m{9NfSJbi z3YjXhFX#MA?!Q?^(Cv&AgOSrPXQ*?DH*p`rHx3MZMG+)Fe3AkEV&@`zr0tM`qSe(L zql`q4**=MYwLUqC?LVN3BQuW>7OM1=F=Li&NqeqJ%-xPuzUb&w*2^Mvoy18 z70ZY?@Es3r;e3Mk-n#YF)#;+5LcJC8;2&`UQtQ_vnCD|y!gjx|y94{0fYkzbv|AXn znS@E^Q$M?dX!5?3f3n2|U?RaEK@q5zxGbcRkb_lqMAstPx1%+L+P^T$BiI4~$9NSB zfI8!d>RVl7YHJJ(Dd#eW2AeJ>d^-QLP_Bs31wwR~x)zT(2WM5NYmJnO(vkDG zT)aMs0ZAddyv3H#xbwHs+q$KBdHtk^A3qu#+Aw8SI!PbN>^xg3JPR24VQ{{_5&$K= zJCG!-3*@vVw3M&oG=U_?utm7?PZZIE_VRHlDlrDuC!4fP?YATb2W&y?#;)JOIB{k! z@1zerfgOzYA4LaN#?>-u)UM~w(PNI!gZ5CVF|&ppKG!##)jmB{BRuYHIBti8)*(A3 zH(y;hrhH?~rBX-0G2(lU+5FL<)#wL6S@xkCFp99VEX(JW>EHV)!~MwMV(4|1p+$$i zeH_X%7xMf*k*Z=)CYeC)^tYdb%>&9uKQDeI=nni!r>qP_*??!MG^LK;?ynCi(ZoDv zmqwipZLmJU^XEKoRDD~%XoZ9<|jS`lLHH8V!7N4Fk(v?=+kS5Kfi? zB8xTWJ2tv6iRb=Ot_(K_NB?4Sxt>Vvxc%Vn2NgYCCeXWxJZo;y8Y}UxZqSBn?b>^B zhB*^tNF4+!ILkoc=;IID)J`Q5nI*nU5n zt7td2KRlI{UCzU)-vsdYBkq&15;2zCx{`Q9nEK;5+@EIe2I^$vcPkoPL*m>S9d12Qb=^aB{-#wCDL{xX=?!>Ba*WHjS52X z598-`n`>nqwqaSOmrcuw)Q2Ogvo+aB=dj&)y%LNL z2o9uf+a(IL1!#75?ef27jSgf?%)ubdfF|enxWf>P-E!3erJB$ly1TC=U-04))g2bS zHE#{8`sE#cYTjWabPjJ*Dg`X|yP()vK27Az5fqtue*bb$6N)6Bn#+2LeO7*NX9P!l zaF8(cF@m{V>~IW=d=<0cEof>iy(J7mF~ZMBGyr{_&TmWzSfV!3XYG4TT#8O4wU2sg z-4GBExywFRoiw?V5gFNVF>Yh?Jo#F*SRF@ z&u8Efi=Y3csk#04=2$a(FJ)0ibUdPUEwN_jU=8tZ@3zEoL)rOB zlze}SVT~Yx>EoQ$y5cWWH)qjVXHoL|?y~#2fukxwZhb~nxz;mdhf@jQ1Dnw)VC0r5 z>tNHE53&&&=RY&pK?(qHe1j1M6$S!TNUmOe&NRPo^~i+p2qkJ;f8GY*@MsnH1?B;w zHwk`%8?fw1S8|&aj8#{+h2T9dlNk@KUDuwHFO#E*#@fE6d49j(f4jYnKh*8}b@@Ky z*;x?+3b31+`1Te-&L~81KnbDvd=tk>%4G-D}^&oHQgp1@d3J< z&DXxvE$!S#Gh)t}V_sgA2eTHbfSSM`ZDNOWwkK;QP8p(31QBxNK1$#7fY9qrP)4{2 zzDu1^;T5ViUUl{jDT{SKxeqK2Z&Ylw7?PSoGX2SvkdTKXqB5H#5Ov@*?PZCVv^%s5 zWlw%Y5EL+>CZI6UbNaq(Rvaq1v~qi)dyqE@i=lv~Pw$ zs=j}-=Zuf1H`Qgce|D$*7nUOg1uS9=rvK>s9h1~IY9khAH8`y)6kK0flpQoN=^hGYB0g*3y4Shg46QX#w5PS5nlS?Z~5l%}0 zCk0dW+0PBz2Uk;q`-r$OZY*gE{qj9=N8*U^2$8h#c!*oPN*gbK(Ae^F-Z&9zh14A$ zvcB8=bWI*~na$F>5xVXB_APOJ&yk%SI9s%0~s}L{nT)%z#V=a`v3T z?qNVFhM=T;&@g*dKv0S*R4E~{;6zNb=6&*@Xq{!kFHtObU?6mT7^{4w&&< zze8Nh^NM%IqN`WaaHTc#l4=?RV+^j~M?Co76Q76;pWkNyl43XxW^_@8NNX}|sAHqL@yhix z#@6_M(*amOG9N-IEKy96YE}7}cz-kAukCIMDk^UfwqYc>+~ZcgPGfHR7`12sv*?S6 z$T$5?_~@_Dm@)b^lrZncU=JZDqqchKHgz`G+yXa#9!=KoOz1Sl*G*7rD+&RYj0ja*m0*C? zXc+jfVcR;>kG%uv?r*5b%~2|ED76{v!%#%~awD3tvJj@5P(DCi2Y<|JVRgOm0M+>5 z^t(%*JZDpP?8CD9sE0klh&DO44$s^*4VX7&kJM?Iu<0SqA5B!kF~{M1E}NsbPE|fU zc#WcTjmN-+g#GQhW<3MseO%CCO)|M35&lr;(0_7R@CGIQMs(3RapSqfUgekNfB$=o z&y0fICrm+j(5b6%$WK8|`_5f|P*Xz{+I;fR$}%T(M7gHrY{B-o-hI4Gq9~mlZHwJE z0;!2pE>*J5Yo2XKHY$XnCHXsUMraAF{2$hbGPq$wX#$R?Ag)Eo>P?W`%PE7;l8Jj1 zq2$PJ!3HALE8zK3uEY4>X^=v2g|5$G>2*7#D-o{FKn8n%kHw-H^4vf zU|2aB!elI?h;ma>qVaWytG{b6p9vKPBej-X%FmkD?(nF=Lw;3w>M!3jFdqI>Y6Qbl zCk+Os43yjokQlSs8&E!SbH2Q)(?6C7J$TN!@G}(jjwot~@7wkGX#E-t4R)7{XnjO@ z5mD! zeEFV$2-{K`h3MmaBy-uc=KS;--H~ei)uNedz-zvO`)^>Aaw+|3Um8C~8MJG>$nhqX*+qSf48oSE1>%fXW35^J_yg+tH7UN8> zp2!L&06j>}w$pn&u-*{`f9#%Tw0f4gX5r8eq9E06W_o9NXPKJtd1k;tY)x}pvem1e zE^dpFs)-K{YeT3UKeoSU6;$$Kze*`UdbMQzZO0!qQWF!IJ&ar|M@GXMHWbTD66t+| zSoq8-4_dxQ<)_e@IK$&bn4cL~is9e{3dKf*ZY^KGQ)RZDe z>X!wBCH;lJzpr0|^T?rl-#--*4x8%|sH^4(h0}wwFC?dBJQ!%nh@-`r(mZwha9blh zyP4S)7$f|j*mc={+aw54`9IYottGIJ&Hi-JJUxyVsDHcS42G)e9sVbBU5Ue2h|5)wFlrc$C3G|@yS34_1-9QDT`~mm z13iI20__j}CVWxugUI?k{GlRCigGoUaJK zAs1N$Ylot7aAk*~R%K#26AYaWHBR+Z!2wAxtn1DuMgskYbTaHNlTN}1H|dK^jjF`1af{%W&N}Rr%|Ry>imA`c^$a`# z`X4_g|2H=sq-L{L{>#?h06!yK5Q%vVz@!~2{D+MuEu0?am%zEa{`r?Fx4!EPJ1?z& zNXVT+xe6v)n;UvGFKq%|zYrSWK@Bj&-zAOKmukeZE@K#9I2BY4-FxBcvN5{KVavB% z0teA#=BmbJdEbSQhCE*Rb#7R;m}D4`cjk_GuCs!V zh0pY+Rr_R4vonaN8qa(&QYvQ~&TP}36jl}*9)668UL*CRT;*kA6(%v#G%C>DArICJyr?(UY5?rx-G=x&sd z?k?%>kS=M4?ijjZzVY_C-|v0a+P3v){l3mgxX#(ny^iW@B?siH@l3b<;ntdE8o@K2 z(KlzOxC}}lA>8}B&6gkJ*EaJiJP)>;z%Z*uu>BWKGD00F#PZob=iJq1>sSLaRqmp z&+}{9nA%~(_F?qO=Q=a|Be6n_`K#^hiGC11ojUk+93NzQ&Q}F<#U)o)b;a5u0hrr; z&vzyzr>~IMKfSa@-8T&O?KynD7uqWnfR2FaBN(K*(@jZI4uZ4ko}(8jv$bc&kSV2L zC{ji(!>ZI3L?5^WgpLZ$_63P#hvpN=e~qS)m=7`$dnFXp48(rv@WnOqyxE{TKZX)f zPRm@V@z!#$;cq1H8cD=uSMo1Nn)j8rAS-k(PuAnxi>U5r zy}ElF&OtErpWi@Zvwz%aoMh&~#t3ujftQkYUC*VPuxgu z?3X-}jC^rp+sE@@l-4%x+^u*PHKz?RWLo33frve(|CKfRMdZ8+50ikd+I_~`EwAl? zBK&~jzxejx$5i`RqHzg78zEevTqN7oOv1x=o>J+{?q+(4J;WVci)7Qi{hs>?{4|~q z5~YrUpR_l-YjenG*?BMv2B>SPFi)~J#^{?94mN`rGmJb@;NWteAvrDnc&YFRTBc7B zZBgG(g^2}Uqp%1Agy#0iMcBt82XHAD74D3P{=*NWi%Lj9fR+Pd%7eoy3clp>@?nSm zQp1lWEKG_5Yt5?$wZ(bZPK>^yv9j{cuT}Y`V!dkhUui3%lt|LsdtGXuuPwZ_mAN`W}buyS!K_QIBSI-?d5k z!mnRl6~>rIF%_dHnr1p@&86UeKiT+{y_pXwCk$-10X!aI0xdVG|LVD{|69+khqhwI zI3|_7x~G^Rv=#w+K+E!n3i|@rgS$YDxX!$02cD)Fgve_oZg1PLc3436FL2Vsj;J6YYbIu?P!zW zLD+b(8iLHL5`NW#kkKb_+#cYK@FZBCvEwXzNfX`j^$wrvVLeRpfmD(Y!x8=T3A+?l za6-nK2SYnU8;%Jo$B^zjO7Ln=q&ZqRC?h+`pkFwHFPs>{Ao_UJ9o7TSxZ*apzZ2B4 zy>~5J%NzBeZoHR42#I2KdZE(2bz@O(^2wbe?W@Y%g!*7WFS&vrRF)|+@4^3dByRO` z`#IzqchJCXxvTT1`rbtP>21yuTAvB+3B3N;8b_rkr^GH|?)i??734oa<%{aK)R5F+ zqVNmVKX$`CO>8>m|M&r&M<*Hnac`RYLz!~EflI+L+bg8JVsKGS*nz!_VwYpPx-#_H zj~>hTmiL)khze7N9fSKl&WiM8ab*?<_(t z@pGM{m7SpJ{(1-;|Jy?l!6O`2K(=Zm+)ae=$tB$N|LNz1k`W?&|MF4#k>^itane8< zVDxNO?5p*ZPtvwM?BzGgVhasd z5M~QQisFfu-m8JJ+X}f9`KoB_B!kBisG5Tm`QuD9mf3bQ=7dSHgqv#YGtqr~Z-kb+ zQ(g-S#BCvuuos;7Ohn}}?1cM9oURGq;3b|F|HfynAwU~AalTk;Up=b5_s&utjw3#3_&63?-;d1Wt2&CfLXpT}TT zm@tn2m^g|2zo8IAee*al$C{4&nizhjX z1WzWonVi=yb57kZ;1n2pij?ty(NK=gPcCj-cCmv zHV$5vQ+%jnAfFHh3_5wEXR)u3enIcvm*Jn+xD{vmfy4w5CNSDVHe|(J5+J+59j;g) z^5^ENrJ`jmr4#CcqcF(Oj@SC8m1xipwY~q{bg!`YC$5;bl|CCC>wpEs5(1^h z0^lJ-_>X{KV2LAzm)-WPVv{r&)_B{qAvOSa8NZlkWwj(ni6wq)l*i%dn6{GMM$F#C zzLqBE>}h3yED;Ex2yYbpCQ6E&oGc1_oIZ$(Tyq%ki z%&#;cV&6$q+j>)%gSp?j4zZfvy@VJTJ7WJON6ct2tb%-4=tnMMkJ z3b9QHfw{fJvIs^F$jIs#4#j^c{kXR)C|1IgMiLrqn#0r51j66$^ua6#x~#0|^rXD$ zX&MhxI-DwUD;17f?I7iJ$U5)~9JB}nb);T@{d&JxGGj2i_rXqtk0Iz*De#gj@8S4- z(-N`aSon~SA?0psxh`eRkJ0JS?UdZjX`HFH_ipZK#dlrpQT|tbJWpCKyTj*~48-zn zv9R*;EMX=^(ZD(rmM&m3f+ilWP?g=;%SdWR*1_E12l}d<8=Zcdh7hrcyZ#U36n`y>RPFaPQx_kljp=PGxv(VxzU91AIQKbACjrn7 zKKxc|0^02`Kr2(!p^C+Jhr_x&2uHG;8cUZo_icfzC+|8DO~$V}{5=Q-y7-m$z2{qE zQMz2$Il3ne#@0Qbi=A$M>Aq&J16XMUeH>r5mL}8py&>!O9`yZ5l>+bA!}q{Nx%z6bS0gv+yC4M?Bi2S2KC<%%dHziCpNa7^KXZ=A_ zlMH~5%({<{kGD78eotN}?d^{Gez9c{#pqfKeb%gC8abq9!cOJNs-mk9&mmkQgPO-) za;4Fi!U58^TPSL8k5JUcPf_GznYlX+Z{QE_bVrwiK#(h&2sa^)E>AGwIA48Nb<&wX z20r=*oT=N(WkU{lVX8&J#Ooz1T#X|RPkwEO-$#Ay8U0+`ZhR+uN0nZONPz-?%cFEa zZuELhM8<+UE*iHm+F&>hSDWLhMiAr!tu>$~3JKw5T?A37(b=1yuUZ^sG2kyTvpSh?MC2SmU_aXKaT@ltfz-;qTo_pHy zHsd<`g|V+nmszC>L;kb}LB+Gc03@fyIA8y(2-(NdfK=*;$C>jQD6oejE7^*n}ndLc3 zm~CeumuhzIMe`qf|1|@Q|M9|S_j5KH%X-%Z7DCJbw^Q`t;qm>_$~E;$HOLRK!q_O^A=2kNWi5PB%slI$y zeph=PY3rTDq)<6Q^PI|br@FV&j0|hK8meW9vD<}AkNhI#ab0&j2Td}Mnf14`kAe+H zfS(Q6&AhyK_U>nz8w1&4zoLYM;P%d5z1nUMto%1)PXZVsyKgR&58d~1H`=F8JA1aNop44Qw_V6H9Izx8s-&XCkE?xmXS@`L_n zR?E!H6GjJOB|zapj3l7zsZ#6la)>Net%dRv~Y93&#z>^RR{} z`!Zn)OPR@7@uQiz_K^L{ka?*6s2Rt_WNZR5cXy~-<;!;uljGX z$41!nmZ!-k{g*fVE*peJbdGJrj%MDA_mg4PE7c;}?D3W?_QvwaFUi)z*jTnO;tOGN>iCOcR@+uC)-yG=X=qwz5O!S=8u%pYLy3CmPgtLs@IQc3DYh$ ztuGrNdT#vbN)(ufZ%91u_J>HAl;r#{{a~mphWArrg|!c(By5WqVd)2&qQVQ}Nlai( z5U4(MpK4dvWO=3o(rm}G36Ri=2DjZmhoF|De2PZ$dJU_{Ftbd>_)SEl?21>cMjij% zVVgi>hE;?Gw$E&&@7G7;N`GR4vdpI3*c)903wSP#$aFfzeS=%2IJ=B6ikOfg+O$=a zkz0o`61Y%ziQcP~6AWFt^E97|^ZVZnH#e7!S*|bD?b{`Gf;2<8@z0(P(m<6;J;oGw zI26wz)foPXt~!=Icdz)atG)wm^61EB+337$G!C1xxHrVGH?{7 zu-$R%ZZsTp+ho2GlCCgLB#BAHzzHuq~f!Sx7+uO#=w|E#ua@!;K1Bf~E#F|GR zs_yKiu+K{;lZ(I!@IX^PQ|s-u($V!5#Ju)2O20)DIs4!+_%yoRZa4TOR}A7?gOg<6 zBUW^4&;?><2-JWRy8Z*Am85Z0@UnmZ{xnt3dmYv7pN-vrTb7@^n1W=*~L`I*U7K>L6drxtc6E@Zj_o4OcNyl2+T9X5!2JWa` zCSqLLditI3mG}A`5JV`sk5#D?D!s2-iDIRUHp5LHG3OGOCkFR!so##A4*nBsM2A1y zV5NjQH64_(GZtBQ0|VPp;I>T4_hznb{YY>8Gewj3{%*AGv_8CQwwf~GGz{9?vyZnc z_}+nL5-6}p*hmE)pUf}%SpDWlx}s|-wcbSZ))?SZ-ja-T&h-LimQuF$qn>OJ%m+>v zVY)o_#&-fzvhQhysu7hwPFw`xc6D}oZ$nR3h27Y2&N^T=WZ7O+n9hqiLLFIWx0Dq1 zFEWlOC4`V7?iRy!mG*Y;&_feLSXB7vw+#vH2R>g0()ZNuqiK!Zru1Y6tSZ|_@b%%O za{QG7i=@A0>v|+`3QQC3b7-`8dT8RO?nGqBX`|TcNnhM&e>LK`e4cq8fdQKw)m4|> zQG%zY;9ap@bA^;#19sINTUktw11nJu*HKcc$66la{5H00_D+kA0=fQkz58aslf&W3 zy)`};Rygrl7*BDFu>fV_laS&BX~{x~u0wb3~rf2^buMh?Ts zlrh8YKvfah5>;$z_U#00G;YI^C?Hvr>8_wrtB@X8US!!=5px3yY7g0hhqq)#a`cta_8@1R=b#` zwgh5IR~7YzhU&Uv4o4EbWx!PP{<%A9tKs?}Xr?(n=3=NsY?rAA2ij%3t&Dpsc;Wuz zQnTlrrD6D5={&3d)Ccp%Rw$)Ry`}2d;r9*k*wY)uby$UT)rEzT@{OZbK9z;)<@G0> zSMM&sneF6tCbi$C&WZle)At>Kf6Tp*^zo11UT&<% zx%7~O{a5v%AD5q)WcV;LY2*(jNY)661C#Cf&yf9TilQ*W*a(gc>ZS>mMvQ+&HV^ir zfqDFbuZ0I8Es=yz5WXr{>YK~3ekMtK3)4d_k>+_g{5%4Qiahu~Z;d66J@ezO^H8$W z7Sg?&K$j7pL4}Kjhv!NA6+yXo`U(wAZ%A_armHa2fHC;UaG!!|h{@`LL*fN0d;?fc$ zMOO~o9-~-14>q2(T=D-f#;}sg$e%=1X7zSJOP=lZY&>F6t}foc!Q4PdFc-oL-H3gg$ZzMKAb$Yd9|EZuQUI0nX)$3e zy+?TMGGO@+DbpYDFJtoqIMLZk_PCrwM@wO)r3l&4|1>y#`I{^3Z)_B`@m9_KM)Hj_ zUhG&zB6w|CRa~3ERy!J@*VH{ddg-L14SU7oNCr8w(M#n-5286uCJG}VE|)44#tPn;@!EYOz6c`pd3cJ)oOK$y$Q-#voM z-WdrE_K4-foRo`HvZ`vTPVFowW9+_~x{u4U2UjiEuH1JkE(h(ayEA=KErGtofxf5~ z@qurRjXD(Dv~*zIUECNm7nANZ;~ff<-S|AxZk?>hqXWWE$J(mDq|>}-!?Mr#&9UI~ zW(Csx;K=_&yw%zY{)EUPHzu_x7H3#|kSw6(rg*w9P_@@1qZBB2MhdQVpo z=@ON2QC2LIAn$C6^|J^%#`R|#KpWW*OPnSRDa`J6E>IEt4q7S^OCOsFQYGxh zMqFC>%1^%UX?$mD$A5t~H;H{c#%AUTdj!ctm%`k76xfq|NC9nmJ{^9a{L=LPRYvew z_hIo)1}0%`YGmF`=G7=r*TEgB!`^%GYK5b7!E|{x{(!~aNdEGw(OeV-%N9EJZ6In) zF>dN89x_Ui78U`0jP5jg;qyA}efH*b`E+~;_IvreI7+>`{3OcFh=k*59o(=`=ANUi z9?gOU#Jn6%o}~nxOVWwB3}y>mzfB0#vT40a6%4rEBD`9ZU84Dn?7ojFLqR!65}g)L z1-%F+p=-$I>FGjUalsAU>Dl@GoK+N`bL&r%FMB0qXkn)|6l^)a;cwo}trw~4V;_C2 zB{RU?g9>+tgousbFImNjQ38Ql0Wr1&7TjDKyj(!p-L4fOfnFEEGArk=);~5~3=N(K z`^7NUlQIK|Gf-OmLMQi_g`V_WIwrIxJFP3lcG!+D9=kh8`kZ2f@A$F~zaWH-hRNPY z<)2u$wwkaSxPSCmr&UnboKq#W-9Zj!o>^QUcHCG&JXC<~QlfvTlUqdZ`v|sg!#bz) z$klH95sM4-Zr`{NWo4Fs_H(t^pBSv&2pMMGg`ch}+J?ut@qqSdpF+R&Fygoe9p?jG zKY*Wl=MyeP?^7=WEj4E^0#7aihfqBAH^46Epm538NtIvO#UU>&70B>UD(9jNZXCqS zAHCYAY}?OC|K5~;YvJ2$k}|AjaXw$?7D~urc}Z7^;=H>}EEnmYGOYTZl;mRX?%TyGelvy%Vj%1i`c_ONm{;X`&kZ4tU~e#|lHFmsxw7hAW2*=>Ptu>dkIrNGw0 zvH8iZ)>HhmF}p4!+tfcBZr_5|ch(-aPCtZ(2U?x#UCxZXeq308`u=yfE_dTw$Evs} zwet2EL48ym>3#y%nvsWy-lztYDC+cu(z(a2HIOl<()PD;CrJ3XV-jF)7l|jW=D}Y+ zvic%pOA%PJx9Rh?G?AREhA$?Dv+S52i=3SY8L56-`B8DVGG&ZJ`-MJb24~{d|jfzxz5cnvQ~0)4_e=HRE*Ep?pm2FwtF(tfgkQqZUj2UanKPhZQyhC$o4Wh;18}IOqpR8$l&G z$ONUg<(gSZaotak`)g{ZkNund)?>W22kvirUH zu-L4s;HL_uS)Q)ST+f@;{NUrX0ElCN*N7`$7>ElfGV%8|Hdf%OVIqY4MI#W-$*G~1 zA_4as0Yta$V4w zGH#yO;2#=-s(TZpzO<2)lYFW6BPMqBo6LYc{aszczpMw?5%pMgB~Ekyy0d!<*5Os< z+S&nwx;k86pGX0VbI&P_(ywxvKfqC^qhP>4NQ2EMhU9(agn!x`UL)i^F$mrinWHIb7fN&MmXTpk_i@n%O#2LyL!(g(U zlkPAaw1awB=sQQYoI$QXRXC{f4-yYN(tGjSf*6Zm$=;uIBAd_jet{avhU(Ap3D3Bb z8in3k`)|?L<4<;)`r+`9r!*WUVD(a%@3KI1u}JE6mfJwf!q=v0y>W(%i{ZZU<V3K}4z%>>GHH8hj}tiLj8j_1#S!FTYjJ=G!%+Vv48vc&EAY$ehG0m4?K28m zut=}GnPc+*?VPdo`J2ssiuMCW;O;7}>`&+FZiro>b1P`@hImr^T!%=P{jGm`YX0J7 zs1LXrz|9QI`m0O-dfb}*uJ*Y^kuOY!|13e29EGTg&<(o&4Y)H0i~8L_eI?1#R752q zn16&)!*Im5a+7*pyo=r5$vawmzg92?P(M{{;5HBu8vG{r0kOZjWQ>_k1pK9@D?^qW*gA!dx#^ zbdDTjly}Z1lxIG<*N1rR6f4DpiqrBmbj*{7CA>( z5fK+xu@r$vM+RPRjG5D}$%`e~KT?_@hW={e`wN4weu_W|r(PS+;Kq|cm1>xpkRDRs zO6#P>U`K|3vL*ZNM?&S>A*ST?UO+G`3+su;t|?Bk?{lX+FtuGM%m=f!er(V}W?izv z>Nk$})m64SxNc8*!Hy6uA<>L44ctYv>!g z=9h=z>l)UKzD}$C2q_XJ5B`K-*kT6m0R2~M<@m{OS>9@|qEqJnw8@T7xr-xWPFFx; zU5W_=CHeWzmO<>NZs^gfyQ{T}enw?(rFeEZ`C&q3brat#@CM zg1n43A%uJsTFH)CcPeCJf>1ScA#3wUcam8|q?}K|ZPj;o6)!J}CBRQL4!akGz4_>j zh9$SgBI{CX_W@^xMf07sJ#&|$xwm5tU~;7wLIDz}x*=GJ43bDn)+hw?48%?c%eS0p z_5hC)x!KIA$EM!#E7~$ICIej2Vgi6YaSPe=KTX?PkWMw0|3#VfK~a7)51jE4whbtV zgI6G>{ESwl1mQJgD(P51g&lx|XC{LsgeVjJ{&x-bzrM6&@A#YiFxXb_e~f9We~f9k zc&EbM0vVQP&=+#-Nmp00k(Vxx!R)n=8Z~VBc|&(=<{!JM>HrSAuUPu8}hzbJ~|o^3bHd>61Ir8E|wft&n=>bMo$bCR~E`8 z`;{;nEscKj{}guY{NKV3l`$jJKaJHWk%I3X3E=;fcVwf*-vrDAz+iOMqwZcA?AIFD zwMyN}{Fb{#m}j8;zLLB`+WfA!X4S5jdZ>cq@Oo5>G4gly7 zJDYC9j2ipwzys-y-i5SSG#a{_L0YnZ>;RlsG1U?ikgwa7ui z%8C42EbhOe6 zb;vBUyPr+&<3PKKYwo86vs-sQh%e>Ae6NW;Nf4?VuS?^?ra>L~xY5zyfV>=MzOUNP zue8gr@g)iNbL-E&V^>;i+yd8`1c($4l6^vS4|VYNR6N>t&6DeI7>^~am)*Pz?_>TP zHc205u-J<#FiH}h{DRK&9OU{8iw3rT4b?}9QVrns#-i8C@_*2{aC%%Atxi&kyLrk6 zziDHi-ye?B8|1&gZoYqGyYW#4pL#_7a+QwR=<>=bNi(;+g+Gjuf3zBN!d!JgzA1|j z6jF#cU=56rLw4pTrQ|hFE#XvrUqhkxxkuwp{bQ9C@`UK-Pk1)VPN5JBdh(asI>{RP zaIP6<8{Jo!^5FLmj_D%K+x)G1PH@0?q>(~q4^jfpV(PEtE)~c^LcBFK$MT!yv&_rx3K0W>e>uE{?p^vOg{;FictKfH2k0Pwpkvr`{0a4&pWs)SAxs^;5mdu6 zl=ZH^j%v>jjY3uq3Zo0>qhPz!0^I2-;|#}4?uqvFZQ31(CuE(%6geX=xaQJ@*eYIB zlCGw9q$cuY5_K5AY{>{8Xv7AhYnqs|xjU_LL&;eEMv_mZWK;`)V~|z?g)8xsC>0EW z;?RWP2xmKl)mNdUVF7-uqag8`7XGTH^8!j{w=5_ItKUH%!}PYjm~&@a5$e7h+!N=)!EaS2w#XR1&}GW{3ZboSWO zyU;#|j&gl}spSMB1tcGa5_}N8dvS|v+rmKKJStyjchffq04i_Rjn1y~@;jYgr8$G+ zOKfiS8GQO%hwZ)`tf9$PqdVruy>;NT$fFyr@8SKb+2Krnl5aj~M!cdgxfD3u?;}TV z_2huk#u4lC;`3QqBUuM=ZTiobH~Ne=@CN1>Cd5_z8u-2 zj}o{=DtY81EHff*PUKZKbWuhRYEx)W$tJ~v4=lg z-Y2fkOFao%pgwe_ma}gH18vFaya1X$aWQu7G4HfJZ-TP48$o@X;*Kz*v2?T z`R~|sZoHctznyq%g4M$9*?;oZuYtE>cm)WShZ7b$6V8@z>A`&4rRZmFa6HIxFj-GDD@TVT8gaMlCnH_m-yaw# zW7da_qr>}5?^<*it_y!Z^NLu!!vFU+H#0bM9ass_r;?!Nd9#aiu^!~z!q5}Raj3Ty zBp&ASnM+vUr!#!c`1D{R3D-VO^z2?-v-_ z0)V3c{0vOCF<8cU`U{Gh=4#4h%eRuC%ChJbd8)N+8m6LDE%FI5-`pdNNjBtuDm1#e z8Y}J+KLCR4V528^;Tw?}J;-#0aPtA_ zd6Tsg84{LkQqjY4w$YiL2z6}~JLmV#4>SFX613NR}=0*pot zCTf$j$FI}=$d@&sh^kLnk>TS_+p~P+TipF@DVicUN-&QR;=%BobljlsX9h+XxLJSQ zbFN;`7VDZb$;kG`5#qUJq3-{B=jj2=|EAUMu$}x+PuRkXC)ZuDrI8;Eg`Z)U zdJH>9&dnr2y+(B*ETV2>S-ILkAlmA!j@hf>QfNIwumP^|mZ#<~<{|stS6llEP7W~4 zvElZC#C$ZuF%15oO`{B*#KdBW&a4geuZId1`?Hw*ZFTWu4ap$Hc+8Dyc~kfHBO^Z| zotp>wqDnuulKwu{`tXK&>GpWxtz{mZCB+ijIOe_)7bNpTL!+|(i?y6m;HY(eX?us- z1?5ikl;Ds%d~r(BOh?C7b5`@#V4RUe+_vi5WlJi{^90z6_f+1QV@eYwe7vrYTamYG zE)#^=Sk%H}A&7|&rrk&GS?Z5B|Z$I(4;!FxbCHeGFJcJV zEL7W9Cv82q?()|WosS(8U!pn`+XLd3c;fMB$qP?V<#uWyg2cH4D1ZKtfSwR*hcODd% zHnSJvRn42n$(1je=>X=%xaFsbsqvT0?EcpYgGr&QU9Plur#k>cz`i2nwvl>S5N@mw z_=)+%XLI8)doh;4n008Dm2j8vH^1`lc-D>`<9w>3)JH@sqy}mpq`$jX3PVo`hZWO> z2*r@8`k=pfe1Z<8^Gds|+yCHp z<8kUmaqYFl(O-p9{d}=z(8c>c70lc1^5!$7EKiP|#z)qTOX{xGI8j-_)Lq*r+lp;{2qw%Ujy}=^T z{K^tk8roY~6dvN4-_20%9+Ws+V`M0BFKB~D0OBfY!&QC5-*tIUhSf0O!!ZItf3u%$ z5@eVuHE_d@`PhW~NOas^QM2iVQR*r*v*yYN`}PFx>MT0@Z12&kyKi+Jxqu*p3n}*u z^qwu}F#0R$G0w5{)z#;E*Wy0pioVbDDim=Xk=|h#Tth98{YGAu&B)A>$Y%J*N=l|D z4Id}hi{WEH7`fJfRLqGic^g(L?8P-(7BE8G#dGy&b4ghLnIBr4qc^A`JjBV@KNTez z`up+EDrgaWgT2UlK-tb9>Fp2o{}Ef=M|Pu}*$v2RYrJ%z3wI`hkzwAC9uNQ<%`1M%RbCfB=w==FY%mw#UKq z@jm67RKP<}dK77g~u%&z`e3v!csr`C?+t)ScvGoEGZ*AsrCAdWFH1FV^kGQkAJ(Fmc zV`v9I<$d(O-Ha$SdtJNrcslQIPtR%Gj_@}i9>O*R7lCxdv+#mOVAd0ltYaB$ zn!H`95<1mVto#zTHy7@P+uV`Dc@3pWBxPhaKlvKNY|S<5>b{XVNi%onzH#y=5vDJu z5DurHLf(SfnxZHmk^MkhAghoYrW?ua7?k$%>r7F8!3mXBBb#3v&~^pv^mN!uZ)zhr zHF4LDQ;;n)J&6Tv@%HL*J-(u zET1uz8Aue^T}|(YU%G7Ft~~%ClpZuNPB*5IqQ0S3y#^^?Q`3B76qVyPmGr~;nUIz!fE>Y8J%S_m5c#0b%EI{U+?IKOd|wEQO+)kPOSE9jnxhOYUxAACGo;RaFVVqr#`VZMEhFAg?W%UZu>E| z4>~JmfI1p`L(a`P@pmm-b(~7$#^RI~pEv3i4GqUqt+^NwF2G=4ZSX1<%OE22@wK;K ztBxNWsPzZTBuJ`#3~1lrSjo$v&Ll zSj!)~Ru2$dpXXhwik32#ru(8@U@uK(<%vdZPdmqlKTD|bXw^H@quN4$(P6meQ(Y>f z=ILF$B{htn>l*>O0KX6AmaAjT|RsF!tk<>2=d-;^*b6LNvR@TGB7J70#6tPQQrt4E$zJU`%+98izMJN^_x+QQb7W=) zuF~Fbzth!Y-kC(n-BH$Xb>}uxrB4*Cu){@vfkX`a z6d%8ntJ&QGh(u`Z4=94Hf`FoOkcV+g`|czoy^_4BiHKkVR-HKG$YUfI=VPZKa>HGg zh%a#SfExHgNSE%c_5F4GY@|5ft6p6o87D-nLcCj~iQ zd*s4*)dd}ztvV51{nL*e3B*tSd7Xe`gs!hEU4GkXlft|2C;frDX?;vfY*{=`3iIUq zkNy^kq}JYX7V}RFck2laA0{W0z(JtlzY`AsMO$)bk3)&hx#;TgjX9gn9#eG*mhfwG z)%`d>Xs)qD!u9v<_s<4TPAlr_thS?0g8(GrW#~sH*FCpAVd2U+BHGB*h4*BlQI@$4 zZ{UyRFfL@)S~5G**D{ty_nb+{Nk6uAEj@I;bV4#(Pp4>5Ri+%acv{Rsq0xAup;7Th zd88qzmypAM9g!a~boNPOoW+Sry6;I%T#02I5)tMdMV<&>CoaO(@+UBBbc;@hq?d^Ly^05{N3RuBs!$csP`o7aY*M$17U<_r9>Cy>=a zSOdDZy3pT4@On4Jr0!Gv1gZuNa&;bsTrQ6{p1L;@)wt*E)Ekp zB5!k?+$0*ek9_ zS2{nG{m@qgRMxWr+kE|;PBPOgE06W#GWCUJ3x5DTYZ_hGXjz18rc9Za;VKn-ex~oc z4N%5u*7=P3o#LFLziwV?g&s5Cg57mhYS^muV1(ZCUsI)KM2SQM(De<&4Is~dj^xfw zL!dW4Xou;oGC;vS#4`VEk<~qi1&mKNHa{X!?#cFr;5Hy3LHq4 zE(AY_Top*^hU~Im_bqL9jtEdcjzlnUCAxo`lLG+Gk9$bJhcIUWj`mi#zLNoTt?p-s zO_T*6{kceq7Cd2>W!|~*j$2edzB3m9lV7AAE0z1%aZhHrcwD?f%o;W{I%A;D$ZDQuC8%A3q{)z z!}sr%{Li)`C<#7H1cI|^(cU_>6h~h;Z;iQ9zaF?~cCKH!NF7C}FPQYmC@)+D|MMUh zG^N$`NBhG!4#Bl9@|qV!8jKe$D;lp_$L`T>8uMz|s2My&d>)&zKkJ`Wj$)3x>I((& zQHF;|3$(a58d=4;^JxF)$XP`q)(L2La_0tW7 zej${^%<#$BXHb)RSJPA0=!MMZyy1%AN1?~w>)NU3#E3Xhm+MWk^QnuQ^+Ck?cQp|D zx?cNp+E0&raqHU-W}D~BlM6JKht&XUkWlsHE zW1sN17fJ+guvV01G0zgqRSIfzWg@>Hxc%gF=Nbo&vGG~RlSaOyzfp*PPpad4mHYWH zXe-DUOM=vPot};&Pt_OmaziJxWu+xOeZ?HasXgfkX&vF>TX*P!^w;`c(ZWJ4GSQ2{ zhXy9#hmzj@V{tr#>0oO$HeGjXs0fC@`f)a=bf=CyI(1L)96a__T(xfUy zLT>?t2#A!>yMPLU4^2QRQUlUUq)0Cby|>Uql6Uxh-@hO3de50NGk0evliAJg?3Zu% z3dY#m6LjrXea&occH}_l{9xWg#_t{kCH8F`Uf(FQ^Gs%5kWvM^L|g^n%UroKLUOZZ}d$5nl``6?~SN7IK{Un1;I z{ZyRPnR+~oVE;M@N%6WZymVNln4i8;WL4*vT;sbs1s~ReoA3TDNFC1e=cXngU1UZh z6&Cq@dh1K_|5NbK=JZZZa%!cTev93Feptg)2}!(?UA?Pt4`~_2_)stzr5U9zl&Q@V z$rofC_~%miT?+f9I#nf?qpUQ=pLbebN8`3On0B>)+>!f*vb6PH9I6EmuhkEDJ|r4G zuDGm!s%_i(^91Mj?xPB!IQF}BHx*CT&MhBkY}cE(G~Tij3Sjx)?G34;kYcKXog@$<~HQXG~!C_0fDAnnO6U!{Fhper%j zb1HwDSGjofH!Y%J+=8$c+N7Z0PTR6t-V-7;>H%X$OuVQ-Xf4)U%UjHV(CoQ~@)cf2(grlKG(z39 z|8E8X=3G4MY(&?F|IBXtCsX9nHFAGr(2irb8v||6;|guh@hLT9b+ayYz`vXD-KUEd zJMTETzc`S*(qi+(sM6fOhwCU~F4&@A-4>(uct~GzWj03UgSC5qHAeaTj|1s=h{)XxLx^&9}A3{#T1l%1}|)C zx8`aNf+INjUJ9;W`pNh+F(ehZ;)>{=NdeZSKpbn$gw`3P*jXhN9!eB|gABA74#0#_ak%UY+; z7y*B>|IakWG|f&E9lh(m)WyJjp%L9ZSvv68H7m#qrf0QQ3FidQuNe>)UgqA!sjZ z`rogIUvGi8Dap_?Xja#8Mr7UmROrIS8zGb4@jJhGSTg^Wf^wh3eW=KOPh3zAUqsI7 zpF8ezmh(?aT?Cxth7WKVq<7^OUWCsz{!5LqgLu`Z`qZ!N){c|xljX)mc~y5rCQ_GA zN~em2y8EwG>y~;J92q>Txy!CkkuK^zWS9N8!=hVAU3C-gVK%E=_Mh4U%XYc&zM!q2 z`%K-ttWQ}t&fZZ>&!_p$cIeT6e&dSPpW$hSgu3*E?{CwlVzczOn!OE+vJj`sjD*0SnjC=`fYk z7cW5+h(35w6zE-FA zUU~Ew&e3pqh4)-`|HAp}=XwL}&Bf1!p3P>M^p1aeels8Z=Et)dP5y|8JE9vUh&OOAqz~|s!o~K)wBImW1 zt?s6`lvK437nF9f-qcB4*OzYO#C@q|9>L)EWf8TvQsDy=mYb5*JYM96CWSodB8>xM zn)+ae!@9*#XTYVN9eXOG2QOBqKl&``x2Wr7H?I7&LL0-$tU@7V5LrQ^XJ_XtX~Lxl zdC9FNcUfa#Cl`8ovP!y#_4K4oNnuQAPkfTAg1LW`;cl| z=O>i9e{{Evh?8X^8^hs-@aP0K+&<)c4!GhOoId^j3^g>oE7hm1-hbAI#1 zJehYPBsm8*{FP+<6}kGYbVftPQ^oeg{>^!&3f z;jxrD?=|&>GMNJL(y}V<+snl(PO%ZU`mf)+=5!O1)o{l9vo`ek0~wx^s^>2XKw;nk z*@}DEc*7^+{)4ff+%(+>hZ7v)qaW_V@%~iOJbsVdo#{O);QeI#WY6A*33$Z%N6W|C z#D$Mvd=_jRVkIZb=^m;)Nn%8>UrN(F75R;@a?$bXN6U(5u#GdCp>F3As~iSP&voBp ztlE7zT}Pu^HG7*emE*oT!dc2V6P46Ci~M@-$j(E#m@;OVZ>3Apq8wb88?vlAIu@~4c4|LZuH*YJsC!1b)RcZc`S+1AB zrm0z+q3{O6oVIxxL3xazw3g9Bz^h!{#&W&SOB?iHE9W++un#DNkTpHY3~IL64An1{ z=47nsFSIx3i1+={vZ~gws)LeL?!8k`7CGw6Tthsqa2NWDy63w%b@|8ymo^oH=O|KS zv1cLc!@T&c5?KcmT9`gD7_$bpqkhJ;vCPL0> zDLb@ns*QI#1Ut36t7F&jPy0f4U&jOQdC5-)PX2rux<}V3?>+zN;LDSgUX$uClGy23 zQaQhByqEiP*X#@N)mmn&=#Cs%30Kd8dPW98+V@AKO~YM%BMK6&d-hYjnu!?XL#qWX_kXiT1Z5`>V1RRZ!?+gC> z>SjZ|U{IO{-myqjCWjqqQn5>le?g(Fzb)(=tm{vNr~R%O(8I&!cAB2}_Ne*3`g6qS zEVuK(0LG~D92$HBs%A6$V2R{eH^^?0>#-ch(|?4FN;N;>5LsUJ)byvFULNi4f5umw zq?0lSyZr@V&I4gbjg{K-@F(h2C)K5Bhb^p6s3~95Vp@yZgZf92oBpJ*X_hzZ1#_lU zDUY>e)r@cOg^VuKbhI7nMTVa+`AC($sDHl+13zhx5R5B)Q6rsUPoC9EFv{;lDTu_*URwTaDpozSR%Ls1Bi zR1Xkm?~W-7&dtCA?nH_L=9xBq{5nxHOEWXNo_n2tPMrL|cT~-tnhJNF^rUm4yY}w8 z#jEr0+A**9zWfOc@0>BGW##wJ#F(E&W)7V@`~DzMn{M#C*<@W9WTd+q> zjLSCM#M(s7_Nj?^q=})mx1sfu|F~1mTq7w&b(33=2W74?KV>(Zr zxULTWaU7SO^+^y{oW2GMW^;k67c-e~h(Y%ka#qHN=&q1C#7 zm&ITB@1Q5QUH7)PXfe7QdgK+Dl{b!j-m=gL5CTt?cxMw@&gI{VIP*v6ho85b zD=i7-U+L_3y-HUQec3jw;CA=ji#Dc2(<>vPo$Q-@`7+C?LdB8SS&Q=7_A;*RVYg=Y zcdnE}w`oMq>2lvSZlkYMi!&j+FMm+!rH|YNP(JappBjG4rW=c~aOLOyQzB$bG3k2C zF6>*+{u8f_zCR*qD;iFgRd_l0UAIfTc;VN1_wc1g*au6RM zyyY!BU}8IUUnKcorT*UIInz_9H(tdOxEM8Me{s!vwT-;^&xJ!zMmnmEJ|1>*j;>}G z>U0O_=^8!usd>u9oSDD7YWFR6JnGDhCHK3M9cxU()+T8v=`6=<-KAxBH?usccehWy zHtH#CI!Sni7ajdmMyXc(^_OM(sFQ`Y)Y9Zi65l6M=7j?LT+xJ2!YAeR=o&nTGNpq_ z#;zPIEWxYGujA-WY%ub3qz!sCOu>e(F@;~{zZGKy+aBdNDSHzgXjU=8RBB_t<7#P( zkk%KwG2i&}QjlQp1JmC>6ubvCg2%s`+)Og$NVSH62ek{-{u5!fi5U2sr4eCBzh)<> zo7c{ng4A>n+m_>>>!GdNcf8vEQu*fScHW|JSrMn$i}?uV-)_^XY!mw>Yu3gm!oF$> zX=q({w^zh3G>zd1S@}p?yscZx2|kGt{yt! zIJMYarr%FH6z^D$7F-{`cPB7)NvSxA?@pP=iNEGdsxahC z?@4^RY*5FVdP0gju2+PQQERgxdwI67uXb`^f*C@{g|6doTy#Hc51Y6xd>u-$?JDPg zWcNxjkiwevZ>mjQ<~7rUcWemG2emtQ+$A|vuFA`8UBfBK#te_TbBrfwp1@@My7FrH zFTKa)x3AYjuSNW5EBK;IWv4~lPFc5J7;k?2-=TLVd7z^|=QKi01!X{{ySI?J#J_3I zY2|DvElyv%sJ#}bW}|@TW4Kc%pO;F{$)5Fh`sly#_WL}qXH4ADlU0;dWqI4~1z17{R*Xrc&AEyaaYPGp ze6vtOnbB7{A?Rhl7M+^DcH$#X_44cUJ5Mi`7Frg1`QIa3eAS`Lh(iC?ct1UU>TZYM zsrqGx-`{j(8PIFUt7BtUHzSMJhJGkK(s^C>Qz2DW-0#TU)W6m;9T8NHKw@J#$he01=5q2ot^3iFXhhy0S>7gWJ6#}3IvFY{w+xZ%& zO+&00{5S_*cG8U9DGGs(xWjj5M+JwUM?5zsXX76aa5PRcX^B?{5et|cEs|)Teqe~7 znAXibr5j_Jv?QuSh&4>>7M_ZY5DsMP22U`HB>Fw^E0dNaI-EGogcnCc8a-~K*&78o zYEy|m9JPr=G6%A4gTjd6cPD>`%-9B;* zwrMsxvI`z;F-E^_XrftqI;V!gU+u4t8Xu){iTYV5hWWQ`d>8y`sq`{OrM zeTdf~|nY7@R>+4Zr{(eJE0@&aCs!Z@C_f3&tp%$Z~ z#A#6~q;b^72z^?5+adBJ%H-7%M{yinAYqI3&oe*9;Sv1%O9{dq>cRvf2zUwD=UKwbcE7RP1qCv3HR$Ubs17gSUc zo?X9|u;p=415%uv8z{`-5Zi|@9A=(McIQS1$3bkHzuIQ;fW*zDt8bLOGOgv? zmc;yR6h&v6$oT)F=YXP()iz6HHo$NzE{grvjE?Ynazi@n)|X~^k(nkWl6R)5R#9l? zL4=pd2kcc++Ijfhxjtode-fU4^QnbxyKkW?BRLS{w9#!18*woK8y)toFT0(k)!0kB zrOGD#Su#9gw!LS-=9x-sSjx}(Eu_g1p26#B9#U-PL4o(v)-Xf2Tj?SzU!wL- z=YNZ0zq`T+GXF?8_DVpl_6DGSceUfq1F+e(;z8ODu?OwvzB0Wy^)tPdgOJly6vE(8XY{2V;wZ|=mhK3S9d?157?Bw+Vk*VtDK-04p7um6k z0+fpqzFDTXzZGq3G;JsPEhZ`Tim^)GJG8Pmt6pc+X(nTewEmD*bY4=J->#kfQG#UA zOWhOo*^)8ZEn<^Y-z|bkD(`;3DEVyn`&CIp*?;EEt>h&M3#*K)609@mt|X@tt%9V@ z60Oyw(B2|e$p?pS7W`^;CY_dxgV^L-l(Q0&S(D<{DchV)nu&hXNy)vA7bR5>A6r5L_bSX}12O`9-mTG6yTs+oO+WN)VySR}Mk9n3GcAss9(cOX~I z6V!8jJ8yeU@>o}{^hsF9r>(PTeuPaY$n}0hDm)mQjs#xr{ zB9ngW?c%yAy|`AoEpA?xcBH<~{cekSo?(a_O9yhu>-iyvmohNTLwz5k!y&I{ha3mL zwk5XWwu^U#7A@wbds|x9v#`-Q+1Ou`>TtQbL=wjVCatA4!xElPc>&7K$i{xEdz9h0 z<=AU_o|Lm)O!8Q?n1O?Qby?V7G?0gufOMzw`mW5tjcwt)_(vUMEv-L)c2ZpJ`fl$P zlQb7|I0b#fDJrQZ3nV~hU6_uL=H^wfviekPrm~7oM(o} ztncq%2FLYZu4LzRj8~A@>i!u%`OBzn-k}#q7`5`(tWnu*>8_eFS*aGAofvDIA9og$ zn&jOxU#)Q#8<-H=+hX>AbjWe^4m6e0qQz=sZ_7$c78Zwn1h<37BL|S8zMX#RK=2+2 z)PSH52-14zS>lZk^;1=VX&fef(mUixdkK71U|NSsl<;i{MBR3A*>R}`ix#_#y)A@! z(2#fyxSeSn(z@=tFO#3zp+30;2wngIClCw*K@kv4YIYpa+L9>QV_~@U)*5|s!dTcZ z$BvpLN};RxzJeF_*LnvMEESv9vch5sXQFEF;zqEboijkMQjA7^^SkA%NipiS*kuPd zOfa@1lML_g;`)_)TlyP7>|a3p#t5d*t0BYMYV=8YbQZHtjPa4E$Oj?+1O~#d zO52vG_yYWDV1WR~0Q?{DLBwSr0Zsw<8}NSv3kEm=;6mV+0gD7U9pKNvuLTwWa5TUM z?dwvGTf_QmO$2^tv9r?gKE>6QV_{tdput6sEgL&qkd5tH1ufxlY}wf1)od*86G-Da zHn5kUfQ@Hihm8R?KK6mt0IUG80?^iEPhXb4s{Ayq^00#p61^6YvQULx4@PEMn4b1(c z&p{0SinCZVKF&wN2OO|2ml+fLbTQxX3?bjnbOB#`lWV|)fq~v{%IDi@avk`hz;5}5 zoALw91N_)6kG2eS;c*%9V_}rMSrcJXp*{26v!IK}E?UsM7cCAR0{=2Fet@k3)&)Kk zm=wV706zi#L|mOlz>G`cSlDdUtVu0{&x}dKVhoA*CA@TjT1Qj&Pk!$Dwmf^7MJUwb)i~3_bayl@MD7ZJU2uDR;Zf!r9}wear0H z>xR&6JeFvEokFs(z=tbnwId@_L$~*?z{zh)v_2^0jeX+qk*bsnrAaw^IInnR(WLA2 zhI9U;YpgwqP$(b!blJzGQtp!?zBl874|3S1IbAWDO6mSsqdnEXUT(2va8I^$8k5sO z#)sBqR@26Y7(2$jirF3N40Sy6_gb;auDiaw)oXgi=f+~u$C|)xy%v+Fhj!*g!jxadda=~s zLwS$|rBn zAw=O}iL9Dxt?Ok^w!G{YudQQvxMqFDvr4xmX6zR&p0h7nXy`3kJd!?;4|Yw&TRhV8 zf``khPC#CItHD*gHQ*}U@km{xq^&)#`5BUYWf;$VhcQ#-y*2ax2hQv-MdOjdM#8>K zmG=)hoRhaDmedz5I%a!YqJ*-rJbG&Iu)=s`nUM$(JOqMI+r&BXLL$a_kERWzX zx#N&!^1{C1-kOI=BrrJ4J_RLA_qOEb0D%?|q#p}JfZz!bfFW`QjO?wX-j*+kSy&M< zATR-fY7m3h<3o-uFgz@Pk-cLX#83`maC`(0n>ZGT_}Y7E9S%{!AUSUg1mxb91Z)=e zDf|)K1qlRbFi0F|9u94VZWk}>ELwEW13?j}!t@dRYb`iTXi&nz6Cj8H4fPTT_JANm zhdQyGf~H>ckeFAk3^P`2GZsF40QPmgw7?-XjY}KTFLPHa(^zYnXGw;!^40H2uGY-FcoGuEC$5)f{hHv;) zA>fMu;{{m2H$3Gg@Wp(EQ?B`Hrt$%tvQ^`%ffVR44nG8K-p>Zg>6;OC?*cP}$BD>? zU0^2A6@zr|iU)oIuxNl|k?tZOy$hs^fOHX%F7o)m2pIVMtPnm?McMP5xtuSG)#R^#_te*11w zle|EeB}B(n)x_X2&fuDLn=zBTut)KB?pRYZYi~=v1u)QQdc!-nky6&}dw~H4xBJK( zNv)de7KAswEki54EzS8rWDg7mgku1w0pAFiJitc)R|6jn>=eM@d%L+W8yj#2SP(Fq zM{tX6qN2f!KtcL3aB^^GQX>+C>mmA>KAHFFEE z%CLY-Gooj8W1wes6Syq$TFGV>ZU^#bb>sJN^|o6`eM6PQA^n$!9Qr!Iz+BEy6^V^- znO$_T>3W{oCTI zfwi>>lk(%Q6}-F0Ug7v&5c$&;q=~DH4Nbp0nZ#VwC@DGVD2mT~G%!fL86DYkJ&2Dy zc(P09t{6ug$z4n)hdIR=QqF&DmtU;^CUX-Z!&z_s8*JqC; z>J8doAP)YuKS>;;K~efBcM!9n{=MCrfwXNc1M z_BV*qz4mvB(gXHfMCl%TW}@^zdl8~^pS=Q6deEMgSpL_Zj#%Dr&r2-twU;E857_%G z>`k2TdCNm8>#-L~E-$biZLMCtGpaP_P&E9uVLfyBNkfQ+#|1xuuHExUm=8CxG24d$ zE~=2YL7X8mz$0ruY!G`H>EWU^QGf|MW`wsZnSRdSurxuq!;{$~YvMW?^-Q141^E}iu zF+&d+t@p@8+%Eb!Dn(FKEL?!p(54mRMclQahZp*N1iO*L0Dt0_utD5qKV~8UGk?rP z14i$d2?b2zF%u6MX_btQ^FFnps76yz)IY~4FXB>pt0#iyaGM+IACk{n=$DZXDf9zP zcC<$ihtl3{5SOqF@IoqRvLoy<^ByqxVilL z>Ii1(cs)33o*e`h((FdUl&P;pq0~P2LrQ1d#mE*;1i`_xZJDoN?y$ zWOk2$`wcChu7_?osXiKz7mb@1jZ)sPV0?aEW{oYrtr{qKNK>NP@iTzKR;+JQzpPdw zo@NDGCYa9Y`8i0K)V+(a`&LlBGisMdh)~-;RFnFKDf?)WZttb)5MNzgGW+T0i_I;z z4xL{wcD8H>ibM^Tp<5|ZwWVc-CMKg>q9aTCb$MmK2ekTh@rUC-@BZ}jaEQpCRC#HE z9R}CEMp6vx5^KJiX}T0mHZ*Vl8|Xe<+>H#B;HvQx;FQ!bUEvp-w5NzjnW9X*NB4(i zYq7KYwMmvVVGJpfbYXcm$U%NWB`uL%LN~a~Q%uZudU+J4WHPpOcI0AprMiBk$IISB z&+_bitjEg{;8^8P_H%fRtCHl`zCI8ozfSHz8hVjmudaTLD94sfAV;q7Hox@gFdE?4 zz(^E`EIXjL$w!cCKklMBirjA8l7#GN-88M_w`V1->Pz0BR_W&c%i7c(2qSGpTSvj6 zlf&sQLf44d`a>Shslg6ay?Rx>(A1kzuv7F1_EF5is(^C`A%s=JMiGu4c&BGt9~ zp6WWvdMIhHwSfPrU`2gW3O2PR3ZE5KOS(@Uy4+ZXoz8d@JP4oPY4M>jOd*#;O^|KN zTDylj)tfpus(f7XFkUg`vPoiv(95mE%VyaXvidg)p}Jvtn7a+jW(6Cv`T{mZn0g`F zH|S;ci6ygWzz7#Y6F%f&vZt2Jl7U_n=sCoS+}=eAC>e3tv*|$sVkxrkVllEq zw+f+Up?R29pbn{!9TF^rx&t`AMa#!1#MD5o_2F)7gZELpd+oz`D$>b@cISWJkOOW% zUc6vCyWz-t4H+fM%E);`_#V@`X&H!P8Va^ki> zBeSzvNP@h+6QaH%n{lyP$8$O2YP= z8>Qco1=(7pH@v>TwO%etqDRy+7W+&Ng)^YNHe}a0WJ?a~HpN?ahhVexWU$_xbI>wH0fThPMN_IqTBSm)YJ#`RR&CMrKgvy1^c^h=cdkT zOAF0-=}Ir_q$$i;)Ae^f%uRh<(($(J-nf0x@8Pphk$fd7y8tHdcKuHC2JWYM9ZDbhW>0 zSzFri-gq^G8!15^zcfc-vtg+`II%RRlADUPOdLm_awCC&Y_z2_RL0RK-AFh3yY#fB zO{ZyYv7{%;Z)58AlZGWm)t(r5`iTbqxcz0RUX2fe9v{noQi22!x>zJOg7FD zAb_BE+hFa-;k6-k_qdMExoxC^N(mXDQkm9+=;eADwsAR6}SI~Cs!&p0wWaG{#8f7O%xiUMN;GC}Ci9HU>*Q~k zfrk)>R;8EDe?mkI01GarfcHxo}ic6*<9k$I6k&eP3XEGgApl>B)E8<~e520^a5EZeou?NsK ze#l-F#-|PEJ45hu-nbVm>-l%V%;kNpFnk^F!3{HFM?(D9bA9#2Ve?j%s6F+oCsON!;|??soqA4$YWUp&oy(BH(dXs6W&Lr;1m9;kz_8)+C?xFNGh&>tmfQWOA+v| zh3xuVUk|F5?%u=sZRN$}|6b5jP>|MB_Fb8OgM2h#w!+dwBJpKe)G2PA^tP^je|E?* zm(0j_rx*SC{dI(nCaJk3Wg+>+#ani@hRT<^1|Q}AcVNh%vMJl>>i_Az?NCu6dHF{F zUo__Zw*?)^@yVN?WxR(^74@-rX;7$A3^JiAv~Ip|V z+^FbA8E5tCNk<>tXe}Elp_-N5k<2pP($sbm6@%{Kb$T|Y|KxVWY}WhYG|MZ}EW^!R z_aYfAGV^Qi!JxgG9FXP;nGfN!*T(gsx5H;MKNQ2*?j~T&4IOVnZZPJKHz^5P$lP=g zhFERy#bTVBowX3eykxhrUoAA7xC96e&+9^F0lmk z&pBp3IEG~5R`+=Y+gCmNN;4`44RyvT387HgA(%W%|LQqC4HH$8hdjEPv$aLFdAD&k zXgZwi>-oHaf<#x#Y_E6kH8Dt_o%qpCmk(W~4qYR2wBi*g2@kX4DlAnmlq8plep5IbiB*zuf7cVR%FP~cb?nY4fwK=Bqa!f~V zOvh(T2QsFkI;NAO?ETFq)5aSoSwl=lLh;){Hd}<`Wn!}5Mkn)zroX5433*BJru0oG z@taW?oCJb{4%!@uaUz&ihhP}Ep>LUH2xTXr!KaTmi(Cz0fN zQB(d5fBIQgyl0Z{C@-|z0#)KhD*RKIsrzlDYMmW6eJ zh4q|;b(@9t`Gs}%h4sXRbv?ngqIIwO!Db{&lH&^L-E1>O-YlpXPbZbctH?4$-(nwV zA>{)rZ5o(Wfm4Mhe7yP?c&`TyA%@3t%UiIb8t5fUd75g3)`z+gwTHA|a zS{eM_M)HDxoBB>6GtlsbX}CO+dI3pgKvJ(Dsb`SXOGs)#6fzyQ5GJ_MG`Z3AJVfkU zBfBIaEP10zc;8$KEdi-bVl?g4C>ERQY*Y*&{iv5@VU%DA6K4sNV9^j~(U4&2I5p>C zWmc0Xzf<_I#!h?Pu%9fpWE|o>Xjg-z*^~Bd%%)mtw9&Wu{_cM^@F({LE*Q|V9t5S`XRgGOkDOX!W!n z<|OTgQQN}v{nhUeC>j9H-I5Z^YCwxSra+CK%GWD&Z+%xCkF6JLOpJ$%#UKQ~f8CH;q868a%s>F18#mJ4MVQD${2IPi! zB=(b=+r4e7kWj@vPjuNSufQW8?CXDqeXR-ej~~3{^O0PgXx4YUKAEG5G_9G?+_f2| zbQMo150tKY|DH*ZvU&8@%H`Y4K+k_ZY#k2v-3ep5-KkeM@gC-c6=Pe34-ZmKZP()$ zIgHPvv{K*Md`Nz(tsW}?m#a_WPep2|jvB^1u z3m*O**J(xAA%)F@R_1;EOT)dYzcAGZ7#mJW0%p$wkvk1r;XwU}?NthGP^#@!QmV(D zKyc7QFa$F>1P2o&h(UJ9V9|^o#uS8k#SLjBnw^G)zsDF8%-CSz!59gYcv++@M~#iiC=+!tH<@f!@M~O>5GT9UxM=AQ5C$VQoOL2ORxIF&v?)KX4e6d7|-4`m-gi{p` z4@M$kF0!XwWN(Y-d_Coh{#k<6(%#;bwSpJ1Y;OiEOk@7GK)zz7GqEg6aCnLt9R77B z%%X?A<+E7i-gZ;yLRjoyc7d;APn1m4KGq_beVt?vr^5O69?0Vx4ch04EA=E4G(E&+ zQ$8(Zo`{xbVJCQ1Xm1{we34(z4j`EXlT0E>Ccp_LnFNtcMCO@y@Q(wiq4SjbuBU^F z<$rn<_rCbAsnEu-RIh7)6{LBG=+5Ya9%=-CLcicx=10h9nQbm#!D__*z_pkKl`T_(bX00qrr0N=xTbn zSQByDVc!#ioCw11okC8q?C;-OoYo1#CdMO881_9cAx$vYLE<#?z9%bkLj7+`h&mjO zYiZfo3~gz7xIc6no`Gwb-`G5ZMl--uiPL#}WcnKE{olcproMGKeykxFQzAhcvCjpi z(j)dI2?Vih44VvE9$NcCc3+f0@ImaKg!;Y5WDp28i2WN%5Pu=ABRWVir_pL=dS@8) zOS6o4vrMjI8s==X%uq7|!W`l9qreIJ?D4qk-_`}#9jRY(t#`VW5}cqV5iWmw_ql$a zJEDvj9_-mcf-w9K=QF==%DuKu!^}0yyndC2xibyR;+(&x(w*n__gio&8TRvTw~`#< z^}5sF3s6~{k_}?v6vUXA$q91}!Emd&XMS>YoJEt(YJDXpVR$szqP8;0k$Wx`dvMvT zmQH*!AZb054==qy)tg))47yVHDI^FgLf0>>UTzqew~ zhLes`sy3{cYUkyztFN+tIFWJbia(sarKjb_!Zb0dkG^x!^nd5%LvCQK zQx$yLy4R5F;?g{@a}f*jeIR5 z@yJv@83ShHSt4uVjW~*eXgpq{A zCw2v5$Wh;`Sq#$2Q4!=Q3^^){92G*2!jiQ!E9xG!?_Bm7cp12pU|wUT?r?EAr<6W)^843L%G*qve3mwOJIz$2y9he3hb7s4DDl_5Nw&FhXmjb% z#_b+0{{an#p~_sQxWEqQJ-6`;3mL3EiUMvI0Z{>FQ|~cV1j1V^#z!8y_CnV4 z5s`2<8^fspeH(~LB@!+pDlS3af?3#CS5!tXj)K}a0h8w-5MCiXPeZwbFf9av6Tum-+PDglumk3GOO_L2?#4SYA;atuF&;lF8Az#C zXaTZH*i22=H=AY?+x2AM@a1IRh~;F8CJMje=>IxizIRT)ZCMjV%a{I59X1>DJH4}3 z#I^nQZnK>w)saX*QWXM`Yj4Jo4gtRBEHc7vGQ7QZEi`8Rw&N)uvamGm-OY@2B$d(k zNcwOezP(wuFkQw{zURbZP*f)7&1r0EZ)Ifqhhvc4cV@3t?C{DUJ0)T{>}2y!)4l0K z^C%}@iJ^*G4s#<@rn}=baw(B(<;`DTj#q)}jRVc&Ar9eHETdOF;AN6)NP8^#2WE=8 zmT$B!n!dC4ac3=fXDxDPEnsIYbZ70K8VzRlh2}>9#oELzR{J-9_HX{`&!6ef?|o4e{^7|S;FWv0oXW`@rAs#`S54ZwJa%}S+`f(J=2g8awJ&MH(85QrS$-z_^ z7{%rEp}#Qr!QSlQeIqJi&-l#l(nj=U-1DqU{r3PH~>(l5tekb&tk_wcMO)=iwI*oU4sr%#NX| zz6X12wNX~pL%bi$C^o!hT3Wm@Sdv$kmi&71<_)iyE-OB*vda7!L8-*XNkOrl@9sJf zk0PO+H)SR)G*e%68M`x`m%lsORzzcFip+n_Ca#osm7jGfc~+)v>ws}5-`Ov2+)_oM zs$X^V@sl=-DIK5mn3j>Wms^Nb(j#t17n3&DnOcTu0##~z%=hrdn#qL>2flfmA(hY= zn~^j=uLOC;5aX_Fsg?o5N9lGh8f_%|w>P|My9#cI{iuwX36d(0uWp@lk6|AjLr&FB zTFyXQY4LOp{)vL*Dj3B$fLh43uzqXX@M|6C-^qx?%DP&a(l$vO zZ`Hv0&bjk0b26RD^Aa{D^=V!`k~St=oym#uE^{xM(uTjJNxoEYvF4oXbni^&N|Kb5 zuyKFYEzdcdHeBHP0|MP`zzLm%?&5HM2v26HNeD)oKzNMsWQ0Qhm>c3+uD_|c0S<%X=+7h36!q9Y($p#z)Vjl{vt?Pt7s|~pZQM}1@#L<9zgV?8ocGu$!uo%VFZ-Fy)^88fY zln;_b`J=4ujnbAzv5gHO`Ly>TIvX3D@<-g+Auj4H^F*FmC3g9&=#X9&!)f^}$!?Wu zC+=`3?n3cy74K`@0W+773FiYufCFnG4225x~E3*c0{}L;FqA+&hE>UpkxzmUWD6}vH z!$}}KMBJo@1Q9aDVQisKArIoAAA?ZZP-uIj(iud>@HF8v7V|P5`c@Bdv(Qz$VLFo! z76(RsLgpP3o`P) z$DBp|JrBK#Q?kHf__-l_H@SX3N92BYMU}TGi6C;BA#Q|BQCL3)bNE#D^?$B^nV>0+ zN?|7;1%%AIu%7{#GSpuvbfi(~Hq7yB4%#fl zrTGpMiV_#B$FU)j&O!PJX0ou(cbH_9I3v`$B^M*34slUI=%0mj5Y5iO^0yJ5pxF3c zoHsa;QHPKe{&yy$e;N`-G-H4XNA%)svoUv3KQ2QD&LD*hhHd_%i2Oocgw@bliwb8cB@mX5DOR)7he#>*v9 zfyP(6smWEu^gXSZ^ETrctNP!BsYJ!9Z@hduU%-d=MXsHx6wWr=d>{UfV97gL(MB&w&)fdp(TX+V%81S0S$yUgSStPR zkmvAEYU8t~+FtZQ7_QDK;8~ z*JS>_ZgF!oNh8kW8uO(pHn3H2LC_0-UJ@1J^bUp zwvHu7ktNPZo3)};b1-P?MieQP6qa+qyJKlrmeANrs9T{_#_n)S%1)sMXCh14 zYDBXAztp|=_xt_-f3L>L%ks*rInVcbKA-pJnYT%C%e$twY&utxnw>J(W_I-*yzrs# zl$gBn-lzUgYG_=aZc@;SwKpUw-a37v-K%AY{{`bNIg)pyAxrIxAb8wc$LpG_GApM5?#>Gzjb+oY14`_0DM0Wofp7}a?# z=B~^=QE6epxhIRc2bR~0m{2_yGyhWTI3U5f2UBe^YawP`1lyhL6JIQii%C%ce zeR`bR63+I;tXD7<%Pn?r3WS-8ghjWYr_7I;&NVBju4P?pRSXkB?8Kmlyflk)`ukwq z(*#PEgl{gVY?eY#3P9_5X|jl&I22D1A2sw(y097qVEqbumI9=QHHg546?7`v4?~7z zni?{uc?b4YqS(ci6W=hM-{3_RgropOU4(E?uykIM3ESe>a74Phv23>@=-8e zB?PDF=zG5fZFM^CCkPLR<5MIFPOjfzy3l90zn9WUcKJW>f&5QEZ5#%APl2>uAu$-btq;KI^b8S<-wRT4?Tc!2=K zzYNPMA$vCKCoKD=-W)&^7D3HChRH>^SBbJN7!SvC)n5?O=wWf_HTgdqEcyM=nal87 zRV-KXpSuUk)gl@Bjf4Y^dze6)A0W=Z=M zztEy*U~;_+Sc-)*C#mUubiT?hysg*ayzZ=yZ$GA6#2cPbtFBqz*`D;e!{0g8i>Y$) z_Fb-BWo_JvY{!9pE%smCV*GYF{NXluzua#1iE|mYN*X?K)#+<;w)#Bj*`gYCz4&d< zqv+N|n&nsDn5x~KjIY9cXSa{U%TcU^vI*yUE=`Sj~Z ziIT(7k19KCp~P4EFQciqam10*qxo57uPrqBN?+aTE&bMG_+qSw)q_u&xU_6<+JPZ1 zT^BtGL+i=3j4HZT6#g~@))z+A@AK9bAT2gbNHW%=!O9l80xk;h&2oCPFy)CDt3eKa zN6`Hu=XF1D{)$3H1Tl;?h{5`m^mzSGY4@v$rk6vEC=?llps7ki0K?L%=zF7ZhYZb0YBfDKY_wth_nrnYZS34(g zt-rojhH`}Uy{%Ku4AvA($NNp!Q(KV-^>I^?T3*@+VybiTV1a!i!(OG% zWfHkv;cX+U2E8_p7YR=p+Kzvons#-Poaz3QnD?PS@lvC1e46uyo%MFT1BtH<4c&J# zfI%~wR0sQ8_Ial?7kFFt@${0T`d9)f&Eejb@@w04Z5EB!9PCfL->BP)`u6IN)qLwu zRBF(r-gahgujgJ)DG)JqKSTLG&2z(!rs40q7p8boNQxjTm7yqagr?X}-un&m64vK5 zcZ2qhqXZ9!;C^82MLEWFC`v@%8-Y`TaWx8@5`jCDq%G*j1(n|_$7=?C5%7`Bau&O$GZAvqG*OPQvqGyeCCeV z_s#76(4XqkXxw!xsMK_BnjA=7VK~FLX3R}1HyEcb8n1UwnVm#t_#!|0c8}HD^rz;4 zuU*q-Yz+PQE@BiI9@T{y%?3vq^SZUae^)Y^4T%ckbsK*_eCV~&t5x|?AC*@;3X=Dn zJiM>g^jJ@zTfMns$AgQNwN9LNLF!SS6T7O`Gm5<{vcT+3+?g*NTS~vvm8#k!99xL` zndc3e#}Gg$no zht-{j_@Cz}u_r&L9T->olxCKOXJYd$vH|iW3_pZ5D8lc`=||C%5H!R~+pz^Q_}L=9 z@xTt)EDQbuiM(>)-rJx4Bz&9j?og8pYFkub;Zq@sR$iZmw~HM4G~9WwXq)6;RulWZ zN)nOYz?x#E&i0@mp1rmH?rxpK9ksJgO1R2Nr6;t^TUqJOyYe5|$n@$q<~8I!GKToQ zrY?RTcjf2XWDiPO3e%N)-81^y?^Ali9~=KY>{VWz&bnT5(a|}q!|b~9DT9N)u|t~& z8lN?Pp)KE3|Aa4{RC1u#*3%(k!se=9U%FP$NVm-Tylf((Z%e=BWA>k32FE*hI%Mq| zK4v_kI<;dc(5uGprGG;5M6{*F6aU`YWT&DiR^d=-)ADCiW>WF|n<~@53P>_6ipz8U z(5czJ;`l_~ovL?rH#6)#N?*5svW znnBjFaApO43(^8Ii#YC!o(#rKejSsGkj>9qh&>s&E%=EN&=f(;Vpwn$AsB^+gV|Ia zsX3&d(CwNlj|@se?mUJvQWJ>>M6+^t4UpSVR1}6`R}6?7i=fC#Vkw5LK@bthw367k z(F1$XM0^m1Epfb=M=nNDaC@$c!t>(b4OS>>IY4?x;W8xoJBo_ImJzr$Nw%z^Bmu2% z1Cj(meUT_<3A`Z`Uzk7a1flo}!V$xK_E6Rx)ITgofK~_-Lb#$3)d%4Yx?-1_h-7id zMxA0e;F^oT*`fG-9;t|OR#!m!|SB>sE{P^)`w!Q*d@4uUCZQ)7ag+Hi{h|$8@mf`0N?zb&X=Hk-cUd zA8}?%1lyVHZC}&zz^c$zjG9wkdw(UnIfg7Q|cyoiFg#;N%L7|Sz?hPF%WC$+J zC{zM2?@=gV4~;UmMIV}}c|kcV1ih~yJh9x8Dgsu9gyLY&eQ1BzD=&>2!bz1&08gT= z0)>t$_A#{3Hbr>RngNDs22RIvWspJS149Q{9D*;K?@cR76}r?FebbRf-&#|Ud8c17X)FdapB6Hi3~e#~R+iH6N_dqVM5 zsCoo0jjD&^n^5&g{9=Os-2?h}FOq4B@M$tl4*o=gKN-S`vGC2UAIM)r>l=@22M;3U zU!ce5{rXKrgqH5y_eyYQM$z$jEfKD- z#++6BKu-sY!m^=HO+sf|uPL7_%4FRfI?^<7@A<^;S@lbP@iD_|N8)OB*QL0g&r8M6 z_`ROpQ&g70x-oR9sojnLSGDe|byamucihiq?e1$=UX$$NmpiuW{f;}P?aG?=48H`{ zts$P?nQewwGP2$=R~goNS`Q37WAlt^9gQmMiarc>oG@yxE9xHk9CGGT zgW<;+pRWa~smD{O{kDqfEStQ<7a>5@y{2L^} zV=P71Mc`|(+-2|$P=MSraM_i}gGgKw%Uud@_=2|exaQgpkmBKZoH=x#_Dc?xfaD3{ zIhMQOHoo5cpOO%aYw<`;l%oh|18NGx)+2Th)LPX-Y|X%jRw7(5_AK1{piU+$LtYvb zZVr~aV}OxWMMz@UYJ>~iU6OP{Icsm@MRC8nhtl65sd56xMwcM8#ZXi^k&cZjAT(ub zXs7;~z0gEtDMP6Q(T9zS zApT;|F@k7aN}0aH8r4On1);J<^X?;%7*}AUYRI$*6jVtVW4XqeFbqUMr3$)UH-Z3X z@IW`BATyX&EaquN^dkqhJkQgCqi?xdy%IK1KbM48UUs(v_M^rNJ@qr-qmRW$AXzEb zaTO>Ie4-tN4)#nm)3iuONXHSFM#b{ROI1|O*; zCNWF^u@i;Pk!k0ChwNj2P1DK?vverli8Vm*j|#dm+AjqO{rQQJ_H{~SeHgw6eHn_M zMHP6i*ScM=-Dg>)Vb?%9_+|Ic8g=XE+)Ow59RdQ`B&H(`n~0$5VW8S5NJ7U+#yaFO zj(@>)R%XJgnv^}_JjPa}CIm0Qbn3eqrQk%(z%#_>kLgTrWKTGL3e%y$PUZ6$fovnO zJp{OeTp!oK) ztN}*)j((Nj59EeW21A>Q#yanK6|EF7@O%^^I~e|F+0Wjo$j5nRb&;-DFFU5F$jgh* z28)YDL;v*r_E>AJy7!pL1brf|uB%ImKW)0R=+o}_-1{MeN)(CEhy*E6p=?}h*e_={ zdIp)*>^7r5y`MOkczWVMOo~%c;TY@v@}|A**&(g>H2BLsI}vA>mHb4{PU+Mf*%bB_ z=K7#id98#v_$tjsQ(x7u>YYwPR`t}0YQ9wc>zA{xoe@e(1?L>+&K8wrk0I|9o7_Lnyng@2(uqIx zpkz$&J>`!4yJ7W`m!4_^&z~9W)_&Bn)A!y`cGK&#UJ~39cKGns;gI3woUWNU{kzg( z28Wfa2u4lh%URh+s{=M~r`|BsI$l@%mnd^138@*mdYye_EI4-r2;#;iI%qrq2I1~SqMYQQqsyfAAeBriV36Gc0 ziz90he-Y?dB|*hT*CT@#`=O~=xbzZ9dZBGn5JZw`Rm4i5^T)!o2hr~i10)oMui%kt z==bGtV8}eCkS|P`zQ-DsN2VpAxiIu)5U&!xxV%s0ISQFB?@Qyj!seiNxZ?_l!s>yv z*hW3{#j@eFVpjkg_NCnhmqZMTv*6$?aHEG#yZ`Qb?KBJiQX}pfe7Q*w^$pqU&nftg z`B$ZdNhou}p~8DYR1co2?%%Z;nEP_B9Za<;w=m?~lcGwJnSVq(7%OVzthlloJt;X~ z8Nea&(G`1IMQkyLD9hlR3yos~_zOXI|0U2J4281~>H|XpXa`eEAPO%{24O|u8?Xjh zxR9XBA*{XoA;VbM*96m90vZu=5vtJRiltW(7NFhKM8@{(_Yb-Lk7CnWNdya1xDQx5 z3UEX@v3})(JIy2EpY0E6iEIiKS6y=9p9zzu}SUQKmSet=Q z8O{rMqW_3;B*_z|(7$!p>U3^5cLet3H&ONY)LF{DRV1P+q%Hq1d)iysExf>{_y8c)y&0Y*E|3@<$<8Hc-xvImqUQTr`*Q8xg-KKK^K8 z1H~gY+G_hq$wX(dfu6yH7N7aGZZ@yFhCNwZ-BD9rGU2{SJMsFiJIB_{X*CX)${KWoBJZ^kdHl_UtQ#kMF?^$vxVVP$z()V4Lt`EMuRr67wh2H6JO-HKHr$5C)hUCLJe5EovYvXOw+o!- z8)XJnDun@Oqz~DumdU*!!1HWIdA_EoAV?@)xnM!64y18FNvK1iwU^zo;z4;zEa(BA zxx(O{2NaXKV-ns3E?}H^tojtzGzq2reYuMs)B?Ty;nq86^l4>l{FaYb+^vaa!@Vqy z9uU{V*m*Q&-8kpo1D1P8g~fBhVTWsM8H-$Y3@8DQU74E8`+ApkbCXUdv77H4d&qW= zW!8nW`DE|(Z&dk;+MSrS2y;UOdpDV>$vuFxKWTWTcXYjuo$}KgpAa7$i4&MQDl~Oe zX3B5N_=Mu%$kVp2&$(r-$Aivfcn5XMMZBI+YiXc?MTq6;L*)JTC7&C?3^8J~E(<2Un$x zwrM?A?(T~j^^PBMTr$qgZ5fGZhIXI;6jW@v!8WoksTGdX692Edl7+S@I=Mp24D*75CVfRtrdWU~~_(m1R+irlOw zH@KOa>3&mQ!fWK1Rp*qv;l%7(?o_<%$T6ZMNOod&3wNqj*3wjSDxkS}RwvL69T zGo^T7*Uqx^jALDXyeg9khwm3Orb|YxyE`R}b;HZ#16{Zs(*j<6Q*Lc4&5Q3`-*xd= zY>?Iq&AM;y9}5C`dac^7*~fTxWiJW>arYUyz906{{0WW`(e%VL?cFt2w7XObGmZpU;X=2y}wyQ-EJ#hx^$ z?q0^s)a=;9=On^ZT~ZYSM>QByYs{N!1vA*;Se__T4&vB~Q(u!#dfW%W>^Lk>oO!6S z_U5vpFEhr0=LDFcvn$FrgyBP2t`O{5F@J`4fB_&DhBcA-+m3Vv~)POL=H#gHjUsw00>wRkG)KOuKalkq_wJuI zaNJb?h%YwoXYF(Dc8&Xxe{@Z^@!l7H@hkUUZ$0{4(dmneor|JdA(#E9%d2vlwNcig z&MuVd79?R%Q$ai0d(SgPs~`h_#m#5y;**%}Aw7%P5^J4bK^Y>$eFksx#*5cKC=nb< zR-Nd3Kc%%+zRhlJft8VQl|!@R+jn(NyO_uMd#cZ!OIcfxT${HxKi}tS54^QLj@#IK zx;pu6wphi?!<{LSv=u(|CBuG{UWx1SE45$D?AD12dOmSNIHh%0K~A21t9nhmdA1Z6 zF8m#9kOy8meJL_Ffhv%$R^ZUJ;-%ehqEn-AApHx$z7=$Bv|kbmkY-ukW?6|tj+oUj zrX%{(E4vGz0rYMt4!ZtzW|Xt{S-JMYkU=?tq6$)w3=LNGMfU91Z`;RX_+{WcWoR|| zuRXsAegOdC$4$SCcLeqf#gjqdMcZWI%t`{##9~lhbPI7d1J?sXaM-WL-y0e1b7<;*>I!RY@$z zFjXW;1aht<^u+WzhX+V$l(P)p;Er+x;p{N{J}@d#<KF9REy`KfsU0n}{n*5v~a2 zRY@3PSWXoY0QidqRsxG@B5IYP{Bi=!^B_3^Ltf=XvY5X2wgHlkdW*u!p7XGTGLBdA zNHNq~8cqqtvv_3U!$Fl&sSQxQFLG9t3#WkA*aP(zf;+?Td>Y*OjPF)G;=QN%{^l?H z*4>Qki&J(O_4Zz>>;QrkJf5t#x2&?m?uJS~bE%QaN@#TSR%K|Aa+mpshve0$hM=|TSbx9{Q4=d?e6n+Ymrf0>B7 z?_9{98%dm19ZVGH@BVYl^+HzEZo`tJnS&iGF9v+N#m!1d3HTHq@aamxCp_TOrGQV7 z0h-a@PWxs0OPulgR?g^}yUYo*LDt&%Q$Qth};^*$=ThCWO?UoMk_P!{llIvnH5n(vB*VB2phpIL) zRHT=enwLo3Ah+|)zGWVd&J@?`uHBpKb7Q7`%juvuDy^$pSGMlHddyhq+oB$m9@Rk? z6T?}>lQxAt!=8>WOD~MuCEm^7<#5`D+Twm9sIa3;=vzv(`_QWx!%5G2oobQ!|Iw3t z(dwOBqyC<{9PRt)VPE&4$bRid-?mQ&?BqO?EI1r!y#B4jXQi2m;!`h6PPjyLyjS{W zz?|Y@1g0r9O)TxF(U^v zC`kdEv)9MX#0<@DjLvGK9r}8pASkHl)t#*!Z(psAZ?{`n!0k1!mfc!^&F&Nkel4HJ z3*RIUZhPOQ=ooaSu}gm}zq7e((OCY{nRDBN*o|F!{Udf``64sthI(dS7{4#oYnDsU zeLZyK@(<~DW9{BlW4=s+vET98L3}cA8Q;09e7ap*CurQJE)|#MJBPT4E$vm~*dIz(*RH0a-8$?yesOz<=D!1>bun`;{RY`VZ-%&xMt6@>;`t4N> zFGsrjgQMPpOTygb%k6bH48gt@cDFRDCm{Zk+xk;i_ zHKMi}a~J0(iBq%I4)oe(%r}By1}yLHUBxL-U~ULu@8|nN*_1IkNeSNHZ z3cNh6z<;$w8MpwTn3zKo8i-vw3p-a1fCLVXKYjt@fY|7|9M2if#7?74)}&}U?gr#l6%qb67XyU9z?2iJ~#*$ zCbR%GzaM$<$Dxt5d{_7f80K?a;XhxDlq;0sfhK*7Tz@MW*M?eP5>Nx@)&AT}SJ)S5 z_CVje19XA-;#+U&b8y|TyG}U@30-m5*)_Zu+Hu)krv-)1DD^Rb0QdlChTp(<8X;$| z-G;Xw&~H;0fR0uYTd~~r$XR)CkdpI<TKOf8O&tm0xIP(PXz+fGM!mYcPO8a{amP+=i$Bx zKr$p_6>_JNz6d!{K?gf|#A9J`UYaO;(GZwoj7`X%5d0pdBMA;-`f?=J>oMNo{`Mk_ zd{49Tc;@9Y!XXFl-w zBxkeqMV6OWe!`uQVDUw1!D61l5AUigvhWlt51OTBH!N+%sJ?$ z8Y3-CFZ+GTlgA_ARetjep7scA&A(1-=zSIqwR0`MGT86mPwb(;(2^_=ax(=CM{~}| zWgq#T?3W$6Wd^+iIn$nRVw0X{A9?I@-q7Y;ji33jqm5I|=a;j$JcAC^r-6o2x??OQqP60@l|~Xu1&5na0$+%#!j9va0%;bRcIYIVXg{Fz5X)cBWwxO zJU6)Apk}!Cg3pG@l+6XRb3V%L#@yk(4CV==3Yc%EocNN{H{cUnE3zi)SwULQ#;x+v zv_nQZTSUvsEDW7f-7ej;?M|DCV; zyJbNu1$~1AG(pTm{lKiml_9M-_^k%A?vVcB53ci`0ztUVqX37>2}3je!vMYhDWoo0 z00*#9QG_NAedduH7g)yQpBSLw=w6DP4ad)6xquYlqu!m}jL0TpxA=nK51x_B;b-N) z&?h0NUKRKUO~eM&TL5-g>^dI@5QK8(U4b?sD2E_EW1}W}D8)c(J0uLPs31(S(T#}z z2iMViRfMxSbW8&&e#jcVS_RnNpDutOkFf&rzjg<&kAq8t!MHH$czzy)`t6q`Ku1ww zsEZ&bfK>n*r>LdKwAjx{0^y_IUw4x(AaoS7@zRHRYU8_bRXCV9Kfk=@;pUQo30Us5)!gX7}u;wK_w}fVcmmrZO2*&x7 zN%(f)3;y(ue5@0neKk=b(q0R;2F?>e4x-*4t@wIC||36p2Bs8&)X}JWk3+z z*Nr5}e@Ih6mPO(cB)J{sh{78paKOF)zK3G>7Ynl$hCY&MG~_@qeo+~+@j>h!vaAmB zNZKRGobXKNAaU5_CuOuJi};2zqxB)H-hiTT$TC<#Y@5uB~)Kf%~9^a2G+fJN`eA z1(o%gu)aElb@^ZK0Q>181;oOO)Dad?_<+6fAFr2RNsj_QGlTVW`j}hte~=)8z)%I( z2+Ezgpv?g*mfsqQX_%<)pISB+@K@GI^I-Aqo`IC%dMnSM>>}xDn zvLdoG%5+36Z9*nyaAuF=i1V$9yv8ZLl_jZ>o%N<8@@W$ijZ-`OXZ{=u6!R_HoLN8T z_^NO2tElp!ib_rI!;(^GXv%MW7eBC8JRH=-pF@9kS*;!oph^XQkq}%}68S{dz^X!U z&;IQdw+&=-%i%%c!5c5u+$p*~9Q~xIh~F{k&`Yc1@?E>8qKb5#dlM%Niu_7Drr60! zJNF$peCUz-$n~KQkHudq-n?*IIw3yxpw%H~+YBA;hf|T&vzro}Sw?oZAB>9*xV>AQ z@%l_ubatBIk;2>K341y}JJ#C>=hz=8+DQ%`=j-`d(DE~eSEx;$ITaP3{m_u!)m42u zBk#hdGY<{T3a^Zx7`nVF)2-!*C01zKZnR#UCclIgEU3lw{RE zyX=)~7=llbWB~g8H`r(~`dytQkEi3>i(yX%%HU$OO#~|9k?T=!rG>1Kwf^_N`$=o` z`(oHA%JqLc0{#%#R6App}7duj@_A<--@z5yr8Z;(ms4A7z<)C*8G=5{q@x&A`R2lYRhXW%!ce<}nia|9!uM;k7{&R-CJc zHFti2Z}xPj8TSgYf~@l=rY<ZN&B}6^P%d{`Imkg)LL3?Rkilb7iBKY zMrRe#wtZb351FS7d{wE=vr`@{%~I1W)4Ud`BDGUlRd4bK?{3sK`vJdub3a2HX~Q(av%o-xFBmfFu>Juz44>tW$iEZ9(!gVWnc15Dc&1i zT>6)T%ICgqjAD^*Ke)S93r$`{(L^11#xBU-+QyX~v=0M%e=Nm+?tNltd= z#3Ao7f{ z!ZQQ!q0hzRKVBHT+}cUM`UQ5gc!JYphE%%x5d~}8OWi79K)Ay`33*)hy7osgzNeeg zvZa%5*iAWMR(1puc{8T`F|ENH+WEpj{l-L=(3xUfx|VGYtS9D)PyUk61I`08CpNK&Q|K60>|LHi_gBH&D3dKCPU;#j-y zMUkF<1p6x1EXKSV$*vQi+6yuZH9N-kbM#CGdfS58-DIXD_enV06Khsx>bEplP&3%W zShEn**Mu`5NmVPay@0t(bCVWRv&t=2a0b}7>!Si+^_luC2HX+@MJ@;9*9D+-LD)o# za@iW~&td7PkPH=MaVSn;Rszrtl5tX!k_37l#RZ}r*r1U(h>Gt)Q3<#%VxAiifa}cm zL4BH(B>76fxL{)Ql)!Ewc!LDWu^S*2!*M=9=R|*DaThQhF<7;dh*i|*Y#$)aQI0sA zef1ysrSf00g<46h*Z4#p%D~_MiE==$C>V!$niyQ<>9zPEyK$A0BtGyD54#K)$pIb8kX^Fh`>#d}KxdxGo@;7tC;G+NA= zR403nXRx)G0amWi$B^um?&&gO)n$6=DA&BWWlCm8-dO_WsmfGiT$v@ z7#M%6>tnx{$PassnTQk@C6E}uvN6SlJ?j4+>7Kmt$4p7$shJYn)*pU(DOXCVd1uEA z4|jbUCj5`uUUJVq8rxU61W|D7KDha#qgcxh6XJriuX=|O(Q{d zMcRH7B{Ko$ON0qK+c)^DR@#{V(CNo=42LhTZfrSRl=)y~p|+N;XvCkTR({tX$R^~p z%(Oo)Thv?GQ0cK(w_SI8Q2}fH;Jt^2``@Z}G}Fg>PI|@Gy%}DUoYi5gzal7WTc7<2 zBgF}QlRkS#Be||B)c+Y`=+HHiXsdUB#q?D1@_zlo{P4ktmwXIMEbj#xZE;DPI{Ioh zB7xfEqm@W)WUf!X*I`m|DnE|-SBItk?xKgw~efok4$oewYO$$!X`@d)y2KX#{M zN8w=u)10ouZ`UM$i*7$LWH+Gk&ZlYZyU8Z&rxJIvPEFiM$?h=qjqp4+kVyYNb>p`4 zE$8&tp`%`@xQ{+lld1d4qD+(9VET$arvNV^2nMPk2<-q~yAQG$YzjMvS)F8A^|)Fs zhJ@yC?LonXr68yD75-r58q9AM*|!vaQBE926(Fda#}GvJgyDuHqdrW(?R7t6MByjx z1E@q>ur$OFeg&c{3drDbmQHo|Ph~>-S5nXSCfut)saaSlVq8I#V!11R`UF<+uQ;B? zUEI+GdVL%{ECik5F(}A`2^4rwSZ*W1TLfuch7b87gMbJrCqgi63GyHme{)J71%0E{ ze5NdNCyENfSHtjh62y_wMex;dyqhGyhv}n4Kl!%;To;Px@kj(kTf0eG6wbc_ZvffT z>VEP>)I6tq07WH#)vub(6gvhBTZz~SL-M8zf86J+n{YbJ?6q=|c zgs@Q+geDA0RsO;vZdgH4N)+1CO5zeWDvcB`hH^k+|C8$|XiDBMg7zv>XaI8sIVCWx z|5LQCW#X+@;Lc#2$|E0&{$B`hA-tbt1*Ixb{1qz+0O1)T)4xH+zQ}Zs>u6phv0@RF zx}4%a?D`*shXEqjpPh*xy9@`0<6R^KIR*s{}O!ith|0(dpLZvpn>i#uYZ!aeLh}xa69G6 zINGN0yTM7B%70R)X^~a*t038ujtk=WGZSctHXmJu<|8r5WSTC*GHa%5r{i|$OB|mD zFMY{NlS0PA@xb{+>Q5aF2yAhsHmjU%)9qDDT{{ zvH!LG-G9V>6X|tgU$zNLpB9sQ5WXFV{07#EU~STC(AIg3^t?`5k=!xnKat9=NveL` zSyI662Rfw^D=3jfpZv$sz=2po#U%l>ursC zQNMh3cY!CZHE?7@&c|x+6iR*km+xg+A4(*yN%VZXeR%5d9AoBNrpm0I_T zyFcACdiJyLhmQK+zkcT0nd^PRyn_1Y-V`@OH=$nYpR`%ok4CW?BRdNEj1G`S2R;}b z;29n0HfkY_S~Q1UlHE$arF`4UD7kWYg!aJ8=y)ajFw&p+R@5+0&@fNhFi+gj{ce^s%pa>c?O2c8LbJkOxgY7#%X*Gxtwpmk(5$UV z&6|>%zY6;~U3u&bo7O+rS^vO&tmb-uVtRwFX}a@OdOdO}MGrP~r}_4Vt(n*}-OAEK zAIU)L6}%ErjnE5ue|$g^PAS`sYfTwa+t ziX947-f+N|BdWY1B62sPyaA7V&EtuCbEK8CLnH6=c#7Vft<}m;ru>rKf^w>6JA-FR z8XuKW!MOiowlj35M0Uy#Gzy-BBb2r-gP7v7FGWM2*hRE}Jk`TxE=L?^J2rYvaAj`! zDes)1MGX5O9sIB?zmzdnz4fbMABQg!-yIz1xP1euQ;o(_X+g@r&(XqWeH3Q+yFzF9 zPnxQ9N58D|r-7|Nf(t8#h^p74U&Q^3#aHAIRiDkqH`1^v@5=6UJ#gV08*RF#>sWX6 zQA6$frCfhOYHCHTGsZ8ds+Cu!9@Fgb&%*dun`(=csUt+~6vh|e`ioLm5Vcieg_Gt3 zy=OR+iE2>u{nR!OIVFJ^9slwSHih4){sqptuT zpVD>pHFNE*=XNP=%l;raHq@ghoIDLP<5uw142 zzPW?Pkoqs}IRM}!U>#_M{>zVpGv`1Q4n|lFamY`LG6=#b+Q{W_+!fOS`DWmI%dh~a zdrbgJ#IAkBu1P|A*fj~r2fHQ(S@Y6cSrKN&E(1gzzu-qkqYyj~|h7q!vpz9**`ftOq zl|HHy`jcOOM=}zt2)8I)7Le+)FuY$MZR;kNpeI9cfM|(Amq>BZX&nz_FH@^E1ha*LaNxg--yFE{z ztiO?c&(O5+#<<pjH-N6d7cQRdZrO|@r9Ppy3{aSf#E#@x4 z<%(1DMYvpL%ssNPwqy}i=?ZhJ2={CRdp(vX%VY+#m3Y0GNC)>6%Uzz!m84Gm%_)## z4o9*fvX{>B5oIbzuuaL{#@N6hn$z^GH!b8>mJs9tVALCEY6sKt{KX4F>P;l6fqEsft=JyMg6YP!u;lBTF00H`625bbhxi$Z#_yfUSv5h3DmX3Ex!bV&4zpo=n zcl5g;TpEVwkmMQkyQ(QfZUHD!sdd#kgjj!QH>gQsE>%{FmMc!>f-n$ScMT!I#JL;qeGOVE-q^ zv2^^C*njD;6XoU#*dTa zVHAbotC1io_Dj3h@W5_25@upQHGWJV*(`ycRK^;>LgI3gJdutA*~&5;Zzj_Okj-JZ z3D$s`LhG-DM`@$EWo&o^LeD;e}T0H>23G^Pvrh|{IxWyun4N; zk@~0t5ZpGAjMzrP8#KvR;A}9=|I;NeMAagC`x#Ff355lb?N4OS!U~UtF@M=Vqk%c4 zMn^v(v7A^nzei{{$pD7%<6!)w33O&L?6jOx1EUE-{|5C$uv{I}g?XTY&_oYYx*6-| z17tvtHbl+_<5#d;AOU5y5OV4G!#USn$%XpV`cD)}`gPOf)wce_!TT?U?etPl-i-%~ zXrBL5P*wfe)zHxB+rY;3$_m-3kapYIIjCmx6*rIDHB&X=R5v&=(^G}cjkTS@{dpTH>JAtc{ry0 zC|1rMx{$4%qkSQ()~!8GBu6bh?{%k{rwd%;{%Y#Z%Wr*s1&(tkij1XteH@LR*YS7n zeQLkW_vTP&Q}a3b=#)PUHW*shvHc03m^(_|b)_oFdGVD`B^~Fs7nK!{t$HteNB;Fx zU*7$DH8JB(QWAE0^@7V4eK6Il=>s)@cgJaRtvD5F*-Dz!OD!ETkMLOUP<&KrT z!+xeU2Dc2-ix@#RHP$QcP27>5b%=B9I^vhDncx*a{D+Nd&HdN29$(0*-=X(B280ZP zWs}NKk>NaYiyS}?=df~#?w_DlEtV?+KdT^~o&Wz~1Q8JRBgv!a_YHK4e+~4$-*e+6;xJX{CDLqDewf%z(s;0kX7HeI?a80PBe zs$dfj2=2(mB*2dqlkqj~u8_|a_iObiGM49mj)%)2IcG*0!x z#E?1UI1kIK%adt>$bqn*>wNwZ#?$tP>fe1ZO}i^yLAOWmLeMu}T1XWgY*YdniJO|p zfrI*YdtLuE3q_!(yfn+-=XtZuq4*1|VNLnJs|D5~PeSpxSi>Uto$6hDSqAR85~2MD zmiDAU$Qam^)6h+>%)mRvp&_vC#~WdV;g(p#a=5U3e$0{s+r-U(2F4n+%E2<9Q52zp z^&DiHHbN7FW=Qg$u*c|=Ci>ixd68lF!YVmn4F6R{oH2)7G!Yuu2?X~0{429n%x^SR zXe2(HLpTp?GA&+8GSrb`5y+*IFu+DPAjJ?gQb|B_d3eh)-Iqk<0NNk!}jZvvVBz_)xPpS>f8@`Fp3_&$I1oa z)vHZ}UDW?rhC07OX!ZYa;D7r+Zdf^S2yMHO20sI>ohaC&@QXJ8yPE{`;>HZTTO2X~ zDH$JR5M=GJT!1>xZ_+}SG!kY1n3(ff@~SVUySATK`+eNu!SMVh4yz~LcX`?Ct?)vt z_<1v6{!LzE*wV#mZ(m@d54AlnD7GU}m(PyLtFBI-NThl>t-2_l-lJA^@cR9AHtBXx z;{&hU7syuR-2B*Uuq$QA&9vHGy1L!XMks^Y`fZU}O5ayTHQ!!&l~2g)9c#5&J_$WL zH%P@7w|!h19nYcd_q=?fe(vkZo{cY$uWbzsLVk2#S5w*h_w<^vGsd#n`rXBaFS+~k zZEVKWcBg#MRGLxVR8~{lcRN+BAnU%vro7JDC(*^k$G6d|Wp{mW5W>D5tX@nhRr;_*jv-gdQjoQ~IWtpYRW;PAvux3=F zZPrFRJFsnv>@<9?ygnG+T4=Z4Cz%#Gxo>*%t*~ePR((hhX#POTU#+LDfAVZG?%z#W zrZDo4mJiH;3twRK+Ds2CzZ&4@?P()6k7d2~FKBNwrS=SOvi_r(ZEju0mU~fj>Qphi zmUQ9=v)2nUpB*S{x8!C1b=6tB&f@6>uNa-qD;qnnZ0WSH?(W#E+iBt6Zu8kmD}()z z=cL4G-}<6<9Lp2p4vJC@2n#Jv`*Nmd2>UI&&7yy%F%zb`jzm4vn3pR22%;0q-CItS z3P8yq-lu^)vDRH_(nxog(j6)YNVf_@cekK)r%H+v zD$)(oAl)$3(A^C2U7+{<#QQ$)`>pT4{;q|?nl%H%%=w*t_CEWZ>phqO*uJIE)Wija zvQkihKjhu1pK#3Lrvcl zLH$il2hiO|k%37tn7N=EI@lmMaO^MVZI3$0j+wGHBOnl13G};djVE{txZ{*^19u3) zvp^3*00t8ibc2A!{Q~jkVYGs$f+~PRhSCf7)&|D~t`7}_z+iHMr&wU0kU+!Ro;BO! z-^1>A!0_fKQNd(95H<>!7=waUQ&^`Mx(j%743TffU~jiH-&%++;_?F96mLo?Oft0w*93L%|%WP5+|e1=eWC$Gappl!5)@RrZ2@BlZ!gRv3U)n_EPh1bxZ;m+JQ@xP=_-pI#L$-k$6 z&)^?T^(5! zdM6MrJN4cTZ**9n@xcwsw>~kyXerhmG~b_XI1qMuT2}N_l(+~`+|OzqYPg|W>JxL5 z+x_vjrXot!uWKFbXlp{cKW6~s(bmp0#|bp`F-K$)Adj8Lq-%XY+7(^P#8ibRj@>Tc z4u@!m(uZ_wVqOxHHH!!pv zi`)JB7XLNMk{RpZ{Hw&sww<5*q|4 z2b$yt-ir#<6a)+m@1amq3JNetjt(fy2mci2C=~H6O=yD2n4mb=-Xu;Rz%SZ1B5~-?Sz90fYqx zG}H0^KKQJF&4G3uMv)r`Eb6Po0kek&vcO=9QGviTeDO2kN~w96C@}IY24?pQ#GZ%I z2v(AU+5H2R2%Mlm=K5_p0FI5UU?mpVHY89F2D?=wDu7w|yUtL++Li%SH2^r@F2rqJ zG%9Ov0yf&V6Wy9$rxsyUf|VrT?ZDeLhJtRKz$zWU@rrS?*Yr8CP3NE8twy(7OD%yH zE0i0U@ZgUX?j>}$y8YJa3bP-xl)1VSST+(LwBnNn@Ff`tgs$8PQIJDc<8Q5 z0N6)e`1J0LVNVVDro`qKJOxVan+hN zXd(sXPT=*FE}-ab0Di^1{a+LHQa!)~Jn*omz+Uarh5?}h!2Ko+?CoZmQv)gdy}#QE zaLdU8d$?bv2QmORHXqiqQwD^rY_H}3di(1RFrO|(9u@cln96ua>7*$rXawokj1ELq zDGdZ>Z-Fs7Fn8b0=sPJ`mti$KV^GRda1{weiTZo+G#cmk-tL@6sfQFfGQ(2UgHk8> z{}^T$1!H(nn6XeUF;g6>3$L!(|H1}){4v84QyeP%l6p5N#eUnAMg}HOrNk)+8>Jrn zUZx-4C}k~886WJl3k+)l)0&&NQ%E-!e3?m@?u1fs^)C~m?C-d-gaLGt)Y};TKeZm~ zt_T0QjzNXiiRw&0e`uAV@J_7jNtTM`xy9^K(m`LnnCsl-<|_|;w2Y;mH|SCo*;}g* zS0+>QJA|Hk?&nx0!@W9N_(XkZnMUlmZm~5DBoRJaH^$AQ4J&~L_vWIYHw^RyGcV7cpyf)RhX07pOo?}EYJ}K z(-#!P1NZ%tA#*z$*tg*XwMP4Gr@Yy!vkG{WTAF$@!P~n~XbM2*D8a@5vSs5XkYpnA z|8(=jTAMO}OPo+l$ zVp@bKcw9V|iI-!^y>6|0&1oU#P1rOvwtI*x>W!^7r(oOUty_Lo*D`^p3Hfp+7h07i z+IvYA0pBuJv&#~!^}b`5)ikxTdyHP|jb&#@zq)0qX4lX-RkC}m7giww+fs8wV9%nM z);V*J>RFoBeKG%B!JcR8v0-yj>&&y|xnbK}_r>&c1>sPA1@cc1a;wi3QozkC;9g7M z%kFapu5x8X^4`IZvT*p9(7l7vp&-u<;D^lq^woEm<|M>0EkHWH9{=kaf`PbNPQ}}$<(0TmPR8AB;^m_BU0iEjiEriNWy4VGC$Y>3vCL4h z%$@N?bWOv&Ds_iXaGLg6j^k+r(cOmYA<+}>YSX!$aBm58gwMlcZ;azh-c7_Bl`4Bp>i52AQoplVwM#ub)_)NT2bPRb$#{!PZ8Qi_EA=hsgv*xJoB7Rmlit#OY57Hc)OK)~Z zjwexSUX$MzRTD4e2{lN6?q$?H4N*jY?bM)gPeVfrn~3NE(OsGc@vuiq3Rri@W;$1? zi0_bL-61Asc%W%)^8Sget4_0`Vti?I>^)^gs|VfoD=oYkDc3dLHbw(t4J)DtU^y3w zRfjhA*SqBt=Dus0==JDcPUcl)L@2< zo=puCpHEuqnNE=^^&DL!+)&)^om%ad!4{hs1Jzui`QDCbh{F!A%4?ckdYDp^wqFT` zA!I7CjxtGN0gI!t}V^IHdOfebQN+X9~ zlE1c}c7V3OA!-SF1C{}vkDQyT>-!btQ`6m*W+4N~ewJMU*jBTU@cVr1TJl;sK{?3b zVW3M4@7sASF!vS7!nvhcP?<;xZJSZnB9a< zWp=w^+QBPNP{qcYHX6x;9C@Ysy>~-lYQc`u+4<UhZ1<_#1Fkz5s+habjQ`IR_`H{G$3)bF;# zKgz4+^MyIfsuRKHetB6rUP3v_-n)vOdOn>f-utzEW&et=|626g?l*|{HDUR2;-fW2 z6r2uJ_Pes-x<3l|7B1>US7Ag1cE~_B&NPSP9Iga%3b(f6oJgBp~JQy<6@>RWb z*||LF(_5Yq5%+vN$xygKeFH@X105(Md7?z>q%x(QL97M3`L~aYdjy~ zC4+lI`(4B!nlc0559}l$6sFqYtc;W%?jxoP_h5{T=8gS+hDZ%4KByPqQ&cF?E+gzd zOc;g%EAhn8jvc4YeGw3U@Ft=trp`7@{F5;={R|Nb zYHd(cKY0WMZ!y%HQR9;+{=*r>+qwFgHoGs_{65DXK5-L7CITB%FVYXILV0B0v~xq0 ziXQU&j-kI*JJ1Pk=Xk7LnuEz*Am77e&swO++sQ)kwKSJK0}gy}{Q?7zGrk*>af&3i z)QyFBAZSdtntp)mOA)Q62OCm%K~&gfi;cFwYDB1_{C#Gcv6r#ttyLtS-F?gZ8k9GD zm{YvB*ZWcHo+^MB>7*lW%9AYzH0+vwmXyk{K9*118Jax86#W8* zPd@t;ykOpToiw$)6k68mZ3P7Nee%GCBy;c-aSU*hF- z&{c@?<9;2y!m{W3E6)(WL(_cklCs}XL^8*y9gS9CGkOY5am6llFBy;f8aH|t2S@C= zyX`S0#&M;FmsE4WLn&T{ocHf`zdvM&Q!iwLWXH4YVn{h3#I*TNfs4xaS;cIYacx_$ z{Y+l5QMJ9vlr$M67dH%(W=fWUvenNDaE%ejSx0zPawFrFLWOefir&WjX!v~hK^feKeJoiQMSFTrd#;T)V3C3kG{Z)lzTMN zn_1b?K=^XaRHI%*B%$&loqY-PZ4eha*XDpjYJizCanW`$jzWc-EXg8stk<4Km^umr zNwtTPPTdl{uUh_#wg#xiN~lA$G$fv;lZWas>Yi5uTLA!BZ$>IcB1Jo zIB?W<$OJvpT#GGj9iEHny>_V>X*XP(j`1F{9nZ&A=$s!%kWX*6oF!#t*21Yi`_4%U z7(%;2KYf-S7o}?-c#RKF6`h@PWa%|GX66%4jS83YtRyNP?K?DFTdlV)_eP<5E=@ZO ze{<|6gJtPmI4U_`5QDN7u*h<0cmm)%s2ARnVjBj&#t^^C@{*UXQ4KRo#VfYn9TL86 z%r6#K4@7p3ktxPS5PlA4lQ^4aiuQ?1MGvjeuP8%yWG+jzAsida=Zhn8`Sm#4=hfGn zjIT2?N4%*{o##prBQx6Dj=Rj6Dv!{f>Yhcol-fhnPF`KC)$WY%cM0?fou6b)`Sv$l zf1f&%nDaHTKTTRt+?G(7Nr*8Bvv_1syp7^iGVS{=z@#2=l2xAN>2o_0}nOpFCse6|2!^XsX?qg=L*F zY1Rm(l2oz$38feb9%2@Pk1}}{>oX{4d`+*csYGYJcn%P7&$$M72?$c7r7HKQz0cew zQq?hE+LTE9v)vn-y`ETip{?ZaI_qefA-UYMjc!J#gc9*z2kmY~S1rZ}+|Ao7zQ{Rg zy2sOel`fM7;aMX(J`W{u#2J`UTKiJAhC6wox`eUlFrX&3!N1j)Uot3VD3;rQAK8(u z)zF{S7u_#bK0es=0Ji=W`g2%_NlInWSw@jYBPKj^DxRt#kZKYy;Z%t)Px%?vx)qwD zi5Ka+=RVNxV$FT4I6X*I8bg#~eChxC@rgbHLlDx@I@)~qxynzv z7)MY)ylJO=K3uffQGVdjnE>_)KA9@?e`e=R{r$e^6~DS zgi|BDJAMu9#_;Rt zNbH%f9r=d^La>|4i2DrFAtx#OGF=>rSxAb7qQJG3?RYkR#(#Lb@o;H$TQyuBf0@ah z>(e7Tq#^cm->vUi8fm`apBcfS6BfqQE<_|YEE3@@q@kEUR+(QU5C)|gI%>gp$lo## z4X`sQaCN*DD2F%dw#U*uXA5Ry3qE{nllDS7!n+C+zTqaF3K!@xRj+|d!Q)Q6AC;B;r_!`8NzC6C#+#{(ba zTDPbjnN++uZW-%+fLN9tmV9$iV8JIRzNLigLSx~+X6zgHYd-Td`UCIj!^MJkj zc_dEqd}B}>q{BnUUtGquAJt-T+Rm^2a`m`O>d`T~ydgS|^){j3KBb?aKp7n)S0R%` z0~(ECx^A>iyiTlPE7Iahf*Cv)E?I?Ro$KC7pK|8DM;7kREL3RZ3gU!C*$H6`pJMD~ zd@(_Jvp*DZ&yi@F+fg&Z)Qj@57e$6iKqL-M?>(*-)U>KdCO9{Ds}Yu*$)Ql=Ay*9X zy8v|`Ce6ym=J5A9U#Sz2$#RhE!fDhq4dY+vM{8MC#33sh||T0{2AXGE8V-$wGfbg5gR*9gM0MEC=+#mF@wO- zA@*L}w-IN~;fN)a(VO(ce#ey_mF5Wam+ zd{ml-p=Qd@I@1pVmViaW_Q~!YXIKpHD2iF-;r`7}kS)Tb0#SpEU6GW(tOoD$Oj7*n z=6MCDsfi@BKrpe9)b9cxG6!q(?n9dDlc1i^C%1;ydq~!@D+Fr99biEqsXX zsQ-~GXY{kagGXo7!i;5=bgW#AJoI#2lyG0gna3_Z?I`zrK-@1%c&MT;WL12aUP}b9e>QjG@`~dtD}DSjgw9!*!|t;$;Trx`sEiJ-}%KEf@O}mqAt&EHw9l^ zPg}qLyg7`146+U8e8rolSbi>^ZoD*nGQRJwU?USAF4W>Td=fPMxYuKFzN^C1M9(?Y z%NvhbIBzVI>4dH4JZ{p~u!DrDe% zw)Iu?$cY8;GT0@z&Z&5hC3NSaMo;30PuvUXfqVZv6Juk}?o)(*1^X3g@A=6dPV2}C zKrI15+Qi(*$SBAJ-w4&@E^tZ+P*FG^TZ>ck`+ZtOG9fMyWQp&`e2UGZhSbrmru0!h z3mw_}71KHOMeOjKdjwixo+8nQJjMf2o4(JoackAZ!}=6h*|C&*I+d{$lta(5G*8f| z*DPB;WT7iaFygat!Z5(v^)m!hpEe|wPr2V$Mub0*h^jno&5cUEf+58{H1c($PU()Y zU}t?5GgO2YXX?K}NkT&5xIM-Abyyh~0Y9!=k{}rPO1uprXXu%Z$a;#qswi zW|Bj0GWdWyYxc?y+3dh*n_3$pbe5OR%go4=B7Bb3Mvnc)hd3nmLo4f}wU`9|%6)=F z38pRq3|ugN$P6-P`3I8bek(^wJjiVf#~};VpE3>2Ws6cT_p3AQ+!Ho<;pOzL&qwRU zQnmA5`=+5FTYN%Bb>mgz7yOX77Ft_{PiN^L&!~Jk6sFtojFWmcmj-;Al}P0q2twfF z^7&rR_@%y`$@h+8!80EqeggAn^DN!-4<90~zdeoEI%*xNPq!9R_;xOyVf?*bfQ!oP zsBX{7I|^I9roP{Z^vezq2wmqVXEG^kACE4ryww!klMo&aW7~N&2u9Fg^Jo5F#r6Fb zzynnxF`j$d@#@Ykq6`=BIFib4AO_BB=qF$5B@5EBGS$c_)!}*a{Ld=Mv z_p)P+YUVbDnwZ+x=3nB)u$)NR6Jy7{n(R!4gyAbSV}$NEa4Y34yVO zn+}SOit?}|A(hM79te}csFDed_tBDHDn9SeFN*3k1rMx-v&~&xyPj1K31>Jj|Lknd zmNh+$Bw1`i4W~GiHCbrG-g_i!bXW``*qMCKCL-cw?aKVHGER9?pk{8&ZuX*1pe3{h z??@799T{on*_R*d{6)`DYMuzWpld(3E}fN?vKH)YlX0jF!z=DGnOz=F`uxcZ8t_RN z!}fg~28x%)6Sjs2MR8a|e&GqDpB1$pCQd-iQ3na3PGb9O{YSM|<39>FcM^p)Nfrb& z0$kotVGhydln$ly;;Q5m#=Jvipbulvv<~9gw=S@@Pfiy6ReooPFH>V;$b4hd$w@)H z`UiG(GH%&B#vzZNPLr2EyV*peB1F39*U|L(Iv^Yt0#hYQcee#*+->9EJ;bAYn+|R) zukj)g60gWOc}d^i?lrj{>!hY|+#P=%@Z>3!j7C_C&?_6a&r9*&!D{;-j6E#FZ%VsHgzNjB)Q+ z!2!-fiB)F92TARC=lNM^fVvwp ziF>~~q#0<(Qm#1GTges@c5*P=T`C-ychFaN(uY3Y<@gry4jVIo@Q4xG*l1MLieAxp zzK9|ru}KK+fqOMH^AIrC8tyuBhRwA)7Bqc@$_@prejz#>W#0%6>O!OcEOht#oCq3~ z1#SA0&aQl#o)Ia+^Y%qI2;NBPNBf*XI2&$#E9IP>Sr*fw-N>T%&I-2L{q6R6|D9-PDH(I`Ck%T16> zG4JQLCE=@u+{?f0^r>vypkO8%tHCHnS^7EJ#x>Q^%ExyX?1MolUQxTC->@@+IcIvz zsfo$0Mc*68lZ4TA7Sw;zbtWy81$9pF=$GH*d#Jb8?CaT|jJ(m$I6A0NZ;7_-DXZ=_ zofGmtvCTE2?4)FMJSK3?)HKSozOSz#td~k`j&E<*+3F;+qG`0sGTsYna0aRv`?7jP zvQNYD!Wd3~Jv5{uv9QALZE$!%!m{;#S?0NVUqqL?hPcnS74qH$@+7+pj9UOQH8MsD zsPU3CLFGY3C65M5KL!j;qu_nA7*6T*U@4?7SEPmM*4XscoDUZl_rkpFZKO;zOcZ?X zqDE$E$EGBuqAqjiB*5vD%-}0+mUQskr5tX*O*|vX@&14|A0avfdNzKf!1R#&6O1MAjDtP8?5e4rkoS}kvbmohLF7! zYQj{=DsL`{VJ&I*0W*Gu#GHhLj-f@Sn@5S8`(Q!p&LZ|bC2rE}ZDFZKiJ@Q3B&{5( zT71x79lL5>iYn{_3T&vdrivyCA1v(6?WI(G6clV?LOgt)+h}N5DB5^=X!ux5c|mPd zACBYoHCC#qIV<&PjVY+H`ICPDYec7_%on|+i5yYj=tUd2?>6$%=F!EXWTQm7)fMtT zYPRk@+%z7rq3s`b6=0t&~B{{@5yzu$`2o*yo8UnyJZw zob4!`6#T4kYD6eO+Y87hRxpSqaTj0e4&F_f=Na9N`fA%)$}tKBpD|SE;?>ZalhH1M zbb#vfO7>nC$90v`_ZC#w2UrAnBnXeAh(`k(DcYSUx`#Gzb|H9Q%1PD4UO~r1)k0C;M7T%PrY0)g zDHvP1dS83lKCjbnNzUecvD+8lFP>$%15z&8(uy}WvX-J%+7PgpM&V`MCPgKR7OS~3ca^HDZ}3zJ3juBMRm^M zWqQ4^{e1BU5n>aMLY3>(tTfJM?VG>x>30!I%+*Cx$zDTh@pV#U^KFLshUaAJTcEuR zhyA#3WCbKwA1{ZS;&#@a8<3I(Hkx|kH3a7Kv8YaBcZ^fjGI_Q8ASWOSRd7BoqgU3- z2bk$ckE78!77R$_Ce{>8WNnadC7JZ%_2PWI931drwmvT_N1fh}Xe6NjxaBwCg2eZ; zNbOa3T^-xWcklIO44&D@_9u`MTT{~4Ais?%UiqJtPFqNHt{UI2(k1gPb$qG4 z?Djk8ZE*qFFd6lSRBwoUW2guZsZRwa6sqHRtGD={MUatN)YHv%r=85!wksn=6C+De zD&*w$HMDC(FWPk91NhbpH#=3Dc=F;;_XE`}yN-VMW{A$F^0>L$NPm?qN(^%&)!~YQuV1kqN*jC#tBqDMz?3ZH=`YH6 zlOmz2E9PcR`KeV0E*b!2OU31p>ktwo^f_HoRF*1!4Os0w$${SZPrSg8bas-6c5Y67 zs+H)q=w;K5D)UgyW8ASWpS5=obE$*&3^BHdiRzQy{VBehiTU!QsnmKqvy5Z=IC5wQ z+i8)F!v*_SyNC$^Oe+NOeuvY1!h*nIsYKE>v{wye^0Bcx5TAKCl7r8?bB|M zCk9!`{tTCvUC9EU*}L2&5uvyg!YH=pqVIc{i6YUT?pVhMxDBOxoM<@wjI(25KBE~v ze8zNVZHx2eL=#J0?dP;Qwfd(Ggo)P)mnR%!*NcrM*FKjO2d)8z?N8B3$+bt!QlnT{ z67d#%Fi&VJA-SU$0{bcnrga!py#mjl_A$@y49VL~P0(srs3N?07VPVVkT1LzSI9-K ziQ53bqSL0%xyRkmM7G-9>)PGc!~Dyo;kmO02a|yZfn$)=?1~%{QT%y3(fmZ_=_zkZQ7Urz^R`O+|{DkFDaUY1pa? zjS)XXMmk@2-&4|V+}oP+Q?W&&d$B1v^`uymRdn)Hup-_%|%6niIJN%JoG{ zOZs`cLSFH+MIrGvsTkTe_K^VTctdGg7h7UJd(GFP5r-PgKNx`leZ#8YbFGMTHW!J>PN`(M9N4V^IO&S`luc^G7VLL^U| z7^GiNtXu4Ciq!g2CmPYZPp{9lD?cb9Y?x_y!m|&zkT|g4E1w^8G~lX8$&Y}a)E``k z!+B4Aw@s(}9t2M-vx{FP9K@s<7-X`XUm!@wE}TaK*%OtY z&2-|8sp0pyBAmVMxaFRH(XB3h;C#Y%aIrA$_FOIJ;$up#KwU~D5rtclatXVLODOxIFveVBkLsF>kJp_+*^}5%SCr`c2&2glC3mVf^?iqu02MfnuKf)SlhJG z_E0Y60oO3cLo{$#2vKy{vQK}ohEXHILxn`46_^f)71X{HVzi#N=eC@?8hO6or<=&^ zRw&F%1iQq`cDx^cwNxFlN8~j=WrSqan3XIDVTBc|f0<5c;`HjG#6vl6y?HTV4*3PV z9O672^gKdkbPbrVW^w2al1r0ADX2b6lDoh6!q14)(Z83N9G7x0HW`eK_XqMQ@Vefz z>b>HnK8s1cI^Bn$Q7_-&+izEmTzq%pJ0KxkYgxQx4{**gAsiHMU$xOWN5*f7v z-ZU-s-=kjP9z0f;bF#kCblVDH0-Gd(m|lW2N4+G!9k)@03>>59T&XIskq&QRE1zh5 zGZ5zo9-1lv=Z^frAv;Bqvt}tXgts8Fyu@h9qh69u`I-bL^E@MSd3LYrlU?TPIiu@S zEURhbs!MjnhVGy@$0mvGcb=+IpSLz!0q8g_`7dCSl8~#tK00V0dI}G6Cxy*-P{A_0 z&1e=u@x@d3bZhQOuw*wLHks@c^2aTtt|?^OGnvjpoZoQeJc<0Sob2VPXUX7a%F-a? z@03V|c0-LqNt0VQ*aYy(1yds7fX$VxPf zPw#335n@YnhvG&E0TLJ#r3?ktmUF(#Frht#0Zi?Pi&+_k)#j~?bLNhN6TkW~Pon+; zglt|aA^ImwZ5Vp=@eNU$YrBK!DhU5o+ra%#9~FCTvPO@og?vvD+Qv7a#0!#vd~MM2 zXP`Y;+rlH2e$O6p$h|GR`nYyd{Ph-j!);OOFD%k~f_T2)FNtQLfJBnj9R=+ClR zlCs&!c9TE3yb*vttjVd0aGq$=QZ_dS+~4D9dX$QYS;YFS3p_exm!HD`v{q)MWf3HM zTN4FU6HN^tA1vv5!E)*{CLq?skbm~GboMCq`a6&fDjvitaUUEk@Z3Albl{va9bb6< z?zWh{kp(7IITU-ILc4nu*xv0q0ZV#w-Ik1T_T+gu{JTu(ozx3!8y6{>dJ@oPLgFBj9)LzaiL1n^gxhd4Ts3jgMDhuo8s=U{Jr{V5r z?g>?Axozt9id}p*@dQPr_{(T)UFL`9I!GOktZbcf97&}kiyhl5()R5j&qr65=8cC9 zn6cMn(XGZ;)cG&$$4j5HExW|E_;13S*-|mU_vEOKea*p+ZZO-sOUM1~{@lL%8hH&; z?vj(1kKc>Ac@?jxSxyOz`wr_}!3sMF5HF6$%5x9~;~e8wmJVMo?>8OFyt>jwbrvWe zWZ{Wt$QMigD^t4NB&Xf4LU)tb$T0GJr9aomwwrPym$#daaz`FV$s*(m&I@CTpYc%t zH0)5l{#PN5{7d^_Sh3G=~<>iEL7yBzW(~=m07M3fR3nHWt+w@7rtM|HM z^_j>TQ6l)e5CK#h571s9ON5f9BT>5lQ?QN~Z$@*orCE-a&|S5k_&bcpNgv+`S15a$ zUN>{c_xsL(5vZYBIO1fRIl96#jhqgXX!oAdg|xExaGB(kff%0zKtVVc50Lc(j-GQyC$h(!9Ug;l zsMA1>psI7$-BnXF$yPRHNSL8|YJ6OZGUa8?&om_) zrCebwBQy7hJUVml(>Q+fagzWMRptXydnsOOcSqlOf3HgE_+e(8-|C&4$ULjUUAMK# z)wW<#Q5EmG5uzb7N3M!CP1&}FM)nZCjb+o1TiBn^OhsA%Z2ImkmFn}1_ma9^OV!7L zAN8nfV!)*dRyeoze48?>=o~(AjC&lF6}Fi&^nKbV>C%~Pt)Aoq3Yo7V;B*(5F^L5d20?Vsds$CE-R%z+mqLFMJ^(e}FG|w@K;fJOXV+4~ zZV>|b9w0*M`IIo7w6c(flZU;N$OuvZnPBJqxUu%27a~ZVFMy{iOK!O|`h*O)G+K!u zJ@rLH-F9kg^Ghk_rB;Sk2PCAC`@6B=@1QNzN!H%~W~?$1Z@R?yNV0fEo< z;kXIiX@NMjA8Ua=_8&q2rqZG&{@p(F{BI+H6KJO`;{YN0DGU83KtlnoT+;8JH?i9x z*Q4d=BmYzMTm_+&&f$RuR0RpzR3C-{Qe}#qSyTlvj#LkR-XrRIK%6I;VU=aQvTR=P zF%$bN3HeYX7ZA*QLfcMIjTqQ64Gda+5nYellT)Sj|03c9%uqJ^Nn|bq1q@lM>yJ0c zd0YQUz-eA1o-ss`e1?+qH7ja)Tbopp6ocXwI^TBCchkFZ%uHzy~0Qt9Ce* znXljUN2Jy&o)p&}*DtPu(KGs$GDE;Z4(>?A$h>+eXq#Bd_S%br>3|Vpeoh`w85Ry< zz*sspHbGjxdY=Pi=a(eV1@%`GM%Q|FXMy=NYMUAUqR9Eck>LM*BsjhArZv2iy6I|k z;pBz`y}0;Y6N`@9h7c;Uw-?Y5@{*oN$Lu-6FT;|D<7-Lm{g-+IJnTRsw1!EtTJx7e zBk`9)Lp$7o*Y2O3fy^UebO7N)5RDHyn;6hPooqim1mWQ1U)|*!9MLH7cr)1WudPPe z4SV5LTE^Ktk&OAl%In6ft4#@W68_qFdVK?M3f3rF@%rRh z<)8XF$rFnDAAz6v@YXdqTbt#Kji|i6QtB5iZJ>BMTxC8THp<#p>Gi`*p;ptYJ4tp!9xi z2;*`Ek{@Cp;9NJUz|0RxmHHXdg2>3u3Ggb$uhc%zH4UZWZCawaTeD|4bQ-id-ot-U zwu1U;?@#G#P~h{72}0M0*@mNjbHsuE+cpY*;Av2gX`4wVW~@7BBTlXqoa_d*EU0Lo zu=R){Q*%hLy`}M{LOTrqxEi?okF%kriR~8|-?P*jdqGorqurS{n@~Bpm7=^}`gaA7 zRkUEM9*OQ?yfnEzz>JFZ#XO2!paX3;F}V;v!By!Ysy!pYV;?H}y|+pbzRSI32}~vt zbrxTJG!qw$g$1=pWImvA)L$Dr{Gqm$B5C-0>tK2;Ao-%qwW93r%K_1(lZB3Iy>>4} z%?@bies$+`jV|g(i4vE^ke+Tn{43oZ4)njd@fCD+s`Xi98wg={GcLiirc-)E;5DNn ze-XcIO|qYt>(GLK0NYio1v_nORhZl2M`ho@eZTm}kKa%Kb*i#1o|yHg=Pe)iNoM*D zVIzXcx0H*^4L|DE!0xo{T9XLk|7!2|OEr}8lCDcb>#L%6WS~xY{Pq~Bd|IaW+_5>K z;b9by3IHBfXY&tRtVE2yQ%bsvG_o}?2_^i&9aRzPQhrlh-<_wa}|&SM=Nb=oU>9eGCy2hsO6kQs4)`LJ2^wW&tsR1rXb2T}K_uy!gaKkVw~@b4hW zC#ECzw=^)isEzHZ9j0JPdhmspql%74f6FT*Z}_D=lZDMxn8y;3f)h%eK6Lm>nF1~{wBwehbYh)xuK*$si}^%Q0TiY zoJdg!{X4P4I$EwudW^w%(`*6LS7(B|$Rj#PT;%wUlGgaY8z-31M{N)MZWVc>OAPt* z=cTKEDJ;mZsUDr9Uz*B8gZM9WNQN$#bS)~!A$R%?AGRl5 zQzJ3U6~sWOP`E@;Eqof`5?mO=Zm4@=2a1{z`}Z96HHYpgIVu8v8*DEE?2c}{aQ6h9 z)nyj0wY&fGK_4Dad+X#3`IPzL(C!xu$#|R+NsGnf!A0bc0grU>c}I8!$wHSM?Hs4GapZa;+moVp2oLqTJpks57LqDE)ILyidj*@~0LIcT zif&j$_zPgRA^Iwx?3Su8_e z)&PNhgG@$90T|{WacXm<)>o1}$gQk6_>Fg#c~H0r;xUkK042)bm}w0g5IRC+AlR|u zw=hPG%m{8v#63Q_Mbhunv&bC;P!Hn<=*NuC^5d8Pqy+x6#Bu`u-=bCgU!qm>hBHXN zLWvbp*6EP~gPvup{1;)bTtl%^YZ-Hb05RQN?zop4Y zzKc3->rwD&E5K8b#wx6%BSlsxk>$7VzXlnh*i@j3^8g3}08YXAzo|!`r@ij9a`>OJ z;rpU3Ak;4di~k5jKL0Kdd71wfh`JDz1Mh_2mEi>D&mm*{n>euL`b!ETwC6%|uK4q8 zsP{O8OAk&oBK{)_IyfKrblnLNM6>;H=BvYya7v;*0b5=y4jubn!=7N z)G?V%F;%rq_st|-4%iEmx$L|2)I)r4ZH_J>H;$@tBfwFGF!#LaxmP*h~$LsJmIrbh*c)9c?FKSsqM->u;EruLDt)>O6Nc0P8p%h9jGDpfQC`sx9Y8-xJfGP2@7g@}!G$mqFRTZEG3qT2j zN;em)_YQ{$@apN!Zd@AFq{VKMe0^d6qUm%vbIPai2xXT37^m(Eq7PB~k^jscL?h|- zhn~A9-3mtzzm0A&^m(3TZ3L*OHlj@z6Tqua-cKRv0u2a-x6vDi3#BkW2w&qoU^)Wv zZD@x$9XEdzC@N@V9ET|f1Zu@2QvOtxTwPCp^Y3-)CT8Lt>)wv*V@ZFkXCgqD z$WOd~RPK@G{CyVk<%Eoh93mf1K?wm|Q-xY{4Tlc<<9ur}jOp_Z?X9CKQ}{@%g&dCzV?&9zXvZD6?;h>YjqPi&p&l6b_-97`e;qcB$P7;@ zB;g*vt#IVS%E?u?d>bgn-;v0d@<>jHzoO#54u5}&*Zd!({r@+;*d2D*9&eVDNM{lv z;Zbd7-l&{J1L#UR`Yo--^HMHXTvkv&&P}jiAyFN^k8B!hwM5yUu=!p2enq8U?o=ND zV5#mq&hmlbN|~<|^elozyKj=|Z@?6<<>;fE(^qz|_9o_Uyu3@*ic z-ZuPc85422I! z=fU)-AN)%#rx_pmwtYf`$*Vxejsh~ zN%zfA;Z2zQlk@ps@(c29e)$^*jT&(U8*|>E{#}^`reg7sv?lp+?r=Zo>_owG!3YzH z={0RyP~{@LmIB?%*5SEA^vE)2H+Bd7102lc_DB;do6DtgRJAj9nbm{%Ovf6T?R_Iyq+z`NL7qwSK z+kQ(GP5L`5?{0x1^=iPwWoh`^i*zqN7naxGc50JbYwVj0JRgXKSmXKH{-|J6brOLb z1lSyXzN0Co)ZvSRGk(x!RZStZ=FpqNo-s|s0XD=kE5DJ|ey@7QASB8-n?vaZGbhMIo+FjIaVYO%~T zUOakx+=UG^NuntFR=4FUqHymKxJsShPgZcuM~dG8)SYm8p>PG6vom`9vxVV+)(J-r3V1(J$Yl)Tz+M1S-wN0}Sbh$O|HRZAeolYckOkN%XLnXea@OJk1Z#~BtgimZ#3VkuK7H= z%MWMJZ&vy)Q$I%+JG;DcNJOG#qL~@IEs*dh30^8<8iIKeJTg@##g>U;-))krn}<57#Ocf2Hm|Eb^Bfv*+q=8qftg79#PfT zb#lsR${z}>*~nk@F3k^)(jbID; z7O3_7X-q_D*v^cj9O-llT-c#)xhU7j5IYB_(d!9a<2D?P#(zUd=+LwkYrllj$ra~s z$69CSh`}hiXwjB+?92J)@=s0&Ew(N&C69e)o2!2C6YTlMPvBV+J`!@%npl5~7I5mq9TG2PwoL`OHgwBSPfuK2i69}5GaDwK#)uWlp znU_XWD`G2oeD@KtsQe#3a68i%R@bFHe+8Xc0pUM#^Bim+f;(_!UDlMI(I0gyK%V73 zj=JYY$}WaG7LY(p(iny8m1l#nl#MtN_6~af1qisR0eQxNCC`%O7q;70C$k8=K81Y+ zLmsTjD?B)dFX~bx*fnE`m>s;yJaZn7LFP#1gDg)3y^IIf+koYYF$$`M31YCYxNLvv z^MJix;l68_)b#qVqtQ01(-{uh13_#->xSwnXkkX_CFoOt-F|bbmGokgT8~LXA0M0| zz&3tMU%{Lq%%1ALOgF@Mt;9G(oWF}%m(GmBJBuVK(Jyeh=zS-{-WmAqY#jn73hp>d zyP|tLGf8&Rt1KJ=47A09+J%N!-Gn9-{^Js+ZSi~KrwEhRN^bw~ZK7<}*U+W4$}22Q z_Vz`V8R9A`E}bamYg2@b)A7Trn>QdB!GqDo_Vj%>cKYrg8e3jeL}I`I6b^di4*$is zdX42S&;6)9576C#kn_JBBskFysl29r(yBAg@M8_p90zMno`S69C74Sz;h>Vi0_eiX z${Z;_7-`Fys%q=|UNF_tH&K#1NsORM z8VLxp`1q#-9OprC3U`1@Y4KMg_YoQQM*xNIEum-l7e^QS`5Tv1DJn>Ky@v#{kXYFjng8_3UA6VFl5VK0US^10?+rau zSSOJZ3m-h6+q`V6VNP+HJbu{;3;{O4z;%CVYLbHWo`rK7S(_rJHBQ8QU{!34@)Lrd z_G!b!FF{Li2UuO1g<}bNTTGYP=M&_bj0&nA(ErMk8;`2;Td1CYScbJ=O5fkg!1(P> zx{k^F;ZKUpEwAtI3+hu}`M8duKRJ%E^Ib)ns_UaOb~swl$*+aEQA>e{U&0upl%L^eu~rBr z#J)}W`bushlWh~v?Pj)hlPJFA^beWc7FWk2BM;bjBM#b`BS!qrYuqB)Ngi)aAhIS- zAFQ+Y(DW3nN!bSp97QVW9}HGC59F6M8C0~d2Vf*&;igN72IB%yfeWf6_9-L8kuM-?A@bJr`knSci#?laH=?{&|tS_bAVWwYNOnr>HuR}AFz0y~3#yGy3+Kyav zFIVv!(q%G63$k#>+X-6YOkNtwLESM-ilHTZ*LUFi0igcs5@JDve!v5;#^66QB|B$^ z%G)e0u^o|S*THY>ekYp52nijr5S?6eG8Nl|4rpJ+0_fnoV|$)(H)X89ZSv(BYRMB6 z#9>cQR)|5^7cMu{+;DsKFq{j>8C&YD641jwq^Dn1)t5K?aEPg=*2xfBBVp<$$`EKv zC_7SI8qn)}tl&k>`=dt(6NmgQXV(*-`BaiOTdbgIRZm$ra9ivbSh2iM5PnM%lrAT& zMEc+0<|6MP0t3~hPK+P0Y*cC4s4liqyf6MmI7l?FPdnvBJ4$ffbbWWqnIn&S_@;b{ z`%ko1d4=g|D1qO6c_U?VDxn+;HH||B+K?!shIH8VYgFlAU|MNZO|XCIJxkPHD-w~h zowTRH3aXDUWvpQHv_hzTYgis`r%;m}ufMKQk-|*J2ABIFbXT8XDtjjPw&#yMj=Qi( z_^ngEjdIOv0~jCFOU|*v{=qtgIIR`_Yjwr1Z6TM z%fw2sq*`HOLmUDspjCK7amEXLp)txgfkmX?St8HSXQ4N{V|!>48)1i;J*DUm zJ%EiU>BgDo4#J9JOMR_W1RX!*yqg^f5YdhwCesoL64R>lej>;|ZX|<+=tf6FhC*rd zzH+5Rqn&l_0<=*9cM@zl7$T$?#oBlr{07OaI&!K+Sf7hj43wB#zku5N#H04%My2Oy zEOSgxAIpgSwD$4L#MQilSJp#vscACH%^g+?f{wh;v>e&Z=$2%54a3Q?vgir+LI#&b zIO|xV^tv}B*iJwZ3ibb}k8n0VY9s@A350b2HbicsnZgy{>%FrB1;X>IxeUdUZ-MK_~e^TFQIJtRJDzqU5~h9T3owcb2YkNq+l+vc{$a~d~PR2 z9cP}Quvu@|?XE|n{Ned>Xg-V2k=cd(1VxSEQajlsQeW+qm!cI4mN{4JdXwkerE|9< zSP$%Xu6Pw#!^-jS{H}%q?&zs|(@)b|H?$*71n)7Q(!4P#I5p7hWvs0@s`_R$%KN;y zfW&?VhBJ|2r$s0w9>xv9i^}-E%vQs8j5ps+F!xXSdYSe*!%}`<24CmA{_t*DRqA31 z_6G`J6MIDc_(3YfOkE{A8;{(V$8viE$inXS-WBoF2+=8NdvODD&2i)~lxGh+yY|zY z3Wr==9;mjb$$N&)%upXFZH|?%d|)#C_NYNn$*vpByE{KL5Z~p#?(frT$w2nx%a?0| z6UmS2(*m9yEsN4>sCCGGf2Cx)yve8Q-t~*`t?#tercpfULl~OH)}9#7ymB|gjH;aQ zDx+?9_D1J=Raf?CX6s0Og$YHp`lQ3W{h?1j5)&wiW|7JQn-h#a#}w}9=vXhJ$*z5o zU+F31Qy;4*pb1{q;Ui$48&-F#_|ts0YZJ z&|yz&+ojs6vb=q%)3#5JluxxfmT-y@57ez0RfZW_bN6uvqvVcpm#Lwlc89$ zrtm7rfDGx2f>C=xXJKt-fyExZzOkazz6-E6qNb@C^Qhf=r=5D! zjGD72`g^Cp98}J~`Vq=hv=o$~Ic1+$RW~~L$Re}a6OmcQqhZLm zGfta(PI?!!&O@1)*GyMA=lUc(pt5!!SinV`)qhu)EnA|#*igGg!;9Q8FW+or<|GZ0xwFZ!3M-v9S@uW+}JpQ)0yR zlS|W)7N5&z$`Bt4-x+aeyA-4jj&v&XWWVY4X< zinLp3EghV1lSW2A37St=h%;Jeha++zpeC-aN^UmoNIP?K-Xq8OL8q zdO5bUX7z5|Fs))QuY~<4<&O}|5IXZ6T1OXIzsSOmGD0f*wR@wL5xIgGYlINGf1n|c1m=7K=FXe*OVF>h&6q05tC+_Mm~b>C0i%E!n~P|~%*|MpG*YBu!q9wzD38Re z8W>lE04kL+V+nJj*)aj*L+F zs9!s9Kx%2N^NSu~J(1^0ZY_7`o|UZIXGss2?2u>+cvT%i;vCq{@%-R}qohk2oSKX2 zrb~^aRTCw}H#~w?m2UFpG{6;F4MatRBElHOBceo3pS0iAb_sqh{5m=N>(aM0G5vGW ztH{Bek`gYjoYlKKl60$_823mRc7A%MH+-8~z7S4(G5F$A@Ira;ZdDo^MDOPjF?rSx z{4pn2Emx1-nDOG4k@$2f9eu_&HpIIP&gLIF`9oU<4dXiy8mIY3Iv?|3G}G$z;{V z!XCRE7qEnFr?bkc%c1}--v9tA12*&u*zvJ9;+Ofs7(QacE5zk ziCl{;@u!PrpPa%!u;aT`CT~i(I#0m~DHHvVkLfw`!{~919acx=gP2MX%>}7lpb8RH z3rY`~=OKGK9phv`PEBLwU*degn3^we?c0G$+MT#3c@=UpIk4^4?i*2}VfT-s#4pEA z+6cg!gHlMxOU`er6!Q3WDMbB9_}Vmc3Pxta(elf&`RAG)33AF)WnlNw0~5qU!zIUh z{#TgYAyxpr0xhC)CGYWFm3-WiZ*J*L$2uD@3w05;SObQ$kqD<9#KV8+Km(Uy&E1`v zwC8kOvq`9udYHq2Lc#6HI5b6gZJL3JrD$i1IfVivPO$)tB?Nqz@v->l;_0~~zf5p^#V3md(97Krbs%_@yc7Sm^spBX{^Kav8l3z9E4wph1Z$?) z!Ro*)i?nH6e0z4OXwkXF3v_7Vbd*keEAs)qq&rwKtt)u~t4=tbjxy1%bRVH4@mrGb zi$7h$cthr;@j${S-7#|FS$H)eoM}@V->rjJvMTD?j%yP?2AaV3 zFSO)bs3Jzgsvc2S9&<0UoNJ1DPb_12k8pR43ex3;$vpb;2QY& zIQ$Tf&m!NsxSJoFoS}5InhbmZa@+kJ&QHM!jG!J6o(9gJv~+A&cbJQ5V8>n_VSzRF zadKHSa5b>r^m+uzoG(#eE&j)|?q7;rr7eBI<1EU^fpS$zL-*Rk(vgmJ#wZpM z*$GE7IOzTXSg?fYX+%0^ppEEoXAS!yqi3Mk`%mXCAF3V45XCP!ma?W`1bT!(`?VM;*=&hnbt1CO0LPu{Xzpwogw7mPFvaiB)q?t0eLvhndOJpE^E|ju8 zMES`IwUZ7=dAmeK^UjaZ2D2MI=QQFP)}(W(3IFaD6HM{Uit6!&k5pDC)X!2i>kYt; z!2^PP?>M{T{WG&mHs;7|yBcPP4kIuy$2Yh@evK3|Av z#W1+5qLhI;W{6YAu4oyWD#`D%yhsYi0C!bVBY9jFpjIGQYQ@sar6^_TU72Rt4OeE`0n#VKz1PM8x~y&WMfGJCA3dEB&&#nnf-mN ze#l9@Q&;K)A3>#9*y(qon?3+m@_#D&ghHmzNK`EfbBj_^gATg_wA%i$GS~9SXs{Cy zY?G%L6w|dLk$1Xx<>Re&5f-~9Gv?R~Wo~;*1IxbKc4x;(pCkk{hvK16a}u`FU&Zg( zQZ{ha;B>lo88t0Y!JZo~fkWOcLzB-p_DJQd8v!oVtxRlaR+p%&;>Q*}%oe=oMaK5f z8eh)!s^n6I!{*t9P=rUWYA_~+K&`Qp%YTG&N;^m^yx&sF5$u{QFP217x*@#W$SZU^ zz_<;Dv<7P4xn_^35nc3iY2?F)hlHAHv2jm+j7po+wLmakJNoaZYkp~Esf-X)Bmp+= z$;tL`0k?o=@i9TJ%+sIR1xm{sk8oC06gBV$2b^os)7_d56}j z%W9d)D`N74^k}&&FDp6Dyu4XttRTlL*TM@Dum}wKbO)Y4CD-2{Ok>0z@+6qxMvI65 z7uOL1k*n89q#|+rxjTK*%iWft5JLFfXSt-M$~D#XuWM@gj=4WlS9_z%Ryd<~ZV0ZG zb0eegBY&5LUJ;YUVN#K6LQ%)NxOyh2n(o^fvG^}rmOm5pn}o!;?>u?!nq(%T`mtbVse??vQI77{lh+~9j>{SiBqIWV&=AYcD7=$HlEFrLGmCKqbD-D2o=M$wuVT*CxdVW+ow=wuVc!3Ypy-^)PID9h_F{E(sKgh5VE-L~UT8Yy3p^+WQ;0ED+)gr>WxW318K_cxBw#?=~+L@R5i{ ziHswJ=p|VN>)x-5`<>@Eo=pzAlp5q1+ZxJA8)}Qm>e)-`%Mn9bt_$v3<@!ffLgBqj zE%~MFaTkkT(fsYK)$4ViNMjGlAlJz7=*5wdP#USSBS%3RA*s;HeCHC}20yhM*JQoVL;So@3V8X}MZx8Vie89E zMK_|!OTOBS0?8g+e%|nyUR}lmXTC7o=chYWEn!~l)5dUx+;k`Vgk*`#lb&z{<|QQN zgx0T%rORZv3i{VfTM?+Jg9SmSCN}aD+a}HKkPHh7SYt&o@0@&*0CG4w#Q^ZyYUC`# z!lprffMF?8vtU!IHl(z3+q48-{scm4Pl#vA`9% zBvRrMluM47u^r`=nG`0MFn!=5V}`3<~jM6v+l30)|zg#m>XS<6dIWvV9Bsd@#V zl=O{@f=|a1FCjhF9v&Q<#wH=kkQ?1wiSI5a_VUVOb@VsCY3H>Z7Wo6|m$@Cj#w<9rdhw~YtL z2QOgnKmQ?SK`>OV5WB=X;>8+H0{Jm^5qk$d26rIb+M0B`adg8S+rKdB|I*>5{@xS3}?EE*ZR@n8v( zW8e4ZnMhOn?`<+1Pljj(idJno!fjuQs2rElGSRk_Gel_HOY3XPD;<@#bwB1%ArO~9 zLD|=NlsGK0={LEfUKilsrjEjZ{rBI*j{c4y`aX7)N_QaPp8`a`z0~>yf4tOE?Tjvt zPUe~wer*ajyRZz+j+Kf>*Lmz~=^N0)ws#U~I?g>Qtht*Q*5t+7TOe*Imc7@EG)seW zABEbhCYqxe%+Ed3Uh=#+`}jq2X2`?)fr{2&666#NuTH#ddL3({Lit#;;IjB`Z84jM zNEBqejAA1vBPmIxI9#!bv(pTo7is#C-bU265{^^gh^z9T~ zl+Z%|ZqZ#7b8gvr3iio-5;R{Un3OYf_!o@1H<-DH1o{We_RLB%DTRiv+D%rUZ(F!c zk7h`z8Bc(Q#D?;wtAW%b8N?(cGnvh`txni z^QX6Cx@~i+t4BYn9(x0aFhbhu+RFCzRgk_q?C#13H=iggP=!jv?n0;E@zM4QTF>O! zx7rIEb%>mVM)s31XQEDbpRR%;=vb6$d}lAzk9S{+;9Dq01`pock$-En^%?`h5CaW| zVoLJu!V5m%vl>uT*m&S&2VFU0?YJgC($TH?){6FXLC*atbKYdz6`!|X$Y1M-7^ND1 z9(#9<+LzDu79n~jxZ`=Utm&DzuQJ_6-8~WmZLhvYYaXO+#S9+ELOUiRm6uplP>Dzu z<~KB`K8E3G@mNg$O(Z609NN}7XZ8y7MFUekv@Z*ddG_6x79#ZqmK!Gct|nl3G%#=L ze9hEREb&MkPQSDzjBu;tD-0_mDpgxEbk73nB}x6x+1msxmoRy`ZjEr3+}g646f1so z|N66KIbNzBvh3W`y|&diBAsL(y1bmIK$y!BpFGs0*pED@c2e&CHP%s~eMjCusXBWs zMgIIkvWDX%1dV1zY#38Hs?$>|Wi0c>`t)Qn@;m2eEnN+4&Y#A${lOPOx5i<{Q#) zL(*Pt{>E3736qg{+&r2f;uL%T^%F|X@Eh{NR!<1aTJzNRR2|iNv>|X47EGjc4PG_G zMlycE{(?kDE!;qP_bA7{`*K06bj_5-O1HXBXfO>7v^5?#Q7KB5=eeXut8u;N#h}VX zBJPo{yhlaX!}HHthi0WyJ3(=Z*Wj;0P^fX0+&5n3QHVZ7Yy`L{MfkV0P)V#7iq9Z0 z5aHaV$OBK)zw5CpP?QcNR*VpV8--eiT$6@<0jBqgpmacCLH^W9kJC2Enn>m{`jND| zAyzP1AZB~?PRcv39%O=zXi@Tq?yJ4#R=9>uU!8<;+e;$D==@7Uu|3nBd@@d~s38rV zDSd32Jw@-!7j|y~#qhJJ0VqFd&fijgEFfA==gE`sh@ilzfQYE*U>&_(r;PrY^XK3t zbNzX_7AF4<5XS(kqB=lgI!waJ>VbDLW0QsRvB|=}Vy}mWJwVhP@#1_)*rMlV)|`Xv zFH?643D~CZ-30pTn`u~B|Gk?#L)0NuU9j5(rJS(agr%oolLV#5VUvWV5->)B(nGMQ zJ*DBWD3a3iuxrGn7h%^(N)=%}#HGEk9*WW+XPdvGUqT^srmWf&rIF4yqLeelgAkbg zPETcmIeOL)yGk{kS2-#Bhz4a~8)Tk3gma>-XtL5i=T%`!42iz^bDO7dk;;cO%D`#@ z(hNZ$qg?)>kJnpxb(PhLX|)+XBWUE`SfXTXC@icR2Fd;FLbgveNN-xJO(@%ub=LBGT! zV(Q&)vAV$#jJ-^EsPS5$RfdB|*9QaOohDCs5EV15;Me~#xivktvk%g~qCUl-!<@fX zKJDdT7ZjkcGk)t;D@IIq33>=4z^_|R8$V__^t?KSI=7JbSe{|*jhUtXOBnX`w3=Ch zgkY}av6asZBE-mSa;3C$!f|n+I^r?3}xfGu3d{_h@nRmqeX8u`gDB~UsjJ{sY_cg zXhn3cm%re1ROh?C=g^A__TO4khguwQh7v5y`CdLD# zgS3e+51uwQSmnC;f;05%^CyJy0vvDIRnv3c(P^9{U?}^?-H&t9yw^|dkF}7{e8Dbi zT>DenCYWX!*n`Zpka>2=>{g6x$tI1@)V?P$BEpra)Q#-Y2F)!-GulS1-7o9I(T~GlzF~G#dFWZV#w}Ve-#F`iEV#iZ&(Q@^`M}M|r}rU! zYC2h-m7n9#NC1Z&@#Vtq)NF-a3N0Y-_C{}3h23EGwD{aE2JAD&z2<4T7ms6?e925hHAN7>Lr)8bJEzJ16Tbp z_5te&YVJ!6RA;c1l#|po7~8|lzQffS%qXxXS&|koKL#@)kbGBUZ07_zLlcUkPb9wB zKX3~G@^^g8L-%tS?j2d%!8pyvas98}UIjR~$a5C7DHPl8_e0+8-DEb2j@JL+fOe+Z zjzVlImn&lVJ(Fw#5t$^TgddLdsCCrmM!U}b+92;q%4fKLA&j1C;b<|E*MCt!uhCzeC&4VM9Qf_0E4fufX;Td}HAA;A}McFw)JceRNP*u5U$?Ot@8WlR@nPlHvL~@F?#pL>DiFpu@h0grQx|2NLpx-mxd+tEJ+|iiO$&xNV z-iz6tx{d>9k)&VvxTc7-YkGxJY{3SIDpB$6(oJOeIzsEiDIMDr_dYI7` zg$thf{L|^dMGFW`)B^R(4$*)cGdlvK9~dJi#z@GIW7;*ds(NhGd(mO%Ed2)F zQfs7Qe5AjJ(a#BqvMxd2ZuR(%U%nqWf_tsbb$wmbH*!E~deyz{~%s&wKntI&izSveW}+XWZ<@Si^;SN_kQ5x;LJZ;0V)eBy;L z?V)=|cIbV6SSF;vNW(ld6#K{bO>gWbzizR~uUi^(2isYkif-#hjRX{2A4nvqGH)^5wEsD=REh`DsTwi(Rj_&19s$ErIxij4%{jm+7Xz*YFMAEO9+Rbl$C5 z@GrdCTN3ciUG#M&Nzsz8Bxq%BqrdU+ty2}Hp)#Ao!m?nNmvmQ(5} zG1gMA5-ZK>eG{q!f{tG)J4|)(N@!gh5GSMO@j`^h-12|=~$Bk zT_y`QT-pFutI4{}feUPM;2#EV&p;p#eM1@eteBZUvn(!kyJWUOeCL>*rPYo%;>*y zUeWO!nuJhRMABz*nq(+Vu%S?!F{SVB1jAP()6b|mGt8HQQdB^4(Wxf72-a&^=IjI& zY24U72*{5E90>*^3~UdDg%%Re%?-8XF62vB(`Q(6>SjdIA2X6|0mlc#BGrMEPQGIw z8!s}S>NhOR?Ju9pM9a?dkNZ(p%`js3%NWQago(#yu%3@) z$cyQxh7J?`S6jKv%uaNf!!BSB#ZQ4SBM9XFCzc~-e3P)Ide4N|-HOo6CTI;`i!7WE zjP{|Hr{nQaL<&7bek=k(BT9taeT1G?)E6wNf*#E;Twt9qdr9PV9vg;2#*fgJGt@RE z53csV6cKtYFg%tvHXtlCFzAtLjNSznOAs3d!Nt&xy!?Fy&-6c2!RN4Y74E#8W0I6O z!of+HB45c%+$@I;S(&Tz5)qN}s_Yy;Ll<$s>4Ko-$(qZGiu2_}R9oAfo(={F`?XZ8 z3@CWoE0e;#mo4a|*M-S)zNFlGGSPY7gklO4{>F4--Jux0GYyU_qlzBq<|PQ#Cum_f z_34%@uy-&Bo(FfZyqc+;{?-*dSL7W;HE~?!%%*(>|Gb~tiqa*LcO}4Et4MlmQ$08* z&S0Z6R2ELh8OB9cyBWN}JN;l@*xoi6=?XepC)B{^oI*uVZ^UIQ;!+kXvi!ed>_b|! zo3>_+h@9Tkts3s8u)cgL(jlo(p<8D0R+?mSwiq7-hD*`F27y7Pp5{kV4ZX;{SH)(> zb3nY?!$)RPS(bf;j#*TXZ%%*ujY%!e)K|v;*ZqYz^QEuTUu0A!(3pALfmYdqXzUFH5h0FmR3lDc?bCF z#Wxu0pIA8^9%z4);Oq2Rqz;(>I#wB@bOPxBdWG=>Ox@=t$MNsKKY0Ho%B#WY%RamL zVPbRr(H~c<Pc6Ls_Xz^XmPi_1MXv1q~*PmQ%jpElApi7xZCvdyPYuc9Mv6~7L1KeqXTM;qq{$cc?j!Uoykw= zH7}q!GAP=}AK^62RjGO8!zoSsCk~Py^T9IHQc@Ke8;y{VeMuUjscDb-$l`+e29UcM zFA~apYBlB$TJG~Lp=Xc%B9oGX-h1azT2?lBUB-dv^M^+%5a|wA>t}rGZm@Af{nnG) zpQV@Ay)V(ME(nkGkg@0sq8phij%|P9CPvpB# zGQZ9hjB)`!Y~lj3Wa9%2Zz#)vwa56zBHGXg~=SAK|7FroRy%ol=QHH#F8;Vs?u?iKHi2|FLnxIJ%^ca%R#=)+aCfym zb2pcgo7PSf^o*8dkSKF`iweE?c)R?{zBw(B*n8WiUtv&9Cx2ys@^sI`Yx#%#ll;p~ z?|A!6BxXG+7taz`8Y-)#F0y?{GDPXkf1R}XT}0#l3e=Ton!8%Tfg=<_drD1o*O%@E z+3ZwCC|;%ZEe(IOcz&6%Z6^i|MK#NteY}hcdJqzVBMz!8bA;(I)mI&HUQHWi$QbdvF!R=Hor+v4K~vQ3mR$ zY)kmwLs%t2Ku>@|MC`KjsUJ%zCY+w2^!_8!W)lu1d|9l7PlJ{4{f>g$#W`n{8o*Z2 z-@{e`VVYj5vHOBH1C(`NvsAXqm^et_Lj#=QYaOkm{{E#kx6n8C<{dUT=T`9svUsB05}^!z~iXYB0#6*0dyVde zJeV%-hL8atcE+X;dk2;-aSN(Cq3Zrc5_eHxjsCf}03))qHUY?d(Izpz-`v%Z?ShXd0dR0-{j3F zB8vHwYem}!h3wY{W#Tsn1uT2O6V3o$lKz%(cKxS>Gh{lyT`K7QcZBm(QlQ%XL&BLV z9)0*b!1-HN2NP8@CVKrUGoTM<0DS&Et24uZL*%~ED;!ZF2`Kl^%Ep&4%8Ua`g}|m; zp_`0(yZr%k{os`6SaN*tRMfsEpbTgrW$-tU46i~@Z4>nwK%9V0IBxc6|6e!{K?yf= zrd}Zo9nT)lEuZb!ZRbvF1y{Tk^CR(I`=|4OCEka=A>RL6=RuDKj9LC^92eRa_}4p9-++sjP@Cc0I(a71c55;|ziYb&-aw zWAW0WPF?7Oo2ujpu(tp~lq~)W*n+VOYms2m%l(po4tS$^@|FxQqnQlBM7M16(p0|* zg)Y3$*p2`&Vd7~&$9_0@MXP=(2uU?*W4?T*iUuIxSaoOB!sB;f?ie)iY&e{QKHPSW_2C?m7Y99=3S5!3KX&II z62=K?w86~y;5aMTG<>t-z>hyL*p15$kk!K+?tTh|&HuJPs*Up6T*DVMLci z;E?Nq!m@)*xE;P&9CB88E3_*V?=3hk0(k)~QR-LKT{SPoZzKZ=WVL8{^Sj zZP#0ph3Px?AN+FsD`=zu#BPQIn}}Q)$&+D`Ha~450;4w`0^BCSG}iEv-KBfTa*FXk!F%#j zH(}laSWh|5i?T7;1Yn6fPI3oG&W?q4Y@{*$7cSA{dKc%6Enebp#?kvNN^=;lo{{n8 z0`uopU5ciy4F)GsE%F%tLKU{&0^H)-0q<$Vz4Z=OfxEQNQ=P+4!uP<|$YD{Dmji>s zG=gJwb_DP#9h2pi=dI+^cbZ#}KLJpJxNGh|Bzt+!lU+snZ@ogu_?2JKa*Q0!xjFKj zrhN5``|9a4WjpEV=^{9&LZ|6eYi=5N7E}3_ezkHMPuD$sjFIT+hRX9h&JU@jC15WnzZzfcZ(2AZ2$@0P7sqA0IG2 z@$Hi8-==*De^{)jatdcY4}8LDr`^3uYQXL(3QpfiazInzEX(WvMOEsD7?x^W3`=w& zPOwp2XV4BDHGCqT0cFPzQN>H}>R%RD@CVOhGroeqlBqT=%2g-WwnZwuMOk3@*ze5A zMVqgP?-JAQY~r>_>X;y%R0Kij41T|q(b;C@ltqdKQlX~a|7c8N{dX~m3mU(_|9!u` z|C1z0|4ji<3krafe<%QOD@J-w{?nYqyGx=!#Uu{13C*KSIB_wF0DAyCJei1l=CTmy zhYmz1-&%h6-h$b@Z>0i_WgU#9RUAD$aMrCN1d(O7J`5>}&D|<=-JR6iCnAc2B>263 z;ox=yWA;j$M6`S}LTZNVB*RQTzstDe?Jtk&>dX(h-p!}}%N8<-f9S|iNETduh?{8= z4E{+%aHdH5w8OL0DGUPC;w|L;C^;ccP9UBT20FjXc_?)t0vi!dVZ1=uLrQKv)!4Z*nHd6Z@q0Kw-a@>a$L96WF7@dIQ0p?1CMPFgJ>fHu>0yq z)ASq`D2tBnJ-lVV_x^|W`(K~%1ONQa`_3BsH#^?IR{P^{^?0#|!xWYaz#t2q#d7MK zjS?`;Vm|$3ng#Q4tdlxU38joEKoVa207fl;nxTx{0{3S04wVlO%2CcIL+qRfhDSqT zLyy%-sUA~d_g?*Op##@}c(IZv5<_$<%_N>Pw+}#S)PEmGD*8VYM~dCVygThqvx;)< z1%(}2A%R!O5`wU+bH993ZJ(ULSKDtRB1&6lqKu~@->zK74^rS^lxs0G(^%t`_cEOB zPI))^6FN@uPZP^y&G7eG*X+$5U8GUbd03{X1jnK17VgNsD!__j((e`O>MP#aGCkA7 zFg1hy)6(UlAVmSRZ3g*4hh{OA4OOAwIkP`~c6_@<2kXbcdME7qu|d2A*MGZElZfls z2@J^k+Hl& zUTG&Zctc3IB7k=(QVjB0E&+S@cLWN~j;Mp*W4N;G8;I%ee2U*;hX1sn%jxmq`#!{+ zf1#pM_z$zkc*uiQT|q2Ge9nFjzYMP`_NmI}t*g$inn`%c?_R;XpRPI(hqn^E-MJ`j zMw$a5=}vok0PrySF{WU4ueyRjg7lx*4&k?gruo_PLLiVJ6cq4jF+Oz9K`sF>)fKS- z{Y?ii&p_^vJI+tEQuNO|e1jjN^#FeO-mX{ytWPYV$FEP+A3QFr0|9<4w~*}rA6BOq z~t3W4)qNg)r+niG}4zAZ2p5N?Zb zd>1tt=4i}#et-GsbVP0p?$*o46ph_ZqK$d7@&we5E*cq2y(a0-EhxxaI+a&F z6;tahdszC_vB6ddHVdzd{M{P3$;m=xc~E*o)~QwzHlLtGmzylcL;uP?R>URUm0>pQ<< zDfTGVy3Lxx?SL+a&8}qPWBsaWWnMug_}Zt+0L9ugjtg&JlpAhzm36*6rf0OzD3SbR zz(i=tXrT^YVH4kz>b_l%i@hCH^}h};AdVNXt`F3`l}T8C8*&XATaa5cy08cQAXS;y z-P6Ky5cA9OOMDeeWpAl@-qEsY@YO_s1UxprzDb15u(cM~>$>(ViN=DCjoN!cmK`C2 zsgDtb@}0xwZ{Kh$?ImrVv0HsovyLe_V}}xh5zNo3LZY~!$7zwpGq$XJYh6bii_t2yCYniJnn8yOqxqd+4`ktq~WLGM15 zb@h>)Rm&;M(xCfSTMzhnv4^zZyef3>h}6>agc>ap`QdWN^V3kq+=Z8?m-WXOr%bw@ znLawu_xY{S)pEhPH_KV~m7A*Oh13j$&kk}7UiONqSUh!Zl(zhZ!sqI;vd7eKNfXYl z2A&muY|ePn@=Epd`9e6wD{JXij#0lrxhXO|#NH=k%2l*FGFfV`yGuuE>PjC!x}ANL zPmeCBCE?hmV#_DQw;x5ebDvS{SCwmxctag=$moUAE0f(vjoLHn)XWt}FD5S6WMybr zA5UIb8?Dd~UOej;kllfLIQiN&Y(+C(Z~-m7syb%(=_=Q2hr+5@-bk^o@cr3{jPdb> z`@Mq|AuNa|N^q~BSUzo`)&`d8$L22DLSL+p8^!pOqYjZxG36{4H|vnL6E9DFm?^e+ zn9$fbWLN%~;hNFsF3%wC1ktYi+r zPxRTZif$;;Ah;IBJVv8u^Giy>zhweqGd&Wc(JyE77h)x5Hh|WN-xK_6Dj%OzEKKly zNHOg6?J5CyCh4-(*{eFoGdnFXuZ0e)$fKVZd@Oc7(%e>)@s}O*JItZ*kA>-7?6x(Y zquXU^{|~89KT~ei*N2|7U1J?ky#dUwStTl!6gdPWVH$ViE+JO21d;9t30Ow*clUSx ze>rDh+mAUkb(ZDH>BPTWKZ6swJaZm@jIS+wKRHr(Ri}f+W*V+DzH!EmhL!K|Y_NmU zcFwht0kZ@y=z15{(4!g-hJlm&N4&IpU1}r04Vc=DssZCQ<26?=TU^f6cG5N2Mj$rB zWp|~HbbYAqfT~q>RyW4kmjtNeMQ2>PAo%bqlJ;!dmmJ2eQ%)HqviG;-^P*Efz{pDZ zS0-~_IzFG+S6fbU8avM82 z?R_jk!|nhQB?wAsM9s%p#vT|Hnr!ApJ7!4ll&_4DzNmw==INq=sy$lW+%hn-7_d_^O{lk!#f3&Y}Gle_y;4lxbqkp7DU^c14<-w@G zZ2pf@N8gmPd=t6#>yq#~&(RLXzPqjHBCEo6wbAy@^e_x@)-I*aQ5AripZ4y8fbgt2 z!A)`OoLHXCemQaoE-wtoPWG@cqK;QYxqljBk7LTLf6BEk%pP>83z;`srq;Tzwm(;=tNqwotvIHI<5ebY zi@U0wvxdWQUw^a>Bv8UMgSz5ASjW`r|B$qH|3M)ckZ3)2-66w)ze@tv47TRIs3KE^ zcBOheT&PG&EDK2uPC?{$X>Xicc@{dNJW1`Ftq3i(Dn=K5Y>#9d%u-2-X*>4~fE=1? zhh#Ow?67-7+jga|G`2(PQ|$3hhI_~I9G~6;+f`q*@tZ==fUto|r-)RTy^&G&v(n%i zd$uz~5UGqz`5wx^DWEfPC2mY{>;75YKv& zQf8I=0Bs;`E#EVo{@2bz)&(-Kk5p37Z{I5#!x$`l_(WRM;fSxauEXBVw02>T*8XD{ zUeJU^nCK5%2wXRRRZO0DDR{+UJtf#-M-=qV7)Z%GjB#~(2YI?!`3ZLIK|2w#1lVKv zp!{!>9pB}Q0)r5g+okCJ=chxL?_WSz)kE)B0$*Nq@vb+0 z4#aY(X(?BvxN!!eJmT|SnTeG~B$Fc4^1*p!&5FB41Q!zt^jw+`@G4z&CNpDgGjjh* z7%uAU{C@ZmgwWCQ*&1~zNRZ%>SE#HJKD)=lbflhG@*>Zvi!+Uu#3@k%%*TuXcTBaE z9zRAh7rn3`KY!sd|6)*^5(bu5Ae)Moowt5UaUn{5JLdZG+)_`-YRPtv3*(d@ex=+@ z8Pimq|IOtGJ<8Yk5Mx=f6>DXD%ZpO$CX=~q;ZPdY6sZ0wZzP-ByeP>diCs|oz&;ph?KP4K+&$p7Vy|C_w=rJ8NtSOqDJ@3^tg?B6Z?__^L$i~J&b zE>t1|(|}nsrE5OF4&A(|NdNw(O8)arB?WG(MD`a?*g3Z@D#=o?h_}S8jB)4=h_fsG zG0yJtX%&1u9j7G>6bHLi-G6@-LB#9MCE|Pcl>kR`~=`n>L6OUf1#(bP7$z9{L&1>-Bs5?T= zylLM{UVShvzcKLFqMYA&uMmW0spVCEQ?HG}^Qk7!oJ~jeA;6Ryzrll~J^hg9BWu=i zN1#q_=4g`RLruU|2M`>D_1d9WP$${r1_pP7gvB}#yD6tX1cEo&fOPqw9drDruf}{i z4lgpuP6ym^FBrZDmU?2jV*n-t?pS=g@=1jMI!X%fdH!Y(%umNc%?O<*ba?iO!xC?h zrptAi$;=MP9kf$_I1~B*>`ZWhBjLUsi}~L=6aD{d&jeF4TKG|}Kb7O48;XKeSsu;a zI^hViQ=tOb>FC!jFB`_`C%scsIaarz48xm`u8*@su>e?sOPUNM==5$S=&+plzj;&t znY<~9DEfdIlL23BPMfi#2O&JaEJng6OKC2`VK`J{fUo{|hhu!BjZx{Y@tN5Z*k*;L zB^5S)iA>g!Br*^G%9WQtCbu0srVn1fkU;|6$bftA4s1v%SWjj`iCs8C+@o8JUkpUf zYPHwD=4P=za4qHTfN3L`OT~xAL2U!p5bo(<`Bi)Q*uYTtuiV1_SyS`Bl^MM4TvKTe zh-F!X-JF+Cn|OqZZS#a3SqoYw+Dg<-nLqAMzr{0cO$E*lN3miH2#)j|R`$ZUow;uw z<~kAw+Li|A{j@eXT*hogHJ#ZEXb!ryEN_2?fIm;c1H^Ne59W*e!-kh(AC2weSS|gt zN$%uYWQaR~fh@D^&pFq+H{$t)zm{RiVKspM{YVav|3nTuL+Vk}7orPg(wAYM_)RIm z0(vf|XA~|!K*Roc*>!!rix_QQHyQIiy`GM zuC2`X%&I&_!>u@)Z#>N`^g{{xKP~FwWlS30O7E)&1TVN|zafG#4#(ed zwJX`lrXve=!E6eQo1pGn`HY2keu^*aMDwZZ#ICr3T=vRcsTeTW=Ks`5B8Bp+-Fjo| zocW13v-^MAJMW+-*X`d+m)<*4rHMc&3P_14T>+IQ$fk>kLIk9DDT>lTdKW1of`TA5 zfJ8b7(p%_A4LuMDxoacar;EjK18pEI9o={3Pe~_!?{^kHmk_+bFf!O& z7ejk)KJez2;_lu1iTN^uT+MpIqgXlIQG$5&glmA^KKPAmp!Qy@OTKuLzGE2gFEQAq z;XgvhM*wYL)vSm8ySIx&B_e15fbTyB7!7{gcKEOroF8TXT{H6u0HI-qZ$XtBbK96E zE+Hn7COUy)MtlwDJ+Py4q{%$ev{Cl(lfA}jGDWYoUGGp2Y5oOUZ{c_3Z(wEE{K3j5 z96hPTi6Scq@kd(%r?mKj59FSCHus(64!73klqKTHe-*?Jv;c(v&dbIJSV-7kJB5tVTxrfT-9;{`QG9|H#9`DEX?5?(Kh*yX`93?0Bw^V z2s!HjZqQRxqm9uijoDcT2Q<$B(2}CXO$&7&YP`^NgXqNgB)nPi?3Z)A@m6#5uzP3c zUe9D(#HtQX8Tc62gmFs?Fm7>#y%Z0oB=zu!!pJb$Z+mBGQhUYC zBy-Njowa2!U|>8|!dU#M=LV4&iN*_wXpL(ceqxI$2{AFT2`Po|0x~uEYb0rvK9lwK z;#ai!`&CJIj}rVl;dUS|3htRey_d?cY6hF4pg!vg;sj!FJh?vF<04z;Ax_VK`d@`= z)2e8ErGHwlD8A1!ADb3`s6z32v{*=1K6I>~$+`wMDb@Z2SWuRBIuA*aUzGV=eqyb$ z+2!#zvY$e{KjMz0=0E~q_lTeyVbsrT9$U~Diwr~w^*Sp^&t^)J)+oyE7tpm5G5H0eZu>}hI~c%RqqB%5;68+r{(UN-q@XKo~a$u zEx_=HXQ0xLCA5NxFaj>Mt55K5VrT(gsDlQUx9i*Ur_Xqo%Q zjh3JMpstZe1hPXb%uhyU-dB!CJ|namrp1zBDJSw23E(Do>=ADSBIX)yViGeaE<1&z z$$zdD1EbPEy~6>-8Q|xBln$IGuNu0C<}QvBJ{$BFt2~C45J8OL94M?(7Q)i&^%NB-a@9x zLka-lvVs8MJxJHNV;~f;CX)(;bbvRO__+H-1>8G-6KQjCyuv1M0Hc04kt^W+Vbk16 z>1F!oApY_DjONC$Cu%E}Xb1Xxy@%C~{&=5liet5-lr;AOEeHjEq^8P46a8@-`G1|D zkc)Q#0tg^h%#>+sK1U4Teed6=TfkDx7=hVlI#6^co|IMi&d7hu@&j}{HAaVDIrmH=puN5sbg+o?X1$^$+ZN3$u5 zzrES^_e1%gMm57W=;FZ59a1eLK?>&`wEiV{h7C9wOi}*ScK?YxCC542bwdDgY2TY6 z7Fv0?EAB92ZzS|7&`vS{Y9B0BzUk4)P^{=!MD$;({0UVac#oJ}666QV$d3OagedtT zgeb^YH%51c%qdWT#YDkH;!@C3rgK{Adum}`(D2{e4K)=X^yWH~mv-Rn%4fVh_M*^~ zEZeUA*aSc25vaf)O)~R)g5Uf&!OwIC0i@;t2~XB~C#J1;U|v3R$ZdX(S{GxpC4slBO^3c=vrR&JgH{ML_FkCmgYYZvSNx9NGkw?!vZF=G!0RWcD+Y!?drne>&|5B z4v(J`i;IIKubmYc6U$0yYo-d|Wee$^Kh<}yUdc$BLL>ASRfhmea=}>5YGYO0e%OeOt#6 zEn8*~iw?~-nhP(4UXTJh8o!|AU=Ldp3!1NQV%sf1sj)HXDQ6JBl)#3^C2(k8@7Z@g z^GZ$}&whdJ=4N|ktJK1~LYtALkD7qCAMknl>?b?^+yz6Is9-!9QQn2cR zg`%+s+7VQD>S$509z`CxRbtlN6_{;$s=2KTZ&)sHi-77h$HRY>b=h5d?b`D-rI^0o z?!bQ;(C2CYp91>C8Q%jYe#=7hM9Ki&6!QiP3P%O*iil$m^+`@;_20G& z*$DVVTnO6_`~aLDS>8I~l;_;bY=&9hxlh?Sym51}_;j<3yL=3h@f-k3kNInxfkh9` z-`nQ7(5iF$kW&f{d@}Hg03n&_^Dy^SfAS(5eM~x_HS^zocrr=BJp}OczK(zD-*~3~ zk+SMJi47P_{6)aH3)s`ZE)M=TV0^s(_Rj;xre-R?1&o<52wn%e#3Kg03qiw<(2qxj zCd|Aaj%{oJ&er(uYdQ{eO}-?nr{_6$?rb9q!O|tfW4Dpi z)k|UQM)*Q`b(iz&;@Pvj1T^yUo`O86mbr)p#XfSP@JK#9H9?J!d9If)#eE#RK8XzI z@S9bzap9Ck^6NP#@R6w6}vpxDjm00%`1kN6F7r`q<1&ffcJ zpX%na&9$^jWLoC3>wRBW8j2qXpS>Ihb+rUD#LS|<-x8hQW?4dRBO{TBFR5Gkj2+Vp zE8`dXRyFoQ5&U^C=X^ROmnA{Xo^Q7#S>|hamhKJ zHQkOk!iCJqx}yqt@dBg-)t9rf*Dfo_CekdL4zD;*)|{qt0p1o1Wv(=}QLtW|Sy+Gt zJ#Sj}r54-5kbU#aL1u$$z={du5;an)2Ch?z(FgTz9l z({)7RIO~D8&~7}-0sRO^NRyJn*%a!m4?YxF@9bvbNN?CsT@{DAJt99XaC4VUs`M+z zvkLY{lu%S|w)}wRH%!EJ%w26X%QuY2rn7|mM;A9wXW?(YS24auxhM=N_UvOD3i^Z$ zgesgJr)L3?)=3wyu1|57)7e68ks!mXt2(+jtGbabzPGfoCnef1>j1l>{mh-v4G51} zZJMoe8l)58AWJeA@YavHHAGsz*VR>Q)w!*AH?tP*1uX_G5arYQgAn3eL8Pp=-0+XU z@-CF5(eBtdq(oyzJx)Wh?5Q06tt-3Cb`;+a8?8k?$jUHBPKO;AT!B4AY8*hrL0SUa zaL_UcIND|Jf3OW7bc{p$EB9#+KtJ7s*wl#Ms<5j-``_UrW9`Tp#x@*ELw+_K08aK_ zH5?*R4veCWZd%yjI{;7vAHMS_ph7+e`4g;o6a0FWOBQO0Lu^nxMmzFGmUAyG>Ci9s z%sC2RMOoV~BqY`UaGSU6aSDK$iL!sD{`A$hg7cF1mGv*rveKitqRmTdISLW^I`9E+ zSDOmRKCsG)1~8+wjb9%{_925`ZOe-Q&7wn?jW^f`E^$L2t_lk6M*@HByy&S#8863| z30$5KrV;%}-eAIjx3yACg$M^6+W{m*Wof?~mF8cHVwWFJX^>N0^0e3j{+jf(aOQL$ zOjT-gxqLo_swc+B3Vx|DEJEEp%KJ&pK)@YzOrAa*%AvR|F9b}(ICP;#;$+vowVQ!p z8$aa%-93@LTp1(ytJfGxp0~9>Y-|9hi0Xt>^w-<7OaQmYk?;gggH3RKKJ~$!^Kys+ zsT_(a)3NykQ#0fLjYB6o$|(ADHv$l@FlvH@bVaX&)lvc8aXhi0@nB>F&#_q1^GCBd zfs2rwf+~0n2lO$Ev7yVx=`xc4qEpmZON$@dF@4m9Ggjg9k#r#ONIFo-a%A=`GbzA) zi7Q#YTjSvLi}3v_OOzcDGk=?c($Sos9*lV?5ipO z{Q%5p4XB`JKV~)JE{+58Ghj2AXFr|Z2JcU8er!b0YTosH#$;=`r^OwBMFTyuZC(X3 zkqa17kl1?(vmD=thp()?Lxj)p&*@oYvs(0U9n~cMle!3?39Ukh4ke2sd$o^Ybt3n-|4T5+$m7Rw1j_#U4Zyt~`p_@9rCkxp){R0Zup+`R0{ z;yz%`@eX1BJn;r$zRFyPz^ZTd!AD=Z>#~t|1Um${gaF4)372dP4Afp5)b zfx~JK_?`!`Gbik$=GWBF55w~@dqjN8aH6~E^vkRLL{p5he6v=3lqrV^(V@N3O3!>K z&!PbZv|*-)IZE+|0(!C`n2sF>So>^@8v6`@5dc169hsQTBR|kGg4V8~dGF~P4 zed3E{EiJ+sx9MY=edZQUPgA2GTjzDMJ@>$GeP%rX=rt(0NZ51-66c)`9}9XBkUqkC zyC_uG{*FCnLjUw1L_a-PKIh0y2UF{|CMKh}U!A z?+Q7GPpr4)_iemQE!sh!7CjR@RhB%ljp;PYqel|6Kmme>>G&aXX}e~&+sY6cQCfhg zP+i)m;R&wSgMS{CFoI+4yhypD^AeE*_xJN*mqc^=+_rU8_lW}NE4ErB?HtFv3;Sw^ z5z&t(bt4uW=cBoJTT!h(8#NovxKYkKL<*J0&E<(|A5rPRDyyiN6_fEcxLsbi5aTJC zb58I9P-5FGm;xiwT-zVPqGiJl$fy#Xt3u}2K;^Bf($HHsXap6Lxs`7QHJ1$$QV}Z+ zmEsCUCvJzAd=3XQMZ_!%^J{T(Woj5#tP?%*yMw_GZ1lfMttz6XJ4I>sg=1;RP-@3R z>hjI=hU4?w`!(tC_G;uoPIgd}B)IJ$WoEwQfGuKGTglNYRB0eOyWBB!Tx~1;Ex*-3 z5$!`VRm}9dlCM&C`twy761Mr0%u`fgC-9&a&sOt0cX5B<4twj?z_Wh4@ceJ~77XJft#$5(_0$_IIfRNCU-G_PAvIgr7Wa$02HIp5*m=OP zN>6~)5M6bYvVFF%MYzgKV9>1hFp2y*lKPXU04Md}VzViQZ%q)S$eUfFE9O(Si88AqsK$F}_{@VCLn*P`A+Tdzx$K^fisS}W&FbJ$(?SQBDhZyl;uB zqZaihyo=;zR>RJD>F(>aZpHw=LeQ$`^w}O*`G#8WT0V&gY@J8GKiq9|(3ve7P9{@5 zjQT3evJ`PoFk0wf=0RZHC1*Bi{^D?gb zSf!jQPa<3#PQ2kF1wlLQ9idWGIwhpE-_@A2-$d>Iz$ znfW|ZG~_&8mnqye`=Z(juY|A6c|BwG3SWa;-O^Gh(*L<{&~jqYOChHY%Efff0O1U8 zg;4V5iRytle;BollYKueG5qv~e1t@8Eg^CK)mIm)zP>6ip0{)eqn@AV@pRwVVGc@< z%v>3?Yg?Bm&b9Hr80w7aar>~U{iI2WB*KY?QnQj{x@GB{a9a2^w}xC!LO~9_1`dck znF!p6y0xS0TmWoup?)jEUU%bd*G`}h-?wZ7tIDihdFU_rL-VYTNem8hJe!~dulI*^ z+a3zcNT2fJOp3}VLC?)Wf>wHnsE}K{o{9C>l4>7I zDulBwWN^Nz=FNo3%7nc%(TEy6@Tse&&V0!AB8#pweD->ah?y_m8=qRd-cvtz$#&Sk zwIm9Gi76QqZw-2@J+dTPg}J>XOLL#TJ&8z;o&LUAK_nrifA|vd!n{^B;i^d?nGocU zi7)Bh8?Z!DBjhLIy+4wPv{<9hiDzmv6}60NerG5^W{$CIj2&p#s(NM5Zst0JTjb}e zrrit6ee$dZlY1&xh%16m7vU-vu83L9t{E7Ook5V&w?rV{-&jOfj&HEHHEjT8S{nL3+Ae?Cb_udh zB&?qYe&zjN|hwmG*~)rImh zPIEsa(&j$R-Y%&wD;vf)rUFayH{Y<{to1^4w0lDMaZ>c{kPKA@!`?Y#1*3Z;23nvq zp|$ZjpIP6yp1bfap6qKu@wTn8VW}q$4Y{@EAN-vN2JsBy5PMwhFG?^qC*=$}hw!{h zaT`=^EG)BQ^=n%DUcNG$Xchzek+cQSwmmHai)#VP2l4$oRXZP7+aKH84t=86+Iq@i zpM@`lBd*{>_KM%bqorlfAx((G;$UizI8p%*r%bRck(aina>$YyBz1A5AiDZFFDlFG zax{@hkr2*~l{Dto(5?Q`XGFS~Smm zR|uW!ol_!hPWmBZeLCL|ro6#2@#=LbDdO+?sD7iPoF4_=;IHz4``T%5OtDAeT1H%q&nUFAve zsV~#`o)ir;#A#hsy)(N_&Wgs2u{w-w(+AgPTlxw3p5U)^P8J8%Kh7tOQ@X*3zh{0i zS9R6_9x=Uz;WlZXT%MecfxF&&1b_V@l-Kcxcs*tup+|o`u#g-y> zc$&Z9Id}4+I$bAZn@y`GBGm;Src9m${RX*N1fen!erm8ZY1k}D)vxDHCPFukO9828 z0_y~Q8VN76d_+5Cmmqgzw)JsuhBC!f&6ibXBd8$@z@hkZL(}9Bx zs|pWA_jl3XUVXUPZY%i=EsPFLQO5s*BwVkl@0}VqUmua#n9KpWz317!Kl^MAHJz2Y z*99T|TvSyzRye?2C3RaYY?ZuKrU*ZkJGo58OB95%oegN=I6$+2!$)wEhBs?|~#HjgcD&>|l z_ZHhHkgo7uP>EQ@+I+`WZX$8D)6Gp!$r)FHwfqAO&tYhdOoqH{$VAWT9Hcl5`t*YD zo9uvsEo90ZLM^%aTM|_8cGj(s*KID{VP)UFMy44qB#L=n^!MN&^BGA3Z-<*uj=?!? zJtT`~`!d2kU$RttCF;L~W)J7auUDJyxh*6!i&p9lm zo#+3c?j4^?<(06E78#jEp1!{#b$|YP{1D#-hTB0N!FP&-UgqjUrjwJB$;V_Ii`Vl; zkg}9|kA2^;*DQ8Ae|_C-4?mY$DqLiG`tRBonCynwoK+mT}@^} z@M40-jnTvrFWlPL@Oq93$Ro;ZYBQ$L0QEI0H##;v?I*M! z4)fZj6L4MYq?jJUpCIal*LXgW155k<@Osk;4v?P;E3Ty(uH5OIdfEv=&^wfCcDehe z*buvcBWaPap$KD6$vqnK0|+HYJ4VUOm(ZqVc4^t8!*{XgoRko^o55R&k-58bcP>gW zIpgBReTE3&nP{{-xJ9v!j-A~mkxGhC3t>@-itA4ao_$ne3o_7h?-_oq(Lm)A)aLa( zSfFsSq9~^2-B)M*TFx5vYvT!}ox0;FSK2gDz3%yIuiJ7wmm-Ayl03>ZIu#8-vY_+k z?)s^TCOiu)LWT4&m1*^2YXZ&lZ*2Us=36fUJ8%r6G!3nzcKsuFS*wCI+l(dQ59Ts` zp)38Q@)6zrE-gC-;4|7#J6I^j>pHq60acNJYO-8(65F1)Tyzy*-_k~ea5$qK-NvG0 zbm-7(YNB=*lDDNWn5uCIhGk*&P&BfCCw}K(ukTu0(Tuj}J39UPg9WV^Q+@ZR6enVngefqzS5q zGn^V!GR+z-*6qgD;UGEp$VC>x^WRzS*Q(g1WGA2*M5{iYPAnziw(6lXwyHLAs(N~w zxbkV9&Oio?IihRLY&A8?+mK3Yda+%H&6b-)mvPq2iS0I|*zunKTf0|+Ms$DR`&d_I z1(;<ztdx*|ne cs6*M-Lv?gHU(w#)Yx-H$IA0vnfF$()0y#=c3IG5A diff --git a/ProgramFiles/sysplotter.m b/ProgramFiles/sysplotter.m index d2703a1..e68bbde 100644 --- a/ProgramFiles/sysplotter.m +++ b/ProgramFiles/sysplotter.m @@ -22,7 +22,7 @@ % Edit the above text to modify the response to help sysplotter -% Last Modified by GUIDE v2.5 21-Apr-2017 14:10:54 +% Last Modified by GUIDE v2.5 26-Apr-2017 14:47:43 addpath('./Utilities') @@ -165,16 +165,3 @@ function sysplotter_OpeningFcn(hObject, eventdata, handles, varargin) varargout{1} = handles.output; end - - -% --- Executes on button press in pushbutton20. -function pushbutton20_Callback(hObject, eventdata, handles) -% hObject handle to pushbutton20 (see GCBO) -% eventdata reserved - to be defined in a future version of MATLAB -% handles structure with handles and user data (see GUIDATA) - plot_info = plotpushbutton_Callback_optimize(findall(0,'tag','plotpushbutton3'), eventdata, handles); - -% Execute the gait_gui_draw command - gait_gui_optimize(plot_info(1).axes(1),hObject, eventdata, handles); -waitbar2a(1,handles.progresspanel,'Finished Plotting') -end \ No newline at end of file diff --git a/ProgramFiles/sysplotter_gui_fcns/OptimizeButton_Callback.m b/ProgramFiles/sysplotter_gui_fcns/OptimizeButton_Callback.m new file mode 100644 index 0000000..9041844 --- /dev/null +++ b/ProgramFiles/sysplotter_gui_fcns/OptimizeButton_Callback.m @@ -0,0 +1,11 @@ +% --- Executes on button press in pushbutton20. +function OptimizeButton_Callback(hObject, eventdata, handles) +% hObject handle to pushbutton20 (see GCBO) +% eventdata reserved - to be defined in a future version of MATLAB +% handles structure with handles and user data (see GUIDATA) + plot_info = plotpushbutton_Callback_optimize(findall(0,'tag','plotpushbutton3'), eventdata, handles); + +% Execute the gait_gui_draw command + gait_gui_optimize(plot_info(1).axes(1),hObject, eventdata, handles); +waitbar2a(1,handles.progresspanel,'Finished Plotting') +end \ No newline at end of file From 2f66c6de1a1b6ee6ed362fde130ebd05d015c71b Mon Sep 17 00:00:00 2001 From: remaleyj Date: Wed, 26 Apr 2017 16:35:12 -0700 Subject: [PATCH 008/286] Revert "Jacquelin's branch" From 5f65c612273e31b9db17b4c1753693c8bf2ccbc7 Mon Sep 17 00:00:00 2001 From: Suresh Ramasamy Date: Wed, 6 Sep 2017 15:28:49 -0700 Subject: [PATCH 009/286] Fourier series enabled gait optimization works for systems with 2 shape variables. --- .../gait_gui_draw/gait_gui_optimize.m | 5 +- .../gait_gui_draw/optimalgaitgenerator.m | 631 ++++++++++++++++-- 2 files changed, 565 insertions(+), 71 deletions(-) diff --git a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m index 54f327c..0666756 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m +++ b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m @@ -25,6 +25,7 @@ function gait_gui_optimize(hAx,hObject,eventdata,handles) period = 2*pi; + n_plot = 100; t_plot = linspace(0,period,n_plot+1); @@ -33,8 +34,8 @@ function gait_gui_optimize(hAx,hObject,eventdata,handles) f=fullfile(datapath,strcat(current_system,'_calc.mat')); load(f); -lb=0.9*[s.grid_range(1)*ones(n_plot,1);s.grid_range(3)*ones(n_plot,1)]; -ub=0.9*[s.grid_range(2)*ones(n_plot,1);s.grid_range(4)*ones(n_plot,1)]; +lb=0.9*[s.grid_range(1)*ones(n_plot+1,1);s.grid_range(3)*ones(n_plot+1,1)];%0.9 was points value +ub=0.9*[s.grid_range(2)*ones(n_plot+1,1);s.grid_range(4)*ones(n_plot+1,1)]; y=optimalgaitgenerator(s,2,n_plot,alpha1_plot,alpha2_plot,lb,ub); alpha1 = [y(1:100)',y(1)]'; alpha2 = [y(101:200)',y(101)]'; diff --git a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m index 7eed959..57e7b86 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m +++ b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m @@ -18,6 +18,28 @@ P1(:,1)=a1(1,1:n)'; P1(:,2)=a2(1,1:n)'; +%% finding fourier coeffecients. + +num=3; +% coeff=zeros(3*num,dimension); + +t=1:1:npoints+1; +fa=cell(dimension); + +for i=1:1:dimension + fa{i}=fit(t',[P1(:,i);P1(1,i)],'fourier5'); +end + +figure(1) +plot(fa{1},t',[P1(:,1);P1(1,1)]) + +figure(2) +plot(fa{2},t',[P1(:,2);P1(1,2)]) + + +%% + + % for i=1:1:n/2 % P1(i,1)=-0.5+0.5*cos((i-1)*4*pi/n); % P1(i,2)=+0.5*sin((i-1)*4*pi/n); @@ -41,49 +63,73 @@ beq=[]; % lb=-2.2*ones(200,1); % ub=2.2*ones(200,1); -nonlcon=[]; -options = optimoptions('fmincon','SpecifyObjectiveGradient',true,'Display','iter','Algorithm','active-set','GradObj','on','TolX',10^-4,'TolFun',10^-6,'MaxIter',4000,'MaxFunEvals',20000); - [y fval exitflag output]=fmincon(@(y) solvedifffmincon(y,s,n,dimension),P0,A,b,Aeq,beq,lb,ub,nonlcon,options); -% [y fval exitflag output]=fmincon(@(y) solvedifffmincon1(y,s,n),P0,A,b,Aeq,beq,lb,ub,nonlcon,options); + nonlcon1=[]; + +nu={'a0';'a1';'b1';'a2';'b2';'a3';'b3';'a4';'b4';'a5';'b5';'w'};% + lb1=[]; + ub1=[]; -for i=1:n - xf(i)=y(i); - yf(i)=y(n+i); +for i=1:dimension + for j=1:length(nu) + y0(j,i)=fa{i}.(nu{j}); + end end +% options = optimoptions('fmincon','SpecifyObjectiveGradient',true,'Display','iter','Algorithm','active-set','GradObj','on','TolX',10^-4,'TolFun',10^-6,'MaxIter',4000,'MaxFunEvals',20000); + options = optimoptions('fmincon','SpecifyObjectiveGradient',true,'Display','iter','Algorithm','sqp','SpecifyObjectiveGradient',true,'CheckGradients',false,'FiniteDifferenceType','central','MaxIter',4000,'MaxFunEvals',20000); + [yf fval exitflag output]=fmincon(@(y) solvedifffmincon(y,s,n,dimension,lb,ub),y0,A,b,Aeq,beq,lb1,ub1,@(y) nonlcon(y,s,n,dimension,lb,ub),options);% (y,s,n,dimension) +% [y fval exitflag output]=fmincon(@(y) solvedifffmincon1(y,s,n),P0,A,b,Aeq,beq,lb,ub,nonlcon,options); + +for i=1:1:n + for j=1:dimension + y1(i,j)=yf(1,j)+yf(2,j)*cos(i*yf(end,j))+yf(3,j)*sin(i*yf(end,j))+yf(4,j)*cos(2*i*yf(end,j))+yf(5,j)*sin(2*i*yf(end,j))+yf(6,j)*cos(3*i*yf(end,j))+yf(7,j)*sin(3*i*yf(end,j))+yf(8,j)*cos(4*i*yf(end,j))+yf(9,j)*sin(4*i*yf(end,j))+yf(10,j)*cos(5*i*yf(end,j))+yf(11,j)*sin(5*i*yf(end,j)); + end +end +y=y1(:); % for i=1:n -% xf(i)=P1(i,1); -% yf(i)=P1(i,2); +% xf(i)=y(i); +% yf(i)=y(n+i); % end - -% figure(10) +% % +% % for i=1:n` +% % xf(i)=P1(i,1); +% % yf(i)=P1(i,2); +% % end +% % +% figure(11) % hold on -% plot(xf,yf,'r') +% plot(xf,yf,'-o') + end -function [f,g]=solvedifffmincon(y,s,n,dimension) +function [f,g]=solvedifffmincon(y,s,n,dimension,lb,ub) afactor=0.001; -y1=y; -clear y -y=zeros(n,dimension); -for j=1:1:dimension - y(:,j)=y1((j-1)*n+1:n*j); +coeff=y; +for i=1:1:n + for j=1:dimension + y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j))+y(8,j)*cos(4*i*y(end,j))+y(9,j)*sin(4*i*y(end,j))+y(10,j)*cos(5*i*y(end,j))+y(11,j)*sin(5*i*y(end,j));;% + end end - +clear y +% y=zeros(n,dimension); +% for j=1:1:dimension +% y(:,j)=y1((j-1)*n+1:n*j); +% end +y=y1; % pointvalues=[y1(1:n)*abar,y1(n+1:2*n)*bbar,y1(2*n+1:3*n)*cbar]; pointvalues=y; %% Calculating cost and displacement per gait g=10; -p.phi = @(t) interp1( linspace(0,g,n+1), [pointvalues; pointvalues(1,:)], t); +p.phi_def = @(t) interp1( linspace(0,g,n+1), [pointvalues; pointvalues(1,:)], t); for i=1:1:n-1 velocityvalues(i,:)=n*(pointvalues(i+1,:)-pointvalues(i,:))/g; end velocityvalues(n,:)=n*(pointvalues(1,:)-pointvalues(n,:))/g; -p.dphi = @(t) interp1( linspace(0,g,n), [velocityvalues], t); +p.dphi_def = @(t) interp1( linspace(0,g,n), [velocityvalues], t); -[net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,[0, g],'interpolated','fixed_step',100); +[net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,[0, g],'interpolated','ODE'); lineint=net_disp_opt(1); totalstroke=cost; @@ -100,6 +146,34 @@ end +%% for checking purposes + +% g=10; +% p.phi = @(t) interp1( linspace(0,g,n+1), [pointvalues1; pointvalues1(1,:)], t); +% for i=1:1:n-1 +% velocityvalues(i,:)=n*(pointvalues1(i+1,:)-pointvalues1(i,:))/g; +% end +% velocityvalues(n,:)=n*(pointvalues1(1,:)-pointvalues1(n,:))/g; +% p.dphi = @(t) interp1( linspace(0,g,n), [velocityvalues], t); +% +% +% [net_disp_orig, net_disp_opt1, cost] = evaluate_displacement_and_cost1(s,p,[0, g],'interpolated','fixed_step',100); +% lineint=net_disp_opt(1); +% totalstroke=cost; +% +% if lineint<0 +% lineint=-lineint; +% ytemp=y; +% for i=1:n +% y(i,:)=ytemp(n+1-i,:); +% end +% invert=1; +% else +% lineint=lineint; +% invert=0; +% end + + %% Preliminaries for calculation for i=1:1:n @@ -199,7 +273,7 @@ %% Jacobiandisp-jacobian for displacement produced by gait -parfor i=2:1:n-1 +for i=2:1:n-1 jacobiandisp(i,:)=jacobiandispcalculator3(y(i-1,:),y(i,:),y(i+1,:),height(i,:),dimension); end jacobiandisp(1,:)=jacobiandispcalculator3(y(n,:),y(1,:),y(2,:),height(1,:),dimension); @@ -208,7 +282,14 @@ %% Jacobianeqi-term that keeps points eqi distant from each other -parfor i=2:n-1; +for i=2:n-1; +% y(i-1,:) +% y(i,:) +% y(i+1,:) +% i +% metric{i} +% metric{i-1} +% metric{i+1} len=sqrt((y(i+1,:)-y(i-1,:))*((metric{i-1}+metric{i+1})/2)*(y(i+1,:)-y(i-1,:))'); midpoint=y(i-1,:)+((y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2))/2; betacos=(y(i+1,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i+1})/2)*((y(i,:)-y(i-1,:))*sqrtm((metric{i-1}+metric{i})/2))'/(l(i-1)*len); @@ -253,65 +334,177 @@ % xhat=y(n-1,:)+(y(1,:)-y(n-1,:))*l1*betacos/len; % jacobianeqi(n,:)=midpoint-xhat; +%% changey/dcoeff +chy=cell(dimension,1); -%% Final gradient calculation -if invert == 0 - %totaljacobian=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; - totaljacobian=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; - dsdw=jacobiandisp; - dy=dsdw(:); +for i=1:1:dimension + for j=1:1:n + chy{i}(:,j)=[1;cos(j*coeff(end,i));sin(j*coeff(end,i));cos(2*j*coeff(end,i));sin(2*j*coeff(end,i));cos(3*j*coeff(end,i));sin(3*j*coeff(end,i));cos(4*j*coeff(end,i));sin(4*j*coeff(end,i));cos(5*j*coeff(end,i));sin(5*j*coeff(end,i))];% + end +end + +%% properly orienting jacobians +% invert +if invert==0 + jacobiandisptemp=jacobiandisp; + jacobianstroketemp=jacobianstroke; + jacobianeqitemp=jacobianeqi; + jacobiandisp=jacobiandisp; + jacobianstroke=jacobianstroke; + jacobianeqi=jacobianeqi; else - %totaljacobiantemp=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; - totaljacobiantemp=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; - for i=1:n - totaljacobian(i,:)=totaljacobiantemp(n+1-i,:); + jacobiandisptemp=jacobiandisp; + jacobianstroketemp=jacobianstroke; + jacobianeqitemp=jacobianeqi; + for i=1:1:n + jacobiandisp(i,:)=jacobiandisptemp(n+1-i,:); + jacobianstroke(i,:)=jacobianstroketemp(n+1-i,:); + jacobianeqi(i,:)=jacobianeqitemp(n+1-i,:); + + end +end + +%% fourier series version of all jacobians + +totaljacobian=jacobiandisp/totalstroke-lineint*jacobianstroke/totalstroke^2+jacobianeqi; + +for i=1:1:dimension + for j=1:1:11 + jacobiandispfourier(j,i)=chy{i}(j,:)*jacobiandisp(:,i); + jacobianstrokefourier(j,i)=chy{i}(j,:)*jacobianstroke(:,i); + jacobianeqifourier(j,i)=chy{i}(j,:)*jacobianeqi(:,i); + totaljacobianfourier(j,i)=chy{i}(j,:)*totaljacobian(:,i); end end + + + + + + +%% Final gradient calculation +% if invert == 0 +% %totaljacobian=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; +% % totaljacobian=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; +% totaljacobian=jacobiandisp+1*jacobianeqi; +% dsdw=jacobiandisp; +% dy=dsdw(:); +% else +% %totaljacobiantemp=jacobiandisp/totalstroke-(((lineint)*jacobianstroke)/(1*totalstroke^2))/1+1*jacobianeqi; +% totaljacobiantemp=jacobiandisp-(((lineint)*jacobianstroke)/(1*totalstroke))/1+1*jacobianeqi; +% for i=1:n +% % totaljacobian(i,:)=totaljacobiantemp(n+1-i,:); +% totaljacobian(i,:)=1*jacobiandisp(n+1-i,:)+1*jacobianeqi(n+1-i,:); +% end +% end +% totaljacobian=jacobiandispfourier+jacobianeqifourier;%+((lineint)*jacobianstrokefourier)/(1*totalstroke)+4*jacobianeqifourier; +%totaljacobianfourier=jacobiandispfourier/totalstroke-((lineint)*jacobianstrokefourier)/(1*totalstroke)^2+2*jacobianeqifourier; +% for i=1:n +% for j=1:1:dimension +% totaljacobianc(i,j)=chy{j}(:,i)'*totaljacobianfourier(:,j); +% jacobiandispc(i,j)=chy{j}(:,i)'*jacobiandispfourier(:,j); +% jacobianstrokec(i,j)=chy{j}(:,i)'*jacobianstrokefourier(:,j); +% end +% end +% totaljacobianctemp=totaljacobianc; +% jacobiandispctemp=jacobiandispc; +% jacobianstrokectemp=jacobianstrokec; +% for i=1:1:n +% jacobiandispc(i,:)=jacobiandispctemp(n+1-i,:); +% jacobianstrokec(i,:)=jacobianstrokectemp(n+1-i,:); +% totaljacobianc(i,:)=totaljacobianctemp(n+1-i,:); +% end + +% jacobiandispfourier=jacobiandispfourier;%+jacobianeqifourier; %% minimizing negative of efficiency -f=-lineint/(totalstroke); + f=-lineint/(totalstroke); +% f=-lineint; if nargout>1 - %g=-(jacobiandisp)-1*jacobianeqi; - g=-totaljacobian(:); +% g=-totaljacobian(:); + g=[-totaljacobianfourier;zeros(1,dimension)]; end +%% so currently jacobiandisp is for the reversed way. y is reversed, pointvalues are reversed. Calculating jacobiandisp using finite differences. +% jacobianforward=zeros(100,2); +% for i=1:1:100 +% for j=1:1:2 +% pointvalues1=pointvalues; +% pointvalues1(i,j)=pointvalues(i,j)+0.1; +% g=10; +% p.phi_def = @(t) interp1( linspace(0,g,n+1), [pointvalues1; pointvalues1(1,:)], t); +% for k=1:1:n-1 +% velocityvalues(k,:)=n*(pointvalues1(k+1,:)-pointvalues1(k,:))/g; +% end +% velocityvalues(n,:)=n*(pointvalues1(1,:)-pointvalues1(n,:))/g; +% p.dphi_def = @(t) interp1( linspace(0,g,n), [velocityvalues], t); +% +% +% [net_disp_orig, net_disp_opt1, cost] = evaluate_displacement_and_cost1(s,p,[0, g],'interpolated','fixed_step',600); +% jacobianforward(i,j)=(net_disp_opt1(1)-lineint)/0.1; +% end +% i +% end + %% Debugging and plotting % for i=1:n % G(i)=y(i,1); % H(i)=y(i,2); % % P(i)=y(i,3); -% I(i)=1*jacobianstroke(i,1); -% J(i)=1*jacobianstroke(i,2); +% % I(i)=1*jacobianstroketemp(i,1); +% % J(i)=1*jacobianstroketemp(i,2); +% I(i)=1*jacobianstrokec(i,1); +% J(i)=1*jacobianstrokec(i,2); % % N(i)=1*jacobianstroke(i,3); -% K(i)=jacobiandisp(i,1); -% L(i)=jacobiandisp(i,2); +% % K(i)=jacobiandisptemp(i,1); +% K(i)=jacobiandispc(i,1); +% % K1(i)=jacobianforward(i,1); +% % L(i)=jacobiandisptemp(i,2); +% L(i)=jacobiandispc(i,2); +% % L1(i)=jacobianforward(i,2); % % Q(i)=jacobiandisp(i,3); -% B(i)=totaljacobian(i,1); -% C(i)=totaljacobian(i,2); +% B(i)=totaljacobianc(i,1); +% B1(i)=totaljacobian(i,1); +% C(i)=totaljacobianc(i,2); +% C1(i)=totaljacobian(i,2); % % D(i)=totaljacobian(i,3); % O(i)=jacobianeqi(i,1); % S(i)=jacobianeqi(i,2); % % R(i)=jacobianeqi(i,3); % % heightx(i)=height(i,1); -% % heighty(i)=height(i,2); +% % heighty(i)=height(i,2); % % heightz(i)=height(i,3); % % heightcrosscheck(i)=height(i,:)*jacobiandisp(i,:)'; % end -% -% +% % % % +% % % % % clf(figure(6)) %%jacobiandisp % figure(6) % scale=0; % scale1=1; % quiver(G,H,K,L,scale1) % hold on -% % quiver(G,H,P,heightx,heighty,heightz,scale1) +% % quiver(G,H,heightx,heighty,scale1) % plot(G,H) % axis equal % hold off +% +% % clf(figure(9)) %%jacobianforward +% % figure(9) +% % scale=0; +% % scale1=1; +% % quiver(G,H,K1,L1,scale1) +% % hold on +% % % quiver(G,H,P,heightx,heighty,heightz,scale1) +% % plot(G,H) +% % axis equal +% % hold off % % +% +% +% % % % clf(figure(7)) %%jacobianstroke % figure(7) % scale=0; @@ -321,34 +514,52 @@ % plot(G,H) % axis equal % hold off -% % % % +% % % % % % clf(figure(8)) %%% totaljacobian % figure(8) % scale=0; % quiver(G,H,B,C,scale1) % hold on -% plot(G,H) -% axis equal -% hold off +% quiver(G,H,B1,C1,scale1) % -% clf(figure(3)) %%%jacobianeqi -% figure(3) -% scale1=1; -% quiver3(G,H,P,O,S,R,scale1) -% hold on -% plot3(G,H,P) +% plot(G,H) % axis equal % hold off -% -% -% % figure(5) -% % scale=0; -% % quiver(G,H,B1,C1,scale1) +% % +% % clf(figure(3)) %%%jacobianeqi +% % figure(3) +% % scale1=1; +% % quiver3(G,H,P,O,S,R,scale1) % % hold on -% % plot(G,H) +% % plot3(G,H,P) % % axis equal % % hold off +% % +% % +% % % figure(5) +% % % scale=0; +% % % quiver(G,H,B1,C1,scale1) +% % % hold on +% % % plot(G,H) +% % % axis equal +% % % hold off +% % min(abs(totaljacobian)) +% % max(abs(totaljacobian)) +% % pause(0.1) +% +% % +% % for i=1:1:length(height) +% % heightcheckper(i)=(heightcheck(i)-height(i))/height(i); +% % end +% +% figure(5) +% plot(y(:,1),y(:,2)) +% axis equal +% % pause(0.1) + + + end function a=jacobiandispcalculator3(p1,p2,p3,height,dimension) @@ -408,6 +619,263 @@ end +function [A,Aeq]=nonlcon(y,s,n,dimension,lb,ub) + +% Aeq=[]; + +coeff=y; +for i=1:1:n+1 + for j=1:dimension + y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j)); + end +end + +y2=y1(:); + +b=length(y2); + +%A=max(max(abs(y1)))-2.2; + +A1=y2+lb;%-2.2*ones(b,1); +A2=-y2-ub;%2.2*ones(b,1); + +A=[A1;A2]; + +Aeq=y1(1,:)'-y1(n+1,:)'; + + +end +% function [net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,tspan,ConnectionEval,IntegrationMethod,resolution) +% % Evaluate the displacement and cost for the gait specified in the +% % structure GAIT when executed by the system described in the structure +% % S. +% % +% % S should be a sysplotter 's' structure loaded from a file +% % sysf_FILENAME_calc.mat (note the _calc suffix) +% % +% % P should be a structure with fields "phi" and "dphi", returning a +% % vector of shapes and shape velocities respectively. If it is not +% % convenient to analytically describe the shape velocity function, +% % gait.dphi should be defined as +% % +% % p.dphi = @(t) jacobianest(@(T) p.phi (T),t) +% % +% % as is done automatically by sysplotter, but note that this will be slower +% % than specifying a function directly +% % +% % ConnectionEval can specify whether the local connection should be generated from +% % its original function definiton, or by interpolation into the evaluated +% % matrix, but is optional. Valid options are 'functional' or +% % 'interpolated'. Defaults to "interpolated", which significantly faster +% % when calculating the local connection or metric from scratch takes +% % appreciable computational time +% % +% % IntegrationMethod can specify whether ODE45 or a fixed point +% % (euler-exponential) integration method should be employed. Defaults to +% % ODE, fixed point code is experimental. +% % +% % RESOLUTION specifies the number of points for fixed-point resolution +% % evaluation. A future option may support autoconvergence, but ODE +% % performance with interpolated evaluation appears to be fast enough that +% % refinement of fixed-point performance is on hold. +% +% +% % if no ConnectionEval method is specified, default to interpolated +% if ~exist('ConnectionEval','var') +% ConnectionEval = 'interpolated'; +% end +% +% % if no IntegrationMethod is specified, default to ODE +% if ~exist('IntegrationMethod','var') +% IntegrationMethod = 'ODE'; +% end +% +% % if no resolution is specified, default to 100 (this only affects +% % fixed_step integration) +% if ~exist('resolution','var') +% resolution = 100; +% end +% +% +% +% switch IntegrationMethod +% +% case 'fixed_step' +% +% [net_disp_orig, cost] = fixed_step_integrator(s,p,tspan,ConnectionEval,resolution); +% +% case 'ODE' +% +% % Calculate the system motion over the gait +% sol = ode45(@(t,y) helper_function(t,y,s,p,ConnectionEval),tspan,[0 0 0 0]'); +% +% % Extract the final motion +% disp_and_cost = deval(sol,tspan(end)); +% +% net_disp_orig = disp_and_cost(1:3); +% cost = disp_and_cost(end); +% +% % Convert the final motion into its representation in optimal +% % coordinates +% startshape = p.phi(0); +% startshapelist = num2cell(startshape); +% beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); +% net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... +% -sin(beta_theta) cos(beta_theta) 0;... +% 0 0 1]*net_disp_orig; +% +% otherwise +% error('Unknown method for integrating motion'); +% end +% +% +% % Convert the final motion into its representation in optimal +% % coordinates +% startshape = p.phi(0); +% startshapelist = num2cell(startshape); +% beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); +% net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... +% -sin(beta_theta) cos(beta_theta) 0;... +% 0 0 1]*net_disp_orig; +% +% +% end +% +% % Evaluate the body velocity and cost velocity (according to system metric) +% % at a given time +% function [xi, dcost] = get_velocities(t,s,gait,ConnectionEval) +% +% % Get the shape and shape derivative at the current time +% shape = gait.phi(t); +% shapelist = num2cell(shape); +% dshape = gait.dphi(t); +% +% +% % Get the local connection and metric at the current time, in the new coordinates +% switch ConnectionEval +% case 'functional' +% +% A = s.A_num(shapelist{:})./s.A_den(shapelist{:}); +% +% M = s.metric(shapelist{:}); +% +% case 'interpolated' +% +% A = -cellfun(@(C) interpn(s.grid.eval{:},C,shapelist{:}),s.vecfield.eval.content.Avec); +% +% M = cellfun(@(C) interpn(s.grid.metric_eval{:},C,shapelist{:}),s.metricfield.metric_eval.content.metric); +% +% otherwise +% error('Unknown method for evaluating local connection'); +% end +% +% % Get the body velocity at the current time +% xi = - A * dshape(:); +% +% % get the cost velocity +% dcost = sqrt(dshape(:)' * M * dshape(:)); +% +% end +% +% +% % Function to integrate up system velocities using a fixed-step method +% function [net_disp_orig, cost] = fixed_step_integrator(s,gait,tspan,ConnectionEval,resolution) +% +% % Duplicate 'resolution' to 'res' if it is a number, or place res at a +% % starting resolution if an automatic convergence method is selected +% % (automatic convergence not yet enabled) +% default_res = 100; +% if isnumeric(resolution) +% res = resolution; +% elseif isstr(resolution) && strcmp(resolution,'autoconverge') +% res = default_res; +% else +% error('Unexpected value for resolution'); +% end +% +% % Generate the fixed points from the time span and resolution +% tpoints = linspace(tspan(1),tspan(2),res); +% tsteps = gradient(tpoints); +% +% % Evaluate the velocity function at each time +% [xi, dcost] = arrayfun(@(t) get_velocities(t,s,gait,ConnectionEval),tpoints,'UniformOutput',false); +% +% +% %%%%%%% +% % Integrate cost and displacement into final values +% +% %% +% % Exponential integration for body velocity +% +% % Exponentiate each velocity over the corresponding time step +% expXi = cellfun(@(xi,timestep) se2exp(xi*timestep),xi,num2cell(tsteps),'UniformOutput',false); +% +% % Start off with zero position and displacement +% net_disp_matrix = eye(size(expXi{1})); +% +% % Loop over all the time steps from 1 to n-1, multiplying the +% % transformation into the current displacement +% for i = 1:(length(expXi)-1) +% +% net_disp_matrix = net_disp_matrix * expXi{i}; +% +% end +% +% % De-matrixafy the result +% g_theta = atan2(net_disp_matrix(2,1),net_disp_matrix(1,1)); +% g_xy = net_disp_matrix(1:2,3); +% +% net_disp_orig = [g_xy;g_theta]; +% +% %% +% % Trapezoidal integration for cost +% dcost = [dcost{:}]; +% cost = trapz(tpoints,dcost); +% +% end +% +% +% % Function to evaluate velocity and differential cost at each time for ODE +% % solver +% function dX = helper_function(t,X,s,gait,ConnectionEval) +% +% % X is the accrued displacement and cost +% +% [xi, dcost] = get_velocities(t,s,gait,ConnectionEval); +% +% % Rotate body velocity into world frame +% theta = X(3); +% v = [cos(theta) -sin(theta) 0; sin(theta) cos(theta) 0; 0 0 1]*xi; +% +% % Combine the output +% dX = [v;dcost]; +% +% +% end +% +% function expXi = se2exp(xi) +% +% % Make sure xi is a column +% xi = xi(:); +% +% % Special case non-rotating motion +% if xi(3) == 0 +% +% expXi = [eye(2) xi(1:2); 0 0 1]; +% +% else +% +% z_theta = xi(3); +% +% z_xy = 1/z_theta * [sin(z_theta), 1-cos(z_theta); cos(z_theta)-1, sin(z_theta)] * xi(1:2); +% +% expXi = [ [cos(z_theta), -sin(z_theta); sin(z_theta), cos(z_theta)], z_xy; +% 0 0 1]; +% +% end +% +% +% end function [net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,tspan,ConnectionEval,IntegrationMethod,resolution) % Evaluate the displacement and cost for the gait specified in the % structure GAIT when executed by the system described in the structure @@ -416,7 +884,7 @@ % S should be a sysplotter 's' structure loaded from a file % sysf_FILENAME_calc.mat (note the _calc suffix) % -% P should be a structure with fields "phi" and "dphi", returning a +% P should be a structure with fields "phi_def" and "dphi_def", returning a % vector of shapes and shape velocities respectively. If it is not % convenient to analytically describe the shape velocity function, % gait.dphi should be defined as @@ -480,7 +948,7 @@ % Convert the final motion into its representation in optimal % coordinates - startshape = p.phi(0); + startshape = p.phi_def(0); startshapelist = num2cell(startshape); beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... @@ -494,7 +962,7 @@ % Convert the final motion into its representation in optimal % coordinates - startshape = p.phi(0); + startshape = p.phi_def(0); startshapelist = num2cell(startshape); beta_theta = interpn(s.grid.eval{:},s.B_optimized.eval.Beta{3},startshapelist{:},'cubic'); net_disp_opt = [cos(beta_theta) sin(beta_theta) 0;... @@ -509,9 +977,9 @@ function [xi, dcost] = get_velocities(t,s,gait,ConnectionEval) % Get the shape and shape derivative at the current time - shape = gait.phi(t); + shape = gait.phi_def(t); shapelist = num2cell(shape); - dshape = gait.dphi(t); + dshape = gait.dphi_def(t); % Get the local connection and metric at the current time, in the new coordinates @@ -533,7 +1001,8 @@ end % Get the body velocity at the current time - xi = - A * dshape(:); + t; + xi = - A * dshape(:); % get the cost velocity dcost = sqrt(dshape(:)' * M * dshape(:)); @@ -639,3 +1108,27 @@ end + +function [g_end_orig,g_end_opt, cost_end] = extract_displacement_and_cost(datafile) +% Extract the displacement and cost data from a sysf_...shchf_....mat file + +% Load the target file +load(datafile,'p') + +% Prime arrays to hold the net displacement (in original and optimal +% coordinates) and cost from each shape change in the file. p.G_locus_full is +% single-level cell array of structures, each of which holds the +% information for one gait (with all segments concatenated) +g_end_orig = zeros(numel(p.G_locus_full),3); +g_end_opt = g_end_orig; +cost_end = zeros(numel(p.G_locus_full,1)); % If distance metric was not specified, euclidean metric in the parameters was assumed + +% Loop over each shape change +for i = 1:numel(p.G_locus_full) + + % Extract the final values for the relevant parameters + g_end_orig(i,:) = p.G_locus_full{i}.G(end,:); + g_end_opt(i,:) = p.G_locus_full{i}.G_opt(end,:); + cost_end(i) = p.G_locus_full{i}.S(end); +end +end \ No newline at end of file From 4e8a9766c9c0a35f80dafdece3d9b06a7b0f5c3a Mon Sep 17 00:00:00 2001 From: Suresh Ramasamy Date: Wed, 6 Sep 2017 15:31:39 -0700 Subject: [PATCH 010/286] No longer plots fourier fit when optimize gait button is clicked. --- .../Utilities/gait_gui_draw/optimalgaitgenerator.m | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m index 57e7b86..7cb338b 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m +++ b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m @@ -30,11 +30,11 @@ fa{i}=fit(t',[P1(:,i);P1(1,i)],'fourier5'); end -figure(1) -plot(fa{1},t',[P1(:,1);P1(1,1)]) - -figure(2) -plot(fa{2},t',[P1(:,2);P1(1,2)]) +% figure(1) +% plot(fa{1},t',[P1(:,1);P1(1,1)]) +% +% figure(2) +% plot(fa{2},t',[P1(:,2);P1(1,2)]) %% From 9a13b7a5c1f80df9fb8627bd388b84ac23b0f230 Mon Sep 17 00:00:00 2001 From: Suresh Ramasamy Date: Tue, 10 Oct 2017 13:02:43 -0700 Subject: [PATCH 011/286] Corrected implementation of non linear constraint. Fixed over fitting with fourier functions. --- .../gait_gui_draw/gait_gui_optimize.m | 4 +- .../gait_gui_draw/optimalgaitgenerator.m | 143 ++++++++++-------- 2 files changed, 80 insertions(+), 67 deletions(-) diff --git a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m index 0666756..c265d20 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m +++ b/ProgramFiles/Utilities/gait_gui_draw/gait_gui_optimize.m @@ -34,8 +34,8 @@ function gait_gui_optimize(hAx,hObject,eventdata,handles) f=fullfile(datapath,strcat(current_system,'_calc.mat')); load(f); -lb=0.9*[s.grid_range(1)*ones(n_plot+1,1);s.grid_range(3)*ones(n_plot+1,1)];%0.9 was points value -ub=0.9*[s.grid_range(2)*ones(n_plot+1,1);s.grid_range(4)*ones(n_plot+1,1)]; +lb=0.8*[s.grid_range(1)*ones(n_plot+1,1);s.grid_range(3)*ones(n_plot+1,1)];%0.9 was points value +ub=0.8*[s.grid_range(2)*ones(n_plot+1,1);s.grid_range(4)*ones(n_plot+1,1)]; y=optimalgaitgenerator(s,2,n_plot,alpha1_plot,alpha2_plot,lb,ub); alpha1 = [y(1:100)',y(1)]'; alpha2 = [y(101:200)',y(101)]'; diff --git a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m index 7cb338b..5d1abb7 100644 --- a/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m +++ b/ProgramFiles/Utilities/gait_gui_draw/optimalgaitgenerator.m @@ -27,14 +27,14 @@ fa=cell(dimension); for i=1:1:dimension - fa{i}=fit(t',[P1(:,i);P1(1,i)],'fourier5'); + fa{i}=fit(t',[P1(:,i);P1(1,i)],'fourier4'); end -% figure(1) -% plot(fa{1},t',[P1(:,1);P1(1,1)]) -% -% figure(2) -% plot(fa{2},t',[P1(:,2);P1(1,2)]) +figure(1) +plot(fa{1},t',[P1(:,1);P1(1,1)]) + +figure(2) +plot(fa{2},t',[P1(:,2);P1(1,2)]) %% @@ -65,7 +65,7 @@ % ub=2.2*ones(200,1); nonlcon1=[]; -nu={'a0';'a1';'b1';'a2';'b2';'a3';'b3';'a4';'b4';'a5';'b5';'w'};% +nu={'a0';'a1';'b1';'a2';'b2';'a3';'b3';'a4';'b4';'w'};% lb1=[]; ub1=[]; @@ -82,7 +82,7 @@ for i=1:1:n for j=1:dimension - y1(i,j)=yf(1,j)+yf(2,j)*cos(i*yf(end,j))+yf(3,j)*sin(i*yf(end,j))+yf(4,j)*cos(2*i*yf(end,j))+yf(5,j)*sin(2*i*yf(end,j))+yf(6,j)*cos(3*i*yf(end,j))+yf(7,j)*sin(3*i*yf(end,j))+yf(8,j)*cos(4*i*yf(end,j))+yf(9,j)*sin(4*i*yf(end,j))+yf(10,j)*cos(5*i*yf(end,j))+yf(11,j)*sin(5*i*yf(end,j)); + y1(i,j)=yf(1,j)+yf(2,j)*cos(i*yf(end,j))+yf(3,j)*sin(i*yf(end,j))+yf(4,j)*cos(2*i*yf(end,j))+yf(5,j)*sin(2*i*yf(end,j))+yf(6,j)*cos(3*i*yf(end,j))+yf(7,j)*sin(3*i*yf(end,j))+yf(8,j)*cos(4*i*yf(end,j))+yf(9,j)*sin(4*i*yf(end,j));%+yf(10,j)*cos(5*i*yf(end,j))+yf(11,j)*sin(5*i*yf(end,j));%+yf(12,j)*cos(6*i*yf(end,j))+yf(13,j)*sin(6*i*yf(end,j)); end end y=y1(:); @@ -107,7 +107,7 @@ coeff=y; for i=1:1:n for j=1:dimension - y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j))+y(8,j)*cos(4*i*y(end,j))+y(9,j)*sin(4*i*y(end,j))+y(10,j)*cos(5*i*y(end,j))+y(11,j)*sin(5*i*y(end,j));;% + y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j))+y(8,j)*cos(4*i*y(end,j))+y(9,j)*sin(4*i*y(end,j));%+y(10,j)*cos(5*i*y(end,j))+y(11,j)*sin(5*i*y(end,j));%+y(12,j)*cos(6*i*y(end,j))+y(13,j)*sin(6*i*y(end,j));% end end clear y @@ -144,7 +144,8 @@ lineint=lineint; invert=0; end - +% max(y) +% min(y) %% for checking purposes @@ -337,12 +338,20 @@ %% changey/dcoeff chy=cell(dimension,1); - -for i=1:1:dimension - for j=1:1:n - chy{i}(:,j)=[1;cos(j*coeff(end,i));sin(j*coeff(end,i));cos(2*j*coeff(end,i));sin(2*j*coeff(end,i));cos(3*j*coeff(end,i));sin(3*j*coeff(end,i));cos(4*j*coeff(end,i));sin(4*j*coeff(end,i));cos(5*j*coeff(end,i));sin(5*j*coeff(end,i))];% +% if invert == 0 + for i=1:1:dimension + for j=1:1:n + chy{i}(:,j)=[1;cos(j*coeff(end,i));sin(j*coeff(end,i));cos(2*j*coeff(end,i));sin(2*j*coeff(end,i));cos(3*j*coeff(end,i));sin(3*j*coeff(end,i));cos(4*j*coeff(end,i));sin(4*j*coeff(end,i))];%cos(5*j*coeff(end,i));sin(5*j*coeff(end,i))];%;cos(6*j*coeff(end,i));sin(6*j*coeff(end,i))];% + end end -end +% else +% for i=1:1:dimension +% for j=1:1:n +% chy{i}(:,n+1-j)=[1;cos(j*coeff(end,i));sin(j*coeff(end,i));cos(2*j*coeff(end,i));sin(2*j*coeff(end,i));cos(3*j*coeff(end,i));sin(3*j*coeff(end,i));cos(4*j*coeff(end,i));sin(4*j*coeff(end,i));cos(5*j*coeff(end,i));sin(5*j*coeff(end,i))];% +% end +% end +% end + %% properly orienting jacobians % invert @@ -370,7 +379,7 @@ totaljacobian=jacobiandisp/totalstroke-lineint*jacobianstroke/totalstroke^2+jacobianeqi; for i=1:1:dimension - for j=1:1:11 + for j=1:1:9 %%%don't hardcode jacobiandispfourier(j,i)=chy{i}(j,:)*jacobiandisp(:,i); jacobianstrokefourier(j,i)=chy{i}(j,:)*jacobianstroke(:,i); jacobianeqifourier(j,i)=chy{i}(j,:)*jacobianeqi(:,i); @@ -401,21 +410,23 @@ % totaljacobian=jacobiandispfourier+jacobianeqifourier;%+((lineint)*jacobianstrokefourier)/(1*totalstroke)+4*jacobianeqifourier; %totaljacobianfourier=jacobiandispfourier/totalstroke-((lineint)*jacobianstrokefourier)/(1*totalstroke)^2+2*jacobianeqifourier; -% for i=1:n -% for j=1:1:dimension -% totaljacobianc(i,j)=chy{j}(:,i)'*totaljacobianfourier(:,j); -% jacobiandispc(i,j)=chy{j}(:,i)'*jacobiandispfourier(:,j); -% jacobianstrokec(i,j)=chy{j}(:,i)'*jacobianstrokefourier(:,j); -% end -% end -% totaljacobianctemp=totaljacobianc; -% jacobiandispctemp=jacobiandispc; -% jacobianstrokectemp=jacobianstrokec; -% for i=1:1:n -% jacobiandispc(i,:)=jacobiandispctemp(n+1-i,:); -% jacobianstrokec(i,:)=jacobianstrokectemp(n+1-i,:); -% totaljacobianc(i,:)=totaljacobianctemp(n+1-i,:); -% end + +%%% if invert==1 +for i=1:n + for j=1:1:dimension + totaljacobianc(i,j)=chy{j}(:,i)'*totaljacobianfourier(:,j); + jacobiandispc(i,j)=chy{j}(:,i)'*jacobiandispfourier(:,j); + jacobianstrokec(i,j)=chy{j}(:,i)'*jacobianstrokefourier(:,j); + end +end + totaljacobianctemp=totaljacobianc; + jacobiandispctemp=jacobiandispc; + jacobianstrokectemp=jacobianstrokec; +for i=1:1:n + jacobiandispc(i,:)=jacobiandispctemp(n+1-i,:); + jacobianstrokec(i,:)=jacobianstrokectemp(n+1-i,:); + totaljacobianc(i,:)=totaljacobianctemp(n+1-i,:); +end % jacobiandispfourier=jacobiandispfourier;%+jacobianeqifourier; %% minimizing negative of efficiency @@ -449,35 +460,35 @@ %% Debugging and plotting -% for i=1:n -% G(i)=y(i,1); -% H(i)=y(i,2); -% % P(i)=y(i,3); -% % I(i)=1*jacobianstroketemp(i,1); -% % J(i)=1*jacobianstroketemp(i,2); -% I(i)=1*jacobianstrokec(i,1); -% J(i)=1*jacobianstrokec(i,2); -% % N(i)=1*jacobianstroke(i,3); -% % K(i)=jacobiandisptemp(i,1); -% K(i)=jacobiandispc(i,1); -% % K1(i)=jacobianforward(i,1); -% % L(i)=jacobiandisptemp(i,2); -% L(i)=jacobiandispc(i,2); -% % L1(i)=jacobianforward(i,2); -% % Q(i)=jacobiandisp(i,3); -% B(i)=totaljacobianc(i,1); -% B1(i)=totaljacobian(i,1); -% C(i)=totaljacobianc(i,2); -% C1(i)=totaljacobian(i,2); -% % D(i)=totaljacobian(i,3); -% O(i)=jacobianeqi(i,1); -% S(i)=jacobianeqi(i,2); -% % R(i)=jacobianeqi(i,3); -% % heightx(i)=height(i,1); -% % heighty(i)=height(i,2); -% % heightz(i)=height(i,3); -% % heightcrosscheck(i)=height(i,:)*jacobiandisp(i,:)'; -% end +for i=1:n + G(i)=y(i,1); + H(i)=y(i,2); +% P(i)=y(i,3); +% I(i)=1*jacobianstroketemp(i,1); +% J(i)=1*jacobianstroketemp(i,2); + I(i)=1*jacobianstrokec(i,1); + J(i)=1*jacobianstrokec(i,2); +% N(i)=1*jacobianstroke(i,3); +% K(i)=jacobiandisptemp(i,1); + K(i)=jacobiandispc(i,1); +% K1(i)=jacobianforward(i,1); +% L(i)=jacobiandisptemp(i,2); + L(i)=jacobiandispc(i,2); +% L1(i)=jacobianforward(i,2); +% Q(i)=jacobiandisp(i,3); + B(i)=totaljacobianc(i,1); + B1(i)=totaljacobian(i,1); + C(i)=totaljacobianc(i,2); + C1(i)=totaljacobian(i,2); +% D(i)=totaljacobian(i,3); + O(i)=jacobianeqi(i,1); + S(i)=jacobianeqi(i,2); +% R(i)=jacobianeqi(i,3); +% heightx(i)=height(i,1); +% heighty(i)=height(i,2); +% heightz(i)=height(i,3); +% heightcrosscheck(i)=height(i,:)*jacobiandisp(i,:)'; +end % % % % % % % % % clf(figure(6)) %%jacobiandisp @@ -518,7 +529,7 @@ % clf(figure(8)) %%% totaljacobian % figure(8) % scale=0; -% quiver(G,H,B,C,scale1) +% quiver(G,H,B,C,scale1) % hold on % quiver(G,H,B1,C1,scale1) % @@ -556,7 +567,7 @@ % plot(y(:,1),y(:,2)) % axis equal % -% pause(0.1) +% pause(0.1) @@ -626,7 +637,7 @@ coeff=y; for i=1:1:n+1 for j=1:dimension - y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j)); + y1(i,j)=y(1,j)+y(2,j)*cos(i*y(end,j))+y(3,j)*sin(i*y(end,j))+y(4,j)*cos(2*i*y(end,j))+y(5,j)*sin(2*i*y(end,j))+y(6,j)*cos(3*i*y(end,j))+y(7,j)*sin(3*i*y(end,j))+y(8,j)*cos(4*i*y(end,j))+y(9,j)*sin(4*i*y(end,j));%+y(10,j)*cos(5*i*y(end,j))+y(11,j)*sin(5*i*y(end,j));%+y(12,j)*cos(6*i*y(end,j))+y(13,j)*sin(6*i*y(end,j)); end end @@ -638,11 +649,13 @@ A1=y2+lb;%-2.2*ones(b,1); A2=-y2-ub;%2.2*ones(b,1); +A3=y1(1,:)'-y1(n+1,:)'-[0.05;0.05]; +A4=-y1(1,:)'+y1(n+1,:)'-[0.05;0.05]; A=[A1;A2]; -Aeq=y1(1,:)'-y1(n+1,:)'; - +% Aeq=y1(1,:)'-y1(n+1,:)'; +Aeq=0; end % function [net_disp_orig, net_disp_opt, cost] = evaluate_displacement_and_cost1(s,p,tspan,ConnectionEval,IntegrationMethod,resolution) From 0a0e173c945e5454e94127d9db32aef2b8e53101 Mon Sep 17 00:00:00 2001 From: remaleyj Date: Thu, 16 Nov 2017 17:26:09 -0800 Subject: [PATCH 012/286] Replaced BVI checkboxes with Metric Ellipse Field, extensibility options for LowRE and curvdef templates added, version checker implemented on sysplotter_config.fig and sysplotter.fig. Primarily meant as a working version backup. --- ...pation_metric_from_stretchable_curvature.m | 42 +++ ...al_connection_from_stretchable_curvature.m | 122 +++++++ .../backbone_from_stretchable_curvature.m | 102 ++++++ ...curvdef_stretch_piecewise_abs_template.txt | 59 +++ ...ef_stretch_piecewise_abs_template_Lrms.txt | 59 +++ .../curvdef_stretch_piecewise_template.txt | 59 +++ ...urvdef_stretch_piecewise_template_Lrms.txt | 59 +++ .../fatbackbone_from_stretch_curvature.m | 76 ++++ .../make_curvdef_piecewise_abs_stretch.m | 81 +++++ .../make_curvdef_piecewise_stretch.m | 80 ++++ .../make_curvdef_piecewise_stretch_Lrms.m | 80 ++++ .../make_curvdef_piecewise_stretch_abs_Lrms.m | 80 ++++ .../make_curvdef_st_template.txt | 49 +++ .../make_curvdef_stretch.m | 344 ++++++++++++++++++ .../Utilities/extract_length_over_time.m | 63 ++++ ProgramFiles/sys_draw_fcns/mfield_draw.m | 220 +++++++++++ ProgramFiles/sysplotter.fig | Bin 151836 -> 143307 bytes ProgramFiles/sysplotter.m | 5 +- ProgramFiles/sysplotter_config.fig | Bin 13143 -> 17684 bytes ProgramFiles/sysplotter_config.m | 10 +- ProgramFiles/sysplotter_config_compare.fig | Bin 0 -> 18520 bytes .../OKbutton_Callback.m | 5 +- .../guiDisplaySelection_Callback.m | 31 ++ ProgramFiles/sysplotter_config_old.fig | Bin 0 -> 13143 bytes .../sysplotter_gui_fcns/get_box_values.m | 16 +- .../sysplotter_gui_fcns/get_box_values_old.m | 100 +++++ ProgramFiles/sysplotter_old.fig | Bin 0 -> 151836 bytes Quick Start v5_0_3.docx | Bin 0 -> 5726257 bytes .../Shape_Changes/butterfly_params.mat | Bin 0 -> 478 bytes .../Remaley/Shape_Changes/params_test.mat | Bin 0 -> 510 bytes .../Shape_Changes/params_test_optimal.mat | Bin 0 -> 2553 bytes .../shchf_LowRe_MaxDisplacement.m | 65 ++++ .../shchf_LowRe_MaxEff_and_Disp.m | 87 +++++ .../Shape_Changes/shchf_LowRe_MaxEfficiency.m | 64 ++++ .../Remaley/Shape_Changes/shchf_butterfly.m | 59 +++ .../Remaley/Shape_Changes/shchf_circle_1p0.m | 63 ++++ .../Remaley/Shape_Changes/shchf_circle_6.m | 63 ++++ .../Shape_Changes/shchf_circle_family_loose.m | 77 ++++ .../Shape_Changes/shchf_diffdrive_example.m | 81 +++++ .../shchf_kinsnake_demo_circle.m | 63 ++++ .../Remaley/Shape_Changes/shchf_params_test.m | 98 +++++ .../Shape_Changes/shchf_params_test_optimal.m | 98 +++++ .../shchf_piecewise_seed_abs_b_0_optimal.m | 98 +++++ .../shchf_piecewise_seed_abs_b_318_optimal.m | 98 +++++ .../shchf_piecewise_seed_b_0_optimal.m | 98 +++++ .../shchf_piecewise_seed_b_101_optimal.m | 98 +++++ .../shchf_purcell_family_loose.m | 112 ++++++ .../shchf_serpenoid_seed_abs_b_0_optimal.m | 98 +++++ .../shchf_serpenoid_seed_abs_b_318_optimal.m | 98 +++++ .../shchf_serpenoid_seed_b_0_optimal.m | 98 +++++ .../shchf_serpenoid_seed_b_101_optimal.m | 98 +++++ .../Granular_Local_Connection_Matrix.mat | Bin 0 -> 14559 bytes .../curv_piecewise_const_stretch_abs_b_0.m | 59 +++ .../curv_piecewise_const_stretch_abs_b_318.m | 59 +++ .../curv_piecewise_const_stretch_b_0.m | 59 +++ .../curv_piecewise_const_stretch_b_101.m | 59 +++ .../Systems/curv_serpenoid_stretch_abs_b_0.m | 91 +++++ .../curv_serpenoid_stretch_abs_b_318.m | 99 +++++ .../Systems/curv_serpenoid_stretch_b_0.m | 91 +++++ .../Systems/curv_serpenoid_stretch_b_101.m | 99 +++++ .../Systems/curv_triangle_wave_one_period.m | 88 +++++ UserFiles/Remaley/Systems/sysf_diffdrive.m | 81 +++++ .../sysf_piecewise_const_stretch_abs_b_0.m | 92 +++++ .../sysf_piecewise_const_stretch_abs_b_318.m | 92 +++++ .../sysf_piecewise_const_stretch_b_0.m | 92 +++++ .../sysf_piecewise_const_stretch_b_101.m | 92 +++++ .../Systems/sysf_serpenoid_extendable_0.m | 92 +++++ .../Systems/sysf_serpenoid_extendable_101.m | 92 +++++ .../Systems/sysf_serpenoid_extendable_abs_0.m | 92 +++++ .../sysf_serpenoid_extendable_abs_318.m | 92 +++++ .../Remaley/Systems/sysf_serpenoid_lowRe.m | 71 ++++ .../Systems/sysf_three_link_granular.m | 116 ++++++ .../Systems/sysf_three_link_kinematic.m | 90 +++++ .../Remaley/Systems/sysf_three_link_lowRe.m | 145 ++++++++ .../Remaley/Systems/sysf_triangle_lowRe.m | 124 +++++++ 75 files changed, 5517 insertions(+), 6 deletions(-) create mode 100644 ProgramFiles/Utilities/LowRe_toolbox/LowRE_dissipation_metric_from_stretchable_curvature.m create mode 100644 ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_stretchable_curvature.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/backbone_from_stretchable_curvature.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template.txt create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template_Lrms.txt create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template.txt create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template_Lrms.txt create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/fatbackbone_from_stretch_curvature.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_abs_stretch.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_Lrms.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_abs_Lrms.m create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_st_template.txt create mode 100644 ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_stretch.m create mode 100644 ProgramFiles/Utilities/extract_length_over_time.m create mode 100644 ProgramFiles/sys_draw_fcns/mfield_draw.m create mode 100644 ProgramFiles/sysplotter_config_compare.fig create mode 100644 ProgramFiles/sysplotter_config_fcns/guiDisplaySelection_Callback.m create mode 100644 ProgramFiles/sysplotter_config_old.fig create mode 100644 ProgramFiles/sysplotter_gui_fcns/get_box_values_old.m create mode 100644 ProgramFiles/sysplotter_old.fig create mode 100644 Quick Start v5_0_3.docx create mode 100644 UserFiles/Remaley/Shape_Changes/butterfly_params.mat create mode 100644 UserFiles/Remaley/Shape_Changes/params_test.mat create mode 100644 UserFiles/Remaley/Shape_Changes/params_test_optimal.mat create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_LowRe_MaxDisplacement.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_LowRe_MaxEff_and_Disp.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_LowRe_MaxEfficiency.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_butterfly.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_circle_1p0.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_circle_6.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_circle_family_loose.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_diffdrive_example.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_kinsnake_demo_circle.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_params_test.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_params_test_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_piecewise_seed_abs_b_0_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_piecewise_seed_abs_b_318_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_piecewise_seed_b_0_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_piecewise_seed_b_101_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_purcell_family_loose.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_serpenoid_seed_abs_b_0_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_serpenoid_seed_abs_b_318_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_serpenoid_seed_b_0_optimal.m create mode 100644 UserFiles/Remaley/Shape_Changes/shchf_serpenoid_seed_b_101_optimal.m create mode 100644 UserFiles/Remaley/Systems/Granular_Local_Connection_Matrix.mat create mode 100644 UserFiles/Remaley/Systems/curv_piecewise_const_stretch_abs_b_0.m create mode 100644 UserFiles/Remaley/Systems/curv_piecewise_const_stretch_abs_b_318.m create mode 100644 UserFiles/Remaley/Systems/curv_piecewise_const_stretch_b_0.m create mode 100644 UserFiles/Remaley/Systems/curv_piecewise_const_stretch_b_101.m create mode 100644 UserFiles/Remaley/Systems/curv_serpenoid_stretch_abs_b_0.m create mode 100644 UserFiles/Remaley/Systems/curv_serpenoid_stretch_abs_b_318.m create mode 100644 UserFiles/Remaley/Systems/curv_serpenoid_stretch_b_0.m create mode 100644 UserFiles/Remaley/Systems/curv_serpenoid_stretch_b_101.m create mode 100644 UserFiles/Remaley/Systems/curv_triangle_wave_one_period.m create mode 100644 UserFiles/Remaley/Systems/sysf_diffdrive.m create mode 100644 UserFiles/Remaley/Systems/sysf_piecewise_const_stretch_abs_b_0.m create mode 100644 UserFiles/Remaley/Systems/sysf_piecewise_const_stretch_abs_b_318.m create mode 100644 UserFiles/Remaley/Systems/sysf_piecewise_const_stretch_b_0.m create mode 100644 UserFiles/Remaley/Systems/sysf_piecewise_const_stretch_b_101.m create mode 100644 UserFiles/Remaley/Systems/sysf_serpenoid_extendable_0.m create mode 100644 UserFiles/Remaley/Systems/sysf_serpenoid_extendable_101.m create mode 100644 UserFiles/Remaley/Systems/sysf_serpenoid_extendable_abs_0.m create mode 100644 UserFiles/Remaley/Systems/sysf_serpenoid_extendable_abs_318.m create mode 100644 UserFiles/Remaley/Systems/sysf_serpenoid_lowRe.m create mode 100644 UserFiles/Remaley/Systems/sysf_three_link_granular.m create mode 100644 UserFiles/Remaley/Systems/sysf_three_link_kinematic.m create mode 100644 UserFiles/Remaley/Systems/sysf_three_link_lowRe.m create mode 100644 UserFiles/Remaley/Systems/sysf_triangle_lowRe.m diff --git a/ProgramFiles/Utilities/LowRe_toolbox/LowRE_dissipation_metric_from_stretchable_curvature.m b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_dissipation_metric_from_stretchable_curvature.m new file mode 100644 index 0000000..95e1c29 --- /dev/null +++ b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_dissipation_metric_from_stretchable_curvature.m @@ -0,0 +1,42 @@ +function Mp = LowRE_dissipation_metric_from_stretchable_curvature(kappa_basis_input,r,L,c,drag_ratio) +% Calculate the dissipation power metric for a set of curvature bases + + % Specified integration limits + int_limit = L*[-0.5 0.5]; + + % Define the tangential, lateral drag matrix for unit/double drag + drag = [1 0; 0 drag_ratio]*c; + + % Get the backbone locus, Jacobian, and Local Connection functions + [A, h, J] = LowRE_local_connection_from_stretchable_curvature(kappa_basis_input,r,L,c,drag_ratio); + + % Integrate along the body for the power metric + Mp_sol = ode_multistart(@ode45,@(s,Mp) dMetric(s,Mp,A,h,J,drag),int_limit,int_limit(1),zeros(length(r)^2,1)); + + Mp = reshape(Mp_sol(int_limit(end)),length(r),[]); + +end + + +function localJ = local_body_velocity_J(A,h,J) +% Calculate the Jacobian from shape parameter velocity to local tangential +% and normal velocity + + R = [cos(h(3)) sin(h(3)); + -sin(h(3)) cos(h(3))]; + + %Velocity is sum of body velocity and velocity within body frame + localJ = R*(-A(1:2,:) + J(1:2,:) + [-h(2)*(-A(3,:)); h(1)*(-A(3,:))]); + +end + +function dMp = dMetric(s,Mp,A,h,J,drag) %#ok +% Calculate the local contribution to the power metric + + localJ = local_body_velocity_J(A,h(s),J(s)); + + dMp = localJ.'*drag*localJ; + + dMp = dMp(:); + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_stretchable_curvature.m b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_stretchable_curvature.m new file mode 100644 index 0000000..6cc18be --- /dev/null +++ b/ProgramFiles/Utilities/LowRe_toolbox/LowRE_local_connection_from_stretchable_curvature.m @@ -0,0 +1,122 @@ +function [A, h, J,Omega] = LowRE_local_connection_from_stretchable_curvature(curvdef,cparams,L,c,drag_ratio) +% Calculate the local connection for a set of curvature bases +% +% Inputs: +% kappa_basis_input: cell vector of handles to basis functions +% r: coefficients for basis functions +% L: total length of swimmer +% c: drag per unit length +% drag_ratio: ratio of lateral to longitudinal drag + +% Specified integration limits +int_limit = L*[-0.5 0.5]; + +% First, get the backbone locus and Jacobian functions +[h, J] = backbone_from_stretchable_curvature(curvdef,cparams,L); + +% Now integrate to get the pfaffian +%Omega_sol = ode45( @(s,Omega) connection_helper(s,h(s),J(s)),int_limit,zeros(3,3+length(r))); +Omega_sol = ode_multistart(@ode45,@(s,Omega) connection_helper(s,h(s),J(s),c,drag_ratio),int_limit,int_limit(1),zeros(3,3+length(cparams))); + +Omega = reshape(Omega_sol(int_limit(end)),3,[]); + +A = Omega(:,1:3)\Omega(:,4:end); + +end + +function dOmega = connection_helper(s,h,J,c,drag_ratio) %#ok +% Calculate the derivative of the local connection as it's built up along +% the backbone + + % Midpoint-tangent-frame force jacobian + gdot_to_xi_local = [cos(h(3)) sin(h(3)) 0; + -sin(h(3)) cos(h(3)) 0; + 0 0 1]; + + % Local drag, based on unit longitudinal drag, lateral according to the ratio, no local + % torsional drag, multiplied by drag coefficient + xi_local_to_F_local = [-1 0 0;0 -drag_ratio 0;0 0 0]*c; + + % Force local element applies at midpoint-tangent-frame + F_local_to_F_midpoint = [cos(h(3)) -sin(h(3)) 0; + sin(h(3)) cos(h(3)) 0; + 0 0 1]; + + % Moment around midpoint frame induced by force + F_midpoint_to_FM_midpoint = [1 0 0; 0 1 0; -h(2) h(1) 1]; + + % shape component of pfaffian + omega2 = F_midpoint_to_FM_midpoint * F_local_to_F_midpoint... + * xi_local_to_F_local * gdot_to_xi_local * J; + + % body velocity component of pfaffian + omega1 = F_midpoint_to_FM_midpoint * F_local_to_F_midpoint... + * xi_local_to_F_local * gdot_to_xi_local * [1 0 -h(2); 0 1 h(1); 0 0 1]; + + dOmega = [omega1 omega2]; + dOmega = dOmega(:); + +% % local contribution to the local connection +% dA = omega1\omega2; +% +% % reshape into a vector +% dA = dA(:); + + + +end + +function X = torow( X ) +% +% TOROW Converts a vector or a matrix into a row vector. +% If input is already a row vector, it is returned with no change. +% If input is a column vector, it is converted into a row vector and +% returned. +% If input is a matrix, each column is converted into a row, and all +% resulting rows are placed in series into a single row which is +% returned. +% +% Input: +% X - input vector or matrix +% +% Output: +% X - row vector +% +% Examples: +% torow([ 0 1 2 3 ]) +% returns [ 0 1 2 3 ] +% torow([ 0 1 2 3 ]') +% returns [ 0 1 2 3 ] +% torow([ 0 1; 2 3 ]) +% returns [ 0 2 1 3 ] +% torow([ 0 1; 2 3 ]') +% returns [ 0 1 2 3 ] +% +% Author: Tashi Ravach +% Version: 1.0 +% Date: 07/07/2010 +% + + % check if input is a vector + [ m, n ] = size(X); + if m == 1 + return % input is already a row vector with n columns + elseif n==1 + X = X'; % input is converted from column vector to row vector + elseif (m*n>n) || (m*n>m) + X = X(:)'; % input is converted from matrix to row vector by column + else + X = []; % input is unknown and an empty output is returned + end + +end + +function Y = toz( X ) + + %first, make X a row + X = torow(X); + + % then, make it a 3rd-dimension column + Y(1,1,:) = X; + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/backbone_from_stretchable_curvature.m b/ProgramFiles/Utilities/curvature_mode_toolbox/backbone_from_stretchable_curvature.m new file mode 100644 index 0000000..ed12491 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/backbone_from_stretchable_curvature.m @@ -0,0 +1,102 @@ +function [h, J] = backbone_from_stretchable_curvature(curvdef,cparams,L) + +% Set the integration limits. Internally, everything uses [-0.5 0.5], and +% then scales by the length factor at the end. +all_limits = [-0.5 0 0.5]; + +% Get backbone theta as a function of s +theta_fun = curvdef(cparams,'angle'); +stretch_fun = curvdef(cparams,'stretch'); + +% Get the x and y locations of points on the backbone +locus_sol = ode_multistart(@ode45, @(s,h) locus_helper(s,theta_fun,stretch_fun),all_limits,0,[0;0]); + +% Return the locus data as 3xn matrix with x,y,theta at each of n points +h_norm = @(s) [locus_sol(torow(s)); theta_fun(torow(s))]; % in normalized internal coordinates +h = @(s) [L*locus_sol(torow(s)/L); theta_fun(torow(s)/L)]; % with actual length + +%%%%%%%%%%%%%% +% Get the jacobian to body point velocities + +if nargout == 2 + + dcurvdef = curvdef(cparams,'dcurvature_int'); +% dcurvdef = curvdef(cparams,'dcurvature'); + dstretchdef = curvdef(cparams,'dstretch'); + + % add in something for elongation here? or include it in the dcurvedef? + % dlambda = curvedef(cparams,'dlambda') + + %Jacobian of theta function is the derivative of the curvature with respect + %to each of the parameters, as definded in the curvdef function + J_theta_fun = dcurvdef; %ode_multistart(@ode45,@(s,J) dcurvdef(s),all_limits,0,zeros(length(dcurvdef(0)),1)); + + % SE(2) adjoint integration to get the x and y jacobians + jacobian_sol = ode_multistart(@ode45,@(s,J) J_helper(s,J,dcurvdef,h_norm(s),stretch_fun,dstretchdef),all_limits,0,zeros(2*length(dcurvdef(0)),1)); + + % Concatenate xy and theta jacobians. + + J = @(s) cat(1,reshape(L*jacobian_sol(toz(s/L)),2,[],length(s)),(J_theta_fun(s/L))); + % J = @(s) cat(1,reshape(L*jacobian_sol(toz(s/L)),2,[],length(s)),ipermute(J_theta_fun(s/L),[2,3,1])); +end + +end + + +% Get the derivative of the locus along the backbone length +function dh = locus_helper(s,theta_fun,stretch_fun) + + % Build the rotation matrix + theta = theta_fun(s); + lambda = stretch_fun(s); + R = [cos(theta) -sin(theta);sin(theta) cos(theta)]; + + % Rotate the basic tangent vector to point along the backbone + % might need to use zeros(length(stretch_fun) if vector errors happen + dh = R * [lambda; 0]; + +end + +% get the derivative of the jacobian along the backbone length (note that J +% is only here for ODE45, and isn't actually used) +function dJ = J_helper(s,J,dcurvdef,h,stretch_fun,dstretchdef) %#ok + +nvars = length(dcurvdef(0)); + +dJ = zeros(2,nvars); + +dcurvdef_eval = dcurvdef(s); +lambda_eval = stretch_fun(s); +dlambda_eval = dstretchdef(s); +R = [cos(h(3)) -sin(h(3));sin(h(3)) cos(h(3))]; + +for i = 1:nvars + + dJ(:,i) = dcurvdef_eval(i)*[-sin(h(3)) -cos(h(3));cos(h(3)) -sin(h(3))]*[lambda_eval;0]... + +R*[dlambda_eval(i);0]; + +end + +% this should go inside the for loop +% dJ = dJ+R*[dlambda;0]; + +%Reshape into a vector for ODE +dJ = dJ(:); + +end + +function X = torow( X ) % Make the argument a row + + X = X(:).'; + +end + +function Y = toz( X ) + + %first, make X a row + X = torow(X); + + % then, make it a 3rd-dimension column + Y(1,1,:) = X; + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template.txt b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template.txt new file mode 100644 index 0000000..5ed8475 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template.txt @@ -0,0 +1,59 @@ +function output = curv_piecewise_const_stretch_abs_b_%s(params,mode) + +% 4/6/17 Jacquelin's attempt at a simple version of a curvature file, with +% eventual goal of adding elongation mode + +% Turn params into a cell matrix +% params = num2cell(params); + +switch mode + + case 'curvature' + + % kappas + % get alphas for use in heaviside function + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s)+a2*heaviside(s); + + case 'angle' + + % thetas + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s).*s+a2*heaviside(s).*s; + + case 'dcurvature' + + % dk/da + output = @(s) [heaviside(-s) heaviside(s)]; + + case 'dcurvature_int' + + % int(dk/da) + % are the dimensions of these arrays correct? + output = @(s) [heaviside(-s).*s heaviside(s).*s]; + + case 'stretch' + + % lambda term for elongation + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*abs(a1) + 1; % lambda, elongation factor + e2 = b*abs(a2) + 1; + output = @(s) e1*heaviside(-s)+e2*heaviside(s); + + case 'dstretch' + + % change in lambda + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*sign(a1); % dlambda, elongation factor change + e2 = b*sign(a2); + output = @(s) [e1*heaviside(-s) e2*heaviside(s)]; + +end + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template_Lrms.txt b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template_Lrms.txt new file mode 100644 index 0000000..0ccbb4c --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_abs_template_Lrms.txt @@ -0,0 +1,59 @@ +function output = curv_piecewise_abs_L_%s(params,mode) + +% 4/6/17 Jacquelin's attempt at a simple version of a curvature file, with +% eventual goal of adding elongation mode + +% Turn params into a cell matrix +% params = num2cell(params); + +switch mode + + case 'curvature' + + % kappas + % get alphas for use in heaviside function + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s)+a2*heaviside(s); + + case 'angle' + + % thetas + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s).*s+a2*heaviside(s).*s; + + case 'dcurvature' + + % dk/da + output = @(s) [heaviside(-s) heaviside(s)]; + + case 'dcurvature_int' + + % int(dk/da) + % are the dimensions of these arrays correct? + output = @(s) [heaviside(-s).*s heaviside(s).*s]; + + case 'stretch' + + % lambda term for elongation + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*abs(a1) + 1; % lambda, elongation factor + e2 = b*abs(a2) + 1; + output = @(s) e1*heaviside(-s)+e2*heaviside(s); + + case 'dstretch' + + % change in lambda + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*sign(a1); % dlambda, elongation factor change + e2 = b*sign(a2); + output = @(s) [e1*heaviside(-s) e2*heaviside(s)]; + +end + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template.txt b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template.txt new file mode 100644 index 0000000..688c179 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template.txt @@ -0,0 +1,59 @@ +function output = curv_piecewise_const_b_%s(params,mode) + +% 4/6/17 Jacquelin's attempt at a simple version of a curvature file, with +% eventual goal of adding elongation mode + +% Turn params into a cell matrix +% params = num2cell(params); + +switch mode + + case 'curvature' + + % kappas + % get alphas for use in heaviside function + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s)+a2*heaviside(s); + + case 'angle' + + % thetas + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s).*s+a2*heaviside(s).*s; + + case 'dcurvature' + + % dk/da + output = @(s) [heaviside(-s) heaviside(s)]; + + case 'dcurvature_int' + + % int(dk/da) + % are the dimensions of these arrays correct? + output = @(s) [heaviside(-s).*s heaviside(s).*s]; + + case 'stretch' + + % lambda term for elongation + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*a1^2 + 1; % lambda, elongation factor + e2 = b*a2^2 + 1; + output = @(s) e1*heaviside(-s)+e2*heaviside(s); + + case 'dstretch' + + % change in lambda + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = 2*b*a1; % dlambda, elongation factor change + e2 = 2*b*a2; + output = @(s) [e1*heaviside(-s) e2*heaviside(s)]; + +end + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template_Lrms.txt b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template_Lrms.txt new file mode 100644 index 0000000..b442ef9 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/curvdef_stretch_piecewise_template_Lrms.txt @@ -0,0 +1,59 @@ +function output = curv_piecewise_quad_L_%s(params,mode) + +% 4/6/17 Jacquelin's attempt at a simple version of a curvature file, with +% eventual goal of adding elongation mode + +% Turn params into a cell matrix +% params = num2cell(params); + +switch mode + + case 'curvature' + + % kappas + % get alphas for use in heaviside function + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s)+a2*heaviside(s); + + case 'angle' + + % thetas + a1 = params(1); + a2 = params(2); + output = @(s) a1*heaviside(-s).*s+a2*heaviside(s).*s; + + case 'dcurvature' + + % dk/da + output = @(s) [heaviside(-s) heaviside(s)]; + + case 'dcurvature_int' + + % int(dk/da) + % are the dimensions of these arrays correct? + output = @(s) [heaviside(-s).*s heaviside(s).*s]; + + case 'stretch' + + % lambda term for elongation + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = b*a1^2 + 1; % lambda, elongation factor + e2 = b*a2^2 + 1; + output = @(s) e1*heaviside(-s)+e2*heaviside(s); + + case 'dstretch' + + % change in lambda + b = %d; % constant, determines shape + a1 = params(1); % alphas + a2 = params(2); + e1 = 2*b*a1; % dlambda, elongation factor change + e2 = 2*b*a2; + output = @(s) [e1*heaviside(-s) e2*heaviside(s)]; + +end + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/fatbackbone_from_stretch_curvature.m b/ProgramFiles/Utilities/curvature_mode_toolbox/fatbackbone_from_stretch_curvature.m new file mode 100644 index 0000000..4d5184a --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/fatbackbone_from_stretch_curvature.m @@ -0,0 +1,76 @@ +function [B,h_fun,J] = fatbackbone_from_stretch_curvature(curvdef,cparams,L,width,orientation) + + % Specify orientation as midpoint-tangent unless specified otherwise + if ~exist('orientation','var') + orientation = 'midpoint-tangent'; + end + + if nargout == 3 + [h,J] = backbone_from_stretchable_curvature(curvdef,cparams,L); + else %if nargout == 2 + h = backbone_from_stretchable_curvature(curvdef,cparams,L); + end + % h_points = h(linspace(L*-.5,L*.5,100))'; + +% B = fatbackbone(h,L*[-.5 .5],width); + + % Rotate and translate locus if specified + + %Augment the backbone locus with 1s to make them SE(2) point vectors +% B_aug = [B,ones(size(B,1),1)]; + + switch orientation + case 'midpoint-tangent' + % do nothing, locus is already in this condition + + B = fatbackbone(h,L*[-.5 .5],width); + h_fun = @(s) h(s); + case 'com-mean' + + h_points = h(linspace(L*-.5,L*.5,100))'; + + % Build a rotation matrix for center of mass and mean orientation + x = mean(h_points(:,1)); + y = mean(h_points(:,2)); + theta = mean(h_points(:,3)); + + R = [cos(theta) -sin(theta) x; + sin(theta) cos(theta) y; + 0 0 1]; + + B = fatbackbone(h,L*[-.5 .5],width); + % augment B and h + B_aug = [B,ones(size(B,1),1)]; +% h_points_aug = [h_points(:,1:2),ones(size(h_points,1),1)]; + + % Multiply inverse of this matrix by point location matrix + + h_fun = {@(s) h(s); + @(h) [cos(mean(h(:,3))) -sin(mean(h(:,3))) mean(h(:,1));... + sin(mean(h(:,3))) cos(mean(h(:,3))) mean(h(:,2));... + 0 0 1]}; + B_aug = (R\B_aug')'; + B = B_aug(:,1:2); + + % Jacquelin's code implements like below when called + % pts is the 1xn array containing points along the backbone to be + % plotted + % h_fun outputs two function handles, the first gets the + % location on the backbone and the second gets the rotation + % matrix for that location + % h_arrows is my final output array for the x and y points to plot + % h_arrows_rot calls the second function to get the right + % rotation matrix given where on the backbone we are + % h_aug gets the current backbone positions of each point in + % the pts array + +% h_arrows_rot = h_fun{2}(h_fun{1}(linspace(L*-0.5,L*0.5,100))'); +% h_aug = h_fun{1}(pts); +% h_arrows = (h_arrows_rot\[h_aug(1:2,:);ones(1,size(h_aug,2))])'; + + end + + % Restore B to its un-augmented form +% B = B_aug(:,1:2); + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_abs_stretch.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_abs_stretch.m new file mode 100644 index 0000000..58bae26 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_abs_stretch.m @@ -0,0 +1,81 @@ +% test template creator for extensible serpenoid +% 5/16 +% 7 PM - Huzzah! It works! 1000 sysf scripts generated and none of it by hand >:D +% 5/25 edited fopen line to include sprintf so files are easy to tell apart +% - ok I tried to edit it. Gives funny file names. Will make do with +% original files for now. +% 5/30 - Added lines to test just sections of b. should streamline +% integration later. Make sure the correct lines are selected! +% 6/19 - Re-running for piecewise files. Make sure all the right files are +% selected! +% - Totally worked. Just had to not be an idiot with the wrong things +% selected. Now I have 300 system files for the piecewise system :D + +%% Make sure the correct options are selected! %% +function make_curvdef_piecewise_abs_stretch(b,sysplotterpath,syspath) + +% b = 0.3; +% template file, in same directory +template = 'curvdef_stretch_piecewise_abs_template.txt'; % For continuous curvature piecewise +% curvdef_stretch_piecewise_abs_template +% template = 'stretch_test_template.txt'; % For serpenoid +% template = 'stretch_test_section_template.txt'; + +% curvdef_tempdir = fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... +% 'curvdef_tempdir'); +% +% mkdir(curvdef_tempdir) + +% generate a new file for each b value +for ind = 1:numel(b) + + % open both the new file and the template + % fullfile(curvdef_tempdir,[fnamelist{idx} '.m']) + fido = fopen(fullfile(syspath,['curv_piecewise_const_stretch_abs_b_',num2str(b(ind)*1000),'.m']),'w'); +% 'piecewise_const_L_rms_b_',num2str(stretch_const*1000) +% fido = fopen(fullfile(syspath,['curv_piecewise_const_L_rms_',num2str(b(ind)),'.m']),'w'); + fidi = fopen(fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',template)); + + while ~feof(fidi) % while not at the end of the file read previously + + % read next line + s = fgetl(fidi); + + % find locations of stretch_const in that line + st_loc_d = strfind(s,'%d'); + st_loc_s = strfind(s,'%s'); + + % replace "%d" or "%s" with values from b, either alone or *1000 + if ~isempty(st_loc_d) + + % find where the exact value of b is needed + s = sprintf(s,b(ind)); + + end + + if ~isempty(st_loc_s) + + % find where the *1000 value is needed +% s = sprintf(s,num2str(b(ind)*1000)); + s = sprintf(s,num2str(b(ind)*1000)); + + end + + % write the next line in the file + fprintf(fido,'%s\n',s); + + + end + + % close the things + fclose(fidi); + fclose(fido); +end +end + + + + + + + diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch.m new file mode 100644 index 0000000..32ec168 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch.m @@ -0,0 +1,80 @@ +% test template creator for extensible serpenoid +% 5/16 +% 7 PM - Huzzah! It works! 1000 sysf scripts generated and none of it by hand >:D +% 5/25 edited fopen line to include sprintf so files are easy to tell apart +% - ok I tried to edit it. Gives funny file names. Will make do with +% original files for now. +% 5/30 - Added lines to test just sections of b. should streamline +% integration later. Make sure the correct lines are selected! +% 6/19 - Re-running for piecewise files. Make sure all the right files are +% selected! +% - Totally worked. Just had to not be an idiot with the wrong things +% selected. Now I have 300 system files for the piecewise system :D + +%% Make sure the correct options are selected! %% +function make_curvdef_piecewise_stretch(b,sysplotterpath,syspath) + +% b = 0.3; +% template file, in same directory +template = 'curvdef_stretch_piecewise_template.txt'; % For continuous curvature piecewise +% template = 'stretch_test_template.txt'; % For serpenoid +% template = 'stretch_test_section_template.txt'; + +% curvdef_tempdir = fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... +% 'curvdef_tempdir'); +% +% mkdir(curvdef_tempdir) + +% generate a new file for each b value +for ind = 1:numel(b) + + % open both the new file and the template + % fullfile(curvdef_tempdir,[fnamelist{idx} '.m']) + fido = fopen(fullfile(syspath,['curv_piecewise_const_stretch_b_',num2str(b(ind)*1000),'.m']),'w'); +% 'piecewise_const_L_rms_b_',num2str(stretch_const*1000) +% fido = fopen(fullfile(syspath,['curv_piecewise_const_L_rms_',num2str(b(ind)),'.m']),'w'); + fidi = fopen(fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',template)); + + while ~feof(fidi) % while not at the end of the file read previously + + % read next line + s = fgetl(fidi); + + % find locations of stretch_const in that line + st_loc_d = strfind(s,'%d'); + st_loc_s = strfind(s,'%s'); + + % replace "%d" or "%s" with values from b, either alone or *1000 + if ~isempty(st_loc_d) + + % find where the exact value of b is needed + s = sprintf(s,b(ind)); + + end + + if ~isempty(st_loc_s) + + % find where the *1000 value is needed +% s = sprintf(s,num2str(b(ind)*1000)); + s = sprintf(s,num2str(b(ind)*1000)); + + end + + % write the next line in the file + fprintf(fido,'%s\n',s); + + + end + + % close the things + fclose(fidi); + fclose(fido); +end +end + + + + + + + diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_Lrms.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_Lrms.m new file mode 100644 index 0000000..3f7f819 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_Lrms.m @@ -0,0 +1,80 @@ +% test template creator for extensible serpenoid +% 5/16 +% 7 PM - Huzzah! It works! 1000 sysf scripts generated and none of it by hand >:D +% 5/25 edited fopen line to include sprintf so files are easy to tell apart +% - ok I tried to edit it. Gives funny file names. Will make do with +% original files for now. +% 5/30 - Added lines to test just sections of b. should streamline +% integration later. Make sure the correct lines are selected! +% 6/19 - Re-running for piecewise files. Make sure all the right files are +% selected! +% - Totally worked. Just had to not be an idiot with the wrong things +% selected. Now I have 300 system files for the piecewise system :D + +%% Make sure the correct options are selected! %% +function make_curvdef_piecewise_stretch_Lrms(b,sysplotterpath,syspath) + +% b = 0.3; +% template file, in same directory +template = 'curvdef_stretch_piecewise_template_Lrms.txt'; % For continuous curvature piecewise +% template = 'stretch_test_template.txt'; % For serpenoid +% template = 'stretch_test_section_template.txt'; + +% curvdef_tempdir = fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... +% 'curvdef_tempdir'); +% +% mkdir(curvdef_tempdir) + +% generate a new file for each b value +for ind = 1:numel(b) + + % open both the new file and the template + % fullfile(curvdef_tempdir,[fnamelist{idx} '.m']) + fido = fopen(fullfile(syspath,['curv_piecewise_quad_Lrms_',num2str(b(ind)*1000),'.m']),'w'); +% 'piecewise_const_L_rms_b_',num2str(stretch_const*1000) +% fido = fopen(fullfile(syspath,['curv_piecewise_const_L_rms_',num2str(b(ind)),'.m']),'w'); + fidi = fopen(fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',template)); + + while ~feof(fidi) % while not at the end of the file read previously + + % read next line + s = fgetl(fidi); + + % find locations of stretch_const in that line + st_loc_d = strfind(s,'%d'); + st_loc_s = strfind(s,'%s'); + + % replace "%d" or "%s" with values from b, either alone or *1000 + if ~isempty(st_loc_d) + + % find where the exact value of b is needed + s = sprintf(s,b(ind)); + + end + + if ~isempty(st_loc_s) + + % find where the *1000 value is needed +% s = sprintf(s,num2str(b(ind)*1000)); + s = sprintf(s,num2str(b(ind)*1000)); + + end + + % write the next line in the file + fprintf(fido,'%s\n',s); + + + end + + % close the things + fclose(fidi); + fclose(fido); +end +end + + + + + + + diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_abs_Lrms.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_abs_Lrms.m new file mode 100644 index 0000000..38e27f7 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_piecewise_stretch_abs_Lrms.m @@ -0,0 +1,80 @@ +% test template creator for extensible serpenoid +% 5/16 +% 7 PM - Huzzah! It works! 1000 sysf scripts generated and none of it by hand >:D +% 5/25 edited fopen line to include sprintf so files are easy to tell apart +% - ok I tried to edit it. Gives funny file names. Will make do with +% original files for now. +% 5/30 - Added lines to test just sections of b. should streamline +% integration later. Make sure the correct lines are selected! +% 6/19 - Re-running for piecewise files. Make sure all the right files are +% selected! +% - Totally worked. Just had to not be an idiot with the wrong things +% selected. Now I have 300 system files for the piecewise system :D + +%% Make sure the correct options are selected! %% +function make_curvdef_piecewise_stretch_abs_Lrms(b,sysplotterpath,syspath) + +% b = 0.3; +% template file, in same directory +template = 'curvdef_stretch_piecewise_abs_template_Lrms.txt'; % For continuous curvature piecewise +% template = 'stretch_test_template.txt'; % For serpenoid +% template = 'stretch_test_section_template.txt'; + +% curvdef_tempdir = fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... +% 'curvdef_tempdir'); +% +% mkdir(curvdef_tempdir) + +% generate a new file for each b value +for ind = 1:numel(b) + + % open both the new file and the template + % fullfile(curvdef_tempdir,[fnamelist{idx} '.m']) + fido = fopen(fullfile(syspath,['curv_piecewise_abs_L_',num2str(b(ind)*1000),'.m']),'w'); +% 'piecewise_const_L_rms_b_',num2str(stretch_const*1000) +% fido = fopen(fullfile(syspath,['curv_piecewise_const_L_rms_',num2str(b(ind)),'.m']),'w'); + fidi = fopen(fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',template)); + + while ~feof(fidi) % while not at the end of the file read previously + + % read next line + s = fgetl(fidi); + + % find locations of stretch_const in that line + st_loc_d = strfind(s,'%d'); + st_loc_s = strfind(s,'%s'); + + % replace "%d" or "%s" with values from b, either alone or *1000 + if ~isempty(st_loc_d) + + % find where the exact value of b is needed + s = sprintf(s,b(ind)); + + end + + if ~isempty(st_loc_s) + + % find where the *1000 value is needed +% s = sprintf(s,num2str(b(ind)*1000)); + s = sprintf(s,num2str(b(ind)*1000)); + + end + + % write the next line in the file + fprintf(fido,'%s\n',s); + + + end + + % close the things + fclose(fidi); + fclose(fido); +end +end + + + + + + + diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_st_template.txt b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_st_template.txt new file mode 100644 index 0000000..86651b0 --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_st_template.txt @@ -0,0 +1,49 @@ +function output = AA_CURVFILENAME(params,mode) + +% Turn params into a cell matrix +params = num2cell(params); + +switch mode + + case 'curvature' + + AA_curv_fun_call + + case 'angle' + + AA_int_curv_ds_call + + case 'dcurvature' + + AA_d_curv_dp_call + + case 'dcurvature_int' + + AA_int_d_curv_dp_ds_call + + case 'stretch' + + AA_stretch_call + + case 'dstretch' + + AA_dstretch_call + +end + +end + +function output = vector_to_list_input(funhandle,all_params) + + all_params = num2cell(all_params); + + output = funhandle(all_params{:}); + +end + + +function output = reshape_truncate_jacobian(J) + + output = J(2:end)'; + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_stretch.m b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_stretch.m new file mode 100644 index 0000000..fe1a50a --- /dev/null +++ b/ProgramFiles/Utilities/curvature_mode_toolbox/make_curvdef_stretch.m @@ -0,0 +1,344 @@ +function make_curvdef_stretch(curv_fun_cell,paramlist,name,attempt_analytic,sysplotterpath,syspath) +% curv_fun_string can be either a string expression or a symbolic +% expression + +% Load the paths where files should be found +if ~exist('sysplotterpath','var') || ~exist('syspath','var') + + load sysplotter_config + +end + +% Initialize a cell structure to hold the list of functions to operate on +flist = {}; + +% Symbolically calculate all of the requested functions unless told +% otherwise +if ~exist('attempt_analytic','var') + attempt_analytic = [1,1,1,1,1,1]; +end + +% Turn the curvature function from a string into a symbolic expression +warning('off') +if attempt_analytic(1) + curv_fun = sym(curv_fun_cell{1}); + flist = [flist,{curv_fun}]; +else + flist = [flist,{[]}]; +end + +% Integrate the curvature function along the backbone +if attempt_analytic(2) + int_curv_ds_fun = int(curv_fun,'s',0,'s'); + flist = [flist,{int_curv_ds_fun}]; +else + flist = [flist,{[]}]; +end + +% Take the derivative of the curvature with respect to each parameter +if attempt_analytic(3) + d_curv_dp_fun = jacobian(curv_fun,sym(paramlist)); +% d_curv_dp_fun = jacobian(curv_fun,sym(paramlist)).'; + flist = [flist,{d_curv_dp_fun}]; +else + flist = [flist,{[]}]; +end + +% Integrate the parameter-derivative of the curvature function along the +% backbone +if attempt_analytic(4) + int_d_curv_dp_ds_fun = int(d_curv_dp_fun,'s',0,'s'); + flist = [flist,{int_d_curv_dp_ds_fun}]; +else + flist = [flist,{[]}]; +end + +% Function for stretch along backbone +if attempt_analytic(5) + stretch_fun = sym(curv_fun_cell{2}); + flist = [flist,{stretch_fun}]; +else + flist = [flist,{[]}]; +end + +% Take derivative of stretch +if attempt_analytic(6) +% syms s +% dstretch_fun = diff(stretch_fun,s); + dstretch_fun = jacobian(stretch_fun,sym(paramlist)); +% clear s + flist = [flist,{dstretch_fun}]; +else + flist = [flist,{[]}]; +end + +warning('on') +% %%%%%% +% %%%%%% +%%% +%%% +% Print functions out to mfiles in a tempdir + +% List of all the function names +fnamelist = {'curv_fun','int_curv_ds_fun','d_curv_dp_fun','int_d_curv_dp_ds_fun','stretch_fun','dstretch_fun'}; + +% Make a temporary directory to hold mfiles for curvature functions +curvdef_tempdir = fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... +'curvdef_tempdir'); + +mkdir(curvdef_tempdir) + +% Test these functions to see if we can turn them into matlabFunctions +valid_mfile = ones(size(fnamelist)); +for idx = 1:numel(fnamelist) + + if attempt_analytic(idx) + + %%%%% + % See if we can turn this into a matlab function + ftest = matlabFunction(flist{idx},'vars',['s';paramlist(:)]); + testvars = num2cell(zeros(size(paramlist))); + + no_analytical = 0; + try + ftest(0,testvars{:}); % Attempt to call the function generated by matlabfunction + catch ME + % If matlab couldn't make an analytical form of the equation, mark + % this + if strcmp(ME.identifier,'MATLAB:UndefinedFunction') + no_analytical = 1; + end + end + + else + + % Mark as no analytical form if none was attempted + no_analytical = 1; + + end + + + %%%% + % If the matlabfunction passes the analytical-form test, save it to a + % file and then concatenate it into the curvdef file. If it fails the + % test, evaluate it at high density, save that to a file, and append a + % file that loads this data and interpolates it. + + if ~no_analytical + % Save the function to an mfile in the tempdir + + matlabFunction(flist{idx},'file',fullfile(curvdef_tempdir,fnamelist{idx}),'vars',['s';paramlist(:)]); + + switch fnamelist{idx} + + case 'curv_fun' + + curv_fun_call = {'output = @(s) curv_fun(s,params{:});'}; + + case 'int_curv_ds_fun' + + int_curv_ds_call = {'output = @(s) int_curv_ds_fun(s,params{:});'}; + + case 'd_curv_dp_fun' + + d_curv_dp_call = {'output = @(s) d_curv_dp_fun(s,params{:});'}; + + + case 'int_d_curv_dp_ds_fun' + + int_d_curv_dp_ds_call = {'output = @(s) int_d_curv_dp_ds_fun(s,params{:});'}; + + case 'stretch_fun' + + stretch_call = {'output = @(s) stretch_fun(s,params{:});'}; + + case 'dstretch_fun' + + dstretch_call = {'output = @(s) dstretch_fun(s,params{:});'}; + + otherwise + + error('fnamelist entry is not handled by switch statement') + + end + + else + + % Mark that no mfile was created (so that later code does not + % attempt to copy it in + valid_mfile(idx) = 0; + + % Fill in the function calls + switch fnamelist{idx} + + + case 'curv_fun' + + error('Curvature could not be turned into a matlab function. Either implement alternate behavior in make_curvdef, or correct curvature definition') + + case 'int_curv_ds_fun' + + int_curv_ds_call = {'%% Padded length of unit backbone'... + ,'all_limits = [-.51 0 .51];'... + ,''... + ,'%% Make dummy integration function'... + ,['curv_fun_dummy = curv_' name '(cell2mat(params),''curvature'');']... + ,'curvature = @(s,~) curv_fun_dummy(s);'... + ,''... + ,'%% Integral of the integrand function along s'... + ,'output = ode_multistart(@ode45,curvature,all_limits,0,0);'}; + + case 'd_curv_dp_fun' + + d_curv_dp_call = {'%% Create a dummy function that takes in a vector of parameters'... + ,'%% including s, and deals them into individual function parameters'... + ,'curv_intermediate = @(all_params) vector_to_list_input(@curv_fun,all_params);'... + ,''... + ,'%% Create a function that takes the jacobian of the dummy function'... + ,'fulljacobian = @(s) jacobianest(curv_intermediate,[s,params{:}]);'... + ,''... + ,'%% Create a function that truncates the s-derivative from the full jacobian'... + ,'output = @(s) reshape_truncate_jacobian(fulljacobian(s));'}; + + + case 'int_d_curv_dp_ds_fun' + + int_d_curv_dp_ds_call = {'%% Padded length of unit backbone'... + ,'all_limits = [-.51 0 .51];'... + ,''... + ,'%% Make dummy integration function'... + ,['d_curv_dp_fun_dummy = curv_' name '(cell2mat(params),''dcurvature'');']... + ,'dcurvature = @(s,~) d_curv_dp_fun_dummy(s);'... + ,''... + ,'%% Integral of the integrand function along s'... + ,'output = ode_multistart(@ode45,dcurvature,all_limits,0,zeros(size(params(:).'')));'}; + + % need to add cases for stretch and d_stretch. + + otherwise + + error('fnamelist entry is not handled by switch statement') + + end + + end + + + +end + + + +% Open the template file +fidi = fopen(fullfile(sysplotterpath,'Utilities','curvature_mode_toolbox',... + 'make_curvdef_st_template.txt')); + +% Create the output file +fido = fopen(fullfile(syspath,['curv_' name '.m']),'w'); + +% Place the input function string as a comment in the top line of the file +fprintf(fido,'%% %s\n',char(curv_fun_cell)); + +while ~feof(fidi) + + % Read the next line from the input file + s = fgetl(fidi); + + + % Replace the function calls + switch strtrim(s) + + case 'AA_curv_fun_call' + + s = sprintf('\t\t%s\n',curv_fun_call{:}); + + case 'AA_int_curv_ds_call' + + s = sprintf('\t\t%s\n',int_curv_ds_call{:}); + + case 'AA_d_curv_dp_call' + + s = sprintf('\t\t%s\n',d_curv_dp_call{:}); + + case 'AA_int_d_curv_dp_ds_call' + + s = sprintf('\t\t%s\n',int_d_curv_dp_ds_call{:}); + + case 'AA_stretch_call' + + s = sprintf('\t\t%s\n',stretch_call{:}); + + case 'AA_dstretch_call' + + s = sprintf('\t\t%s\n',dstretch_call{:}); + + otherwise + + % Insert the filename + s = strrep(s,'AA_CURVFILENAME',['curv_' name]); + + end + + + % Copy put the line into the new file + fprintf(fido,'%s\n',s); + +end + + +% Close the template function +fclose(fidi); + +% Concatenate any mfile functions onto the end of the template + +for idx = 1:numel(flist) + + if valid_mfile(idx) %Only copy valid mfiles into the + + % Insert a blank line + fprintf(fido,'%s\n',[]); + firstline = 1; + + % Load the matlab function + fidi = fopen(fullfile(curvdef_tempdir,[fnamelist{idx} '.m'])); + + + + % Copy all lines of the function into the curvdef file + while ~feof(fidi) + + % Read the next line from the input file + s = fgetl(fidi); + + % Print the line unless it is a comment or empty + if ~strncmp(s,'%%',1) && ~strcmp(s,'') + + % If it is not the first line, indent + if firstline + firstline = 0; + else + fprintf(fido,'%s\t',[]); + end + + fprintf(fido,'%s\n',s); + end + + end + + % Insert an end command and an extra blank line + fprintf(fido,'%s\n\n','end'); + + fclose(fidi); + + end + +end + + + +% cleanup +rmdir(curvdef_tempdir,'s') + +fclose(fido); + +end \ No newline at end of file diff --git a/ProgramFiles/Utilities/extract_length_over_time.m b/ProgramFiles/Utilities/extract_length_over_time.m new file mode 100644 index 0000000..c580b3a --- /dev/null +++ b/ProgramFiles/Utilities/extract_length_over_time.m @@ -0,0 +1,63 @@ +function L_t = extract_length_over_time(stretch_const,L,backbone_type,backbone_section,shapechange) +% extract a time array describing the total length of the snake backbone +% over one cycle. +% +% stretch_const ---- changeable value in lambda(a,s) function. usually between +% 0 and 1. +% L ---------------- Total length of backbone (m). Should always be 1, but +% left as an input for future modifications. +% backbone_type ---- For current version of sysplotter, backbone types are +% serpenoid and piecewise. Enter as a string. +% backbone section - A percentage between 0 and 1 for which this function +% will evaluate the length starting at the head and +% traveling backwards. For example, 0.5 will evaluate +% between the head and midpoint of the backbone. +% shapechange ------ Which shapechange data to investigate. Include shchf +% but no file extension. + +b = stretch_const; + +if strcmp(backbone_type,'serpenoid') + curvdef = str2func(['curv_serpenoid_stretch_b_',num2str(b*1000)]); + zfile = ['sysf_serpenoid_extendable_',num2str(b*1000),'__',shapechange,'.mat']; % shchf_circle_6_dphi +elseif strcmp(backbone_type,'piecewise') + curvdef = str2func(['curv_piecewise_const_stretch_b_',num2str(b*1000)]); + zfile = ['sysf_piecewise_const_stretch_b_',num2str(b*1000),'__',shapechange,'.mat']; +% curvdef = str2func('curv_piecewise_const_stretch_abs_b_100'); +% zfile = ['sysf_piecewise_const_stretch_abs_b_100__',shapechange,'.mat']; % override for testing +else + error('Unknown backbone type.') +end + + +% load target file +load(zfile,'p'); + +% extract time array and alpha inputs +t = p.time{1}{1}; +a = p.phi_fun{1}{1}(t); + +% for this particular system, go through each time step +% length_end = floor(backbone_section*numel(t)); +L_t = zeros(numel(t),1); + +% for each time step in the gait +for j = 1:numel(t) + + cparams = a(j,:)'; + + % extract backbone + [h,~] = backbone_from_stretchable_curvature(curvdef,cparams,L); + + % define x, y, th for this time + s_loc = h(linspace(L*-.5,L*.5,numel(t)))'; + + % extract total length by adding each step along backbone in specified range + for k = floor(size(s_loc,1)-backbone_section*size(s_loc,1))+2:size(s_loc,1) + L_t(j) = L_t(j) + sqrt((s_loc(k,1)-s_loc(k-1,1))^2 + (s_loc(k,2)-s_loc(k-1,2))^2); + end + +end + + +end \ No newline at end of file diff --git a/ProgramFiles/sys_draw_fcns/mfield_draw.m b/ProgramFiles/sys_draw_fcns/mfield_draw.m new file mode 100644 index 0000000..38d49da --- /dev/null +++ b/ProgramFiles/sys_draw_fcns/mfield_draw.m @@ -0,0 +1,220 @@ +function plot_info = mfield_draw(s,p,plot_info,sys,shch,resolution) + +% 6/23/17 - Copy of vfield_draw edited by Jacquelin to plot the metric +% ellipse field instead of vector field. Checkbox locations replaced BVI +% 6/28 - Finished making edits. Currently, code manually removes the +% beginning and end rows and columns depending on whether or not the +% metric stretch has been selected. Should probably improve this in the +% future. + + +%Vector field list +vfield_list = {'X'}; + +% Get the number of dimensions +% n_dim = numel(s.grid.eval); + +%Ensure that there are figure axes to plot into, and create new windows +%for those axes if necessary +plot_info = ensure_figure_axes(plot_info); + +%%%%%%% +% Get the vector field and interpolate into the specified grid + +% Extract the display vector field +E = s.grid.metric_display; + +% Extract the plotting grid +grid = s.grid.vector; + + +% metric for evaluating ellipse field +Mtemp = s.metricfield.metric_display.content.metric; +if ~plot_info.stretch + tr = 2:10; +else + tr = 3:9; +end + +for i = 1:4 + + Mtemp{i} = Mtemp{i}(tr,tr); + +end +M = celltensorconvert(Mtemp); + +%% +% for trimming vectors that would be on the outside of the metric +% stretch +% Convert the ellipse field to the plotting grid specified in the gui +[E,grid] = plotting_interp(E,grid,resolution,'vector'); + +% trim outer columns and rows + + +E{1} = E{1}(tr,tr); +E{2} = E{2}(tr,tr); + +grid{1} = grid{1}(tr,tr); +grid{2} = grid{2}(tr,tr); + +% Create a set of vector fields along coordinate directions +E_coord = repmat({zeros(size(E{1}))},numel(grid)); +for i = 1:numel(grid) + + E_coord{i,i} = ones(size(E{1})); + +end + +%%%%% +% If the shape coordinates should be transformed, make the conversion +% (multiply the vectors by the inverse jacobian) + +if plot_info.stretch + + % Calculate the jacobians at the plotting points + Jac = arrayfun(s.convert.jacobian,grid{:},'UniformOutput',false); + + % Use the jacobians to convert the metric + for i = 1:size(M,1) + for j = 1:size(M,2) + + M{i,j} = (Jac{i,j}'\M{i,j})/Jac{i,j}; + + end + end + + + % Use the jacobians to convert the coordinate vectors in accordance + % with the stretch transformation + + for i = 1:size(E{1},1) + + % Iterate over all vectors present + for j = 1:size(E{1},1) + + % Extract all components of the relevant vector + % tempEin = cellfun(@(x) x(j),E_coord(i,:)); + tempEin = [E{1}(i,j);E{2}(i,j)]; + + % Multiply by the Jacobian (because V_coord is a flow) + tempEout = Jac{i,j}*tempEin; + + % Replace vector components + + E{1}(i,j) = tempEout(1); + E{2}(i,j) = tempEout(2); + + end + + + end + + + % Convert the grid points to their new locations + [grid{:}] = s.convert.old_to_new_points(grid{:}); + +end + +%%% +%If there's a singularity, use arctan scaling on the magnitude of the +%vector field +if s.singularity + + E = arctan_scale_vector_fields(E); + +end + + + + +for i = 1:length(plot_info.axes) + + %call up the relevant axis + ax = plot_info.axes(i); + + %get which vector field to use + field_number = find(strcmp(plot_info.components{i}, vfield_list)); + + %plot the vector field arrows + + % metricellipsefield(s.grid.metric_display{:},celltensorconvert(s.metricfield.metric_display.content.metric),'tissot',{'edgecolor','k’}) + + metricellipsefield(E{:},M,'tissot',{'edgecolor','k','parent',ax}); + box(ax,'on'); + + % Make edges if coordinates have changed + if plot_info.stretch + + edgeres = 30; + + oldx_edge = [s.grid_range(1)*ones(edgeres,1);linspace(s.grid_range(1),s.grid_range(2),edgeres)';... + s.grid_range(2)*ones(edgeres,1);linspace(s.grid_range(2),s.grid_range(1),edgeres)']; + oldy_edge = [linspace(s.grid_range(3),s.grid_range(4),edgeres)';s.grid_range(4)*ones(edgeres,1);... + linspace(s.grid_range(4),s.grid_range(3),edgeres)';s.grid_range(3)*ones(edgeres,1)]; + + [x_edge,y_edge] = s.convert.old_to_new_points(oldx_edge,oldy_edge); + + l_edge = line('Parent',ax,'Xdata',x_edge,'YData',y_edge,'Color','k','LineWidth',1); %#ok + + end + + + if plot_info.stretch + axis(ax,'equal'); + % axis(ax,[min(grid{1}(:)) max(grid{1}(:)) min(grid{2}(:)) max(grid{2}(:))]); + axis(ax,[min(x_edge) max(x_edge) min(y_edge) max(y_edge)]) + else + axis(ax,'equal'); + end + %set the display range + if ~plot_info.stretch + axis(ax,s.grid_range); + end + + %Label the axes (two-dimensional) + label_shapespace_axes(ax,[],plot_info.stretch); + + %Set the tic marks + set_tics_shapespace(ax,s,s.convert); + + %If there's a shape change involved, plot it + if ~strcmp(shch,'null') + + overlay_shape_change_2d(ax,p,plot_info.stretch,s.convert); + + end + + + %%%% + %Make clicking on the thumbnail open it larger in a new window + + if ~plot_info.own_figure + + %build a plot_info structure for just the current plot + plot_info_specific.axes = 'new'; + plot_info_specific.components = plot_info.components(i); + plot_info_specific.category = 'mfield'; + plot_info_specific.stretch = plot_info.stretch; + + %set the button down callback on the plot to be sys_draw with + %the argument list for the current plot + set(plot_info.axes(i),'ButtonDownFcn',{@sys_draw_dummy_callback,plot_info_specific,sys,shch}); + + else + + set(get(ax(1),'Parent'),'Name','Metric Ellipse Field') + + %Mark this figure as a metric ellipse field + udata = get(plot_info.figure(i),'UserData'); + udata.plottype = 'mfield'; + set(plot_info.figure(i),'UserData',udata); + + + end + + +end + + +end \ No newline at end of file diff --git a/ProgramFiles/sysplotter.fig b/ProgramFiles/sysplotter.fig index f295015a23652d5ef371e25afc7e7c7d192110ce..c6b63d2c8c8d3c9f1eb0ce1574a1c14574efd47e 100644 GIT binary patch literal 143307 zcma%i^LJ)Vuyu@yZQGpK&cxOe+nP9eGO=yjp4hgX2`9GA=bQK5`v-je(>bfoskORS zSJ&RPs})4m}_^US`` z*|8;*B+To~mc@{Tvmc5tlS|kOijhrjQ9qmkOrbPA-ehX;=1*NJx{qGWFgA8tGryo> ziuzWDqr8=p_Q;+Gk@mdMzU&3bki02ZLD8Y#(eO0#`*`qsj2k?e*yJ0gzh8N{_Xr;~ z?&N&VY{LD05Ji4)b&qUiggb?&v(#Njbu3kBXY+H;RO4iZ%}su0xjR}WqEtwaKhdP+ ziRKIU!fhAfXei;3@T@y0MG|MgWgFO_+AidAA=*1h1I(2tuh#E!EY@o zY5gV!dc!^W7G|}*ui7*1uL<`Am{T-AGeJ=+e5y0SS!G<}>XBfY;9Jw_!|wQY$rWP0 zM+VtYLcPM|Zg*0?Uq`w(+wYE&V+Z@$qc47e|CFp1Z}!dNCe-jcx3W@!#P56`s=X|9LYcJy~e{%g!${`-X-4&l^DL*JQG z*rJy^qV3z$b4gR#EaERSsKj17CDs zkzw~g28vj)rAhK_Z3_%QU!Iu!f9G+3?wz`m9SF;QH6HZ-_{uu)pz5W0^&2OV`AR$B zPXsZ&ijRX5e6{YnL3leFd%opUrqUUfoYw}YY+tu+$Wi{m;=yvkYQcKJropzsuE9Qa z54fOsVfqgeBDec)>(AOamk8y+g%zynYyIc1=l5-@<$1_Rf3h&Q2l=cW#Yaf1U6q_o zx$eYL;5WL7UI5#H*Z8PUW!}PtxSfn|L(1v!^;W>(rEqA8K>x$%wF+k*NUaz2oK`yD%WJ|ynxi6&$&{|(Up5LNkQ9`^1!hV%y8(rlFp_Hekcy)Q*y4wv z6W%k5ePhejgs#mO1>>GYT@CR=XGtUCUN zYC_2_7{uBlTP(ct=djNd zBzr5BED^|5aA&DHl9w1zmu$1j^lo>oxmP0}3*|g0(Y=YqYG&N~>NJ3wT^DNYrJ2z${rhiuasa;orBT^^s$V^ z&Tdaxk!sKI21H!xW3+~#W6jO6Y_w)OF@J-49Il)~8-(gC$Fi&VZtsHXc(HyfVPpiH zz@<77GhwDh9)(S8liT~j(g6(xN)LV4=LL&D(C)+FrS#))GfdnN zC-SN_U4ftXbK9b2gA#1Ymn1slEBqpH zNnA-eXF5K@8=kR7^;g__A%b!46|243Dm*$IWMMmT5S$pgFzfTGu%tej4s7!$OXK-U ze_8Ulr^>TGn8dX{p>|ivwM4(;#8_bjD*Wa1W;UGcP0VxXr|I9}9o}g->X{M^Ht{oj zSL0aZ*!m+}wI;lg@@erQ>#47NVJH)#yRA<|E0S#=noDC1_E7VOgnB$VD@#(V(40l{m@HLg`j{^U|6tO{PBxknd=W~ zyp?sbLM1tLMucD||Ikx~EEuWZIQ-+Y|*9)wO*q*Y()W&0V zHwFg319>E-T+!qG%*WC6>b=h_Myh#C#c!D`g|x*^sAV>-yEgjo8d4g(wG(Vr9x+2M zk|_}{tC80QUBk|(UgRLYv20U5SM{E~>-!>F0qU4=?x+6bZ2O-?q z(-UID3wE#0H#^XjJT3_oczs65K1}WBaz zl=2keW&eoeD88b{+n=!UU|dFildAl9e67oQ9&kJk1#Q2Y?Y;{i_3%$#R^<6-cRt5_ z{9T_koW`2B^c2Z6u2QY|`RK)(-IO(k2fG9!)9|M)`wGX85vpUowh{OC4C0{n0U@B9 z#8U02rb1Rc)!;;Fa(p9{)iG*y{#&WR_?soS5oQ(T;O+6zd`6e>-73OcqIxIWu$!&7 zzQ?7R@11_TJ6C6O0<6`fM(=QadC#2$<4slh(69xOFwD z-l-JISvgVeaCT)CC7 z#q*osy@BAG;2z-)cnL$Jok&GPYr_+JA=R=q_l&|(yH0$W|Ftj0AD`4L&x0a`t~mTx zz&slEtT%P>+El8Sw6i#ZLJ51}y?CD3jEpUfizas6PB%`#ClC?&ET-2wOx>AJ9d*Mv zAim`!1mY=FpJ^b6y-h8Xp$Wx4iAfd$#{{91KoN7{xvO8Wm!@^yFpk|>b4K7Hxg~O# z!4m09XF3fP@egX*8u58GYSl-NMv-F8*KRGyc-C_JWfbYF?WmJao27+03C5D$RA1M5 z6PW&f-^-_@b6dgtr9f1yH~vQW0G!>=Ve_;UDy_Lmy90n?#NL;XB%2$1tJoRbAw}}bT)ZHd_qFL6JwD!t?&wP@`QCD8uWBj(s zcc1K02PygK->o2+mIVCl5yzdpYWq9 z24FN0vg7wjByahH@As^a@KdIMIym00feAvU*1fcKJ2WvsQD9nu6hRo&a?0Qz@{+y8 zNzHaosn*Fw{&T-3R8hORhZYqCHJvG9VOuAWTD2L5+HyIXAX zX=>GeJeLZ%=9Q9Tid|LVI~K@AwfS6cwDEL(U!mW3I538%in4$0p8rVB>|ns)n2q(k z45Uho^#IL30x?G|3W_J-u!$X4+T{R7qTvX{k6F7PhnIqoh4HgWdj0d3l{^xj=(zklQ- z5I~y;kDRvn*gD~d*zg7Nn)d$(r2ie-=?ZoPl9;13&gd$nBWM-t#lNZ{eo!15m6cFo z8pD>UpeSH0%WlXdq~2bw5&zEBxr{we=MYOlg;OUZqm*EP3WrRIN7ZWUYo|e$kxW6| z+m}Gejz{Hqsuj#-+9O(hDO-T8v2O% z4!P#4?onJ!A?Vq1F|E~O8jeuAv}j_lvM}~^xmgP(2tWqy*VZzO?AX5!2}T>PKXwXj z8W7R|e8eN8aA^7}u_5lp?#){O<+T4cJ}ZMsVFbZV?2t+3)sqzz>lT{Ba`NUJWf11UANG(b>W)`iga|^r=NKw%1sg2Kq0RYy z$_V!m`#msA;Y?=MVx%7d93wtP9d<(Xlxf-GM=b zt7Wh&=MbNd-u7{c-x{7C9Ykh&;mURo+Rx0jbyprDKA-b#wozIbd>8DT4GqW$#4JSl z+!xOq_vq4>jT-u4o9B<$+m;I|a{xnaec-1&-gz=>*2HlmhQ7%rVbtn^ z+X#H@ojq!r3;{L@)8Te=o}h!*KM-BXq|~HQN9&Z@r+f@-?sw?NI0Y0t{m{kv<){67 zUCG`fT+xp26P9Q!9b7c;wZ-k!b|h~D-(D;$81Fqf0%=qScf z&6N6}^ZZt~0zJX^I%4^ipWQCXC{M-2P4E8w%kjYODG-BYPr2{gENn%{^#cvdHi#*O z=l%6)(a|@x<9VO&lN*dkLfLxjqi;FT~#mJ$P`eehVv zVE5{TFZp|8O^}IRjM`KC66{J~6D-s6GqVhI6SJc1VT2w5B4CZ^Yx?k0aG&x}4~-D| z^k9cdU?$x8wqp0}a*+jhV|J);%ybh|a?(dyN5$mhum?Dnsb)vV{Vy|k8N76o6;41I z@4WsUJAv%Od!1A!R;gu)P+8D$q!3h~U{0kXoVS$Pz z8Kuw_JxXri7g{2Og2iD9 z_`IRl$M}xnGUNG@gP6mi=DVJyqY>)6fSA`_Uoz}SP_+OnaqVHi_6ZN!;9oo%!f>y^ zaIa`ljNF-~I#3t$_2M@F6HX-oj?9(5!?m($VR;^h$R&7^Xevk{)bh))--q5TE2e^N3@Sh(y@04Y@Df&P)A{}QaWf*mF|=F?T8Fu7Q~_h0EI-X`({F4~Al zF;Ocng%EGB#6&16)#4bBm8|c#v0->DuV`Tps1=uFHC8AxpDI4*;1z_r@MQ5KB|{M{Y#z}i`P&?zrCi1eOO2u7zOF#$+VG;OY*M^Jb+2YQ5;(W zla#Sr(V{$(h5d_Vl%VF+>1kFGQseRz@_B%no`U{QohMW6y!K{eU*G*TJUp2*%I^qz6uFS%e6vdWB+BnQ!hsHNA>Dy?r{>_t6cs;3+kR$$nsmE5e5R zaV*SWjy)%)sZmH!xr}=##27l1a=#6SOUZ-lm^C%>Vhbv$jJ-MPvr>^3H=vN z+k2l=ouo8Vx;0-k{O_=Z&ta8*I9i{DK z?`2#ec)>Lt(<55Vc8aUO;Dl(DF(#%B7nhq%4$^v+H}0_*6ZFllOvpOwdzlY9O~Op! z3FpoTX8}78F|_(faO@YnkOuljJC|s=5Vi-Lh0@Omr=OfrlIP|2*0-}8bNM4? zp%z3A59{1z$rJvq{w;L-Vt~c@t6ZS~k6%=`1X|ppC+`a-j!`CIgCViNfYxIYl3@Mo zN;AFjj?{fB4d#o)C?<|P++K|grN4`G(J~9h!^rjc$5}3y-m4%Q1NZJ{S827cO}5>n z(P1GC?<;MW8MqlNtUQK~Y!q*IrjO6ZhWB+Pt*^@Sj(7PieuB83%+3=1?w^-ITF3Xt zLC?boG5MZ?g-7>}_3^)|`VkJ-o3A{{uy4fr5WEatp57^XYwS#Lu&Eq#z97JPXos&{@jJQL$He9dy zp5th7)chLczuDP#)7Hnm*#Bwn6i-D6lO9kk zhAVaPC*&o+yu#SoY5MZgYw_~Zq0{H|kF8j@I;N<<0drt(p!aEs0s39PK_Vja?=guY zFRa(qGLks;O5=q)WtBKFVy{l)ot>j*VM#!AS7h^hL;9slvWoMMG_8gJoPM&Q z$UyoifkPS$gW`)Qr~59L6(*K#E~F$cn-M#2sABqc*SE}MW(_GZl9)jOX~An$tYUJN zxrW6!&$_AM2CkUf1xi@~6EZelL=7HcAP#D_W~YU zf;T*Ei}YCkZvs8&=eyZ!D<+6Mh^YU~gzAZi^wE0^GUB`def1tkkK!}WfX%1(%e#r{ zF87sfX`|i#nAUY~=^=>$$AP`70-=QT)(>vvbybeWi0dbrz5#C;LY#s=s~cG=m|Z6v6<~ zXSV0~M&9TBiGNoi0HhrJVHO@U9bG)BwrydNQN%R)p;UZv&L~4P+b1}OzsNUT7xz`Z%FoN(B*Loo_C-(pZXS?ray|KNVWo?U8y1ZS z3h_i#^6ScAlwDs9f_#c!LPIx8uuN5FO~p8%wSe^7Za(fpvojUw_2ea);7zB#jLXso zryt8`{>_bmCg8=k;KTe4^jq0>bq_Qd6M74W{DwN}gVS^KXU(H{lHvG?C`IUA0K&!5 zFk$@5$nT-$XFcUa8w0hFf7@FuUi(GMY>a>ofq@BXVca4q`p-pmXHt)%Bx+?o zT%e{Ts_4yM(NhIfde8dSClfT4p;b{)Q~}zDzly)JD)s?PdXi8rJuR)+uA2^<>F4q6OXp<{uL-TRt&bQAGzN)5_Cd99 zW?f{YF!YWQ`n0rb7>q^dGqxo}+Hmdj2*1){InLr>9RX&!DG!ttG<_Uwcj1>zO#YVc) zwU22}5u8drZ?uMA4L&krzB>Ryq;yBQJ{B=`#8Bk7mgQ%-I@ZB}|gEP?+ ze~Q3yun_W;6eYQf@F{tQ(DmOxe~MXt+Q0bs#2-Q)-HLvzqcAL=_*(%%jF%*~`WWqR z^BzQkFmTg3srU5kivx7VnJz-l3-r5z+Br zIHP6nI+-h!gP?5t2EK_#nkkrmWkcV1)lcp)I}p;kliYf760R6kx5JJnUY%cF2`~Fi zd6YKp_Zg?}wDGWe67|7;i*n6yPQsd;G%bpNP4Ck7f-nP^KWh}hByt$uNUIxRCcvqF zG!+_#P(p~b%&tFLrcbgAzh+}Bz<#flhHw^(M$=z`H-7b<`|_PTb7jj#aX4Bp;&Da( zSv%g7`){!}R(EKgA1m%aUmc(w4}p7Tn=|R%iL{Wc?)#nKlBl4vEcaRX!DHd>HlUk1 z=)Jn`&!Z*7DoLcYm`q|&kT%r?onOm!ZK!Z{OHblGJSy`$6z#hNhs?V~Qsdp##eSXS z9)`H&6~@zBHK9Ft%@ zYkny#G^)Sj&0}HU=#y+-ReIixk2R?5JGt_YuVO#3-6V>ncZ-dpci1fe?yn34IcZWq zVyF*_=pz!;UPdO4?=)1Dz4=f_929L{9Jn%abzRCr;WM&~%>fbnx=Lh`8Zl&#j z!NCRJc!US00_KsSHb*0lgiw1qIq=dsBJW(|r^rV2NsZ3H=xFGrCL`uuAaoT^{NFnD zeET^nQ!#=E)P8|43zJ@4Twn)e!;2ot8|6E^iZFQ~b-IulHvw>&aFi!Q1Owk-JMnXo zLtV&R;!_cDukhUu#Rjd~S#_E7QxWVyX%%&|KJ2&?A@QQR%tmdtYbgi_QlkV?lh88l zq;N1Omn;{2w0Ex4_V2tLqJJrql{Ri+L^(mfUg$E0q0w-=Ujy(QNtgWwYqNP+brqvi zG0G2z`cLJ$C2bs#BVEW{;?pqNHn}e*B4CRShpc!5bQSHGPwf_-dxU5w;HUls^lK>o zb=j$BpuuJDyXxpyG~jIr2)J{Bz_l##oQxUD&MqE0u;cM>A}nYl>`&X7-_L>{GYMXo zQ+!op`aSb$yo~iuQW}ZBe4BP@X-wxYf^U5E&4>->k09wIj!gOLzs>kx9?1~3#Sr~h zf^CSgFZd3P;+;UuXkQSfi#jaVA{7ZM7o|WIV3fUO_uG_gwl@OdY)Xm}dsODs8+I!U zyhZI5#rMiS|6agskONk+!G~HSQHFP-J*qg|TyXSUOJPD<)#t#t7LWVuxEYH*FHzmF zbZg-to86wV%EK*Y>g@T19h)qG!(ppgK|cISUg;ED{Zv`;px{iGM6X1+A>c+08JA_`m@;;>sS=|cuR~Mi zc0?fV9+U7&Ao|;_!bzguoWw99Bj~b=nM4_fx6XKbr}B@NxqP`=nOE~h@AqQkD4sRU zJwhrL3mlqg3j+cgWG%2&WQXyaB9!CLpvE9|mS??Ktl$ z{;%;u(C7X9_A*C3QJDMZy%*VH5g`8ljGuWkt_{_>U^s+uQ0yrSM0|TE+#{Wxcr^G^ z#oOo_28VCD>bmWQeot&DgcJuo?>X13)x#&~Kks6-v+ean&SZOH@d(>K5=u`0xg2}o z#p!8jo8$4~WbOhVJ%-S)S`Wzn>#z34w_t1S=N2@x_wI~cnhY#HmR9-MKN>ML;uB7F_UP`8?5U! z>E{O|^Nwtzq5pfIaGoEnbMNNdb5?BM;OJ}%Q?!y)w4>$BVs5T!4Fp|iq$Hf1f2$jY zZag}|ONVGefvFO-%x;bpjEEUTA$7#RRZuQ>MFswP9>zEqVU%%?wUEfMe~ z9m}2i-1!5g3-S8h^y%do(0C@*B5o!=AoBgM#GsdDkB!yiy-CTx=ZJsz`8dPbG{|Bv zAEj%uSPJv%KkVS6=(toj(ylPHv!V<<8XMu0MPaPe=_b(cJg8i0FcH zcJuypm?56E$G%<*t*^6{Tk@m#qIwgUrmV1g<{p#zh@BThBE$ckvzd@j1zJ);w8v zj5gv;ortKR*+s%HcunSjqdmIb;`IBL-byB7Cbbm(0kwEEd8Mb+d_m@<5pdw{;+l!s zT8SH;-IFw?T1~4j_Z+5y{(?=Q*fwT=4fkfyEn`@mu!@ZE8Tz7KQMMx3ZMa}*`qXBX zNXrqheXIDD+{E!6v=_&{ld^r@^*V7b{6XK{+aNZ#LsM+=LQS8SCE_Pk`Iwe9YxmfV zpgYMiy%*6K_xw3|*q{tV+o3V`Y=OCP+7eAhwY&Zq|2~z>xR*|L%M@kl4ahx>8RrNS z<(xf0tJzN>RT{(1DD9IF&27)}q^z8Q0vGPlU-~eQ<>dzULJ~xC81O z5<^@lH3j!JhIf;SRRxi#V#({MbH zEUMhYL~UOgm}50pN!sBE8D=Of^@;zGBuT&cl;{xa9LGTa&&*=(q&VI|E?+Aw(mic$ zrSFEF;!nNqbyuMFN4`DK5NwrK?e6{9@}mD<9!*^xT^!;TnE-o}n82Q)E1IWfwvx*g z?@0fnw~4}x^adobjTr;*Ia{A{T;%-HCz$q9<37WiBxqp zJBcv8*M58!{n>gP0{UO5Y5qS@Q;HH1q8gDA5kmP3iqw5_mH~cxl94WSf}&BBw5^zy zgM}!=Fe53Fk|f?RTPHCi4|bp5((I@hvt;0vEJ7wTpsyjHl!k*Bt$3KKffCKm-^l`N zQ$~oiNyaZ(~lJBB4y*^t_p;f@drx;axuQ?#6P$~G(ezU3$%(?&c`7dlV+TEdo=(0*xp82Oj@Zdw!<0Smie6!d>dG1EeoO_vPQcmCKvBA; z*QW>NDtZ<8qUI!N1JGfj^D(Ug3rjoW_Yw3wDLSJt=#k+$uwaFXoyb@8v#qWmZsj*JTzF7u(yj22X2^fkOiJQS=@j*f}O99M&nKsLSe{<5G0xY zeb&Dh=%z3dK4FRhq$~P^wE*pZ*fBa4A>L(ISEc{xCARA3X@G>U1*iVFw`(a;REOE9 z<3AV)D>WH1?*iTo_|=S~eX?fIw{4&#Rgn&>Bn+|mpBqmwIvl=#-=G;XYhScg_!pm} zb#>naMP5RqKzyNz-J^sXs$>`{2d<}tWpM`ubR0r9Z~X(3@S)Z7E`i2P*~&&D$rw#m z!l)BrfmUDOxBaiE&9*4qaodMb6;}lAhrt6@yllFPA`=nQ_rTw2hh6nbR{*r{t%z)2 ztoesfHd-VO+xc`fPHm2BDHzEAgHFNeXd>N2Ij~t^iUk82_4A^2j8Q6quycO@2P3r= ztT5RyXB_-Ls~$B4tx&$2lnXQ^RGeEhKfs4=^!)RAEG#WM|5(rr%CERX7pOv^5DSFU zo~fLQDxdFZzS$AMw{7 zvG#$CJ@qC}_6_8-4U*ZILsRi<#YEFW-oFaVwBM_+cw>j1HIE@pJr&*TM=ktt99?isz``q^}BuaC%41yWV@T8A10n|Zi~!I za#rE0=w#TU`GV&RKWnYUVO96Q0+=Eh)c`E0N_sHD^4<`-Z0;@^!kBj;n_&=PtNpcu zhfEx#+M^E|*VdJIO%AM{hX;wh^>z~$wg<78m$!I6K{7SY?E!OW+3_eA@m1mn`3IEM zNa{5kL4ea&n9$xs2N$P{;XA4VsoXK78^Hq9%|*viV{Y4?VeHmR$B~Tqo)f1ve$%+X zU<=#Gm48u|v%Ng+_nc6qQs^SPN?eyldrXWXEgWzQ@kPwt(p=8H8s&{OZST!c>;`ta zMC^un#~lf}pCEHkwemh?wxGTQ9H&Ud~Uh z+nxISO%0%WIFJZ9K)JuYl}mo*xtcu?z5&ddvv$ANPYrer&y`#-iL+gcW-4@I6JF!O zc}n;3mrl%5UwdAzp*%!gyL9c__VGh(lLtndjXL{>uBm(P9S3?~ z+OFE&BhSBeQ)oo`5tbz&d3k2TU*mpjHoLT;Ws5}t^WUD2urhd2@e(7DYGGo-Nb&eU z5hzT4^^&I!z(>Qx~{^_g!uDTnY!w=H#y!+BISsfC;oH=ei zMZwr#2W;+}d~z=O06tHj&)2n$^vUb~e7noFj2pi(;UD56ij+@78zO9Qw_g-NJ-&F- z1MSSHB`PUFd;JJ_oOyn^V>zUI4pr>2`_Z%FZWRP6E-Yk2;WkpDKr#EB6?i_s+)p5y zi+(^SnyV@jM+^Fqt4h&)&!nVNJ2iTn!Ncw>FEKprnppO4%3|;SobV6T`kz!I&OJ&T zheT?gBmN@{K#2drz3B?_|8Yi3hJ4(9m%*srd~kGfXi6ZVUBh}hEqDp8OlI<_`v&sX zm7RN;$Zg?#5F53(7>22U>wS23G#iZ4o~+=>ILcC0u3PBU(rHUU37lPKjv4#A`|;=T zbXJC;2Sb4Gt*$*o4UM&Zp&LmJ(#ogQWNL8gJDZ*&oeN*+aXP5{?~eLNujq|qX>-sD zchz`vfFa4p=r<*uG1kwa^1h&5+~S4)s;$tH}YXIDa2d1y3j#5VReDX^{46tAa|GDrG>EVG!Gz8FhUaY;eeT+>u$#+bQ;1i z04xpEMLg^00f#eyd??n|(|#i`8}jU9yFZ{-@5VgWJmD|~UtY;ZTZYgw8N=jiT6Ax3 z=!nvtSnX`PJFO}{={l3?!AH8+gP}L5?GLjwW;lI{DAX0biXOHgIEdK0^8F=P`ji2uEmI}t}`kG=B zSgVD(>|QaF(-lkVjFuzIe$#dqtY*y%X6l{d!jSe0s9ln=(@l_#V;4_jQ=Ij0&ERmu z!YIVm&xwRF{aMb#zPgbfdH6FKvb3>msGTN5vik7%)>gACfsOX0xl?Lm!$QZc>eWZo zt99dJQu%_DlUekiFp=@En01_hQ+?D2T{~wdY!^R^)?*f7?_f*V8h3{K_1foH$d=o5 zBE-;dy_W#XvK{`)n5ykuwW<9g2n!b*tC)RiaN~Yw+QFV=h5|j6Lv8 zBxZF2tu5z*!Nb7G5EEv~?(H2Va>MMt5ZN%70?OKseX+j(wLCB*Z=ZL*{DB9+@h2lt zIWH68l$N?*f+lz*& z{^LAi^6>n^u#^7a_@Of23g3#80$+5)z(Qq)!i$P9Qg67s8a&5m2M58fdwGFaBKNh= z>6zzg?wy(EjcZ8Kb!IU_6_KuHG)NT*bp&qFXh>z^@LkjaQT>SS>tB8%c1W3_35e~H zjqzf0^6KlcwL_`2#-E($(A7A8GF>IkKmcl3ARmZOD$6c$@1rgae zC~;eh_(F({7L#f}L%4Wj597&EpvLO`wgM^dm_@gza{)&k_H+k#Q0?R^lREx)MSw;Sb-^O;Zz+ zb7L7c#FOB;6Cd&Ud}O-$fDnyHb?7YA2PyRo5^8_AO3~`-J8^ap$?w;^{nCzHuAGNc zR={?2y~#rp=g(|MtBZE0!j2^wXbRD$ zTtW66#zx^MkfAV#YbU6MWW{f<61_0iaOv(bC2LA`)4hZQ-O^QlDFrJcz2s_j>|;Wv z@x%TpY$jIe%9ST6Sdrf#?J7vwHLt+s55RjRS+TY?2DW?P_B`b5H8i|$4b2+kOv};T zDCNmRd2`P?b(nNMqQ2;wr(M|;m=tO*39n(RX6kmn(As)j1A9!eh_G>V-*}m$gn-Tn z*VVWiV?8T-RGry+@%J?i#Cg4wEySa{2E~8#ha;OAysrWuhs7HrUWvqme*5En%M>mK zS*MLXSG;tL5yrh;gx5*jsCBqg@%N%pHVRiL*5}h;bb9i8UEW3N58~bNfD}J^w=2kP zhLc{V^!S$()@k<8x-4>c53mSk7}&>AZkDbI`0JQuU_VU1xRc}- zIKMhfz}v98;%oJJM-ebo474|M@mK_)367!5h{rFz%~+NDYrRf)Gvt_Je0qOGwT}Gx zPGhb1qO}#Q7RU1#t`>J7CTNlqV^=L5DZ1xP*eISq+z70vdX(vKKLl*E?JrTZr)!xd zl5EmU7MXb&yxrIOKOgMOE|gKe_FLSFMc4}y-oKoqLpU*blIeH4#NzbucKy8(BWDp1 za({U`Z;#XIN7&MtKyd%h2KLhvoTp0}d9TZ}0Tdp~F?#^I3RT~A%p_}7Qzc+H{VkcAgh>)y z38bYVt%E_I9GzDiQtIwk5`?=UA8-e+zw=FW_Y~S#_GY_`v+sP4zVl91nk-;hDshAb zZhpOHx(Igt_Prd}|MvcAkoJ83`$let<4Z_iYrCWGRZe7Ru$(cHcB76JJ(&#MJl_`F z8KQ{Alr;g_>qA2p<|UbasAUJJggZT^Pog$-aa0czyXoq-WCq=>G|mv zv|JWWSbrU4u&9?i@wCIrtEHFS^3U+Gs9c&~s;UkRmKx*2Qp`=@4MMKrkhZft62oFhwqCz`5}#mt67V>v`GqCe>E zI3wcuir%oVPv}|CBWZXy&;H>dmv%U46&b3b;+b5N`x2amI0uiEdfV@Q$I608uc1NO zj^NPeTqcS_Pag3%t9Fs%mI+rR=Peie2sHDpvbI_r%nLJ9SdBSJ_4m~`J}>Vvr8|S` zZ7^>LD|&SA`8tbjhXsML6~AJvVa2HSE8AVSk_1<0Q^v1dW*$j@;IXPZ&48qj`M_4* z>$E>&sQIg{QwwN{_T<~2178!wulVmB%X56*XSx6%@+BK52;Fgum@iJI*1H#OHs1lH z?H1p2r%P{*1i$yQ`ChcqlKGi^^7>PHF!YE07}avk#%<*_b{!at*m}l=N_m2GP!vkc#zLX6!0J-dHJN_%U55iVS6vx!AOv148X zu)2_4x%hSC0kx0-xK*mmm_r(_08ew*{-eMIgsmvZG#`}S8W?6==F8rHjdA}qo=^W% zJ#fQl8dfxAtd@feI0M(Qb*(-{E~%_3H0Bme)U4T1Ex9+$GN=C~QtK@5n|*ahZwv|A zZ3!qP@?5BYv1x~(i&g;&$cH1&k#*lQ%cQo}wSnU|OZW3|2j0){bIi_+pn$b0xpGW1 zar%e~UAo)F#os??{hDpisSwWs1o1^m8wD=ETO-4JD^NYGLv?e}gbj+L*`a^0sGx(M z%`xFShRQkm25jbg)^k~Dh~H^vNlp2%N%=5whpAX2#a@BV(fu$vMO1bHGF_|#y1cs9 z1dvo5N021!$_%?i{3`!Ai)Po3o$)@C@d7k*iv$%IsoL(3S| zg4j3>`G35XZ>q=_&BM_hosE0`E*QJXUk$y zUjbq!8=@%u>tuqm5<1gEeo5_x^=DDI_PIN@b$Z-3ee=QL%sUf)!y$n_ydCQhaMtgM z)$WwT8d+qH3H#%0mW8nggZV%lczHPJ{=Vvz4cC_K#H%tD!9Vhz5;fbi1WiMIo{d59 z`k$%&e@*v}*9I#Nz*+=FiL?JRwIv)6o#n3c+(OvpVEmk6H*W`b(+{wzH0mV$!!A8> z>EYGW{V=irpoicOe60Sw(9uISAR!iTI`97>`&AzbXsrpZJwfsLGL5-zMxC~n`B|=w zo8;SFlQ9W0%#VAxn#V^!KkMU>Xu9-QAXF?5&I_vPSS`Mt=V+_E2kO0b8>O%Ji3jddt@N9k3-?==A>pL0$R%|DIUv>g`?zDLDRayqe(>HmGKi zEGQI%77ZrXP^NpK?5D{q{w5YpYF*F-{V3beg)` z{GO9BJGD6s2G*$^3&tJsdz7J52N-eaUblr@CqzAdc{lD{jrFspJdu}Kn0dSvcI-O- zfL}Yd(O2`*eD>c(9*;&P#%@s3-OJ%YQCgBP!;#j@PEneWM%#A3+e0MfgA|oNy2i)p z)9YYErCK_+B2uRt$q(;BaBuR&T-@`D$-%Cnxl%{5=-<}qJ9eE1x8EXL?X<$Qu17A6 z3iTq@YTVskF80<$@&D5aifN+t1-d=unErfUZE5g)_Dqjkgln`|5LtTanY z!kabKe-l!)lR#sGQp7@?(e=jj8PrykT^y1L0vu?_7*~Mco0K(mCOd3kQ=AXiD98SW zuCgbkK!z8WL}-OFX*9JM6jl;S7jlxAk* z>@gWw-HK7Mg!@Q{XX7j&O(2|7ABO}_A~5g|-VU_p0}YH!5346JP))IHhS?o%rM9{n zw%?xOJd(R3I^A)5+P$86zi7*(;;wz(i*}OF!F>mzL$-6lx_=9HeX5T6G4|gf7UNc8 zlP!HZoKrWEQemU6<&Vt`-$C$>&b^pTVCE;7bF7kt<-Z7@MhTBr6fN#!kLx*63kB9Y zD8*4PI#R|d<#`%AoxoMw3rWyFNcC~T(WKoRY{xh-#`*{f&<#rt!OwZA8H`p#52Ro< z4$-euFHJNzhGWMk>>_bc7eoL3^C*ku@6z+)Vt1TNB>#Xlvc%CL1^duwhudiP`R|Iy z{|Z#ARRqfB`sNAx^cwO_CQ_*K*M0cA0bN0!bW2aqVaN7XsHVVBoP~07gyE`Og)BAp&nf>qV?7rbm zj7%oKoO3?cb-s@XKoI*#bt%6`j{6jeaLC@ZyfNw|iK6S|4~t=?e9}1eak3qq&nq*> z$%h$9zNDu=#mkB2s)Rgp0OLBHes4tk%X%K^AKqR>+F0*)q0js5_m{f_0X6H-oz*@N zq&S^uYJ0XDl`Gxyq=|N%FRy)Sjw29Ac}Xk!AaK?YZic8TR_nJcdXY1#H^2r9Tzfy2 zh>X9vxV#<&-*O^tX0ym=w z+6U}87d%rngZGX-OpO?f@Qe&QAAn@P2eE4&0ZvX|G8sGj@Xb|M;%>#NoPK%;vbevs z7}*Um$kwBf3h~U137Bu{v!TP7P1!pq%oH{iJ8f2DJX~G z)RY7W{|9mN2xqC)8@mTV#FZ#qKt|4K)G-C@?}6Dg8K7^P%Dau^L= zHJEpDuCFVQK!bQnLF5CKh7lCBACt@rPoNHTL`U9r_Gs>gV}A7riC5ooCMZNJ7f13U z{XuGo{M$-if{!uOHt9}(BBcDyAkZg{?R_DHOr#F~OWQz~E{x+?!4waWj2tJb2tX(# zDsXT>JuI0T&o3)Pn2SH=B8p_>{?-=ktYtX+hvb>!aUCKMPKoHO8jgJ|5g9EdovLUb zp^rF2NbCVy&p{;#Y}9>h=yZPI=K01=8UV~^m$?D_{x$(dFM0-Wg2kb{-z;s8-N57B z-Xga>Q{)Nn< zc$ zdmtRbNgCq3Gam0V29^awaD%?*zoF2NeKDQa#F7&(qBE9&XWC;m=Bt8d#2gyN+&%%! z6-SZZ@TMD|&wj&)rOY@7LLeoGjuXj{m#iVc@=nGF+UIRd{u4pUK1^vxm_gh3|2}1( zNF!ct%Tlr`gN1H7>VL8r?SHz@yn*Iso6oqRC~7DS_I1WKn35^QRVgT+K0Qc>n)0pK zCENc)^w0<*lb#iX=M_uBVczX2V@e#AhpRE(O$Q@lpahZQ!m$KtTPEe2d)zD)+tZmK zhK+LbUruCmU;5pu!6#K^-RaJf6q9jCt?DDh4TfISWsAw+^!ekQ!by*=|3cs@uo3=!tYl^M%z!O$@qp1xC%COGko(bxEeRM}Nqv*T&n zcYvHtTPeWyV0AA!*7R{|$l_bY?Imq|1)9LjuiWq*2~u6dlg4i6TZy^{O=4w%TCcu? zNNVNEM})~v+o#l@w2Nap%6sGDk^`?Fy2ZnY!>o$+7O`h>@@AJ_3d z2zkH6*#Wbw4X-N++~l@SpVl`HAqy4?f)r{PqYWDbT|pL+ms#m|NCWJ5wn*E19tIi( z2yC-Z{U~WTi6wX$F$^&8XpE2;pt0IIA>*{3$Xnq-LG9siPMmq;;x_FhNk8B3w#7Xa zKEOpukKwPaU7p``?)ZN3&?!#Zj!f`H-%?dnNGbZ8_`~p2XWeF0CYYZNaL)F%qlC_% zHHL^M?G&NZv2O+19cJzUfNqI?9Q}+S^VV|gWRQwERJgcG z$uO?w_lDXR4JnKcoAQLIAlHz1m;A8el?=2fN_p8d~ zy&|k&a6e8y48is3E=wSQ_LP?&ACDb`!%YM5cggC`lr&#C;=?z9-vlcrBBE$>=jkVS%K=eZypl#ICQJ|Dp2Y z34(C{CAj}X4;5RR$tsEh5z_>8vP4j1^~$4o@QNgho1~K$5zwn$d|W(|$ImM}Tx6?R z9wgsm+Nve~#C@Tp!#R^T91w$(d^MM(vyT2aErg>^7bEvee6@6Hwa_)FBB`gl$)TCvHWluu%tII|Sy$qCFYe!_@mQZxE zM{18Zl-6jYayt=ReU|(n97H!7SLj;=@^%VseFB}huH|M3<}Vixj2czA z2LsoRZk2bi*b?HbC;Ufm6zy8hwH?>`2RqgVX+zG;_=GF59ojAzEWb!0m+1^nI+mxH z$e{%vr4CUyM2ur&U=SdDBurAQp^7_ulNz~>8l}6wbsmn+A3&gLcjf#I^c*i^shb=x z%&-`CdI%(A+|Mo}OK~&-317@5FMp3I^D597KZ;OcR0G>v+922A@37 zQJFhf+;-K_vWTN>>2`WMe;}o}q~2Z0W(9yIm+>CcjX7?3Y;p*5hbP9i1e=AUuUBuD zpfGPdNDgf?a+&iDhf zjb6U^T%32bWF_^eLIx9WlUr|>PUmR&OBQ&SxP4<`+#b2uDIhwXp)%Z zUKUHsn$5O%Q|ll)@bB2@tK|-E0N?#}I#-R1QS zBnxRU`~I76=d+Euph{b}mc)kVnHb5VSNl&4g*{0wPEpoF^>vm2Ab&+&9f4z}hiv}VOTKhS5WlB1mYf2r-!DP>? zLPX3;^1|;{k}C8cX0)#9@&xE6srir18?x*h?UDFd$Nf28H#;9KHd~S-@weGaFqaJV zZJnxyoA}ly7Vww98n1FWRXF=ZjVxsEA$_1$jR;?$rxYF^S<)TR=D2y++PwQB!FQNx zptBQtIj6~}-F>6olN)*ddY3}RUk5zuTaoWvA!{(y{b9(x8{ZNktVjcp$&Cn{OGy*k(k{k zxjIjs1&W}bVs#iJ&iF{z#A)A&X9m_=>&Dw=^A&!pKuHWj2Z#)HWAfx?_bF{II6phl z@|25(LhzT3=8QdLEsalsE&Gi+2%Xn0K(3k=BH^|eFZu24e)%c>gA10MB_qKOpWR+O z|H&Z72=awB^MdrI@J?|3&qmP6;AiLrw7#sLg=ekIG=T^SKb>$Gkr*fyS(vlb;OaBQ zuv92L53_cSalu^bK;(yW5|YLF3YpXq&%YV>t7*~$v zl~Xy_lgE!TNif-Fs_q|;Hs0O(`0bVdE$*(=;p)!PU%GVnGZ^~ut+lDUM_NF?TNrK^ z$Uj8$$Koo;po1X}ul0LBYED1u`TB`qC}3x`M#<@`_$B>Y0$_M71rO!yCy(J3-`|8t zh=urs$Oq_R*GB9~p;FqZVyr!Q-KQ|!*3)>^GV5hVb;-ivI@dfhRi{LtO30AFf_5(wsAr7X+n$5L}lP!d+s-2jebf2448p^D+mn{AxDR+%1NEf80ObRFX z0m4?PY5?1;aB%@M(LeC+E$aCjCWd;I$`+Z&;KUBb#(liJMqiV>QlSD0;Gt4xn`0Kq zN76z+pnvM7N=1lB-s`JIG$U+Gw76d6Vc{9RA;~Om2`t-tW7bur_h+kdpNqot<-;!? z0VkwBRJmZT#g_dIgK`h>t6o`LZt}o$g!j4WY13mO5g<(D%~wb9V?yE37Ee;ov_^nd` za&g`z{sb|(xp z5^N_nxbKFJRGiE$Rv{!s;15OCrgs1&?z<99Tl=Q_`%NzhNTB zSjob^0MGYfz6p8uRvAbRqf!a6Jar~ap=y@Z7|}cCF(DZ)Yk%(~U)6N&{MLU6pO1Ir zMbQcXnkgQY-%A99U9xdp3u>s;N@G&b@4 zO!T)OFf|W=QX)SHFhxLsz^M>|BBys^+5Gd(3CBFs2l@-OQP+fKvD(ol@g5I>F(_$R4wywla(|Em&1lJEa@ zl4XqmGaM9@GrlL0@F9I5Nun0io2mJYYNj7nueF}-dl+McQ9^zuqB9TMbzf*H*}&8o z%WuVTXg+HAZFE?e1J>`E;+3zw(|3VSqXgxnE3(hHZloK)5e^DG;IEU6n_V6FR2CRAQev(*6%NfA-TC5 zDunmsE;OtvExzB={?2Ir{C7qZq_@%sI4M^~6mNUaD>DX<_E$qI_^*ZruiPJE2Efik zgJ@{x|JBg?0wZRw5yEDiMWG{Z-|3%2`tN3N_wHHU&fD76b2MrPdK6G!{D1e&G8$lE zIW|RpzJ?j__P*!URbqv_Ar!O-XR&X;H}7-exXTTd{xcrR6#WY)gh7li2%HcU6eN=< zM|4DSuXb(RtQ8G0zGO>MjdSdpM>(@|-8^QwLdAOJufKO81tDJVj0PJDE@V@RNvdF+ z%VI`xJCeddhC{CGv9eh>SbgYd4dBVizs^^8?pHsk0Ol-y5ehfHRdJVm_4+*zSD2Lp zVy?)n*?CuD76`r3#VK5{a@hEoR(FVb<~B>}Lp&izvby(SUX>Cid41EZchls_L$&s> zV#lb(rH8QwA;qv4oh6mw%}xG|Emx9(Dw|=VLBYyHfBBG9JsF}8BSIfQ0**XJs$NI~Hs%`>P`$cj7<+4GEp)6}MXgw!Q*L^=Zu z5a;fnrm-I1E%8mCDFFIYPZ&bp*GokI9t`^~FQ1*Mu`&uTfqH|yR!9g+xDuZD;cx&9 zwB=W-#O1j@xAM#JgeQaqy$yDf4k8Be;-3xXnWYI2WJ*BHQ!VL+UOE1!+fyg$d3cve z`~_7r$TFGdePS?s_0rEM^|`0g6&xaGUl zPo+92gvjmA`#dSp;4k!V3h_o!N_srjy$WEs+0XoZydT=w+&_BXihVQ3S!^a1_~dh4?qWjQJUasHEEq6C001D$s>(|5)i1pz`o z&`L^oP_yL1nk4yRk=wzr?vq?@3K16X-q|3;%vICv+kJLRTP4g%(#B?A92?LA~dqPO*H z6gSJ9`b4J%A9PiQyWuHBQ-H$oXP7|`frbWX^k%Z3xx(mUHO>4Ub{{55#x5RZ^>P_c zc*$z}dp8i*3c7t?Tz_oQF6^u@#)exrgDpbeEu%5dpJ=Z+L9e^FLFqH!1q(7iHG7av zIQZKkGmkgX;hFcW#-T?24L3{lm;Hb*m;L-Xh-6v6LuI0!MIS28TWb%Td-ufxQK`Ui|Sv6EU&|srL9!4W;#enM|Uj= zPJC3;E-K1rv`KVe+PHeK|CgJChohsj&tHjb4M|KyQnhzSoE~ZMMWYwdDC8vidO`pP z2D)mx+v?M&C@V5KKUGTy4;Gi?CXba4n&ZSklZUkxa6TAp33hzzl81q6o^~*$@b*)sr0qa-By zO1i2(Z20s^$V)xSsONUO!bQ6TgqO>WcrhuDy5-w)d&we{CIOJ>^1r>8;swmU1FkSX z_1CJYAdf#Ami+XdbowV0&B>c^EwLxHC_=Y)PI5>{3f1j6-+5%D+w3$zzU(Gy0391L zD^0AXzCSZv7G;Ng*WHwq@jG;~5o$Eg`H1wsbS9HpymCra@tTmE`rHCP+a?c)g$?Zz z80;U=*2W_Bg~fAxEM`p8?cd~DT#bML4`B*>bkw!&Z`6v?fbPuBsNk1Yb~{sZ*8c33 z^iM&)wAX!!@dw*_uLnzrEapq}Eav=>s;s|^!LMNmV{lT2N5>a7ZdmGzOo-y=GROlr2xxf^2;-PiQq<9DF#bA) zKdb3u<4gT|GjcS~7#^n9U)%Obp;pEXQ!2vK)=2y4;QG~ReR~^QUmwT=&2Dz%rI0V; z4T|MhW>}+1vGtfDR}+)U6U^YIpogBSMtujQN4fsG%uI?e_n01sSE`wb_OtAmi-8l2 zct)@`&qnccVXKU=RwP|5!GHvnFKx^#-}nU~9T~$0-L$C2-I!d!Q5=?t1NZD{ec5UY z_#p-C>+6m*CHbTDdi+{8j0|yXbE~rzSz#+Wr`tY=L#!E2 zV+i`JsEvwF;h>=1ak1=G{;C5$`grWS^WZY~xS5D9keUrR-kX|zu11l16t+F)r_})M z4{>M;dWiaXm1_F*?Kxc-Ek3~CpaSyXRvP4M!%Yw|W87Z92d{fbHPo6RJhf2fWkPaG zVd|;zpdo=|$>KO|iM)}c5l&tjEUyFAoy6KL#@Iy+K1cRUHdF?rG9JO$#rTEeNN9bg zu!DGINPOz^mR?h`_nG(2a!c{}N;^MZyA-eF75O}Wxr_0yvo`xQYU5X2_#{;Wb9~O~Q%?z%S5Ybuy!-gb0=}Ayx6K0o<{JfkB{=~9%P;;m34r?7 z?}F5$v*f=}_Bkj`-v0@S3Jy39vO`RGgR=4WJ1wrP5P1(z12u;*#*oM4$ha)MTPUG8N5jxEEgk|hww ztIaEN6(4=nI?H)%@1J_X_MYj9Q0R=d+B*paPu8NR=*-^XnfH}7fq{*8qp17AM>zvK zNvy^L#Uj{PA1}yh^CjO9p}&3;3SNm<;(z}QgBI4tH~6U}bM#k=QA&QWIeOc^$Omz> zWk1}aeJI7>&|(+Hk{pNw9+Oj}ET-g>Bm#f;@g)K8?s7CF0!19WzLR*(GTO~iy;|q6 zR5o-stvTu)XJ_O3uK5%CIQSpLOX8#=?hPoj)9Is8yzt}y&|_9PA+<@zfb2sMzjf~Y zTSCU1!-`!Tip(MI&{`JLSkmrmC+MLAg$5t@9_PCrPAwccJGUS{_U3A#`X745@7HZ6Sr6+nk)d>+dASCRWC#XRVp zi~r@iRLh7*OujER3|YpoGZvbEsk{z!1ygi(v4;Qu9JolxzYM9;MLyA5v2BXbk)aeq z1VO|@@%d`ObphQp?Eloj{~4^z+uNt6Ehc+UqeOi`X{KbL9AA`Ey(-hu6R2cfS+TY} z<0P=GZ`Kn$5~X9%#gtSXi2gxts%!{k^i;(>RTMq$jY2Vm>kTGVu%KOAIa}SBY}QIc z4jJbjg$!1_o^LF~$TfdkR~2g(Hci@pDR;XT!OAwbT|$>sPu;{PwQ_&8wc3!d4P`V+ z6wlwA(cbT_ah?ACEmj)Cv7gkhfcWJn+$+A)5sK76pH!lIo%7K#^l){7SMtqQuf4JI zk|t)-(xzD5xky*j4$!8h7GFe35h;rj;m@)jk~O{=ww+eZx!Bf{(rck3%+iuU&UXfZ z3g$%A)0sWuWC|5Hpv18nT=KaZv}_&e@hh>1uYu%KtbJN!oIfb8W%;vij-Z3`#LjDQ z_V5p`fA6jJ&R@TW$-GukK5dzvcLY5PMev2uvIz%}G#jJ#Hi zs6*s-%Sd`JSVAc@hAwO3E14Mq_60Az$Bq~w*^5s9r^CnStVjq;GKxX+=EY>>ahvio zGxJo^p-uc|5~S~FkKSeIv;4%C|EQa>C?tc1-@r;!?yvW`03Nv+YB=IZW`7vfl{TR- zi2kQ2PFW)33q?9O9r?|&)y<`NqfhX|S%u@=yM?$jo0XP^ueRow?WG5?wY8oJ?00hH zFu>7JgSLYDm z+ZN|OJ*As;_-Lwo#x~Qs%V^3Jd51Wd<>Y}8AQUPBjYQL8r50w)O!-dxc_SMvW0$HD zYXwn52$2sKpKaS}7y`KS9j4T%P|lzA496|cQMb3Qw{q+uS&g~sML`lY7U(b6M7Z3d zowOD3{5*KhAT$;wL4Ug2yXy=V3j_b#ge#oex@*+XXM9o_3&SggDb|cluaR`Xc#6Tt zbPr;Tn>g~zk+l5L&VE9H&o9rzA-+|&drR4RdBxy(I4|i056GY6J(96raJI)h(k)xg zOAo8p;FRR1>JI~sTn`+ZExSXqmXddIe!5oxSFIaVVRwm$(j=J6B9$;-r1x$CPZQV= zM(GdefOg9K3lZVh36GoQ8Eoz}f%cE#@l{53i>*5IU{zs%V_WOZKby(M7G4E9K62;$ zd(Dk(f1p`C1XP%hOn9(dte}AZa=u^w-I5jS2jLzxYsuAAWnm@fjMwhI&Pqi^lq@vQ zif}45teLwuG@L0_mQzOHVUWuC{gM0uKXcNXd^G5NPpMO}>HSdX`9L{I-EnMzJppT$ zmJn$2xV8bF;s%dDexC-__4|?3Sboe57I+3;0xudKZTf;o%)nPy zz*4(dzkrHi)0fL~4G@OrJqA-T0PuX*v-;4rePC&O2CLuoVGiI}asp^=$AH>jL!8gP zVI8+63Uq!BD0zVX@GAUEvk(lcwD+fBZ6JIbpAtX%WE(##8Z)S*Hpt95?Hcz0aTp7z zb%I*qksX#FtRM`PnI^K9LXJXFYGMQ@XJW!c9cV2v8v|`_lh2hOVa_|D!cGilo)t1Q zc7*NSkYvPT+kD$-K5AC!V+xwbIb4fz#KFRxq{mO*^V3WyfI-#@i2E2sEeg(pzGb6l zGZE!85y+)$m@+4N6q;)#cz6d#gG;Ps+-Qat8AOOrmMQd^osehO+5NG1$6xqez|Kym z?z*j>iJRTRRZIc1cP>=q*m1NSY3AZRj23e_J6cIKGdY&1T7n>c3PmJT>{18uZkyvz zmi`kUMOh06JDW!$N~L_OLRn%N*0&!{njhFGf@ZDD4n-v-2^2DYWaAxIlsV*wt&Y|b z9CJ^~shqXalC2=%IyHUE(Mjvo{*`0>bUN-oxku(-G=g~ekU4#sPL^dks#_*X&iVZv zPQe@WqqBApuB{mJbpc%b=*9Xu_1~tr@}40mE$D?jLI(FvG;~%>636$4aluY-=)u1Fh+Yq7r{vtyoi0)qLnT73tzU5SCZ{ywtu}E2u5NX1Bg4vlfj_Mxvby;dhFFOT%_TT=+5*~q|=Ia1kCkbXXvwRjUp}27>v&@=VrOf^B>cA zNVx%=<}#b+Yd>T4ZPc9-f^B8rl#TT z(@aKPk;ijZbC5%rNSu>l6Z*UbBz+sV)vA=s_%H$&`CQK5+ucgE6O<9*`c&KRXsx&k zN5xnWtDf>M?9jrO`pNA$kA@=9j0u$#rksG|vuI_T@v3`y1bFi%FIPQ);`V>?)NQpN zfQ9=Ra)&iGmwtC6pmd|oO36X&W($D{KB)yWxW>icQv_~u#-CRW8v>A6mgn>tBhu1D zU}NY$-{s&rfP-al4~?vB!nriR4GVYp`;KL;p|Z9#`J0O}ZMR(*_KVBGYlqQuX>X)Q zOCa{CkWor7%>BAcJPu@~&<@Z|>5h>0=EID(=;gPaVMZSzzt`pR&FukamG61GA%E`! zgX010lH8XdJ*fbu&U2v*P&ybnnHBYj6N@NSK9WS`6*xU#oj3I4zTSrCH_fXn`?|9= zl;&mtm|Sk|S(^AUx`*DnqI6{Et zVDzvFs^ur8)dkZ0!ium=$9A_&CaT!Yn2uI6=;IqDvyj-YWv_{U@3G+WeUrxMzFs{Kj6Y zpKhFoj%yLEzlE@R;3G@InYu_nLLM`@HlDplH3p;!r`xurg5G2 zWc@QyGqQ1Q*Rm6D`&G&Q)nkui*f2xT%i4apn+gp3ugzc-u`Yq1e|DY+={G+asv7~&wPkl117943`jo&$^QzeMSD--n0qR=0f>E%g_`sDF8BXN02 zdlQs(d<4WPLe}H=MjTPZ`zqwP>g8}|IME;PzjcVbf_R$?;zpz7%VkP@!L596+Z`(xGc)rakNfHfAz2 zH6b2!H`w~hm*GulqKelInA<97lHWFXr-kINql}}sKs|{m7@@A4mnFB-Kd0l_$Zlcr za~5tE8Ezlrq@|*guWzhvk?w|ywEb3Ml!yUUZ`XM(J&wl%h~Pk_O0b{mJ$oZA-wb0- z!Ca*J8Xub#pDJfWGYWzE^R7>MnE!b#dLCKo%FR1?Kc_<;LFsTDW@mk$%rXG9}AY2vcTq-X(PX5?w*1< zg4)_D4&!fb7QLTa6fA}AyT!ZhkH-VSRg=rrywiMhqcvN6bBt4dSjuq*3dn3Z!ORcB z&LBVucNxF7Xzy;D`x4};LmDUyliLoKUnM zc3%Hgq)^gSc14* zye!dsil$*OM^qc7W1rwwsn_!;4?1YQ8@TCIwBfQ-7&nFG9UHdzke^G>%p#B^?27+T zIxMHB56={A?hn81A=FeSaDnSdpOj9nJQGTg$jh{FFKb%E_hDXFTG>>0*do+Or;fY| zw)a#`0Wc}^yuVy7l*6L1aHyqJi)csKH4vt1880$v&6g%hC;2c>y;fs2Jq;|WlsoL_ z;WZF%#5JGofjSn-8xJ)pvt>S5D|f4z+D`&#iza7GAUMH7M-mJg$H*#C5ImbV@3Npeeo?hT ztY^j~Q&-55!TV&FO=@!lPnTJz_RWBZC_$SSjUKLHpx`S|x8FI1M7iD!kN?6#S~q73 zsVdSoi$|EIQNFgHsPFX9>}0EG{&1CIlcDhoxdlg@evESaAniL8=#Lu$V8i`qeV^$8 zbKdV7#cFdJ9G86?~AP`U0xfLv!P1`a)7EzTeJko^fGUrQqv}QSv>g^ED93c*zJJiZMsG z!i2t>;bohOJg_r+bq?Ln)$)Lsggeis;^n+fxT;M)GFQXe)n@Kt>fOj<;js*hl#?!H zi|dU&W=wbHKXs<9)N4+nv1{+_jL->XdJ74{243tOrLna1NA{gA9(E{$X8#Nfdjwz? z$#t|kj1Svnd_Vsq(c<)unD&N0=ZITre0e|z8q^lDeEG+Rn{ZcTF{!F&;t8M6dSh+jx@7UFw#+97g1li z?y^~Wu0ZiC6)&TB!l3Qd{ro%WJfCz>)$om|y>t}4;+*NDqU!NLs-@W~peG4XO?0~? z;Q-H1Lq=uCvj7r;>e`pD*(Ktc%-Pyj5Oz6``C~_9sbp|?Nr49j=Ul^-)$q`rv9~ zwfODVf6JK?E3+m0|E-)UoYf|l3yN8JZb&oV^%XET ziq{1f?xShImTj8gE}GDs(n0E(RZ#7$Lv^$=OR9j{?VpnYrsl*RPHi2}Zq^3Zz3X+e zaAOaFMP1*|wQxxbW6|D+YI${n-F>_B?c5%T>`xm7pm~pT&=n%AGxAVww^xo1w6%JEm=Y^M{URgug&}b<2 zmGgj8JBP&uL~ccNiQ6=%;Sf*fBrzTVZ1X1vKIzG|H|-nTOAO-o{% zge&8$=p+Dd*!(+ig{xE9QjfZ#G%6x{%6N6H#)Rcb5lQnr0UJ?Y+C-Mi+==dx-o75e-@5wCDH%=zYJEWQQtq*5Z6SY;9&#)>^7gHSM}EuK0!C)Fdo&d)F8Klu%Oh%*|}UxwPC2 z7bV>RJk2+xIN@TdO*X*TOH5q(gW|GAg} zX5zY)agT*Hl#s@S%gj)Y`zLnW5@Wud;Dfv-tLTX_{?uWGg@+P^QOeP4!nCT^kbUmjqD!g@y-U4fDA%%A4Mua$bratXc&AJ^PJ zLM1cMZ@WvbKV88Fwydj=^_|N&r^rxKo?A(3=UGp`ofiO6^|N~j*`t@I2gtW~We50? zS1VY~50>2cU{PA!5L~M#iECpO=Q7P~O-Y=)QC-7UrKC?4Qj9v>O26bihIpdbnMp-B zoY&QLjNrP=!4WOw=Jen0kyPFHZ;-y>OSmCQl!UKw&L%Q6QWynF5h(sZ$mnGv7a{*i zzkb8VH4*SlG6h9qaCrCQX}lvziFmngPA}wh@8sX5#l3tce_|FX?dO$4ayk8EE_M>* zN=Af6Gy=#8OtR-8(b^*^J*K-6(yZCQ2wDB~?X7%;UhX#z^I6U>zIqE<7mlgJAxjK_ zEI)G=JEeH+z*b~d)Sc&8FaLa6$i*ii97E3Q`W9}vkbv0yBQfDpIC5@_!Vj$)(xJ+r z*uvI2D={r-(i+rvtG9-9JurGD8!L5*awZp=LcLNm6q~Vx5ZA?ahTW|XzmTeb?|mVT z?T@1fDKlXzTf@?olUS z;pb;|oOYI8D#ZiTIhZX(%H1yfi^f`q$8gW5tnFdEC&R}(Iklf_`y|}6)lx4_ANOd# z^%B84^^n00t8}{I(5ISSju8V6D_l6%z#1vs4nRYmu4?^`n_V+U|EJiS^GDqWsRz^& z_3noGG4-6o+xEsd9{#(nbGbmP4j`zmi=13JFA0@{o(=OW{uhy|PiLR7%kkUe113FL zydCDYqMtHq!7Q)MRoz>Ac2cWtMr%iYQWuBC9v`%or>EqV@3gg2<{2-9CXeI+`8qyN zEqXT_tz>Yw6yG$t*QXk?>!;S3YIts+jsC5lAV(?@f5v%mXs3rSvD2gw3F5*+v7b*x z`ow?(-7uHdW1^YWpzo zO=372N1?F9BA7b}4;P-h_i^>f#|PoHX-rdxkW-^>8$i!qcwo%^#4~pldYkP1rrf0t z&kd}*GMJn{ZhF&EN$9oliaV@wcAHwEx}Q7ADr^TOOK$ddVkXY` z>^g5C6QFmhTD-K5{+g)0KD;}!d&sWp!M?+Up>g;$R%08LmaDKDq4G~+WgE)(6Y)Nr zK7sU&tn^PY@D#WL;>OSSb@21m@k)js8{j3|Z;!lYZ(_&cs3q{Qe*7-AMV@OF z|G|~`XreE)zv|MI0%A+B{kYg@f4!UzyulW(bH$+<>K+NXEXWAoos~GcZ*p2J>CvL3 zLfP}=ssLAA`PkHFB8|)-KkltAxqn>t!A7oB=u@i0eaXu=1tht&KmD0nrtZCzZ)n@J zFQ|o&`CRDkm)rD)fca$Ro2@VM>Nm+$?{@0cqr-nKfMRW7nVy8;CKmE7UYG1hlI)uU z^DAnkyS{>jHrn02>%q zR}FQ)6A*UhZ05nYj>#3Oz4X|<>p%qLy`Es3T}&HW?Bufiez|FJo-7gf zyuY3r7Qk!hOe1eF3B>ASxD?zILm?;-F@>NFqxP^vzQZ`tbVea@gUT|3=qA@|C4)wP z*5``EQ)1M0PR@q8Zln;sl}S&}i3IC<4zFoVx-P=6X>2^Pjd2DV#t_^&MpFl!qywZ= zT1R-Gxz2w+!+>Gdnn=_`lsuU^E4tJ(aO;xs$PNrfqM+svGfj5AzC_pj+SJijc6Yq? z+}1R&N6Xrqv%2=%I#=|mR>T)~y(HCLfqix&J1ogN8=YS-(H}&Hc;TN}^YCfT z_pQ6SRX&PV-A#=MKLu?4Y9ddTN;{SUy6cTDx~}hDKj?sb6v>uCoaB6me`99nqr~3C z5lbc%_^Z1gd5uJbTk%38{|3;rwEeh}7?s}vUXUN(;Y*G)NgX1;8W}@fM{=jP?o@lE zw|47^#nr^ve!4V^z65dJC;4pZ@JMb6f!`d5(jRAl{aZ#H2X8#U&t3;bVUKKr0QtW^ zPa=#{Hv3;}Q!U}MRn7{v^5CdGi%y zR3P9Gc1Y0&6W(@UtU*28Rj^rLGO}Ar1N9Rc%CIWk)~{kwUbH^-xK8{O_a%`tozz7} zs;-t;^ZquZ0q`zv#ww2Og733K_^}UqtZQM#lJbs$E`|hVyd*v)a8x%Ahs60zR| zian+23{&ajopbH4Wc9OwPm8h!Yei(-H~O2OhY~Lxxnrs7qHrUgRqzX~qBwRHT!?An zoF;i3Q)|S9)4Lt%MO0;f(`?D9cc(`B^1?Tu>@|H(J9ly9aFRhw6j9ZhG^0_9jZ{ze z2S7ix3V5T`7eevU>ls!>YImT-zk}-wIc)f|knMS2ajo$~f;>r*BC`y)rFX!-cF&!< z)sm?-md2szW4flsXF(%vx^52Ge8aM@x(J%y3UOFvJN`;op+d}7SDhc8El!mY2kBcz zDqxDcV2oQ@2#fPs);if2#(s>9Au-lVI603-H{xASN*D%zJoVXP7Nog#)fqeB#Hv&6 zIi4zhuA?j@CmE)eF?byPDRWYb=@BX+t76QsSjM)1E=id*;$kk-(hUFc;t~%6sNTMg z+!@BMDrU*YQ`JYv?6fVCP&1m?uf&Q|JORlgiUl?>LT9p)T6KKVgUR+ z?cRd=eD#s;$Z~x8e2+W7XmbnpGcnx|H-38rk5=GS#A{{Q2ZoDzDKvluxamz*|*VJ)hShcw=w8rtlfYWIicqjb8XB zbSArMM!LUSge<17#*}VpNTu$HI?&z3zi#3G?|jd-+y9#nomZe0@FG)HTIli-vx$3x zzY+`2GzL`fc=+9$xTJgH|2Av$1vYE@z}<7PGhbgAjD?6ACrB60cE)_T-#D<|Zn#+*7URaHffCYm|4p1Yxa@@7Z^Pgsxh$&oD!*Da9O7X7w? z)*IUu<+6@T4=&xhEN85%hxB^@F%Aja9TDfbTHhfZZ2BbFRED3GH~%GM@u7bN#Diqm z1+K*%()2sy(S4@gXS)5^5au}lv0uN0#jPvfypzMjx#P&MNb4RNQ)VI zyz@qRR`yZ$b1iPIBuNER`x9O7p$0NbcdtHFJS?oh_oDFGI}K*srdc*Lz;fejVcbL~ za_raN@P4vkH-r*{WBa8)% z-oJ$&2!TpjEHNJ1w z%lxFWWPbM-f3x_F+|id(De1f49Gm|A)p*0*$W;gR9xGeX&y+7zhwiKoDwT(dU(yN$ zvi9sZ@7DlNFnyVm75i2dv3D~hh*w>Aj0WvX&NN*Z3UKKEwMI>w7n$LcpYc>tk=3H# zVP?CaNdA=_(925aB`yewc!0})0E!*&aGvrX#In! z<%73nl)udp<0SWlob}Z-8HV55MfXt3>Z2dc;Z1xatNCMt&+`7P!gkggnqj3|+jJ;% zPvTxvS<%Dd(lrAn%Yd;)JFohw{^*S>zh?TvXKV%`#fU5DftThsDUOlxBR%n1hJP{O zq)+YRTc348w|<~;KV4?NA`a*QtVLeO4_l-uxxvq{YY3^RFQQU1LdTv(`5uMjJ76FE z`lk{}yy2cq;XQNh#L~Jhy(3uCptfyP-n=-9BV5*+`!jmbyDH`Pxwh<}$u|AkK24MT z{SYIXz(cKBDNTBSFERDx+ar@vp<5=`aJJ9`32F*ggdjX_xjrg1YMNkV8_iA(74wk_ zFd>qBFt~$*_jw45`gS87-1a1at%Zko2hIt9VTJz%|KITYb`bEaKnT}pJ*+sfb<9ji zJ~u%=^;DTdN$o5wSk|WVRkh`@_O_>iK_NyyK|qDouD_;p>=Ne-W#tOv z6aCl1>`&3#eUE|z#{1ohE6u;MoAUameA1g9XigPwwE;U3)0+^K0c21_qa^pC({H=a z{-(uOeVR5SxWBb%L^ko?yoc+vc%FKFYEjt6;X?>Kvj@$)`4_qw5RKwCKDh-aUbFRy z94ah~#1O+*8Y2tpHz)NSTUgHLkhaS$2k_gTVfHS67QbzqPgh7s?jTur@aFS(ifiQ} zufIa?eYZHu2!9+Kqe(Ca)>uzYwvy>Wh^C) z6m!3H?B8Mtn>p7qx1?LGs z9{J+qQ`=5|_MJX&yqTn5?ohC7P_(2r+EL1W%jtWvNaoDj2;+#IECrXo3?5Rd;G~JI z!Tx--&cS%SznWuap(p&SZqLcD zkb-eM!Ewg_=0~UY|1p>c9hTg@wZny5mK52N+8S#^o*pIa#;Fy3zD|M-NrlciIVx|FABLW5eC^9Dtw_P z&}{Id))@6@7214{r`c&Ne|HYA)SOht?M|H#d$<{fJTwn&rgn?k#XLd%CxkPVZV?0b z8Q%LGtef}rRM2C@k}oR2R);%i#9wr@yZh{nsnz%AB~5?V8aw=aXDIyRapa5CW|L=E zY?##bNpY#{4^hYQ1~PvdFRA^dUEG(1Z#}Gk%h=z*RUKHM`NE=?(7*n~ABN}(O9-+? zPa!^1KPb4lH8558sCLUky)KkU1Dj&U(NnlLAyWIq4PfqtsJ2Xj7%{pp?-E4Hs8_2{0rBim*73kPj+ zEOEPOG)RwP_G7HM#@?iTWHm4IU}htD5o!7zTB$Z8`E)nZ3rtT&o!W~X)@ulYwQMJv z4wabt4|NOdPrYv5c<`xa1veQ&_{ByQ9@L0@WdA#@na%d{h&n`0>d$@segvY7k(JlV zJ1lM>BD8Q?Z?py~b-IIBn7s))`dVuDRXe97|DmLK zsoTK*Cx>1E4xT#??8r6iao59x7(mc7KZ^w>tJ!eE;qluGr_+rYcBG0}QJa1UG`9Hnx zzB>%)_1eig8X z3k_cnwRm&OYJZ6`d|zoS&SUM?c#T}Qu$VC%*29QD{n^Uvu+~(u$$kJN@=}(2QW7qh zpjuD36j1C?LesoWzP9czKCVJegqtK8nw+gWDb=lb+iigCu0ZSFILGQ?1WW&6Gkz9p z%rFJ1Nqcq+rzg;NrY7@8x?qJqGCz@&i))cr8_1o79q*hapJTW4AJ!Cg*m~TWNk}vD zD>2SrdS6iXx3HnsSvP;gqU^;-ubb|198w=8-v!xQR6ltAr&J}kQt31Q;`ZbB#{OwH zHF9d|FVmB0;6q=l@!zr@ju%`%E5UnXK|IO5y-xTy2m| zkEHqEqNH|%a#C_;MHcSX9`art;Cj)y>g(?%=JD1^@5kSj*0Md>g8wd&HiI?z525cr z9k$zl`s!Da2

*Y0m5SGY4`w(kBcBkNpg`sd2hld58+*cWUONEJO2=PM+n^uMgb2 z=fw_1xt}G?z8O5SL~o6~es4tin)KaAKZ0`ZcGe+yqDg+*!IZI;<*||SptJ5)gBG>I z79z`dO}8;=;~8sXR9RO@VUvNn%O~EcJWo zBi5`jDT^l@Hqu!Fi=~oAs|ZCKlC@CilT%)#OMLD!SHHyOj6c1<(eI!ZFJS*bT$d8s z$}Q@2KjvI%BlwrXqjeFq!v zi!R8}$|_B6_^UjW!s)TVll<+2yZzp$A0!(ja6bYOBpfx#8Nvd!HlEeG z5A}Rgk3E0q{P616nOoH9_R?h`+atJo^rTUUc;5N=_1)`84-FKjCDv8yQyShaB)zm_ z^;@s`bfCwkcVPC;J*CfUO3_T-Iqqhur525bnCDxRKW_)pCYG+b(Hi}KK&%=RzwcX$ zDe*KP%J0Rx`|KWbDeJ+`DDFNH`+U?zOr>r0EZ6ZFZyMzkOEyW6r)y>mR6HQcM!v5c z$nt=vkyK(s&*IZbZpUdYK~J^uaipf>6fd|*$MA8G$F59AoLEE_spB~4&aQGtw-|Jg z${TBUj>Xe~K8H#m4Ijtd*;Vh*K5o)QHH;-_vkW@y&a&h??6g=q9fY$i^$vm-3(}D; zypu}`6+6)Az-h6-u|-O^feo4C?+oDVGBy^ayiwl1;_lO(o6~Mxk#~0In$KY;-MetM zm`Cgj;_Ot?s6ggMq}ajQHF0(hY0{$C0P5VuhTQ6Efx^0Q+9>+b)v|PN6pl2bjam>| zZ5j4vHEMg~AJ-aF2hMR#&VAyc3wPO_ux40#s+gFmFNOl% zyl*!mL@QoLzI5uPC}wUVUly`po+>S9AgGkNIsEO$!J&%RCRfxK1^=^V#Kjk~?s%$1 zK6mN`DP(ST1I&+rV6;;&PCj!J4Zv9d94Y|m4M393-1G&4#{u*tASjo)Nd|)R03@%c z3R@l^Cph(**r+f5<0PE4W{?3q8W7F*&Gz%=iwK-;GX2VoqTa70r<((Ge%p1U}t)GhO0*=ZiO5N+swwkFL*N*Vg2PlrqhpSq$u^N%&s}t0{f0NJun6(58}?{`^Wave!hYv21Q?k)-+N$UF-4B~loT^lAc_ugmZ z`Sx|~(qoYOT_q<(b?4szmwe6Ld>{N7;NmK}d3gZtkio3qZS;qIKUGs8OZ})YBea?Q zY(qm9G?K>o@8X?Fcrm4U?9p|v%%jq}A5<1%BxnIZL{{c2!TbFhcfv=qgr8X?*UNr0 zORiS|E{qf)l_gz=(hk1*{n8VnHDu%w^vovn64YsU@)A^Rp8FE?qk?oFxpS%%fVGAJ zdY{x-h;beg*}SN+%)@x=v#X9vtk(sylBWC2LSy+Db4u$f{x|nNwh#cpJ_D5SRW3pM4mPyr zD>f;7Gy6M!V($G8UIXwkD$1ev34(wC#R6b12z~zbqp=AfyTfvI0@aY+o>}~56a!hJ z`2LHg|BI#rW<^E-)-rApntNY6Ej;&Laat4*LCKe(Cuq&B`8z0?f7sVvCcdFp0K&_T zXAl1OQvAUvXSsv7P%J6D{KVS&y1)s)#>SlWSLUgKX3LtXw;Bo?&EyLv*VkRkLVOmm z`{$~B2&gLGaCRgaOO`&@!)71z#<_WJDj?Vy@yinF<6yPi@TckYzOKh;LwO~z=&;<< zk6b+JYFQS`5b+}Gz_4l58`o4==Xn*>qt>~VLA#lD{X>Ob4F`t3LdAK3p=KD;bUE2x*b z?PYF7l<~Ql*6i4k_0w_>mh4GPBX()cd$akpyyPRbd`hDGkz@1lL5kF|z-;J!w zicix=XUjKfcq&>4^<@=rMtsil+l*Mv61Uu=SK0J0$x|rg?Q!xX02ko3^qn!;+5Z|J z-mh-x8<#a6JeZ;t;!Wt&qRB@p_%tu%d5T;)xZmFnXf*1X*~`rH60uA{B&KgQoei=~ zYZhJ7NQd>iC@{5x>KBZ?Ze0P3l)eTC8ckVsw|2aUMrmF|iRI3T&_YqZ8Gv(AnOPB# zw=h-<3#$l-*%F9HxD&haHk;6;0Lvj9Uq4f~hgq-uCOpt)h~D0w7aXBJrD(VmfC=#= z3K%La{Y^8@YH$fwpOQ0N`kQf@wxh6&yhH5Xgno#SF%*f&DxkbTfc{5Q8cIaCe~-Aj ze=}H}bv3Ml8nV0?w22u?Or7bCP-j^M_cNWtv?!9xop?%tsC{JGzSC~gg41rymL~~4 z)F`v$ivaOOrqZ=2b@Kc5t@w0pgo$WpC1D20c{w%6(B$`ltfBdV3i(@m%R;WxE_$u) zl0bHjSAcnNQooX+i1aJVnN<_M#c*}VwcrwC<@9DzbLm{m89qLmHCRMik;$$C=o&Ij zVz;k_X>C4SUNma|SqU;izd9|4ehpKHSOGeVEqAt`x@+=VTFua0TB%74f!|t>H@r^l z{thg5NP;M&AGmtlsmLXmZLHC5){B~BRmk1nhvmCxhZl3l5V5(ZbTAN4eMY-IS>FtAwg`#p`%)S^R9$+or@}znXCFVI^0Y8Pw zF&XO*3m3A&GPXR)zX0=%T7k_)QuoDfUkN_0sope($lKaXL^a{jd1i~@YwDWhZ-Ya@ z(n;!obuwSWlGGKN#87}y$r_a)xuDml<$}^+N%-4gTD!NFI|q%tP0WdkhUP>~Aaij* zx^6(a^qz<$yi0Hr-U2WTY`JrmStx1*%G@7gL@l5~;effeWdT`>0#P~Kt9>!X#|1G) z79cwh$l6(fpF-7`6*QHe3Ys6l<@=8-9nb^J)T&Hc5Ocj1R#BC^<$3o-))7NP^IQEG zB05#LP&7u(G9@oVq5HdPuzONTHjQ3=dFQsnj)$*qPepwL>-5>0Sk~$Cs?1z&qt(US zqPsh{T>w20Jz9+^x!nG%y@>MK=G-`nM6$ODm;S5M{*qSU-+F1VlJJXR75L({?paZV z?g_=A#2T&@Dn8_{eO1Qt8#4km1}Y` zattoXQzExb0Dr*L-Id90vxSu)e^JYn8lZIgW3GTR!RfH$Fa>7CQ^0JEfZ3h`W@Fq3 z3P=sWIFowXfAk9Yce7fP(*YJJ4(8+NnpHrXZNOxb1)_a37}#;5Dj=N>NCRej3Yd+d z2S~eBg6!+8Q;LlMl|!w-J`}(r`)A2Chx5!Sxh65ZWAJfe-3;RYUNkFFQT5Ah*m8=0_m%NsWin8Sv;3f^w` z!K*#HMb_o~8@6n0oQE^MWMft$oU-1W@;YiL&6&jLzQW0-g z{&()LWVbG$<|3OXQunkQftR0>&M)U;b{j6C`(E(c54#JlZ`Uqd~imK4Y*9WzZ5ls!x zQ|jaLbKS0hlx1KN^E!_{U)W8w}7?BW}0##ba{ZF5;(_ zRL|iiU9TI|)u+Mh_cJ>C21-?7fgxWCaLB}ORd3++b(1~)}c|R!F*V? z+J_2!Dn*)FYnUtK-Tv065hMc(d^%h}dFMShehojhY2IGHnCuO5{&{(a)P+-EKJ3fs zK?O3#0W$d|=2os6ERcnmTg)4*-agves{p2q9Gr5wH#c;px z-gApP?y^7Bf6{r1axvib8Gi-6X( zqyw7R@dA+=0AdnLdMH;kJwk9&9!uyw?Yxou@C_A@64W7aGNkXdTUQDWAdLNRwejS> zxkA}8o+9D0UTF24?s(iSye#v_`_Q{keuTZj7q~UPdM;pNC?T}dIuZJsp|fC2s-6o6 z2!h|N)u1QAUv{r94Sz(x7=C5ltpu13wy;}zS z3|oMJ{72}tR*T4BRR2*T=`8pH1a|-<;uIiay)>LK^J4g;$v11$10gU!!v!D8xvEO@ z>oaNhy8^Jj(ggIL24cf{P!dCK1~#j*u!$jiyiP$VK3MUQ#JP(*?_~EotxflMie$sR zL2rKB?Yz_AxGTUfuACct{G_cZ7hjRA=|afQg#R`poV9Kmd=XQ`CEhxYA(-WxCtzZe z0KGh4KXle|##ehL!TmZ75GKhIU`mnfDQ`PxEr*?V!s*Y46ME(f&Fld+KEz{g_1pH1 z4L^-1KL*qjZ} zB8eDtjsL&_w-sR$l~zl`uNDFEV;e&sGv*34J_EV<-G`E>G&kVCtp<~*0nF$9uat>o z+nMSeE0WFmW}UB>h^c)b4CWtKq4|B+BkA02g!_#MYz$?(0d``hA4JsHK|%qZwf}5g zc7R*$k6SYh5dbRT!pr_5S#IF|na&knkL$E{NlC!e=DucBFJ?WQ2nO!u;&UJ=6+qd? zjL1{`mjBu2-x$_L`dK@N`GEO*(y-&!rj>wpX$}U-y^6%)fd44VwJ$M|_6wN|9i_O3 z6KVGNY6T43&sut8sPxD=+|q)ut;=RSrglLT9H62Mo49dvX}J1QyPxeHK;1JyhC9Dm zyIA$0CLCN122_CCdgBJZy098RKxErB_VN@NdIM_q0th!xfCGx(U^h~pT!E-1U_LmU zv`tj)gX$C|0Ga#L19&p~i~N4Q7=AA?S7@l)X&rJu5wkRcVd#8GdFXu85wBB(h5OlZ zYz*Zpp2L066|zl~h{r7Hh=2$DRAFz1)tAXcEg1WMCxQa~$t!t3p+m?}pMU)a@SUF6 z8ULSW=1UV8yw@FIXM4F@H1+z%<`akhyEbQ1ujtrW%b!ykWQ~iyeL>wn?94^TY!^Hl zBn+`QW+H~Sp{}X0u2BWfu^&d&wxf^UQzGWKO(xQvs3~*C(s&o@Rkl}Cny=CZmgmRq z-JU~kcX9S@jlIx#k7;k*)wZxcR)1RDfkR3x(6%!?p&Vo%6dINwo8S-eMi zYNg#fkNms1_O`C?P_t;8R}8b5WMP>4n8AjKpdJjb5N#tA)Z=0A9Z~F&{v0EqcN^~= zZS!ByxX17}7tJyCYQ%z0Nn;a`2i071k4W5FHFE20nj=Cv<^s?_zxovz%T|t zi7L5VL+*9Dbf{^*JWnlzM?0YB<8;BEr$ zYP0CyaI4ayWHet=|-lCo$pn}n)#^dywm4M{Y zcL79qgTMP1@H#Y8APID*wWJA#QN3}BR86v-n zAz7PDT^YoI8thHIoq-Jz%=|IL0d#Hpv@m!8q6vGG{fg~= zZ;5wfXd!*Bu&@Y#(Ju4_PG(XEa+eJ#SG|=4Fk!Jjt+lHXFg{B_m#3XWWxr8@O=Owk ztF?fJ%nO=rhYaB>%0>XvG@yJe0S%eDI?XTWFiEHCE!@vXc4M>j=4E_!_4EFsY_k`` z{ho7$*`1x%>DCFD%*+giPSxv&Z*Du|b*g}l#Rs?#D^}-lnVF)t+G;N`KDUIx110LP zH?DH~{ViS`>Au1nLt~%X{rrI5IrA1K{GOi;&`pm5FtwQvot<5PbW-4ce#QWd`8izI zZ&6!oNg&61LST&mb(r(C>(cO;A|MXjj3FN&(;DBbKTm#u&@c8>6~g_3)JQtDHEX6` zlR#%so401#VFWb2lQ4tizcMh1$?JHX+A6r;1N3X=Sp&q=|G)zj)m+8U^zeH@q2qBo zJHV(Z$UWO`5($)yrcP@l^Cf0y=M?y_6j0ugkt7{N6x@$;VPlBc22`dFp!k8#d*(hA)qvfMFM6CebV-`1yH&WNo%I*-9Yn=Nb4_R%)c03;hih&IR)5H zDG{S+2Q=T22@jo(fkKLS1NYlJ4%|#bpkE;f*?#to$0!m+z&2Q*K;V@Z>jiDFv~PWl zttgTX>e-s#qzFyeo|fl)=X zv%wdb9L%{1D5qgfaD?a>aF2JnNY!EaaKCLuz}y;hi*6oq{Y4}fK*xZ&!e5h})}KQY zFrm+yfR3F4WC!SSZ&Bh2e!yEdHoG6gnIvs-{Kd?NJ4@Afx?;2ceJTQa`-OafPuGWj z;Pb^|H6vUp=&`+n)ft=L^a%ERoi+`zJ|shGIp6clPv?fx&}y1qqIu=zFyo;Ql40RP zK0mHxTnV}`aaF?aKZ9BK7I{>(f{k#Aigx zW@6(qqiGk>{vBjGVc9`;8nP9KcBeiC9^_-I`MOxAt{D0MIb~_&JCb*K0+GLdcSuuW zPiRO}0fU=Hx_1!F%%bMDlAyL1J3XR%VSx(7pe3o#3jxaNTm?cJ}ryolg&^-i#{u7Jryq$sJBHcS|walrS^ozd7|P#OKEu$onnLSK31v zAwD;3^?&Ena>aS+XV1s2yB0Wvoj*uHvbU@Vtu+3(sn?gY4O&i*zT8qT!4#!B{Oav$ za2Z}Z-KaazR^c+7`_I$)D1*H#{R=XaAJ&f?d5J*3Suws}O#k?Wn4c1cZh%-=EjF1a zb>9Qd9~1EpfJcbd?Sq#5%a&GKagFqQ-`=doB>zI$I8l;cNs0>(6Hnra6)9_1Lu;<5&BQqLq>Ki#wEv?+3=SB)XPe3%YwZ z{1PMl1|#nS%hoZ%SGh$S(Og|luW(GF8)7zK_ThE3pMy8ly>2_$eA@m zP1y5t@>jT4JF>Ua`UKHl6P7^525+2uPJf+;*XG~h4Q+ut4e>F(^8e@Gc1~a z4TW`{x(T_yXm_c7W`7&(Ss~pnAyN>E-26$E2C*UW)W$XxV0?9b>wTB|XbP zA)qL6iU`3%1_F9PMJ0vk5|m^hxaU;Vv38mt55X4*0Ca(N8p8E9b~?-j;vNMeh{{4t zI7tiz9s<}D9>Lj8`&^EQ;NR3=TRl;05(SzBwWI$MUg_9swxQFD?u2X}f1d6un+xG4 zEg*Q5z!wY4{g|7#% zLv%-Rre6<^v~Ochl(s}a+}C}+8YJTy$w%5Va=l#|K1#RP{X(&OwY@K1+1&E56gD#> zv&uBO8_td@q2K^AUuAQo>2Esd`(6XPv}-0NTISA7b(nXh3`mQ$lYo6)|x!oCJ*ctMqGlai0#HKUkix}2l z4VwesoYLWi)NRh@t4)9x`c ztj8m0Gu{zB=D`0NU*wa-2N9geP^8&k-QOwF1{6QASJ@Hdb~_@dJ~CG-{2|eCuzT{S z`ws8ZUTJ)b0C{^%vRr@eKrxrQY&H}ZH8Xm=9^8>~IajHNc)!fnz%G^PJD#eF{2=95 zNvQGqxJFwOQ$#+K>hK0vdmY6Z-WW_=yMk#tFL7Y}od+suV*g>v-OEBGV*LSLpBq`q zLgup~xo3hRY{x>?t(WB{=jFJe!6Z3B=qAZa57mEtOGFK64QVR;qhT6k7^e2aC7$?6 z%y?AQc(g6V7^43i9vDq#Q1OSbqV2RZaA19c2t07Q3mbR2-M9_`sWSt9CV!^T1Pm$V z`Ql`a;AXJ{Oe@=Y*PWZaN@By&Y<_BF><~NKicMC5XgGv9FKtwx#@=cjwt_oz+I=SZ zCBLU1^`^vQiRnL(=fdnRQi}f=^EVZB|6!{ava3k!)4L}6-`EUl*l3eHjO3)ZLb$dA90qi^M_DGqwwft+(4UJ6&(w=|4@}P4xG4=oS%8@U@E2x*U8^0O|4v^>s^U?f3CD9u9zwFYTG zTEtERLL)%YpNCKa=Z0z0iYy9k;mTKZ2SkABK`|vp9z;Xthv9^*=}Jm<82V>UR(4BoZN8OZlOCVdS@=fk{}t3~b_T zy%^T|5(Lv0VhC|;4N-tNwuR_IMq5Jya>GjP!%E}GT=2jbWIcFb99aNOo}We34ACSC z$^6Ga$yOj6X%LO%br_}o9BoGZc^ssXKK z2xADF`+pp`U?M&0ox||L-$0J)N8$ ze4g${j>yj4ue!TrOEhHYAu8!m%J^a4)X3(_p6wD>zXb{9s@ON&mVpI`@`bK9aaRK0 zBR(#CcoSzC_yO^CVd;&Z$eSW7&5wvT3-SZQ3Zm^4^%9!+ zxv~$4cMFdV(t+b6>hI4+ekvx5_PiB2piIC6q!t?XXp4J%r3oxLMgENMk18)<8>y~=Bh}q`E+tS4G z**p$n{cIjLkumG`7MS)-WjYZ$nhiLCod5&Ejax29?7m$pOiT0wCQs0g?cz^D%c2RN zNi>OFya==`hOi2@$LWiO6M1m@ZRBYxLJ&pd!_g5aq9D#rEF9{$#mH?#515C^a$fq zyfH7A4+0@syGJ8X$4sCxAY2C;Jll=o!nNpc9?X*V|HGR+qx(`1ju743m@Y|BHlQqc zm!*$N`Lkb0;MJs#*SC^C@}X>3kKl#@ubS&@NSNp@sxYyPfRH0Wl^P!68hd_8(WJwm zF?@7Let)9}(Se+Om&i*SJWp7QhJBxlhJBsjYuBeq%EFD+WgRfp%PV2h|lc_IR%3z1&G}*fn77}BTSd;rSh>8T>?oQL_ zcN(JDU7kg|;bmv1cM+s#2CD5qj!RR#x$zh&W6EO4pN`Tl=$g-32Qd~n+jR}IgpKff z7U35k;rAlKFFC?5Cc@8uHk|mK868JAqdq+n z@DnJ?a+G_56ftTFC&hr8!c93!wbh{xp4}YWq7ELRJfIF9rnpiEIVdO&$|X6<89|CC zRr4_A233=T5={&?&w z+E#3R#(93>^m(CvUF%~ghQ>F=kWLeAn6lqg#n9x- zp4Qhd=xTyg5MTN#G*8+oe;)&)~o%zTX+0>nP3s6O$tyWr$I_E z8I8eDF5XI`f2aG_`+gkRsh>F8!*r9@WJLAJ$%7sv3Kn)dK?;U#i$Bv&xk<|z_AFLt zMS{9z(H7V!h}IHidHkc@C2SIelU(#(njKF!>h<+%hY~Ir_XhamCwsaY^X}j$g_A;! zhT(NpSF0z-yBgi5|4fzMc^o*Z+es@(`iV&Md~dAck5?-0Lf#mJ+x1FPEZ=Nk3;Ot! z1%k{Jf(j1>3Bc82^hNOwtuDg&U(X#^pA4KC%g2{`<40?f=?y6;lcrK%{OC5|f3^YB z*CDQ&QyaAKfk(=6GAl;+)MQ0teJqbEt8%RbselgG-LW=+oVm; zq;cyc2OfB;t^`LutJ8-wUq77Lavbb9oE68RCCF{o-!ZHuNN9yXPSL39{T;Gdai&^= zad)Hzz>5f{T;|yu2#`7FddIz~IIXXOUXMUsBxq81c-GsmE$OfE=^S|bRwH3NIg0K| z#c~sA!g!1_!uKfLH=2Hf3gaT)p3UPY8XhAetcZOac*iKZ6&1!w{M?4*hnEQxe_$J+ z zgd^BU0Yc=pu!H;|+Kdnp|7B|_FG`=%oD5XEtJUjjc9 zMR%b_a1$xke;9UFgveNOODoMC7;;Nt*@p@2=j6yXS__F`LPbF#?$>&;-AK?Pqdkhe z(PESjaX*R^?I7z?5gI5MH*S<0MLdKHRShQ=ZXsIQ(F#^3nOrOAwu?Fh1wAKhfK|5)+rn_CzR(SO z!f?skP!}e9%W!-JrRmi~Q2EWw^=l&B27UsX2*Lr?gp3k;{fA!+*S-~0X%OH2&W-$% zUyRiI`TNSgO`ydubh&{rlOf=zBg{lq86NT)pTU8z|JNygn*G8>T$%kMi+9HPi?&HG zhDfc3m-;smwilSoAsnmWf%lpS$+IC|yHiJ@`Y#A^ZR8H?KQ!6@YizSauK|D1;~eK< zNt{Saim`cX^o6AN%2EYZ6^Cvd6@I?uk(dy_tkpy(A}RlOdD92aVrtPeH(r_O_2aW= z8i8efleG2F!Q*AV%0er5(B{ak;{m(=mtaX#>h=43A|-X~?TWb6)3p{sJ>Hwn-C^zs zVCn9V;OhP&O?53bik{iGt+n(1a!-Yxl4S~C(ATHs#;V={C2pV7AcISYwC+h)4MXCR zM9--Qr5U*%A$bdzbI8`VmG#ms^@kCMH!m%ieH@MaLb-x0x!iQC=gFzRJ@4bvL}&I9n5uJy4t`SY>Fl`G_=# zd@mYY>8d>eyY_O%S$0| z)*M0N5voXZ9S^><{qx_r!rlm{*a)YT2m`gZpuvkKxrq@@&mx@SBb;7D7zpl{OYD~` zw(mdm+A+-wHtDCY#f7cKajnI1jtTNrfJE+?=&0@lRi)K+b~J+FbPmeFtnnc{cQjpw zlM<{zIVMPXH|xerbeMJHC+bm4uT!N<7u;4!#z*iL(R5|1G(XX+6vTN>HG8fHix z!&3C@Y2YyEc?-; z{l%+ii%Pq58xDu8nD-awoGl9M%5C5bS^3RFP{EPwRE&Wq2n;DI%NBlc0um{PH90~6 zZNm@5Ad#?T2A>td-2ong8OmuiCQfk#t-sKxx8*QN102+)i=32sE20tvZx>Bhp+fnI zzO77kIBxX=8LVm?$%}0{PH^X?vUK4G=OK|C*cM*GOf)&DgBCi=X#8&n-?VcP3+(%W z*AQA`FsTfVU6ums;21QLAJ?+6%hEs{*eug1R=80$*6y|CZVPD>Xepa zb~j!`(~T4;bZH`}l_>|0JVGJN?sMW>o(_{uUPIZuICeB4l6!YbV2BhVIFDNQ%O&K9 zkwd`qC;>@wmDV6xna19#ulvcs7e9j1fv{{B12STOixVf)9-dmG@yw%$zyF|!wv5P{ zyu}XvE_Aaw*}~-1nnmP1>!scx`fwLR>xY2}mpHlGgOhSaf#M@g9B6Cggx4LV+?t)1 zz)$iN{3icx^bp)ca06gJ4RE1p;6g%UE7^@i3#1}Kckw_odJ2k;CLqnmd;`M0GPaXV z!@J)$dvUB7NpB}xge$#m=KUCSW+mtO-g@$$ZPLT=aDtMeI34BL{D`3R#)e9Z7n#S} zRlm2;yoh#9kgo3^mcvK_(Jz4L-x7c)k3lD&s<_@3uA^x+YB8Vhnisv)yP&yb^@A3F z_Y@@Pg9q_yC%)&BM%DGc(y*q5%wRs9h3%?Azg{)rR*6PNKP&f!lS z?T6s!pMw5B1pR*suAZ3^)b}wNQKOs2_?oDcYAY-jY?cZ}w&f0JWNx+BOat;$yXQjMnr2-bDPR&a3 z5g*M;2@-i{^LU7s$8I}gC3cCr+xtD65gH@@{-ttu(j%)Ydn%O?JS(O(P=}Rm9lLZ_ zcN(h4TL=8g^%m_?kG>yFp5cQcT>b*i4C5H^pF3!r*?1$_JA8$%OZ(+CT9(miQ;lUj zu}9U42Zw}5rjuNYBneNvq-6yKlr!Tps8FjP5*P^F{>m`HfSuI7z*C_G1z=YLRWImR04ADIK zhk=bEBS{P>{6Gj2DS-t=ljAtBpl4*TxN+q8ABI0y(2iu2;R))J3?3mwgm48($LZU( z<|y&wEt2uwNAQFw`fVzdn@DbB9)Y{}e;{`!V{uXBvR0a-93)Z-i+fHEYNhFu7{H^) z0Qi9bBvKz((LDA4v2`Y3P2+95mrZ0>5do2QMqE%7L=;5QGA@Xsf{KcYfQpJM2vxdM zH(*qtZitQ$R76}x7(m6^maS@4gs|u+0%|@bj(N)ct$-3)my_c)w(0TY`sX1<)gUnFuesU zgm`&s?RcRra%p8XAOc96r{A|;SDDPCcc2i@JZqr+Opk;tEcoH(^{!Ku9ovSW*aaz60O-VO`u^Ofk z&C667B*lr@9QTq>NL~4E?vU0JVOKWO^GhzE+G!fr0#>ChImRx(t{QQXVwouKsIBg3 zhh$Z!{<=sHpBWP_*~>`~>1XfZ)WvcJWML?_v^97zfDV&N?{f`=D{zo!cY=FA;|f8^LK zOxQUMsTaPXw|s4^dOS@>efEo?I7=U8GRB`hLS3Lzew9m3S_^D41)0Wz%$hb+!G@YP zYe9WY+l*US4>>kaKpaDjRHAK@#{RGw*%PS}CCk$Xn(P8@6O&g3_Mc1n;-9XQ^|q%M zztJ@=I8J=oNmf;}<>z&mGIWhr>N^!O{jkr_upMeUPWcOJYpmRj+8QZ0nj}2B?6;u$ zmMv_JW|=D8QL;7MG#)Np4JR7GgVMZl@Of#TDI8oKu!Fvma`^D>&{Tbbe|?ZalC-Sn zqxFY}sW-weE-acF8@j;a!^6TG;e8pD!@|VSW8S%a>pOW3mbraLbNi;}_U+2;19JOV zxqZea%0+I

aw}wAfTR4=oLecI*C}Ai^{>YBe+e=(F`I5>{pwy}-EIEBHq(AnhxHRp`20f` zS6lQd6hrN;Vt+{@TrQ#*2H~4N*sXG;QmF)6p{s<8ufOuQ&fBJWcjEEW$V2g&7sY%1 zzd+ezgYkheL#8=aGs8~sGP>4!=41n{-APx9URmYm&|;>7d6~O*HH4mwTerLFUSw~O zDsQShz?B_$Te)79ms(lgM9osw>%(H)c*kz*+Go6sIi-Al6~o%KzgY+I z>%N3LZGGJOPHtK4U8CW-;AsuytVVKcBO)~Zd9>N6Mv-3cSyZ= zsM>9?baij+v1;)$&2~GYi!|1ab@U9k-VzGPW>d{Z6ssj9Ip2}3zN1W0kuKdsL?O_5 zbA6wGJq_v|n!#vT2vhD4g5??N>3(pzH(b61raT`6FW&m7+EptDau&msxt*jO9~j&8 zhDrWPgTyxuLgHyk?aTsDNWSy&nByHJjLV;Ww!XDxo7=xvm*A34zYa=o0|DOmuW25NHi? ztFZ!f)CmZ*g~F<_t8>3;=N2MGGOaT$WfB;32Fa0Wvri!rGWze$SX&50bZ1$Ik2n#~ z!TBt}oCt};6Esd1L@)P|tj)u&u5#V9k*wvC&rNC@72BRI32DXxLLg-=#zaR`&LMU( zts7p3gLuOqCe!-R^wYtrHJhLqytX!jVno^-m(urEV>4;seH9SZOV6qm`-KoC z<5?_oqC_ONLkHbhqo%|_kCD)A!+DeCI;#==h03ZsN~K(9J`%d28M7`#ZlZt{7#B>_ z+k=KP2oDA9KtzNY)ATN&xCf7EOcAA)OmQ zJck1jEGIDbPiAO2OnLboytqT@FS>spS^pTz-7iF5dk-Z{$zS4 zoCH0#=OH1_k1N-(oE~F)I<%aBYQ`@ok8auF^hQ=|TsQspz_?>~{DZOBrX?Cb@z5Z^lO>0wq{ z*K*&u5W@Vbs-h@tpI42dJ_q>NV|FFIwS5NtMZMK5?jQ8aco*-uj&KN@{I1|=^gP#< z-2HFsE=T-Sa&0<8Kd--Jb@W-mROIuXK-C2HaF9lDp}YNH+hbE*;g!1nZ|BC6{PXug z5o-vsl)|p_xNZRMqm*@>xD`G#?n~~4&+D&_t>?$g^7oS(s2h((*uddWa-njh53TGQ zY#-mXT1zjj6>l%(?n~!R(X2`3F4j1i6FX(GXYMNZ?U&5Wstj+UP8$ggmdsbxua@L4 zBq1Io$7;&YfTNb?c^cVF^E`_r(TYzY&gd=+XzRd7%ClyQ4e+@ZJ4yphAc~9*iZB)p zPn8m^=%qiY4bE#07K(yRSc_|e?OBUO;`N#vg>wEctrf4Es6UT*u8_Qz^G(?~ca>!e zNhMnt(Pp^sMbG5^I6H}e(hf4O#!mlzqE=&Xe21sMv~3+K7ahx)&PwK$an5x>S6MSy zplSXb5i-{{zv$~2>s?XnuAj85TUN7TN^eEN0cBkuF5Rw@ox9y|eD84xn0`-n{11`n zXY{x`aP&-iJ^F_k!8Tk&+T5yk50(@(shw1$sci1bzZcdZNlP{xI<6wwv!NA|@+S3k z70Hneg{y?Ww5nGGOD;C5_o{@ZY_A|mU86dw*M%qxyEmb@AM^Z}Q-CRl7ykhmq_kC<(Cqr_okL^~h z-tYqU!@oJx$9{ZQ+3~(oy>tY=Sc!k=jLCK5M##Tb+NJte5w|ud#S5#5;?b1axRgNr z_bu*G``nN~ds70_wPQe!dfNx(v1340ls;zT2&YNL;fsDS1{Qirnt>`cL}@sX%)r(d zR`eRy6&jRN!02rZ#%o#cRvN4#IsO3mG;%%!x_S*P!Wa8(BTj#z zm&XxT%3_^Z*6G|y=;a6UfNiaQtxbMr?C>T(8@Bk4lBUX=cpo`Yh*;Aa&LQu}U{Ni$ zmdUu zB|4zqE1N1pTPxtE3L~~lQ-uZlRugshNW*4^9&f5~y7kYK$FBwBWuW5%VXAbqqx;sK z_r`y8_e}k3;=D@}!+yQJeDX|-nvRabe~kF?4qt^mz5Nw=RA*3EMD+>4Zq?6L*D-bU z$@ZqpXYtd5&)hz+aq!WBhz0z4!Rmp-9=h|%HdisXer@uVt4HI#{QWm4K95#q^cQ{+ z&V2XKch0)da@>9SciEZe-_o=A-45TPbq&w`S1wx}bMx(vx25dXF`qO%wncPy|ovzZ$7a;fF#I5byhiE~Px$i53 zz{=P100(x_9b6B|J6$-RM760~$G`Og|L zBS`Y(ePtWKt|(C2syfbB@*AmsBhixzkjL3z$!X+>O#5;o=mu*wPBK?M)e^TdptWoNP;w~wN9j}d#cezK$S66l158$1tq6&3_!bpmf`|R zP9s#AR=D*0Xk{~Ij*k8e{8Om-p`%a47!@6T+>9mQzC+AyX*G*=Pc>L77SBNk=dxJi zaRxx_hz=IkV(RymfwU3*ua$v!l+cfQMX_8W^k(RzdbM^x3I|Ratr$mv-oK$2<0#N0 ze0Lxh`SylRe!CP}vYy2te~|;h8Q9Sbti5_EWRr=t<8Nf*#L#T~@4S%%M4TGpM$n26 zogg2+d7NnRM*HAcE_WHeJCe&~;JXqz^Vc%v9k4R}j#4IPnvM|8R|elvHZ@1|@p@BU zrqko`19sxSeixh%;>3=zjXZQsz#<2O?hQn|h%#3Cju*N7NbE8c-7`m&y;a+5DqI=btUQI&8aJK%1@9MwQZ zWmIFukqnUOjwd-F(I{)vuLv1sc?0THBn53Jg7}BsFEqjwb8ubPk=M`H-Rw%b74VmT z@|Ce2$yMcDum5;yx-F;n+am6#?&PYAT@Jp~Y(Y~`{1xh$cpL7m;Rdxg~<+ksPsy)L{#$m*s{E4tw( zx<=`m3{B@vp>!?!aJkMqI4w3Sqk8(<&8iI%!}X}De$_u!!E}{tY9-IRL1^6F?vly# z8&63%`nKJL%kwj$luV=~%;Vz<*&`46%_|-noeZ{o{p1Wk;*{ma z*6T0%eCgloVrbjFE5k>Z?n~Klz?Y=X@7Pe;)lp7SSKbstYkf&;uk3nvzNCFuPWCA2>&k>+*aXm00Q0;~e8mjd50Q4T2V2 zj^65Ba^Ih1!Hl+q>V5!W38#=uR5151x(}fAX23^OthdrwUX%F3uiR|3)RMeSB%X%D z(ZoJ$c7>BJK2z0^R@v4>H6Kx|l0?b*0YQ*115}GJBO2N1NB4lYWSekS4id|>5j4FG z$bt4kf9l3Wv?|VDDTdlHz3U4J=XjNKLefwQWhtl1Kd(v>o?9i^)gVcTN0ffty05wg z+2_>V4{`KI_rApngBj!!D`itluB1SVZ$WvIg4g)|HNKydh&Ldb1I}EyuT?@of*jOVzBc)27-hxT-MEAL=KC}+W_#M)3%ZFqumB3~H>(3scqsz*%*lks7nok>x|!4oDx z$AmBk>BAYo)-y%7tl7$i!$O~CwWmtx!d5PqFq?1`^hxer!{OBiwTN?4Q!)vSvDY7| z;T+SHm>5pVstBW>(+%Ty^al=eHi_1crsw*dLEfP4#$aSE#e){_iuVX0e;SGE!%)Pd zgSVT+D<=`{L}E9z$&~zCZLp8#V7$ET&o32G_Y#<@fm4;PO%?Vd$*U!va~UZg0tf@n!*So$+T-}DVAV<8WJbvIRfg2`=HK=6leuOHP~ZxbQ(})3ni=qa3hI`3(H4U zqp3AwY&Fqq73-czd=VX-%u=Otb7Y+kDu?Wb{?9ur)Mrp9*M| z)6;6iUaN^?Gsq(%@i>js1mam~>_V2cx5{;Yf55V4s`W@#kR(waK)|gV<*O;AFmDEE z3AIS+jB0E>4K#zwWprBrN=4`>Km;A}!&zm5jy2d`TC@ptL`HW7O1Lz592AfV;t{J# zKh5^Ns?x=O#X7U*r{m6g>16V@8u8(klFT=iw`Q>Y3Y1e-9TzIw8mR#ziZxAGd;vm2 z1&*NF3?QCD&Z4Xdpq&VtL?c^5VyTwqJ2?7JhV6$>Cy#H5a7r6=S+iozFi115i88r7 z&2(<|T%&0hBF(5J;~efSIQcI*w4%eN0(7nXKwm})n=R3|)PHCY_~+J>cMSVkocU=@ zId}Q+<-Nqdy~`Ia{i1aUB+g*oWZ(Nsuv$@4p-z7f?^fdx@lK|NW#RpvS39Z|Nv$>m z#nsU7*RU;2@~-5A)Mbi&ZwY&dZk>T)mBd-8hE55$h9cg}y~=^?sNhX$Rms)! zd9$c~UnO2?*v9C%yFk@25UEHg%b^?xJ&;=i^veDP$&PQ~!_+(d$C4f2!SU46e%I0w z_5IYBuxjDUicNBc&x+4&OHT-I-s!8ij7nG!OFsNGVn`Gek@#7|(KLlAFF)2xbv^G0 zHM<|6j{&+HGvmyLkCyeX;1|91EMq?E-^(w07r$41qIJUn_%r{N;%3>cR+7i@d~xd+ z${)yH$f_MVL2hu|?ez*5#x5oj3>T`@pJ-KwNq%-G!N_wBl)6T`!W7Dr@vH#qcbZ~6 z#CIntAF0|SWxVX>;3HhFFWNMf{Iw>SsgaK(x;h9uvW0~pOpp(phZm`?7gQJvvn?3# zhF&_A2AhD)AX@PmydG$G1a&nO4h^>dQ4d5L%8@HSeZ}CDwCF6%A&HZ}@T<0Rm}SwB z^In^R22Rwc*BFj#h(-oCl0LY`P!nQEcOMJeN_(`8F|BKGu@jh9-J(agn1rpA^^OZt z9^9{V3R7-ZWv#?pm(X97r{yH~dbBLAC(H(va{OK>m2BNQ60~tl2=m85AeN z{83i?6$Ux1SIeSRjsr{1A&;fn!?embo!XtW$_>5Rm1(1Cm3E*q9Wj?` zm(x-vfW$N;_{vADAOzypV4diwF;In%+0-Xk5p^~gcaJEOByJ@C4w#g6wuDI z{Yiel%b=TY=nab+D5n!at4wScUWf0sAK;x&1lyeQkmsur-ql*l2RZB9?62wGc#LHt zIVl6XjMvpbC#%bYacka>>5KZtw&}tJjct>KPa4~HMz87PMY-ahMw<)5JDUgwyzguI zZ&5cL*N=XDG+g~ix!L>=vhDz=Pa~CRJJiVw1njmjinlR}H{k;{>0Hj=A+~rmcl=|p zQ~Kc9$ss1~e?9&9z+-`}g+uNY(-o8dTGM|1=e3ti(|=TSe10E}n|BDASN+PN6DhZP z@gcrNm`i1Oe-zl>3tMyoUu<{iVrvmq-nY(`Di| z(wgKm9cTB?No$jM4FyvLR3JHw7tj>_Efs@@dk^Ou)7fHruySUYa-S-6Ic}nduEcxB zhD!-k3?(q33Hm+?S}?%;JvjGM|CsOL_aLg^O2LKKkQv>5)Gi-(?9Zry?i6eE(weLh>v2HlnLM z|2*WeRbeKh z0}y7*pR7n&!Z^~%pCEj;i4nh%5q}POjS6N~;|l;jU2}jIe;VmV1;$`RE%wOidpo}N zjmPCX?Qt5}7{uGw%LFL6274C*6}gl0AEG}jl_%o=$5Ocf7i0^?GzK?FnJ6a_gmZ4I zSE;}$g-Ccd7fHTWvTG6G_p3P7*Tj7lfa>+ha<8Lg54 zCZM#+NuUycIkH!4l*(O~P4>hzFQ$`=PjNkDo%1v=rjd&`so;D4!qyh16(b=?c}y;J z6;f}j8{A2f0u{>(keEYib6U#8|25Li!%=+I}d%=IEX}rH_gS)Gsz#0rfr)y{RqV4!R zOB6o3l5H{EUcVF)W;RgpW?Ahw5NCKT_6i|ZF<7JHiB%#o5gnYv8Z{$wJOHtCR07q$ zo&PLRNXqEzc=H0LbuyUKKDVtS$2^H^S}Qna4uqXU)}ny_YEsyyf2%KF0N2>2(?T&?Xgb0wMCc(14_JW43gqh!!k`mnqjIY#@65g=p$+k;|mR$A%@5) z;J0jW8URj{9r6YioGvOvpIU>zO%Xo6CVT?IzN+HY%4w?NAmuVuF}K+;`_R90G@t*q zave=ynGF+mdjH`vYkqb7ic4v)H@$2dXT5Nv5pLfqR=>nk85PAy1Gz!F3`kbv9oi#)U_6!cY81iqq%&`LDYU z6~~?J`aM-qQx^G+FoU11xKkF{N0`meRLIKOz7c-r=P53iwH=8aDlkb7?hpNvcXCc( zl~n_OFIA+-(vgmXqwcf9mUO%`lzd|(Ts!fpn!ce!*!?aY+sWWOZ7+Gk%;;bCvgo~M z5%ahHp_ll=bDNpge?jwGwu*H>_wy&=nq;H)xexdt@O{u{Nu%y!cgo7qcAR#|EWIVK zDruBZ52z%{tEZ#ZD6{aJTqibEm9Ed7qtY*Rwnc)zvjn-0pGnJ;EjsM?=X@m1y*w5W zqIg%ft`FQR&)eUh=PJ)T3-jc8>9AHFbqY@XdTY{a1EJh_U|rHdE+&`)=G0(APLPL; z?f{ge;pnSiDv0}!3>ti?4y;=>2>SI%d3FuDZ(|$I(~w);f;kP$UhPzk#L}RXaso$* zrwnI}4CzwCtO7$$re3m;_Vs}3DM@_lHbvx{ksIn)jT!pc{!adZUtfvqPfR?i4CuHIPAjR+n{q- z2)L8+U9W(nU1`Ghqbz?Q#_B)b@DCMqmq^aL-$Zde%k{`07h7vySd!<7 zf*mvuEQt{!@sc$7R))~eoRP3x`9vy%XotArd=b`dR!Lgq zRgRm;$EPV8>~MNhmNG zoa0Oi^JRd0(7~ro!G=>@Bh-5$89dEhj(R(h)0`N=&dgwQhWIvhK0|zm3NYr}rtZA} z7CDi^QjtR_Kzj54>rL-HL{e8n7o~J>0N0qGp#od*v-uDG#&z|N_Ee3xq~0Ujr=g|R z20NuCocd|)1gf9K#Ocej4_WNA`gq*#Up?;H z-?baRZwlU@&NX{U9rD&arT9_;_4jW2`y^EM*Ru~mY`8x6)!x(?hmKF7Nsstn`5v#M zeEurkZvG)41pKRb^9{$hBRAvOaqr4^DQ3`1>*!Zgd?IqEh*DpWn;xr2U|#(lNRX2TVp;k%Hsbopoy6y`PKfzP836 z8{gC2%^s=i<9_gXJK`VDo=$PYc=0!8(ZRY_oMp*%qc0brgjqu?ay-^X-;+k&>56ie zMw!8%q){gDGij7L{C&u(Wp9(ZG~pCGd{V!bb}Vp57496*pkJ)pFe@QjU7?uvQ~5x= z@5Uk99P_ns@6hgd{9S|@^oqKbvy_SS8(l(AyBq=3J;~cZpMD;&q%R)2al??C^_n$( zh}LDXJ#Z5CDk6LPQ%H9arO)eW**6w5co4FCp`H0*PTlBFqk*P|IwvJ(N9UMVoWO8s z_E*D+&N0Y$nSqkgV3>FR`1Opi^lb7h(+fj$U(@nKoRr~fJK6L03&I}0(QVmTb8F8D zLAQzEru4};cqz?>wt!ZSkGODN<0CGkCHn-1>`ZlF1e~vrSOOakztP2X&nF-~%vKS#zTe&veY+lQ>+Fp1>U={k)eG_DT<)8+&qbtX`!56Mu;HzSVl)`8{JB zSo&La&~HnxZ@UtC8`*gm*?9-qY0fClyj5|%{m*XSEBqJj+ma*(6_L-o`Fn5NT|Nrz zceGvj?t6&a{*uMEs`u~Y+2M^IMRy}YSC-^vMZb$s?GB%%bT)#0YM4`L(0HZ4^w@Z~ z#}ZBsfrpJ?Tj{_AI8?e|96px@K9&wV>Kd3T9k7K7(g6!NS~_3@lY{9Exh4HIR*h#J z@0#m^RnlKn(w|h)-74usm2{&@x=T&)gp#>Zfo&NQzGH2O)GaCS9w0j>9&of6#!{bi`PVM?OQW_bbLQf)ba+l!RKX(EqPd_yWdsX;2Ol^VjIG_{z)6t zI1%2wV5j>(2Vw3mmFl z%u6OkKQXih{SmCqj};mmo~Wy?2m;5TXRu)&exOeb!{Z%F&dI*9l08Dh68zok3!)7x z4UQ$pPU2tiks9%KB_&FeYo6a%gNzvEyHw*vF|^?o@-Ir$@^1(2W)^Zb?()lxxy_T8 zpJkpqH}loy7gpyiKOVH2a(Ig6f*;-U-+%ai^qcJaSfo_Qd2vf?6XVO2y}KN?-hIm9 z*!I!7_@Hjs6E#V+Fto3ZaVixm{4&i>gO{zB@OnX3hUcO<4^0+GN7v&mN))n}R;d}C> zsIEg{@Cw~QLB)0j_nBJ!mJmlR>mM9arW@R|%g+yc?Jt|t8s*6>>u@M5`Vuvl`KV)S zSy5}$0_Mw(C1rSD?U5;qa7`v9nUBKbC;dGbi|d@cWN}?Xd4Q3`XHx?iJTrnmuqK@X7wg-9wYz?I%qL?r#uN!NC2*U+L1 zRf3(p+L@``sfFCv1fqGZcsZK5kTu7_ZG(navnZ z==sfMt_=~X7W2?V@UD9DekHDD)-^Ky8703c@f*Ec3L}E$+GT}E zpG-TRR_R@h)uSvcKw=41)L;WB%N&qcKveu+h?8c@(?1CFf82so$Q%-wkK=aPV9X{) zO1P|(T*%dt$b?f|b6Mxl8k!TCaGD$JAPnw# zLnR{2#R!y~K`LZgS3G11l$=G>GOYyKeRMl4Z}q-JZOT6_tJ5A2*utr zB<0~;gpD`uF$EZ~M#j6?q?I2&!#?5D5KQf4y>doGPDnv|BAGFdK@A^PD0(|ggv`5C zFO?z_W;eD4GoFFEV|PezDI7fI;uLb)2*i8liFiQ&$6u7?9at)00U|C0uILQXRCzDs#h!1Ll>N8=zF6!4aEM~r>j z_y;nB=9z|A(u&U^^JvAxwBk}^ZP}4M{Gdb3(&pjG<;OyM=H-3Bmfp0RV;9c0$vJs^YsAF#1ow>>OzGxxPe%NQc=0`!m~+nf z=QU?${`>-$0arTA`+F(lCzO2{TSN&)i&??Jk{6p3=6hoBRyvA$93=K&3t_E_upsgCtDm+WdAPanJ`TVrehXf!xI=&11>#J-qR@XsQbK+272QFC2d`w&o0zdnIybvt z2oL=A`sEMoR)?+#eKWRlBe!ba+xLw}Zk?O84vT+xvXuM%X=U)Y?@J^eybC?LnGv5@ zRXC$hytK=;swnMG;x&Af#BOc;1Fglo%*9nsbz}WjZl9Z&4bYcAd9tP8d zxmm*8)56@|*18>=6AI~x^S|c&xm-nFaK3f;P$A>8QFuX6Q{xQ2oQ4p&Q|wF!}xu1rZCm@N0l!hsoI=3hV$(zVbssNd_iA z(g}>zprg@C$W@;KNO=;d@kz&(Vq47$pyr>W#da25Vd7F`u=1i9ryoM~*m71>~ufAM7_5*{U| zcsq`;e!Do#dtt@S^1lT&XgHeQ5sv1aW{}&&<&aWdr7o2PpRpQq@4}17#5=^)D0%QC zlLU*n&IP@9>FZAWO%fE=M2;8iuZaw$KOyHpXG!l7OHUQ=t`)oZUVd1<2fq>V*(Jwr zdaAVZ@q<0LVw1(GEB&?_ zeRS%WaGEai*(vpBHA(o}MMX~Qa+O;3&GRMq&*OWD!Z)dG)ofMMt)}3F0-Ga;d8|JQJOLmO6o^d{<-;W$KHn4U^EoCAEf4C};5~(ZtXq zWM8$9p`FkPBw2b)QwCcr_`sNAsp9A|d4ZGJ>Gl0AuB zk_H`-VmmbgTXIP{&X{4VHG*EwH|#(GPMKlbGy*%aG9B-}vE^JSU5afgfW#SOqMxR; zUM^1N5(A{-P)(^-N`D%WDHTVXDEGK2C-Dq{|8(Y`PG0)Bf4X>3*r`~mkS^VwPrP7} zeEXc)cK5qaPdJ}&J7eUud-v(xR`Zgneh<%`z}xc*sDVudD}1VuG^M^%@gbqd2O3LO zv#Gk@>NC4Y%>!FMM9&?bHYsye$Xmi8>Xu>mfQ9s7&Fbo{}u%OV*Fx$5dlNB$gz zG8OycHe6A1x+-D=FX8&Yqg3o`neMBH4RW$u-#V;klp$ZDVum;K>)uBnp!&Dg4S0Gn zQ#%~c-yFJGg`|X^nBj{@DUFTMnP|Y0>pH(S-7Tp){sQ7FiuVkZ{A^I>zU4^f^!xbw zk@jrF#L&v&b0A`e`kRh})#5P`ZqVYw;}^SZ;hSVr{SB z-A)84c-`P#fK9(4D8D+GxT?4FfmrOVS!zq1BX#rri@X{4>K@7K7r%s8%oh07y?~E) zGOS!aN16)#J1%5jtM>r%*3gv~-(a{)ZcrqUWL*~X|`-K$-e%3TyfL};vBD;W+DKP8%X*h9w#fX>AphJ`dk&Fc);x2;fYBh&7m)@WVQ; zz+)rkk_@;5eZN^8Ng#@3oyRmZb26ODRZBbBLCT`{Fa!wm3)EJsl=E;&qizYKYHcH? z4uJxzF)lh9{wosmUncX95Hm=RmZj8=y}aQGvKzJu`qZvyqM2wfit?x8n9;iy+ zb;kOzj-KW|K}&7O&qZR}RD}H=9>ZNDIq6q;rJR%jyU9tv-A3#~pi)0BGt?p%*`hTx zQ+7&$BJ&2yYAN7oor`>^rh86V3hg+J<+`3@>K*@9Bym{gTEvvJ!BpeIpFNq0)CsRH z&3qAg$NOo}*#L*ztN+slcSIGzSKsYXwA@r~ZqSPk^xUE&J)XLK*Cj{iPrbMxr)bab zdK@ST>9FbAk&68ti};s*S?=etSKZDf{8GSP75!**?~H~yy|8XQLsX)UgPs^`AL&n;BXgAxK%cpQbfDtT4HoPiDJgE(0}CIe9wjnNlAH#F-y zx>9Z`6lHZMam)(39tVQouas+FGV7vm2gD>lQIN|VzbQPJmlejX7f(9AkG{)aGu(W` zV0dB8jAVHFGVlqJ6cjN1(SIzY5eO(?49=NG3R}b|UZ{~LsJwrY#{R^*RvYZhx+W6; zq;WbbcRkea>L7Q`guUgi7vV&?D;KuFDTXFFeGw3L8p)dhMAT9ofCv#jWb%)`?Fz=t ze2Cm!4V6prY>4Oy|2gAmIF#6z0aBMR;N58H#U^q8DXu^2?MUva5wkSg#}S{U!TaC9 z-KSv(dDMA$t2`I2bwG~K*556GHmJVJ{~a)yKHe@} zB$_n7O6naA1oyCl}1D@=DuEbG+H3nU3oM}MsmXRjtkn6Y-*5Izsm;!+oP*@Gtf{w1g z!btg3uJxy-5dN1350K(rwH_z@d z;V(*^d~BSMcvtPFO38r3CaXqyO_<}~wzh*z>q65{1*^^?N}1N2rk@0I&LH{tD&#eI zu%ha{mXVv#h)JYc9EfV5Lz%hi_Ahj3!>*^uK%P3c_b6DNTTf~Klz%LfiwDr@tu-1e zvObN=krvp#IzY6+le8Ke+dj53sK=Xxa~ssYluEx(T6nSQeu3Xg<`b~IqLI+;FQ!Ah z24+Kxx+o42AUzGtc$omXj_g*qfh^z9LJN@_$d$JMo_G3 zmoAX}&yAKoe5M}XvK2@D%q;fGPjY{?;s3h%=qcgtxidd*X}oj^ytHENina3QfL|Tv zfAJWG9i~j_7v_}4D!co;VjFxKNX}Jb>GdD-=*V#@HnYo*>gzeh^4aqUALgucEARN; zc~i2K`RrK)h1vb(v1>zH-PrkIz3oz^JF<3IP~N|f&woqUOO0rqn@qimOJ&=K8;^JD zf+}Oy;h@ZLF}!$x!pkB*lmEEw!3ER|)f+=mMRx!EFlMOzfC>8bD39~IkaHVHR?Ocu zTvbZuCUJAS+sb#fnk6IeJfAXi`)Ba6{f=!>KjA>$iq=A${qrp6Z=dECGwVy?m;GP5 z%iKzcT+FgRq<>y}Oy&a~+;Cy~V^n&AH*<%r$KaXFl*i&|7K(T<| zfUjIdUpgX&xA1i`lCDm>7>5;y+mEA?nhDIzSJ2`RMSh$zOa$d+eLk=|?tPWlX3c{w zBM*i&57M|6sP`oD>>BYt&4W#<(1_tbnGBc402854Q-GDQyeVK#2;_(}1?h+xDp*+k z1O7CI*2(D3fLA)=fC?sq5d#OHj+HfFgrAH@Kx~o>za9Srdp0Z>k337NwAFi^F?h)S ziGlTFjK-K4D&~zz?yERCwJonh!g6Rplx0{>O-ncWlmPlxw>VsYk7Nr!(-|ef|IN5f zE;O`d>-}mBt|%w&lz}fZ5HwYedgWPzPG&IDa3<=B7n%^Q=slu!Lr2|#gwsfz48O|Z zZ-Y267PFO+f^&7pQn})5WP(~lGbV%QxJA;=LmJw6vabgtKVrC2+S`!@yUN*l z`&E^b3z5&+|E>{F#z9IPltV`eK$RUttj1F#M{zHEdI5xmUBfpLgh2ql$qZKiH6g|| z#7G18ozUNM&NE!UKiF@ejco4i_23qj$a-C9BU8cT+7>E4Kv8Qbc@IkfVO4?JPNhE& zS2gPV7>4uB97+LJm7b`NbV33{^_*T#Sm$WPq6S0s8!gwbfpY}^&bxsViSK+$wLn6` z3FwDXr#P64C~$N|yc8m3V1g2hVL?6~0E=s-yLx#QwUnaS`Zs4-CwyzjFL43xaU%Jp zGvanM*Df}fD|8U*JeYQGw+|vXcLhhWY zS?Wvv| z6l}zrGLKQ0E$k!-9pq0|B{(o1Hw738?F&@9@P`$25(Q>e|1;Y59k0kCA1Qq{fX|h; z@>|Q5*l_M_z?=<(N6zFyJ~jCjh{#~9iLo#|mU5PimJDiQtPFkl>FGX}u!Xksf$Hho z&i_JXu8UeMgOsW7;giGqf3d$W|FSVwWgcaJ%omzdGQBs|8qZ%AYiIrOpdzp zv$w3kZ(GXehrgd{eKbEn*PmO`z{Eov^Y_QWHzm0wH7o(uDGl_v@V&i(7D*15JkocK zZH_Hn@tba)=kN4WT{C_&5Al3Nzl0B4m>1oziXreO55l}9exD@!Gv@U6rM>MN+6(0G z^6x(E8L>m~{AL4j9#(gVFq-GJUcMmKGH$#2UN&Zr)x z4u1WOS(k0qss1*4eo<9c&)O?}hrwCAb3LtB)*S}jc-MM(SJris>f{>0xul3rKde$q zQ+VGx6As_TBHoUsY4|R(XPK98$(5hKjfG~7sVR3WW3T%BAHv=Roaz7n|98kKLMY_0 zkSL*2Mz%TSoX|-n6h#Mza@^6esK^SX!jMEKk|d|ip&W7;l0(?$kj-hEHfF~5e|h)* zem>v-?{{7Q|E|5R=U%(6UE6hSd%T{H$K!s#J-BJQ{t!ZUo;K^`e%$z^^vY8}EJg7@ zg6@pNK1;&09$=I=tr{IA+tF%OFj@JG6KwA%c0_{*IL}7bb-0h>KRWhg>K10*RvfsI z6#yrR5WR>V#F5kuovADwCJ7WDxcea>DL7vNM>ve+chk6^8e5MSV!eeywd4MB==nQX z46_^rlT}&OJiH9uPD80<-0~St?DfqUf;~C(BaMqHq=G112RIDaBj~~Ts<_yAs_!^g z1|kqA5}H{cY6;cy!G@(BfZCy{P%5BM5d*H`lP{op=8V76l^|S7ExWv85h$8DblUOS z#_O;--8?fQ0#u#Dc|@th9m6 znXL;f2I$d%iG!<6h5F9dQC)I4=+`WqaX2abIj}?z&sD?s{bFr1ny;2?;mxiYczFG!N+XD@dEOQ{Z{@#jh&{bhCNB6n zP7q%kye&A-^tH%d_ZqB9yMqzn9_pd-;>2 z;_(Z;Ridj=N6E)&BdVBMl~q{4JP)1^B*P<$7*s)MC>x`I$veo#vMuczK|J|7(xnfU6an?CE?doF#s7s)`}cYvyj9{6f%lwymQ<0 zut};!#<&^5vXu+fo>NrzuZvoe&jc1n(9xZ zz6?6&VSVEQ?j!g+RryQcyPV*#z{$&@QK-6k!w|QJ^*cmZw zFI}&eCwh4>9F;%6ud3rpV6C^7MeBm|aCM01c=VYL1kM7qtG4r~03;JdlwWhT{f)oH zNgiitrg735H1}ABUcXL^YH_&V%XK{53+qeec#z?snHJvFi*;C;NzCQFNY>+ev3QaV zdwW5ZO1&=4&@R+=<|p!VTSQ%_AY$QkAdFf8p?M=~0m13g#B~byBAlL= zkCOoQDI!GCafA{C3o!4;xgX-FfG_G}9}5s&KidpS%!G+cpk?B*1*RCwnY3>lJ$}w$^7%upz*{We3D9nX0-K7ufh81cWAVE!a?g_e#xjRf?$o z<6JW!uK$mm`=6bUND&nP*c+c*d0NK4g>Gn-V&2k5=WGJ$HMfeanA!EBo_yrYTQO|d zxI|#*gVIDQ7jV|hpuR8JfL+#CgqURy$E)MY;;07W+`Vx8j{k8^Z(2gv_p!Dx(K-;a z7%{q;1!bZ`8(0|T+Lt~SP%R?vMUTE@-wJPNHDum0K#z)ps+wChn74{waAK}7MB_;k zy*zm&$ey7?!zk5bzs+!+04NNFdkr45yNMOfT!Z{OH^GJZuW@>J33V_N=bKCgQ@FNp zz9h~viRvbTvjkinnK;5}B;RR#(zOU%B?2QQVWTON-Yal97%3Smr&OP}2W2V8j)^B3 z_wu$O3HA&>w$Z&GtZ1Ov_s;+Y|J&5Oal{^oK!iwWVudo-EFb{ewL_tw6;|{&wE#D; z?BM{~1uO;$O`;;tP|d&1Lckv?11%=~ANRG+#{IRO^KWAb6n_o$JK%TqVt#A~Z7hkj zKpTrEJzc7I8sO~i;JjVRxgLr8@s4wWj06xyTz1Z-dg`$`Xdpmw89@@w2TiizrEtG8Dl4{Kdt zDgo~VYlFvE1NtrS_QU@5IR+p1sp)!-s2dEjD;;wBZv;Vo{v6D1b@B;e!P^aja67BN zP2XFI-tAQXb3k!d)o_kJcV~9SE>K9g<>-inxqT_3%O~SO-X4e9vJs?F3>`9R0W$aP zCMeFn1G*OnyNlbnjwsl+CG&LfkiX&VLKx=M)o{|G*A64dnyG81fsSbo#)>^1N7)D4 zdpj6DC?&?l%j&7KMu%s2XE`wTk z?@xBZyn2s)26->d2_S~?J5{dA;Zgse;P+?4;=6RyrGt$g*ELKZYzH1> z)k%hj9+)Pj?*T(D=M;Qhgk?@(^qYC^X`BKPhOI6sdG9x#*W0Q0;mm==D&e{Z zlwgri6L{8MxaVGkC%`;RjNSqtOsLYRn`=PjCvYz6GLRAsac0OSh8AUP6Unv_^^_Tv zBmL{7LqvIT!gBAUAqR&`pxjg-RxbCx9&#u)U+$e5a!}Ui^xpZ7iFh`_)p(DNX*I)< z%i%GAnL`6hjTXU?@4;jA_P~kme{eGtsB~RmB1fHxlP0kmP%&}x>& zFYGACmNvj@6nM0~^M!AL6Cgp{&ZE`rXB4KzNN~{@uz;*OwY=pf&;AQWc@(b}LKdxJ zM1H}5Mq@6_EGs%!mbkm@bCQCT;7oL=M=|WNm>TyR?<6*j30;37_?qk-4Q;c)>#yK zAPe7oVO2AHM&g_Lx@$YHHjyL8}m2=U<01{3CFj!+1dE%-}u&A`04I z5~X9QnfL#-a1Bf=m-*|EMw0v^!FWyadX2{I@GK2spHVyVh^ zix-?6kKMI~-CQ9kB}5;M9*=!U{Xte5n zyKr>eL2Rw$Ht007a7Rpk1NOWa05pz%ofr*}LldLL;9d&gzApjykv29fpLtcHfx88C&Sl zrv|(oa5XE(me_oeYF|)Zt+3CCeC;DX`r7%Hb9@@WTS&-tV5FtjB5vUT2+C_bpN$X( zjLCH6uLvzDNQZhS68qTuD93ErE)wh3v7%PQkouT1hr3G44Vll~O3S@RI!DWWKr*N0 zrjQW7vK77wG}I)1DF^iVXqE-P;3&7RZ>~}9C@n$V!^d8qf*L3O#}>C2m>&l;@e#r4 zNS{FV25_x`bsSC-Bi4>1+yHkkJmwdTt6E4^-U2h-feG5YG9&}?qWBx2gA#!uF6GTV zwZx%X%N~?ay+kicvOc*NwW;1sm&QF;NTpJ^2zZQE%U@)|hFO)lwi!a$Oe||;%{k3- zw-o+`x$xz2mI+ksI5#71gFUBKNDX~}i#@mkAE8a=#$lt!C!s5F5DXTFon+o>>Ou7l z@y_LQl#rGV3}xE7LcMPRXKoWTHjup`oD(8iw){6c2gCUQZa$7`InFKHwX{~%%d%vu zn==5qDzw;)VU7jdCN*#(H-~efa~Pr=ZA!dmG&wI=X`2XweXN0lhJmzv3;{9+mLGqU z^pT!y@{rfg9xwU&J3ZO=Nli4v1k#INHsmXYP_xr=S!~>7*Gi6Yd}G2 zuu-riEC4qMg6##5H&S$XO&@LMO`6&SRWHb!L4qf zp?{t^s)EaIV68LPtQuH}%+VHF_50p%y+rIUdr+hZY_`b(x>6zs+CnMRLLWNFhFzWy z-a!jaB2CkR<4I3w!FNalQpk`%_TL6}tIB`d*UV839I7GQ4IX3W1hw>I|7}*p!Zn39 z_WAA&tc!3>e>P-*hDdL802N{#L}8kV*w*n$sTGfxbZEt9`Svk82Fo*j~q4ynTmzpk@O8x7Ib6|+GLyj_D zZGr+`Q<6AwWE|m;O7&*eso^*qe~=Bn;5b(Z0y=hrn4J1w0>Wj1^#Am8HykF584qvE zH)m`f4vt4&6YY1K?ZDBZ;^&?2ldgRy&BT*b|97M@s6XeiMlQ$XV;Z%7 z%~2{frua6|gwlDtkim@lvm`PY+WiRgiI%Ll7!+kEIzp2G&C^xdeUk+CafVYSKg zKSMZ~^(_lNj|8yg7JA~Ca;@(ap?LikObE4edFLo7l{Jw!LBtCKGNZ82_jA{8vsykT zSLYEpKe2lK~-h~3%^|An_fLN3Yc*%PaM*hy-vaPM+Mc4p$G<&|^PC}J;Fosna!vG&uMUlZhI|W9fjZ;Al+=oGZqBZy3l1~YMv%coz@5fD_)nrK2``l+ zc4gwS4WLyXD`uWElXY=e*7&5z$`^Tp>D_Z?t zYocN1|KL?7s|_JliPUB0s4xz2A>N>D@C=NcpwXw0f8{80|DvEQDF{Hldm5?vijA&q za!@Y9mI{N$D1{bib{rPR?3IQg4UiIhQ4(TEpaX$qlj2Bfy(mRw@-7+|P>=%*vNLeJ zVGB!xiPrmXB5eGRxf$p+N@U^yU?)(u-SdwMWSlz_2T)qL+lr{3Ktt!m3jFNMdC17_OIG1tT)1l37yFg!*AN4`Vl zP`DU4UkGP;n~DX<3az_I3wm_4WOwp+?q3c9z-RfZOlbft%|Nqa1G5U~+lh~1c*&I& z1sFa7TQ)wawz9GvhCj*XznEVKOrvVZSO*4(wyszoTM!+QfNR|Y#U@jwn2-Z4EHZOV z4&s(X-NS@z+mNtCz;TaW;sW;yV*ip_q#(w3s6d#4P!K@2dgI+SwQpFza}b2xTBOjUMQ*2cW}&m zaBFxJv9|ea0&O&Ruy#ryNW%~idHIYXN&w#98kTf>MP)Onnc{DTzTCJ$@V!Q} z_%#%L%#mD9vyjEGdaHym(!J5>99;B4ByJNCuuM3|ZP+RS*~!1qA3Np+8KN#A8S8ZX zKRJV~7YkQu$eG>tzSvZ}ubK z$Sj@`bNji0WT|AHl5kr}!q@KLb<54v3SpFAFtpj;sd$&3=xaHAPnGqu+k(?f!jb3QL*xMzEkH5|0Vz!Yg+2g|$30s}&5(h8R>90~ zoA3`^8Ipi4-}$SkS~g)rzYcMF9{!(Lyjw^Z(7S=dVZt~!87BH5Bu|7`42&dZqK`oG zgo(f<|C|&Omj@6wiBjf7;uhdY6tKnxn^y=5{IUeWTibv7*E`n90qoeS#vfw#ZpumU z8cCc{Qn3qV<^;S(24@6j*AEPFY98VT3xNhUN@taH8xOFL3~#Lx#%KVUl%U85c9_-wwl>urc3;I6oia%L*8CG@ke>{vJNGfH86l8AGJ~8>wWN ze_bMfnNsGESYe`X6U!4QV%`Au%oMKIKS(kF(L&)8<%zM4;a=qkl1~uM!uiKLT^QbE zbp`hIzm#SG(!yMP+sGof;03qY5AH4p>;9^$yh>g;%KN-^A$!Ww_boNbk5!jgLS24= zvsmE)wJ#51t{pUb>r&3XS#!Jo@HZvYLmtGL^rtwJuhZ3UOQ<0)aKO_b4Ys)z^i zPWn?qRcp!uXL*xU6wD(bHq=dF$?{x(YR`r4aKsOP(9uhoVm+($mwoqgTb6P;Gh7=4KUP4kM!Kc;!z!T+RrP4dpK z4}yV@6Ps8fu+I{R{jlbY5{i78>gE$bkLaQ!>J9YPmv@;%}#FD3)AR?pgZEQ_P^*-`ji7u3LDbr2#Ip+y$n2!dvo5MJdFU*GXav96jiBkt) z(V36|>Tz~x)Dy0mB}1>ek2*#>X4}5LZW4ztjt|3s&jTGLb1tsV%YV21%?R9SdP8B2 z19i&eWL8x3gLIyQpKxBbQKP%FzjGn6c-5}#4hWg(&ipV9VLg&dRb%i+{yR)qZO8N_hB*;n0b>Q?$S?AL@;dfG>oXlt1Lig$TC0o zCjw!K!bvSbq-PPP{VeqoYPCC&m5-y^LXEBbkUo;xR6BQKN&#-r3P2SheI%CZG{u=uQy14}V*d6pXA9hARn>3DFxy39D>d$f~p#(C(qpGec3WQ z8C8O{$cNEyuYQr9odl@m5)Uw-`!wGECCu$rm@@`ch{v8J>%A=d$@*~%0D;Dc&vMU| zP^nYv^IWkKs&WB_B8blCTi#g}$jl1DO9aO9bb(8WAnzheU=qX^SOFi-jnOnc1HFwxf@Wt#ON!+R zaIggAs>J)QEhGy1H zZy^b;Gcnn{>!!uLU~A6E$210bmQ!@b2u)bt+{C$hqnP*c!4C`~?gvJynAc}MmL*Zc z#2_95PkpLb=veOlY;4g^tliBk4$cwyU*ZKCE8}CAqiSM*nU7iW%z)zvaBMtQTh$Dj zM>!rP+rDO8>gU{?MQvJwrmt%10>K7*010~niQY-nu!ThLCbmAJPPVh8rnpD{pcN2w z8(b~$9bX16TkWhpQ``%G(3%KX9wa)2IhqTQZ2)F78`4jiJXMJO0rZNF!@75Z0@JY- zZLPyolj^o)%@#aVXLb1nzW#M6Xci^BwBUl_{p@2|6;iFI5c?6D3KIwwgywOa!$Ycc zJInD8+gQceIn=Qz%!EnEv>q)q%bRlTbzd=CN#yd9uJz2E5Ys@LJnZEVn= zN4BuAb_Y#vn;u9k319dC(|VMx;eu)PATRb;rLI0XNxpv`xxp5E2JuX%zL6)MY-b(% z1IdLDcM?t7S^NG#vLQq#cVhSh9Q6^EJB1KK_&DJ_A5nj9#SK2BzPI1dR79(w_w8Rj zt1|Atm3#IW?8!rH(UiX`_iPBQc3>#l`zU#-KU#EY%n<|jAb0ggyBI=4!ASn!$;?0g zOOz?{vi=6$yW6=WGv2RvOnfX@@AHt@-V#YkN5IKJ?aTcf=S}>Jl+kRV@+1FS+Z*M| zxITDs-$Ut2df?M}=bGe>ELIn2lm=91n z(}=)kjd{cbcEf8+6r%#?jfT7sCb7XX0ebpo^9Pp7Q>N) zS;fMzleYDQ6LfGBH6(S=v@zsOtZy+nn*O)YXUjPLq}Cj8F_4Sz;Q3@01Q~mOl$gQ- zXu_wvrD?d`wfXd!kJ2-^N6!~EiWtv6rqFO#Xxz}_hI#bUce z7T$LE`3RQm@!3c!{~>HMmlNa<@pP~-+)!?MuvEL_SFM)gy?CDeDSj+&CoxiE?#W&yRmpNNeL zTo#~`Ihd6Lh+<5Mx`0eZ43d>V?PFdL$90H9$U?*_6(|`{zJ8-jIu~N!ioi;fus0}^ z=U4QlK!c5~OGzZP2lZevWJf_21Zj|8rHwQw;7o6V0^7$6s<_Z(s)gS_uHi=37!xfA zAxjfak5})2c)Fb+9!|yGXbLxkhsY3JDb;%*U}<=WEYMQNjR5%4gDWM$Y!5w3p%J=2 z5xdIl6@u*mdXBaXObdx8S}&K+v1Wg^3Uy(Bwh0Aln^h+NcHsR}sol&`vA=zIx-1b& zsn&yVoKFztRH2stObn@Dj;i7E5~);CoG$>&PQ{TA0Xs;_q(>pPRRpG)jMW3GX)Ex} zFkBKgP^R8^2g-Ld8=p$@?BVT2^71){*?3$&wF-D$5)~MoH>N^lGy{0;f0&Q|Y9?if z>p&tYR7iEB08FrdsHI$&|BDUtthcox4w!o7FOQZb3cAdrNwR7<@<@K-g3q7KA+pu^<9fjoIC$%>s}WRkElCO z%hf`@+!}9j{qf+|_^a%Y(L(_jZeDq~U%Y)erfwS5nIoWLTuoFbJ9C~H52F+OVUFWhn?|t&y^KLY4$nl8up;!7Lq!;LNqmfPLdwsX_Qk*R zeI)C*{+xYrAk=0m#!`R%v)WqBCV~cqqqwpz6GMn2m(35hhVh}V)ap5bt>D-GK`ZHF1%aeRrPl zFry+!1DbZv$UY9LMq}E-N;%O;7_T&4YVee<0{40Ql%?nU_L62t&3*d%e#-{5(Bjx7 zd=hp2nvXEc87G&IQ0?qM!0t{jz7uuQ`=DueBr|gVjOsgw3|W6@QpDl;bIsu+QS_AZ zLwVnjIScf(Yv1WlOXt(hecqRBtx394tS;)KH#4h1yLy?c=8phaxmNo>{lb3qzW znh43e4arM@OR%A*?qEk=i`^1GeZ4JJ(iZ!09^m2jPr&Y|q+U{gHfPE!w{Ar(|`ZO(~#3-Fox* zoY7wH4QKwV?~f39BR2H3hd1_jsy)Wj_rTqFhoq_lv^Z96l`7M6VsnpT-%+3otYdAJ zQq@&9rDOXU^6wl-BQE6)%|Lk$bHOq0p|nz1v%1;f)!P#njQZ&>srygUERMBxZ4G;r zME&6Y1?JplCtZD3D{JS}iQ5;F9(E{&Rp&B&C^3L2APn0Rc<15U?O_hLFT8*FRymA% zd-RG{w0GN>d|1_y*LrkGLRsU(Is5U|+V7kN{7v$1t-*a$nv&JqwK$G#P!CvMaTCT1 zm<%R23jRkNGXKN(sO=^7mc`u4Gc(xqg9`WVDcsxh)6UQN-q)iqj%x4m-Zi$%PFv@Z z~@++m`pmRU2Ij+0$v5+`YxS@&i6&Omrf|1>i)6Y&%?(;eL9H@APwy#jbME2$)haZFe3y75jT#x+$NX@S z;#J5~FQHuN8ih;5u%~m|rw1BFkI*1Jhc}}>H;kInj^xj6U!LDGxwHhcmK_ds9J-;z z_c4x8>~XaQi{{E5v5b)JF|@7{8Edi3k$?uO(Un)GFVGvgw&Mtkr0U`xZ>wmru`LnN zJy1z9(WDcT*d5?+BwMqKcA_BMDoe`SG{U^$H4HSp-Ntj1_p=XyVx8}mrU#lvk+dE8 zHx!nG?o==IMA{7M%nvKK%+0OeBnZ=z3e@g&OOI`eIN8%>MNRCM8xx6e>3MHeWn|_y zI~s61y!OK&eu2fZep*jLSNj_?t`?#cf)5NdK_b37{AuQyLE+7Fpr&eT7;J^_Z5)e^&1zk ze{6F*?}8aOf4o*R;Se+R|8wW}P8qwz=(OaeF9*V>E3I!GUF{pz+3R`1_nD69oYfLI z_Qo5Au_OOfs-+gUqVA8{1jPOuCmR(Wq&c?PynWk9HA}%9Lb)~lkZbBYGG&P(U_+>M;=W zac4d@SGaOre4_ZutE}xsJN$-H4AoV8njW2q6_@{j73+eDiK~1OdH~)oA^BdYNLO9* zn~s`j0L0nqY4o#)Q>ppOa;buzc!(7kYZWcTVU`R_}Bi zPP6=3%KY);;xDHmqM$3QYMB~Wp9#cMU||!6ewzM0w~HSyd%W|~4Sa_RGX6EUVlp)$ z!`niNhLw$eOuK0A7_@ruPEEFo;6VP0oQVAo-F*;y`?qLOS_@qghfoYhB#Nv&-Z`Wpx?~Ial9ratJKkggw9b#Hu+aa1+7Rh#=)TT249+O7R#U zlNlAl^tqB{Eqk-`j4DD_$~<9cvfQCZR(C^ox;wRl-acENg1{nb|i5B z4;4{D6Zjbwj{KG%siPw(bexT+pJY=b@uvD+$^(JHt)m~e7+eWRP59jz`uk6~J;}Gu zPnYj^aj5o6-D0z?hhQfB=3V{@Ea8{f>umI;pWjQ{%LRLhKPDRyB&VA(QQ@xn3-XW~ zp9J2g=fiL51N&smzA!qIh(IR}7S=f2SkT z_NMH5Ne1Dp?~zmEIXj*+exKE%d4#_)5M2H09)A69_{}w{`QdGT#}{^D=%*}TOF8g9k>wD+5uOz*4=cMQw0Oz~Ox zxU_ZE^H6VYp2%VH8}8?RpQ*Rmo_?}%7-J`pR2lrZhg7plx>P{ox@O!c|AnVnVBuWO zS>wyBq~P#SwICUpMLC$sHT5XX*GyRptHs`xqyLY%AYD`o%{w|du@j&X{J&Eca zipI!KQh^hVi4xfEPqiPsw|_P?6j|2I7zTHu>NwN&U{;ZjP)UBFOy8+emeG;A)lS;e z?zf9OpV$cfWM>Z!e$FWS*k%%ArQ7%Nkj^Ud;nAJ%1AAV!-Y6{Yd|8|>3(|OBSz2t6 zYn!(+{I=M5TzRyQV$<4OXmEj}>O0cGwM&~>zt}hTkrp|3qvgm5`Nl8bE5nS+`M|Yy zc3|I|j-t66rZeFqD_5TEDfT(P!2R9c6(f*c_7dcQF@8?FIYSxQxvdenVt<9LsR;+{ zv}Oo5UflP)tAAiW{F&p&yOGqpbg}4(`bB-aT!dIxW$kH;Mayhs(IG z*68lL9?xIy#V@BdFt-VQ@BVaHGYaXgiu9KMaL?Z~tj?&lHaunWRxaVn{gkbGJEcx< zGO;VkR+T>K9AtCSU6oAJ$nB+JYPHv0qvEfPF-`LL z&$R{W#A4X5GbexanZPQISMOFWgDvU+6PZo#lZynk4u0}TfLOK1L z%@igtB)Z_w&qCtx*N%*>#&Y_P+DfP364lq+-g&hIF5^$+E+iw(QzHlDvLgfVtrZAg z6-KD3|I0@QZWl52cSy9+@q3Y^P=`2DMb>`N0oW z;|?$cSv&c>sBb{^BTs(@-njH8(KEJeoEKU>^Ssp3iP%)oK)!*xO(=F*sol9U5^J?s zb@86@WJM!+@>8nV{dafv8_teWqDkxigmH$}&^wObkVn&qdz0{oTGR)51WZOCNBYbg z+gUhh{knVEwqCvEh+2GXa#aeBW6DNSCKi@LU6VJ3<{7AvH18;ojK&v6rwsP}NoAbA zIRxH!ojc8|JVkCE{X_h%rwl6%H@PR_n-NM1zwRx^UmUJxnAc1E9TPS0Nxac-rG%q@ zzG3j`lzv~LV}YaB>o3TXq8Co@uZpD<4ZQhK(;ZMTHgs+Gu8Plduayju@^#1?)^>C6 zk@C0u-b(Vtw%5ZyEbmOX>vJgMSX9OE#bt+8mxKF{`IwTcLP>QDT{)rfqeH)55-$Y| zj?f1W)Y|7&1{D=r=LOI2I2s5ieKD){+eg%7wuH}^THIwbbzEsy+m@_!m?5npbI_Gt)#RfBClbjVD2VcdM$Rg5l}A@0N4xIrjL1hyy|* zxbA^0>8=jFKjg5nr|oC5kqM!GW%k0#`5^RwWJP5r{Eqa*HgU7ZZ#ECk#gCkhGg&xf z?{vCf1oL}Bf!5)M@fJp4#wr%?sH3~X-~Ff$xoqmawZBc}=!r0;G|`r-D_r`)Gn&Tg zN7jm>UH)_tF%W@m@@q9qfF!$rl0FqaLiTZo`}D)~6g?hm9Wi`$QT)-RZ3edPuixQq z%)K(fMNw5l@E;bJh^K; z&zRG1EE>*O{#ify1tM5L%&^Ja*sUg_XZC~~xq!>->YQFOmy$}5+UD=aFTJ<8aES)pI))o=jfT*L!p}(=7y14N{uct&~{xt9jCT+H5$=-sZ)2wOJ699J|*v z>=1HFW#9YbKb4pRaZg>;T^bj+8=dk|=j`XD8ycO-5o+J7{Q;Ya?@CZRc{aC4Nq>rd z+-a9#`>oZB7vgtqdFm?%T@G*F>U;ghYf%rp2}bMINhQZBxQk`Wu3aBoI<9YSI%@nT zS7Vi@UYL68xfDbL6ep>hzrVNFd()gI(J`V@vbM(gwZj%!LdljZ`vUcDB|R>DGg}Tq zV&m&b;3n(|US7U08HQ;Lh;e(u^Lc-WSQalR_N78^cICSlM_g}-cE?YM9jTa5q;g5s6@?by=fee>64nAuHsdFU;lDa)x?CPh9{jWJ zFhxi95JVYhxz%V^YyyAm?u8yg;=&+7&&r2kEs$;S{daTacJ+t5N^Eddjh5QUB)I&Z zyFrN>ZxYh(?GE3&S@vyr<0p6D9}(?Oc55NV20HX#G$$s2<$R*HLhi%mk1p;?P*n>5!CMju+=-8Db6#@C5q z8JINjbL@OIO@3clZfW%om$`>Zx<4{~S1o!fccr$gOxj~sGw^+_PhCJ3Jogl2#BX38 z7&H3@{Vgt?SSHmv&=`4Yyz@YNxMS}jAJ3QC3fqPm2-PS1D&8&rUUBh9!jlij=yjGp z(9PmEQEcNWgHzWJUx6AkoV8f#BF$tEK9#f_JHK*Q7otm|Tj2^R@d&Hl2=L-~L^f zGH>8B`)FCP1Pdyh9G+vQ%<-g+MD_;Wn7muIy&}C$EHQA7;-vwf$oqaz|CW=AQVC|| zHLr?8!s5M*Oe_K&o4qcV8o^@EAeZhsUC!*EjO}JbmIoR%E>5!9@4; zj}NnHv+sr3Y1`}$juaq~oz#^Dko%db6V`iX^A%b{1u_W?krE~bIxv2kFoZGb7k;&F ze59cRwg2uB<;H>DktIIoQ`~i&0+}AEMVPO-yZ|q|RB4HU z&bApZLg(hv=?*@jsu;t>&174Q244`W#Q7&_R=9Z4uZ`$`k>Y>xqU1lRZCu~ZhRwfC zL=H%2iVGj#c}8eL`bVgp507*aU%jEMwHz!tuP!Fp$9jE`i zc-A3)STVrpuCeeX(iNNZ4hcW`yoZQ)XFCAfKk|&Fq>}$ z1&+`7;#Va6nlkPQn_rNhi7KI~b#mXv2|pqndD!W1VErN44I z4V(*M&vfrW;4COJO$Lq%E$X zyT0zvGc%qY(^$Vf@j%SZQrh<8$)|eNGj);Y)j%0d+PtT&F&J=^`sY~sC-*Z^vm!jv zDjOBk=dQYEySI8Vnnz8}V{IB7Upwq^_5J#!P*+B$IQRbhHT{ju^8l#JH&H83rgiP~ z_x(2)PCYM*-q$exy$a>$6`72-*p?oBs$}4}p}$ISaoXpTPB)5Qw5ol0<{WjzjRucg z?Cm-NH|O|$$~|%(JJAD{pGg@C`;>m^Q|@&?)8_>!1L_~eMIJAS32`t}C5(KG({;Oh_x60P zpZcn(qH@U0EKW5_qM`r3kHm+XR8xtF=u0Nb<`>KhCVJdo9*a%h= z;_El^#a{4JmM2tHJ2rCXv)0=Inn=h;5$`VP--)!GuM_DXzUFjhKKvRXUV;#PLMj(Z zHXzgQ1^?7|$hLQlwfd8GU$k<9AbfXNb$^Fv5MR;X>VdI5*`#b&rM~fjR^7vf<%f!Q zaSKb8z!d5dj@F$Vft7P$uX-}!=|pMEIl;wR(4 z^KQVerM=hkJhpEiW~*0P)PCS~uBi^J!HaEr%?Dy556Uz}?Jb(okOqEOeprD~Qg77k zRg1?T7yH*}{a|LeHMdxyoW!hfqIXI-yuY?;S`J>Q<$ zdurGv__ecFiM!pWyI*GHUi7_jG~D}hf7kJv@?oc^oxhgPK<*}-_L!@#N1Q6jhkx)~ z)Sj@jUZhy}BqqR3E3&^-RP1Tz58V&A_;mdv!j}YOwq4oxM1=-Mpt677lNz_y4w~!S z*b)_5ftv1MO%h8VP8DB?WK)`z+llKbhK4NZ_TSMulwLk}Du9<;C<~grrUajqE$-;J zsV!h(GI^ohbQ#{_PZaZTI65T7TxW7_d}S6gtueXsJm_-C_0wVXu&_n#YRIdr&*>xC zgB&G2P`_LCfQf-qH7GeNygAW)565Tq&92$s-#SJr8xi!gPi3n;a zFM#(3MyyFDC~0`yY-pnRzLuuP&(4WhS_J(+yuEc;RQ>h`N{6J9N(%^r(n!Og(v6gW zbc-M%%`kK--Klg)cZzg3(%lV1=iP()#yRIb=RVKIFp%1>5+Jm{=>D}y526dOztS16Ve_8Ih#gs z4!?nPqG)l{b9tQ3Xx!6#jC&n9aoHRVjt8&(V$ev`b4ow$ExaRe&~SBhwy8CCb(ln+ zvD4OyRa0ry)}4MZ3J^RRtHPfxmQQNbr)H%DkMG1KzjeG3a89+UcNMdA2xe|>bj6)n z^gTIkIlxG$o#oj8Ea$gG=q-DdR9+f@;;|o$7ecJ~Al^?$iN9Y2Qxb_5O)Ky5kljSS zx&4pnr~Tmx96lz83vOTZ9+LCxNc)N5;dye&y{DvEn|}FmKZkF6+RpCvv|`jjc%lK@ zMFzC49w4t`&vM}5+Lm|1FYKyR;nE$I$7xUAZTM+?WH?Fnf;8i2MK#1f-6JQPL6pS- z6lPbXUSp43%J-4hmLYt~LmEOix`K!MWgNp!dm1KdI|Ix^yV^b(lfB5kmJL|Cb-QSF zOrBa5yqP_VN5+0f%05SeO-@gKFeC?xzF|_PxGz`XuT2BIcfhn1cv%eFMaL=0HrI8s z-1ujaAQEU^ckct`jHM)>dx)tBZ4#Zk4;Mbe(aOTbbxU#t5-TJ5W0HiMeEOJ1Nn+ez ze8trj&zsW6_ryL4?F3y@5wh;X6ep}#S)rejxoA+?kbbtuTFFmt#1J_8gwxP)oFS(lQ+HsJt$ShOc^B!ry}$p6 z{^paIj0R=OgvjeLWz#~8u8`$1^SCa*joJ~g>Br&J`K_!I-xT@Xx4OPRnm-A6kwId9 z97b9vt*Aq}MV198W>WB*m`NZs!f3y{Y59JcZARskTLAtG9sUnzGN2 zZjhH!_fcfqO-2@we|WMy{f+is?so;k%0!TMrrM+4>e^}9M4k^u_K5;0-n`Vi+j=v2 z$~i$|C;@{a?fv`kF-R$u7j`|+nKaj=n6V3LC%ZQXy|O~!t45h@3ciCmbotXrh2&Vb z3kZ0&aH^+Mj)RabQy#&HSOUxltqWn^uJtw_B@}!mD^zN9Ji|a>+!E}HLK<}@9r0QJ zc#exN`RiADoa98i)4ZoH&&q_)w(`7%PB8adtXW;6NQ6B=Z3;Ax-`^LshG(T;eUVvP zAu&v#f7M76b|87#iGZ(a;P%by;M!i`(RU4RR3T(eRVH5kG%jxMuu(kQt^-!M`JaevW|Vg;VYTo#nV`B8vQRtciZXr_NPZBxLoLO6+@F z-7%g+Vi?`kq&W`Tk6-g&|97(HXb8(L8&$_s?`jeO@}jd~Pxx^++Mk_=VX zNS*_SJWGSCUP;q!&zrR;Co8~CYYlrJuL5g~KTfJ_l?c7(ZkY>jl+8)+GsN^e^zY+W zd9vb98Hp`Nr2|7k%Kg;AoHp&Z}@AjP?a=k{Bv&o{ZlzU?{O}lfZJptjz2yEr3 z%y(vsvx0iX;s49d7=g<_AwvGO4rIR^H)>0xH=qbxYDM5Ylg z)2>veWza^gL?GcW6P-Q^8^4hPpp1#o-Ei{14Wnpf6yyDe?x#N|(!+t^uU8vU+7Stz zAh1(3-i=BOeZ$l>5`FwiQn_5+lum2>{up?`rOrc$BdQaa-M(t zWQa|a?-~@Tr}g0-Q@2&~)^(_xOfEjqmudqGh+usL7!?5(B+bTDAOTA>9ux$;%_fAv8ceP~|Hfa`1DJH2MAj zUvhl@+>-HeBYV7_+4Ah_7rwDvvAah-&a=)neB^K-_8si0`1Y*QXAd!A>ARZYOj@9> z1~TKjk1qI?=Uy1@Ss>0}owKnO%=vt%%wXeY-bt)X1vU#k%?^&Zm>P(-LkfV^ z#W(vZ{KVP5Pdh0Szs}dzNkiI6;ALip>iCa*S)zoLehz1|GWOX^Rg(`hGONB*uRkDp zmX7bHA8u?PhJDaec0HX^sSc~;aTm0Z{bm!{;#@cPppp5h>fz;vd?tqMv?Y%Jw95X7 zNUP-KGTUhv^6ASjOr&p6e&~J6W)t#x8S0;k*4zR&=2%XCu&mu(B9;c>A7n(Isto&QrpVK&q%y@P zx1BqGn`r23P%NuQt*ss}yFA;+KYG`e*phxMH;lJ2ecXemJ-RBO2c=a{Jn28vwNN6n z5!<@>$oY-aLpyS1n|<$QiaP4N{_(KO(esvG_8uX-q}Q>=eZq@7cU2QlXeZun^^6y~ z2BS&yJHT)4I$hMv_*HnQmKeCbxx`sE;T2j>ytvKQ03HhufRhQL+aK^A}2 zH43693Mwi~6JTI?AXDHeSm%SxlI~^hV&TSryC|nXTLa5K0Q*B@-J+;YYG>!|w8E({loG6zeI$%i5tFo3$wW;nHbUR()~2akv3bz(VvGY+tfduhZbJs47uJP zc`35N-!T$%Z5e}g{a&n`rQ0{SVn-JHkla3mU_nuoms8*W=p+EQVOCp}Mkuej;~I3t z=b#R4G^rs*65U)E)?f;c)9QE{Ee9}8fmGWb5yKt>cKa!vTurPEiMqsj+jYr>xE=8>!vU?(f$ELqhB) z$)tQ7Zu)}y69SE6@9f9RT#L8kW@+=5^&o}@;;4jCY0^0<_rb0zD?q7sajk$ zj6N#CDs)*h!4xVB&TZqvBSPLf6Mn*(8D2@tLSefSAu$OoFI4~|( ztM|#F1@2yp&wEWW%}hk&b)RM_M{)+2dik$tx=G{v=+Gza{LVNk2U~>t%p1k4f^9|% zANWRkUb~~z!x2<*-;sh$EN(QvZF1aYB?q4+#q=CmqVIZ4wH3^+6dur_k-Jb9BMy&h z6kKhi^xCi=g)U-iIMXvoILO~wW?e}+ThJ~QnU-zO>&}K0;+CyK0)0i|>hptoolns}*imhRJD?K>S2hI0Vz;*d0$$a^zan)4EhgOf* zrRT%GEo#lP@w7f{W_hQCDI*+%AFC9W7n{rErX}ySL5|Wf9_2-)C375wRBKLS>Pm_K zR3KK1by9<&Yb8Pb=)!hlwr*-=A~^d6L3Sj%(z7+F=!QD(hXr=EY&;T$=;;%y1e0+# zQMcPC4aV~p{#77&sEa%274YI4sEMU$$4zZAqJe|nPbQvF$2t_Rm7^3!HkXuWx@-a63D8_ zj?{|%%<*rvkLIBBw)dRQMzTp!8{Fu-|l3I5Bt{UFNXUsVHsRD^jE zsBJLv6GWetB;rMQ3H#y0w&)v5xDKIVaa0^gOd@QZex0o{gsB z&^;*|NrZp{3>Q3%c1BA)D8v2!E&{zlYPRH=YY4mnRA+}$H5r-QH3-wM(t90oA44+S znk_s#HTl8%29uJ2$ogzbV{SA9A=*Nw}sSo zd_qBL>cmce2R0uEp`r#-<>4yB36cwuG^&9!x-q#X?MWW)O_n3Z1wfPQ$Am+X0=v#vC@;?+mQ7(W^iWT_t&$oR zaCZt8?IPPbuX2!8Sl-e6aIjw`b*B~Eq!>ma zAycrl(zc4(lqs+x45BEv!gg@Z%i>@bWM`&j=P9CTFyUyx@^N7&g-&9iyadO)8<2Ch z#-hrcw;}A9ch%Ls`#Qhoz^?A((7{sM7XK4n=;=b>RA9DEQA$G3K}t%v<^PC^2w7P6 z;FmEWF<3dt$UXeTpl3Kp^aIB3VieR$*suR0@SILz4Ymb+Nseu#ErZKrhLfNmA#{Br ze$MT#2JhF$)2U?@;i`ATIts&wsK+wyxw3+S_8nR+HurGf6rsj$3V+iy;;^Be`+U(z zo+!!{Ow_}#lJ%Me3fg!HQ$R4$-~eIZ8pRV;1{=4$2r-5i_s(aMTC)DdyYW@+J4*&2 zSyh*abxV0W%12}@tdyCEk9;oq7Y6%u2E>971Cr`>9C3JDg@-oZJff-MlDB`wSjYCl z)cU|4to}gcoF8qiNrjvUV3z3UR%qHX(+Hc5SJDk0(M2s0eO#$%46*dl2RnED?*YQ- znymjY7_3p^R_m#5Sf0{&k~VY->gkGtVaKfxwurX4HQ zRi4SYuuEpb<&rtd!O+EiRgPuSyIGx^Q-9c~)U|CtuKgoy$62@GeQIJy+40-d?bmvT z!J`EnQh+>`Npast&Uw@wA}9!GK!UY`a(@HTTX?^o><8Owe>}j>drAg!LHi~b1W(Ca zjELVgd@9#|Y}rt~OhlW>Ca<-_GisDKzgx#U0j3qZF{zU*ITSH>JpZU$dUYqiZHN;2 zyNRHucb|!1s*&JDFN^qO!LaxVpq5<_IP;!1f)bAzZ!4ws-!wyjT>&a5%Wu~(3L0!w zc8|F)=?Q@giH=c4A2oJQ3q}tV6s2*^1BHj4QC^WFZ4taEBKrP^2uU?S!2&TS?vs9y~vz@!gA`DJb-rOCorh(VGGW_NKB8dxTp8?7B@|qF=_y6Qd9}YHghtPovdVa9 z3orGmef>EC@Eds1oL~Tw*jlojSQp9EIZAcyxO-aiT^S+k3HPe#2kW?mgu{Mr=!An) z!K89)J7N{VSoglz3!gt@315+gr=NxQv%!GDCwtBQ9$J(f}(vA{`2=F5hmEXNJx)F0@0kyU5uE%H{9ot$P7cy9M` zmyw=!8Xlgj!L{2wdD(L+vd+MT*n?lH+T3Q z+$hQy{&xGv7P>cM-jy$D{zLKkP6!P)21W5CBlgj4sd-6>`JBsvPo5BbTVTjT>}KUn zjA3eHPsPpWoeUKxL!ZH=Qg-OjApPJf2t+Y@jaAz%hZF^fkmf8)(ep8VAfzYBSOH)G zPJp8-#3YV$)(i4=X}HFSyf_L9O1(NC01M=R&C+t+Jt5W+&nO|*2$W2dc~iJD?@D4 z2>9KPu$90Zb>F|68l?Rgk@U)mfa#-~GG(hJT@%&ar4W-*ekFYVU@mppMo z*@;50Ll0KPC1GqS066}nOFdw11mHVaftE3j0`i7oUPwb*X?t)mHX1n_A&FF;0JG+Xa2&0{!Ifn55l#_TNEeYugURIH*K-4H?GQhW7(v{I6pqJq z?6JJ(5+AvuhYV%5GsB&)wA<@nZsoM(!PI0a0YoRdo=_oeY(r+g$X$Ig@2l?gr z`Iy;Lly@~T0qYbPl>z|fj3Yk5e)bXuj-ZJWY^1||nBnE_k>kC}m&85Bg?smVjEB38 zzl)!lBZN5)o3!!bqA|y1IzQ1FN7R9|662ixYApasDt&7~J)joVkwDXvMlSbM4mkcAr~jCM@y6!9`oWYdpfu--bjO1teO1QUO^p zujjYK7*C&O5>#k8%8)zu)(8aEBDJV;(8N7ZV)nmRs?1@y(MrSNSNoaaV1eLZ0nRL) z&C+YW#l>N(Hm=BkaQBFR>U*cnQC1{ZF;*~Q{M*d~Qu8rK<-5l|vs?3g4$rxeLpOw4 z_B32hWiT7CetxHYGgZ3p;w_~1ft(ySh zwsz`OuCE)$<#YkI=T~s#!|7t}s@Y|gOBGu;jnA$4rLqy`Hr?!fL{Kqv2I_T_?jgl>COS;CklfEfwJ#8wbYy z#P!&en6?k(4+&Oe-iR$#(LU(+66bOc-Tj zZXe_I)}#nt?};3Jj)@_im~sBcPllEWWV|-yD1jRJ&zVq*1?@1uFFuz0wB7yb4SpY+ zoz*sydvSEI4E`u5tWc(v5Wew8T;?0S1YjMreQ@O_c=y#8=a+6m+>K;GHdhpXEB`c@2zi)K z=v@RUkAcZ9%Zad(*9*)_bA%vYZ>%L@rl6(wNy#x3>eT&pj!lK4qsj4#EoL!-4;Hb|~SE&O+BpgNHIl6ZJp-SqP<-66MK1Qp@@lvo~m-|rTcqjwwZuZx_e zzZ}jy-JN8S?*;OJmjlN%-#-DU;)TH!~VZ|i7DG^KJ%-yixPIng80$(E4cUFrR8S2{#}TN4up>q;_4HN>~a z@~`hm0~c*X4#QZwD8<>2AQp99Ly7&#t@Tae5CH zHKgG|q-^Ykv!W|@9J{3RSr9_|2SZyWps2D2$5H{Vw!A(B2?{(y*Y;~Yj%nBhL zxN-g%zV?w@^bADebk9MT9)oEK-3I4t#v(&F3w+BJ@C>Y0++-2dS%Cx@=Fg;JO8k=?JrS0l#<>&uO7QqW#7XHjB zE**Xo1015_RUiukzE^Xkg)B z-1}G*rKpcOf_Xwa&q9;3%D$@Z#Yg`y;NIcJ5$$LH>cLIjcHmtj@jFEBV*fP?8$jTm zQAWWudw6tF`f}8Jl!6qv&Y%%1I96sQ3LqUDkcMiMgcjz=@(nXxc;!A|uk12>ZaPk0uA>00M6MkFs$A=PW&qY#*jE}rYNqSkVCr_h^p}?95{&JSn0m=#^xCBjYPZnA+S&I3p2$@~_OaIi;*+OT ztElE@UGR_p-xxow5bEG1EQb$KX?C-?rp0{Vd?8$d3G;&oZae5qB%U*q-s_a5m1-zk4YZPC_Orv04 zQ31frODmf3hgY-~MgP_+iU(Z#e*eO(Ghh#%kWKfvjtL7I4tsepR8xkg->0(r?P{r) z;$yk$ebLQVC==<-YH_GPd*R>j|1skK*ZYr2`G0i(d(^#(jB{<~z|@{&t9LtzwwYD9 zm_nv%re;33zElu0&Jp;02`44heg>~`eIVAUO(wp=`Z?B@JU9=e3jG(7BoW?h29j={ z0I~!Pl5k$ZcknS_4+q@90TmMRx?T?o)5l!?SsyC^^fBUfpBP)ezt%)C+4{%7=o|3! z{Z_v($)QwX?g!Qu7bIGfkrzy%ntwHf=ZbaQ8p0b>w}BtGbP->psMS(qqk z<+WZ0-e0eZObJ_Uie)q5CN- zSTCJ!a8PznJfT&>9}!=Uw#>t;X*vVvWc-W}1F}R$fNIv_#vh_%{OyT$(V1KjJZC+~ zrLQ(@_)BdwY4mVu^I$?4{u`>5$=@gp8B8$7~E z_~W^BZsu=IL6VnO;o?k3@TR@o6I!%7h zMf}x7KNqYLpm+gR41b0Po%Td}6BFyb~)(lyZ3bC=P~ zgjm}Luk;OEN^D=o`bP+f4gF}B&^|PaHcaR%I8G}fCU-6>He8)_ag%sqaSb2wwm5F7 z{uHLS%5z1km2mIkq^ArLI-As0ic@71D43KD!*uCz^I{S%KL3uq=_4f^t(TX=3;_?d z_|YCZKq<`{0|Wf#2EOQgCg7)c81jsj8I&z=Oq(>|v|Vz;!_wwwi{ zf$qWezb*F~e-{50U2V{O6LZ9`G*-@3p5jx9Rrc6JrWMb(&z@SA9a)t~(9-C<7WsBp zbKoT?kcM%`9bK83_yInlD4jtk4(%ivGG!X=e0hC&j8{y=;6RVh>l_7fwx*3e{4~B}(IwQ| z))4jJ#t%C*fI+0pU~Ca=W#d)8IQL1ua`b^FLgk|9A=&7nbdXafi^?p$P@KT!m?*HJ z)2eL-&9Lu&=8rP}VzJTECRRY>RCaZ>@+dh}$QAmKl)F+D{AQw$@JDSpW0Ty@g2x^^ z%G%LK`0qJx=&Ev4hc-l+tKi;Z`&MR`y4jnAx|2o4{F^Sua(yRW=f(M_&+_=0*`j83 zm)}n9c;=~2m1$X}NDc%=s`_H4)*krWUA4>gZr>=P_Opk5xGg2Q5p|R& z0V*1FbqH84_ZY10FjwHv>}G)Iqrj5Q!^oKPLVKA50Q9SoPV{(3qUM~Hpg)xt0yySqNq)k(6iRo4EowVzoOOM+=H>jjTGX<=CIr z)csWrs7PzIr#w#UYN1Pf8q9Lw2HD>0IHxYbM80Fw)f(fiH^Em2=!VhRMN&46v0}uv z)}!=6E=j@6eQvzqvg;pUW?c~npSeeiUC@%AQJxY4Diz9tT!!))k}oJ9{FKSKdB3yW zBhYx0CC2XPS8O!@n#8T3_ATm8E%o`Fduhi=0(KyoZ%;KK<=_NiVUbD)i+*rY%5)yH zYJPij$Mb}@r2QgGHh9B#q@D|f2dAms#`DZ=yO@8I_6<9wvQ7tv7#}q-(Uj zap<#J=lk+QwLN)64D5#v-)|f`9b9S*^?L?Cg>EfwfKU8-v`y=d>#wi^d%Npv!Dr>W zV4`UaVcR5+)@9Xx*V5YW&YQnbxQ(-%NcZ}eVKOus;t3PFRCk9ox`ebbB#z5uQ0Q6V-dCnw*Xdhf4V8vD8<;!=l;F|rP!<+o-Q@b8 zyU8rjO;8RGykl(r|2la5I~dzoqr$q7?gxRK@>{D z3DuZ}E7xC-x-N1buzNCkC@(beiR@h)8>S}T@#+O0m(aAExZRCwDOnebdI4KM6Ku|X z_OVh(&jF)*r1gT*0G7&?tu!Mwyo{F`onYEoF*qiG66`+q5>9Pj@=4GD0@Iw^GYI4^> zMH51MF2=zN=`N$xVY2470RoHpUw$7RAa(Y)({ttGwy=_UfwTRiXU4>#LBHlIAy{Dj zS+Lv$5xyV~Ta{%wFsL@RLSlsqmn*RU!a{@+teI)iQ@mWIA&mB-T`|b;qRC)q(OH>= zm$@1H_PwII_T&R9&6UCsMM!Ph0_f{uKRV6WeZN4MN8$9JJqm6=Jqkp6gS3A|EC11> zAYVIg&Be3svP{-{Uzm@1($ZzeUVGz`_o5U$<4?3KJGpxI_0HW%CJ2yN(}E?|fLQ~E zLY#dR_+Y9n_~)M%mXQ2%kK#`fyzVy%-tdbAH`ghh4&Wp^{8+9bHu)73an{27=*Md4 zm^Q_`3N~QE!7PQz!Krv+@->k-Fsp|`Y_z%u$1z7-pUymcTwhjf-y}om$r%HceauUQloj{YS0r^7y>>5dJ39ev=&VHdL%E$XmkmS2O)6#=zpcVJiFNe3pZdO5Y1ALaYO)V z-OBEyXlsiv22kf!m3X}!9~q}TGNxNrC4SzF5YnyNq=$_W#*+ZbgM+&K!&y4L4ZlkK z3cp4I;a8U!;sdB(U|Zvt-~@*Y*MQxQ-E8M=F2R!;<`3XRS5cwe=0NMrZD>|PUk3GZ z3HpCWIZ24_dtV%@+fWGWN0#df_$b#u#a%;|sDL3h-Sa-6$NXQrTy9Sg?ecW>I0@FS zy?I6QNfF)j%D%(}!ow~;y-E0A^XuToD{I*Ny0&$9*kW1i_74~Z#3QK~_6A%~Fp>vc zM0;GG8N*F}<&ZlW`({!DP$w~b6BcCeDt@7u-GtIzjn*=oLpV(dg^h ziS3H7hdn)a>fZ@{6yOqqwtWG7>o7E<44@gkt|8>6tSd=bo-j-XRM9pKR1sK8_AQm- z^#*WrA8e1p(!}4~kI1zw@T7fQoH-8wA^g?Xx@wbBz(Js8n9|G5cy`nd=&?|VAM9ZE zs*;QCA%ZGuIc|ZHbrFvAB5iXbH)oZmPk22s)z?sgs76JQZay6g>L>Ol;?$Ym#Dh zd`h;tXgDXoPF;J?Xeik#nP}k44n=;Gam{MYy??%TRKv_q3R+ReWr@DqqlxW6f1r@j zAUy6Kv!|m6!p3>&Lv?6d(*+_*NRMZgr=}~R!yzjhGpKc16 zE}b5P3kcIUKDemw)yUB7AbXyawl5b=Tt!d;CVg@_IKlY3W2?d~#)3q9eZLt@q2ai7 zy@heiH)bIxc=48GWFuEu{D^?+hLuI9&p376dMT~Tk-~ZK9rV#Lg;pua0IOlvFe6I8;S8DO-i(epg|b zNGJl$71uK*h3E@W^PP`q_ZX0<9`8vV>fzsgu0T0lGMUlWlj|IBkLx^FWqk9lVfK3W z#2g8Z5<>=oULP;a0UPq%R`X*9K@UGi$;c*8j&vSkK33D~)VX3-O~JTylcbA6E6a|+ z#|N9yP*v@^BsyQY$y!4a!BEbcWmd7y+8$y{_fJ1^tj%hRYn6F4+rQ^e)8g0Z?=Qcc zXKXz!)m8Z6aB1kj7md6psI6`_>GKV&(J&ax+p^m=pMXuffy2karvajv9t8I!f|DFIp(6sVOEO6RWWCiijJV%vD#B{$<9y!JUF$R2_Nl$ z8BjqXM0uTjvZm%r!;FyGPM#h-)^k31sW%!OdUS-FTTnureD`7|XxTY})it*&-P9qt zYIdaMCbVjn^Q4B?C9kq2)xP?;O6pBn>SXIocu842>NkHL>o&DLrIA5Q9=@~6(;r7t zx-;lO(f#`iWhvvjFW;C7vOP>Ddg{L(+$LAhaP6o<`yFF`H#@5Na4M}6KkiCi@3Y37 zqeK z>yxL|>YIsT8zh?BoFm8T#M***cWaT}i|p(3b4#|27}Bn^JyaI-ITL~6g*=CUFxTYU z9mLJrj^U~Y=cLk$%@&qCU%gCHgD8K1s9Z2We0*wq9cehAswJa*9$f8g8f=h?Do4F!Xyptjq9G4_5F4>^!MI+ZOl;v|-vZvprM+dqI{YFWmLJ4!_F}}7 zJY`{BTD?mY>?s0Re~upyy7&xUW*!rDi*ym2F;C`pGrt?Xv>m+up6~fk=tp-sT?F$O zF$>iD=LEKct0))`?1%VoTpiC(OT{gZO9ta{UjRI=B&zQ%kN-cyasZD%1Mv84DbbA0 zX<~od{DHxLPJAEN3S$U$f#{Z}dnG3H*`aCK!g{dkbMExp@;SO=!f@F~<@CukRkhUR zWN-kp?+P&c>4NDTFvLSnBD}2v8-@idud#)d=KjnAZk@uFYnUeOSOIAWMnrX9Zr0nO zh7HrDCUU#C>)H>|7#L(>1i#!*f?qDUTtn&}HSk5x#|@ZmE_OyN+Me_r6{R0O+# zGA<_5r*aM0=7(fO0oPxH#m^|{GfE>bJrsKFpGH1=cyY+73up^o8FjD^W26nhPI|0z zNFDsdz&=t+C??Roh1rAe<`5bs0e;3m^j%mw<*`IIt^eJQ``I1i5@!THIyV0|lP`` z{qomQ_cv9$HUb-UVOYU4XBYS7kw9GE+%G7T{|m|h!cPTTO1kG}>h>sbJes~$XpHaF zZUu9{k6Hqso76<=mI@lCyaBXN(mKuw3z;C&cNN$~Uoi7s%8MKo20wIV++ooi`Od)r z_!@j%aU~_%6ztIN<3)IQKa97eq2^l~jVOwEy^Qn>5 zn}+ar1B=eM>92Aeu7GbTTX)VaaJ@ zN%KiAaWB20a(4ULu^%5-%RUXso~nM zJn6NK^Fd%+I*XkQ+>9VPr2G9vrN)x_cm-X7WEagD{z;cwb&(7=Z8wxh^Q|Io_$NJaAOIUBwu$~ zvSzsgm}Aw-WK0rXajJ3dMSRSYFe!_&{QMg6y7pcxh2v$zk9p3dzM)j*sv@^`bRB(5 z0iJ-bIp%AU90$S|grd7EGjt8jDvJj5Zvrx;txOO5N!1(}$=`-BCtKBe1V;xWTaqa> zM;fQnU!IAH*_=Z!R)5Ui)TY%mbtzdCrSb?k-;WYc_8x;2f5f#b;LAaN=NF2_Z>~43 zgoWa+!by-vT_W#eG$7Bl+#w3K#~;2RYr)He(x^y1OCYOEA;}3(ChdDeE)<_E7)f^D zd;aou)*=C@-kq$eT|(O8$v^_x1#x}rcuNW1H%=*Jm!WpH%||PtZ>*kV<@NP$R_4Vc zJLxxiRARvi=iGZW;RpeVgbkgw^#Xg)1yl^}B8nDKk>$ojjJ zi>DeuI4YUKg=m3SAb%(|dq`v7CPKi?i1SQDddjIbY{zx>(7xkz>dwN+W0Pbz@19hl zlm04Bdbi_|j;a{^brtN_F>b!j=WY9hZ5qS-<((}gH&>4Xpqu&oH%}*L1lq1|gOm#} zA^{di_RTlk!HekT%CBef(V-&jejl{cikv2;} zgKb_S6vYi{?vJSdmm~7FD4|lW>oiu>X#cZam*{%y+_qSZDkkZQc`^ME}a zzC#Mu=W!^+CW`?6(8t}f4LoagtY&qy4Um$+9;;tqe}Fl4d(6Xcz-}w08O`E4DWvZQRpP8;X} z`ttuj#|KA)H~9D8q@vjSX82X|#J~Jaj3)6USMvZ1izblx!jR%)v67rZN5P`Po~z{h zlX5?N-)6*A%*S&-WC;G}s&PMmF2LO3pnq%bs7DQ~cNd3|eK*8Zzn$n2slQXYa&RIP zNPK)XA}d4@G{5P!Pb=(dr$H<1W-BE(za2ez|IN{ZLsTC?TScBTtx*szla6V3Iy6h7$=ThJEr-4UG1{iyI(8D+G7m)3!^lFR+_ zD=&0h`mG%^p4}B;jbKxTscKW(;d*hrgB`9XBIqQ%bhT%GH8k&P{WJhV{2Fp8;^WN_ z{JfYR3nWqTL+e`-T~`t+h$?aZ10KIUHhEP6gL!OoO&v~2=&`hr^@G2Xv&zIvNEkpY>U92v8FC*mnTbkSS7Hr!xZe(kD z_Epv$a%mUdMHL!nYVDDzkvL|hP_^6mvq&T86oAJ#uU1VM``pUUgetcEua9lWoZGYY z6L|@@-jLO>4stp>S$yO@+gUt3Z^p@Sl&vF~QcDAWNCMV_)LU<;@wu$lRqLM@$BS(O zKhn_V3;V%_$}@_^ue#c!MFgX6Go$OnMT7zzydUyjwRtRTs96%uVmz<)lN@ne4BU`% zpP@B79I87nzy83`432j@(~Z3I)%yjzQ~|rAWm4g0@fdBHd6G8m0s^r1iB{G?Kc~>up#Q8X4sMa(xFhw%k(83~O$ENl z$LwZ2+E|QR<956u)#NoT%?ga{{spY?cQF}EMZW6>hHIsW#Ea*I1!SYmlWcqPQ+Vzd zMUB2I9Zl;rO*Lg923FT$oGR<@OEt;kdLLG1F|<1IoE6{O2M^Z~?DEa~LfuHXkA&!V z1;jTtVL9`gn}6umbnr`mVxvGKaz;Yv%aCqQcq4kiMhobRgd9-f&t|$S=s;-o_bLGj zm_!j0uB|Aqo)D^}t{9eVjP{HUu7ea1BMSlW42Y2|eOzALkYN_m-`ry=V!I{=!pcKm zW;!L(2XViGf10txAx*xwQ7i}2C+F?{T%q2i`441?w()j8ps!cgmEedwSLqMLiXFqt zy+C-tlwSzIW&j+8{Vat4O?_MiQP!Fy?G!_OH+|}1XciMFU zON-@COUukZi;$DIBBZr<%;DeMPyZ}J%JQlvX;0*xt!D_ln*VOhfbe6Rd7GF1z^2Fa z0z=2?S>wT{F*~?!0RW%?1m}6gAP~^wVc_$a`07G`PI(#8z2E`7*J5~SEA8@5(}2q} z;)AaD-Nx340N??X4fI0*+?cF`z@^i?6BaN9F?TMaZj*=1a)QzQj1DN$X@7$0NZ@;s zLxHL;d|TCDk$Y{cCbot_8 z_$NId?)MxTCJ#fi>+wUN<;0@E&L6Lvt~olktC+0YqWr%0G>zg=5ov^?pMp|=;3Xyg zkr@@?kvxw3(Zf2<#ompr>T>5*EzzBCEGMy(yQ}rkt1@Wa$Qf6`;Uq;&d0RS(e=?IA_6NWA-Mx5v4!3Wiy>M^-I#ZTtkXb(7Z zdR*^>s_n)9cAt|vEnuO1Ne!p!QG9|wdsx2AK975!%|@i4jb+4w>HGQYOos;p=4IGI ze2ojh+pVE_{%t)UHh2SpcbhwyUOWqP)$7^r=qoP)Z#_URb^QWT1~!#whvv3gZohRb zYtI|y?yJt?uX(XALgpeX)EY8s<+0E3V!9H}@G(1l31qK`{5Z#P%96*)j%LS$-#7Nf z|HIx}hE=)l?cOvfNJvXdsdRTqi?q_6N_RIZDItxNgn)E+gEUBYcgLV}-vi9G=9+W8 z&wlo|_mhWk41;lv>;A`i{!RiD8OsoUEtF9;^Qj(th|$Y;d&(`S{&&Nr?>wY#|N2UH zNF+%?z2@yRT=otBM2FP98D1ZjSG*FzMoVy4#MqE{wIz%6!_VTV_Zr%qPrHMsBWk1- zqK!a$C)=toaIs?wFy|(&Mi~d@G{-oB8rTyu!m<-X$NY6sYVOP(nx~^;o=K#AG4bL1VRc&)sG>F^^ zy02riJa|^TgElhWLv|R39|etIpp+p63sebrdN_sK-X{L+0blfRQYf@g-Z|k48o^PE z5;n?lp?Zb&WN|&7_#C5^F5Cn9Pf@m#3in9^TCJvkqjE7_(u?R#_er9*4(YY0 zV7o(EM1Cg^%k<&g&h)p{Zz#GM8P6(`B5exm;w$llrYTeK95oSnE{=E+KGfmYsAsK zHL>jO-*|`ZK;zEK>lQ5#Zq}(jK%U=(H{Ww=gw`ofduB_1Af_?b(4(Hcd9Nn&unkpv^ z11FF<~oMIs_Y z&wOuUM^fAet~nMGKU+sQ0`)C_ZpK3eW){UaMug(^&R1@3YzUKXq83i9#w|t-9!sBK zVZ{yX0Gy_q8E=)9j*is>IM7P8gc*{a>n6^dR{81Y)ht|usVDb!v0J4e6m9S1OO}?d z#VU;ie#jKGw6{}l5EkwZeak^G|1imk=T#xmn69Rm`Qsk2c;jD+wxPNHk`fCVAx3UU@i!k5PSpkDDqva+rwbYCwFlP3Q|%^-CWQw&$!Rf zkX}mWM3(rAuW+?jX*XZmRHGeFeIs2`m}ycn0|6?6FtX*|PDEPKedS7}T1Zf=FF6%9YKj$(CGYAU1MN|d|y&JKh{>*EG} zSsFQ-*TlzEK7|OAN4c_7KJ^Jo6=u|&7_jU2tyM<*L)||Zm0$6p>=Eu_J-9= zoNy;Nan(|~VK4J;;&6WTS%NR>b9XvOL~cBlHgE0K97dnUGqbchY$+QeFiUB1!5+#X zu9OxyzMy(V$a6_Fl=B$7_v_lh)6bU9qLxRL&7E~PhK5J^W?Pjr=fxRjhsV&gUsO{n zF*jYOD)WyP&+`u$zNk*ji5|Zm0sj&4C`x5lw>>2=>eYIqgQ^9s19nxQLqpLE0%HeO zk1q>9qpe;dGD$MrU@ON7iqiO)M0Hu0wSaVy) zoekvQ>zI02ppNk2eG51NTC`IKyl4pUrNoQA!o=fY7vCaQ(k6_@zbmluGn$2fKM2tP?7w&a?!RvW{Pz!{#jVpJ!gnB=EBweg{KSP%PsveF=Lfx- zlbb(WJcPsH%Ohi=V}b9`7o+Nypl$E!4d@l?l4uuic|=)|#s&EAZQ$p*R9hfGMozLi zxn8OUQbv}6dAh#ADe})lLOnk@KD1nmL2FSHd51$iCl<&HpTUbr(cdVG+JPc`7h8#) zA^ZhaDkHHsa}t{@Oa~~SFaYs>*j(~b3^{I$;~w$bJy<_-TqGI$ZsOTQ=D+dZD+9O_ zpvZ=zW@Z_b2i*_zP)O6m@?J{?SQDELE6s6nsm+TfwggDsH-7sE2HBq}EVtmKn2$aG zwA-s2EjklX2-T*)xd|n*5|y70?f&3!;C8<<|Fi5IPDJ%hPmfou4j$6EMP~Eu z?q5@7h?nO;KPlqWyQ{iyI!HEtltKSplrvZq`ZgyX{)bn@1;>`2Vei6Jj*}Xv+ zJcQG)ig>n02w>04bfn?IeZb9@r9}1T$NIK&s4bAv(jzY%?wCCCmuK5YNB|5oxA{pMWsHK)>_&+lK#*BzEc)JCcX}nZT?b<8Spd%YlI|x`gkj21t8ZoPTZd<`oQL(1r!n4w(-;g%p#ywo?A(IH$k>lWc zAhA91>Lq7cEr=W-xZ#{U((4gtS$2_6kdPo|Ap95U=+UC@E@p@lkRvrousK5U-6;f^p+3s z>l#zfNWa3nK0fN5ejf=RoXhH6-s97AwpB*uGPl598%(v7k?Ht+o^%k#WyBYiYU4h^ z%BeE1trNGQf)(?I{fn*Tk?Sx`Mb0Da9iB1qL?@%}5uL)IBWAwT#Phe)iihz* zONy872VDMi0*0e^Pxlh!U&7*DImsD%-q~Mhe8h32fns(jU5L_&grfD#Q76%D$8|A# zXHX*QEwhPYsLJ(i90^#|3^(WkJCD7%7}Xr57rsofL~gK*A+PrnmL~k0fKPmneq9k= zwN}1}PeotOQQ6E0^s4Rwje11jQI_cW5KwEZH@raUD~j9GqFdaguF&drI8J+EdAtmz<7a+c*%toc6EomqW8uq>;>y@{!bZq(h7rc!pIyw$A()P!qS zS2j-Pd|iI9WWJu(>5n#;x2(h8tw_vUKJ_wA<-YmziYigi%B!nXyQ^&cEk%@A8%F#I z^4mwz7abifh=+jGl=V-D)h8Dm8i+K3GwNI3jW58vd4dc{v?*`~jj(DcFpvk)ypi?L zWTcI!=y;X`R1?vvy>bXWCVl^etS|R)1|HX1upFh~$WKAjvl4Z*Cq(^}Pz?rTI`&HaEi{Z#@ zVWzT<&X{! zq<)WSA+$%mbRD#`V$a_NL>flw=`FW-V|>LXi`1j%pJMU$aPR-th}}#lCC_5F_4v&2SvHfo=TJ9fQ#cbr;wPv&(?7!J2aeTAP0aa501Z)~1 z7Z4Tthx#T1-s)e}Hz=boI)COcL6*k+qA6zf=Y2{CFaxU20e>mwz4|mLJrjXyn8dfh zUR}-2IxbDLl^%RFAbP&W-sK5tvV_gD?>g{`&$alPpWL*aVUk~GL2~(a zFA4y|(=Bhu4s+ufI)3*|-%6|$z!Iz9n(ur8p!r7j*yjjo2DZ5&9ModV;A*`q1bDN) z%jbB*rGBXA^z6Y_fE!!MU!yVG{L0YH9(R0%(H!?FAyWQgR@89S`1Sz%tESXAVs&(t zu?pz7%r3xR@}oc}xP2as9&{k3`2no_@Le5)wwnO}Jf!PW@QB^NoWHwR;pihpguaF|L$cs8yo@4PqK}(B10l|bh;{i~>_^nakGn2riWX?YvlMl(w*?)0NK6-}F82oM27F^c_SJE00UWUrQ zpOP*Z;D-2r;$%t&h}@XH5`Xa_281K?hrz>Hw+?#ie{e8a-)avt`rK@PPMh63;fKVnoU|$CXDQ~cu1pmey6}(*35CRres0M}iQvB_i$#6u5X$$~NUWg7d6)sZ)@Rff&Sd<_a z!A_B~f2cwomrQ{I6xylc>2s&=KKvX4(OlmDDD!>RQ8l7i+A--^G<6j%WEDJDfDWt$ z*hUu zmh7g$d`Vnu?Iz`h27S7A+5LIIscMG1u#D=$=F_@zUCr0*K;d|!vdt}CP+i5IHaLF+ z=U4v5JMBR?@^pN0xCrR4(c3Lp(nvrK2n7GV0xDp1A}^3iv^o~I{D z8!K^ABBUfA!tSTBPM|X(1v--qb{Lm@_%#&ZJFt>%D^X$>qb(xrk{Tcr!j8(dDPzj)lpMFtYCi-yiDcb5V%Zbw4Aji2EzT5 z(21jbC#lZYVcU-9L852Err8sj3YuF_zvQ)T`Mke@FDSP>y#GKsYAmm#bkb7(+V3)) zn65ibo_0)8Z`5tsy$I|vI{r(Kk?wCEBc9({l=kUck5Tk5k5O>Y&iy=h=Id`jT;NCd zBb1aQ^vp9Ckyd+n;VYb=)Af4d2Qz8h@e5EX3snG<#LWV*6lHw9y4_>OS;bZU(0bQuxvOhu^K^OhNq`(mI79{v1ha9v z5SRY=V<mZ{sPrm4;riI9iFl{Q9Dv*|MUEX8ppdsQL)KdQ7x(tF4n_ zkXFh1^QlHWCsWt?u_$xRwM=KpP*V8eSMDFMUaRjoJ~e+UY|b$JdVOdni-9&O(_MSI zkW!KB-WTl;U9AuBPZ)L#vMqa4ql%00Lu_SYh};ey=~9|w5Q9V@(Z)KDH5xFJYr8Z^ zHnN7x)jsKS~{BmiNxk#(_g;cin%Y`dIF1nq9ac-G=q-TV6KW3j~am-D~5aa9ZEqOuG}s1PF%v`v*kct{h<8@`%!e{&+J>pQRk>Oa~0!}mswrK>FLqBpi`lKZe+aLrwMn( z96D3(Db<-2QM9mw(=Gk4Aq;hHBU8urkcz%%g~* zY|&AkZ=m;S9^Y}5+N^=iI!0RDz>AKJ=H1$^ioBpJKhLe&fik?Bk@w{}Ze6}}8C*L& zplogE6ne$WTg1%EBrVbVR?}3Pkn*tSz7r2tjUHXJ8+)IkL10|QO5*h9CMC$QWai9~ zT;yF;SY5hPQBl!@&Op0&pPtm`Q~Q6}Q=21uB=|Di^D$|JXq<;I>U&a!C1DJI0SvVA zVvd;1?R9>msWq!4nvBEsBqSeK_3HY^4GBS40R-_4wesCGhM#Jjj#5_-J+$7jk2f&j zj6BoFZuM5GecId-h%SSEA70Gg$n5hZ4%!llu-E4B6q?5Sy+^5aI3JQ8K#%5%a-E=; zG%H3$tnL|nCb4_$;;lPGu^k!t72$<;$_E)Tffps8#$X=<^*tRKG_I)L$`O_!29s)Mu`5^vF8E9shkH_#LPZOM%c0 z-wY>X3z+7iz`lhLo`fL9WC1!5JPg4Bn$?t0$3S&fOPh_ zgpA?GCc%L@@!q=|=L31F3+vzB^*YHqL*k`ul*R3zT)}r#3+7H z36F|i_z)YZ6f1vUCR}s&qY}S{Yy7M+ot%rOR6gKv0A`}+r~2&6MO@wmQ_pg2f&mT~cnQ%kb)$F1 z6u+HD{>9SjcJOoR!Tu-q9@CNT@verGR$b>eO}CtJ;d9{4^IU!7+Rzbqtbq927FXd$ zt^A90k5aJ>10GBKL#GS)s&sYugV?~%=bNqsId1LKOL|263? z_=i(1Q0xZ*gz(qG4&{Gr7IJ|3U#}{8CUW$}*ZFO_d2LiHHs4N%9WhGar$w?SJOKRc z$?nCxY0BWuk}KzT(VL6RA%Ry$El^Z)e=jPFZi~tV7@($vE4JBn`Pp=2`Sk>am@XNL zw*J2Tss;XJ3K3wD4FB>b6XTHBq)d)x>gVeXfY(19&-w8Tzaobxo1+~LXQvz(_vT+dA4F_OVcX@~ zTSSU)ET%SFvs3qq-_$!ZSaCjI?mpL8(Px72s7Xy1GuJ0IC3s%iQTT}pqBv|tfK_y) zEZ-Iv83oE={E?Y|Q;9-DiA6bUf0cM*m~-1o&56~k{aKK%c}wtdVn{DupOZm$Ah#>E zT+Ir5&6vkD(!knU+D7GMD>`~3x6X;Nugftn z59hFvCA51aAucNJ)C^VG}o(V(DDQ8 zjp8g8TfA{poloA4geQLq*8>f=zcJ+Uq^k-w%);*_v^aa?Q9H|F;5(#DG0^9MTzmIk z4gEbshylu>UB#vaz%Eq%*b;k%R}GmUbl%^aPG}UGb!Ecnd;ubqfAvh0Eb{PC_3X}fBQG+YLqjSr67zu-hr&cH?1 zAyd=&k5GQC+~#&sWYMghJ@^de{2)$Py9w z!dQcz-+{94y+;$D{ib#ZhP+stKi}iV)h5VH<5QwK8Ko~Q7lVVEh@<k`G-jcehne6q^Q3gWCV*1_6BG!&~nc@2j-{|!+!ky08JkJd~I0<-4 zTwUk3@0miLXCQ_8Jt;C6(*_+bPO&>&tB=mQl5UEv+k_0FB-I{k<6B-W@O>F5s_&J5 zGT`)w( z()3lxMI8ogVzo3LmZmmnbw}OCJST#W%avV`Lb#H}R0V7dI-+#RBDi+HDTx0GCZG1{ zPiiZ%!eUKoz4Mx9&C(pj&fxmS5gX?URNtL*uLzEv9IUQi4g4QC*NPcntmoYY4oX4C zvVRCHcK(uPM^c5N>ToCd4fd_~=EHA;U8D#~HvBzk9-mJi2rVFy=`+DhnO%5bu|rII z)r=#vfYSUktm2RK3u0Q}0sYgSq(w~g&!qMnUy{7sHp_B+#b)gpMf(yV6|?~-Heg6@ z>_>hccmH;Z#lDUFV}=dMGg3c|LH)!(dhT)(zr!%l6vH-9|dWJgQK!ylT>^4UNl%EE;O%j^6en@dI z*0{ZW^|gWDiv*VH!t2)pP>}bwsHM7@30GjJE;Y1@lNO$7Yfz~!E?h1F7kQh6^;)>- z(HWKG`MsLN(Zmq3Z3b?;#)P?+N%etPur2AASt#5Zr$m4Bz$A0yJSEz)<+-q|d4e1^dSg2G|4=%>LK} zdf-JPkKz(<3$X$je&ADc@4r1Y|E0xNUT!)K5y2&%2o%1!AM~AEWv~4jos1EyiSY-f>Vnw>qy?bu3Q?rTL?x4W5ZPM=SIjDq<5VzvY;523{Og~|$SjEPp(-mt%7 zBWJMlYzjs#oUuPrechXlG>bbZYLl3WPSu~!gD7^S>U8V+(LUnZRJWq&PB@IZ7sU1A5l{k(ZHDc6ZiSF~Xal z^Wnoq@{IH4Ipo+kcMi6~ghnx5`umqt_r6b!@KdiZReXkz9btV;SerOg@bCh0pQ}s7 zNY8t|$)L-JrC#%j6=)QF-GoG{DFoMu>G%bo*2E?s@egTM>mWNbKrE?2jzIb^kmp=) z?c~2LH9VJnlDmLXj&KsMiYIC_Bqs3?8_6xRnr7La!_|DJYa_mw*6m5<&P$KC+%sCd z%ck3-D@!NJA>uJKi`(tu!-F}lul#LWr#iQjj~`~xq7Y4Ib$+F*bG1RV&4X(gi7tui z7sV8Kgs6DN<3=&+%$;49KkZ>(GnCW8!K!uTEY9BQw6AT<-ulj(TIrO-?)d5`lMRK} z$J*ra$*zVvtJ~>T%0wdv*33eB69-myZRIJ^MvnH&o&reFj6@^Ha2U$_IefgHf~0Z| z*6sRMfxOftIY&3gQm%pBRm_3*p7;^CT6)D=!ZW*-bJfqwYljsd>9(=Yrjhj7<_jgP z$AUCbZ6ULH5O{l9{XvOAbrbH#*W_JDOLxp3D#RtSME1DB7{P(i<~?ODJTr z0SMV)q5~X3(d=CS6l_B4*Lv@_T`Z(tE-WM%=I=Le&f9Uo_J|Ahu4V}D?N%0`TjSGt zivx6wVdq8~VaEYsXHg%jL*Y+5o9DF^*BTecpK9tG))Wm0G_|F3Y;qfr{$r2K1n!Z+ z=+)GuVs_HZ;#4xeUZ6>CXu6f#y?*##v%;XT;%ZZDR^JZ&(JU8xta<#;XkjK>G=Cl6 za#Iul1cmgK>$u2kQ0yg{Zae|WMD9d@iaAEn{Sb(n3CPcD~59+~ydTCjMZS`v12|2n3{UEz%;5v3IM z#nnTXgc!~E7)`7|;e(p%ZYs}?nx1yk{k9xKMuG|(jV#v+EO^z$Rr$;WJm#DL8)T(Q z(sAw$B3`u2Nj=<(>V)?uaj#zzxSa*!=*`S~%#^X$JLO;UJ}Or^i9)BUb}t!=GPc~- z&}9Q?f1k!t3Cq*HhkNoq-LO^^1P`nq~!$ zZ7)Qt?QAT~wThDc<93u!{p>N}oNea94m`VBdKrgV`RieHGgel*gcUB->>CKAx%hZ* z=Xy8%YSwyp5*6KdKo2$vG*Zgfnx_v;w5!Eb2vrcC!3NTt*Jk46L(r%}Am^#Z<`RE} zD#_@Ke0OMrwT_!=(i!IFX8)l4GHAc)^6~ww1=wiwy3Zsn&)*{jP2uA|o2vabFahs< zYTZT71}6tZv3Q~5(&Em1BnW1@qBR7(74=VW@6L*ociP;0KKHbTIjNe1Gfi1pQhLDe zHMELy{Xr~M5#f-oX2-|%3c>;=XNg!Dy)4xjvWaL;Ftj*DKYwMVL$!S@ z7@Q#mFMA2`#To3DP(+rEpN5&VeCDWyg-#m2}J6?u%d@cBm61L^sJ@G^x zT9b`OHad2_Lv!U~x4B0-_ri(xQhV-W{vZY4j%yvY$Kk1ck#x$AMBjOFCAUhBJ8XA~ zpwH^$_4_#Hq_Gy8l@#)uVh`5RtxJSz~h%cv2KVI8O9uVQ%=F z>)>~HeH;^0^As`YW*ONM-?m%;rQZE-fgm@_NC^n?YGQV_8(H(iAH&G#$=xPc!WXof z#|NIdO)}!}Zun+4Y`6W&TB=FTJyuBxI()0g_y88=;|*7 z-n+mek{YG1V0Wcf5OG|6n+i4~!XtaP<8{CSPU%zP*#7@r0^dXVz%BuMgBzECQbD;O zOgjOR*gQR`&CH#7k;7xkiFg#U(Wn2;d*twl>rI0ShHLeD#7Yaeh`GZ~|L!eF_(O%{Ir4`J>EcG>V>bS?-}7zWHv^M>R1&}A zbAj~)D?@<)E<%nd7t?ayk8WSq94WmJ4sLFilnNhrYiNvi;L#hVN*m=623L#1W$95 zQZ6)D$V-2P_QMWOfv@2bOsC(%vLB(=32 zX#83lsKohQ+=t3-pjNX67HhMdeX4s#r$b9TwCUyc3(1D|YA%>#qrP>`9(6)mn0IOB z7CFm%AbP@z#zJ4`q#ElFRdOMGV4t|NSBSk};uTOt8CUy4O!EYP!f%MzeC^d!Y)zlf zp^0yV>kry(FG{wmgN=?gYBWxr_7it$dt4nDY}A4R;KSa)pYxm6z8{}KL*-_BqA8+e zkIGE93aiAh7p*&%^39BP=IIOAx$1rdBF9tnohI{Y-kBf+OF{SgJ6a1SuJ{pK{zeZ} zxKEr`N@J#S7P)L|nF}4RRprW9y``_xC%)#1fL7n9n#Dg`ACAYQb7tuIY^O2xfM_R0 zMXpR_UyCzSHLMb|S-y<*n(vf^1&L@f;~FD;FaKr7g#d>1vv_KlqwY?Nl*JxF2t{f5M>pVpPIj;5p)G194c~qVS$xD7=)J;ro#K23i5e*XB<%dIySn(i$rN7|X^$Ha1#o@+yPO;0 zMnUV*PYfWanV=XD!{H!r^xFi~49}ecN45sicWg{6PA0G3+)7D~kZ$#Z6aRtNIvaCXmn7cMNBY!Y;keGbpcAM^eiOh38 z;~xR~4@k)4hQ>Sdyh1J?vVaJyS%|P3O5R?*P5sY6sQ+aZ_xC-R+tt%E#05IGEnKMU zM5G*-*Y3dW^?x_Rq4=vA&Yh%H@7coQuEDr)R0jgyUy$ez@VAY?Jzx!1@Yy^3W(yXf zJv)&T$z`@qwB`iNcz(ma!~)7K*x?z#8Km&8Aq=ch>ck1(Qh1W){2f@W_lx_&Qov+X zUABJ+_>1rXna<;Gus-k=z+J;sau)?}-Qc9%AlJSJM?{;y!Vtx%U$I(#{!F*T_v{l5 z)P`AOpMr?UDf$~u36UMWY7v4z^ zlTqKGzvdf7$qDfqN5PcBkUj8r%dD-Kl3ZrRvmR5u*FtbIwK*|$yxk4>n+<5aP>moA zNQ#D3tq?MboW_^EQZo^{JvZ+0H#^bIC$k0g8N*;fD_)63auNnvbt;yjsPQ>{tST29 zov~YE^m!)QLomtKCR;_sVD}NCTe6o+At=6jjiOEKsT?aMS56+$6-pZ zy;w0{pj1m(%A`?TZ)^eA*=#RX6^$;;O&lviC@jmNo6(t5 zwjy?(#oHSCMx)y75x>t-!Pytdt=eqE30ppjH9dx_Z@-;Pjyt^=wzd?;y68(Zn*Opk zLDM_tXq4^S#M86EiAy+sW@yv;GB;pC5y#2Or)p7-4v0S#M6TLY$#0!&tt`}C6y=R- z8~`Q8^QB++>;yzJxx8P;1imnkyTBdNAk?sz{TU5ZL9)&s;1?-entfjx6H`J+P72dE zJF@^o0o|YdlT_u>lxha!PR3->7nETm#sH>(kv9KV2RS>_#kuF+wY|VdL}7M)pW}r# z+nY1Bd8PM+=4-aYl5{~JYDXq?Y%VF^MO(B2NiS`M$D5jzMjaD<+YEiE=!${+oEG6 z2j59(o_5x8q4^+LCIye%-I@`ZCC;=$M-5!AT$l|LYTgD;kaavRlY^A|w&TvQmvyBv zVaRM8VcY=0S@5?-$DtsKP54@PWGL_Y;QHQr1}z+R*b6u{ z$SbHTI5UWAs4|bLdgxh(T_V(X&95P1Jw`m=*5lPr)I0NIyn>#Fukd0`I;YILzqb(MbokiK4OjJk%2GSFhc^i+i)m!N?ji65i-o-H(8W(Zzr5VL7&YHvnQkObr3vsAl4H{)xE`6pv;iz^0&PYFq#6#r4`~LJ;2AWN2-F>G7`>%CiU%kWjzZmhjo*D z0C2&TKDmgHAu&Zk8_+`Em}45w?u8r_Y4!EKN!0|L-o4P{+`tk66@dt=cvlu;o+Yf( zM#T`nMB0}+0o~FxxTZZ|lK1^V&QYXjnEoYiZT?TasL882Jsfsruz4u(nEOmZ=?x8=V3!I}RV)>WF4W)f$ELV*{}4q!SdVM-qHQ zo9*`!jfG)9E^sA`_uesetr#?@y9^%o<$rt{c61jW<@0k@CUlc+WHM{qzAj;8=xDwS zw1j;6rzqGIP;-rU56CN>HGl@iZSh3Vp0Co?Bm}1xv45ogc`O%fk_$X>k0f=w`12y;!*y&hgSmZ$JJwyG8BYBKtCWj2Ipvr3vD{%ui4Hpp|jb~C%M6T*1w-<3_1_*q2 zOfb=9!V~{3@dsT`PwQ2Jn3|J;5JOZb37iD`{ghtFFTGxV#TFQE_60*5VX>r;$Rl7g zk=lswtx95e?q4Kt&U-cMmA`T{5En7f;1<(%5zrBbgC108LO7wkN8=)JG0*%G8vZ@f zb!ztD;{EtRMlI&gWRYY>Sc+I+e^GcU*6WP)WpWD0oM-LSa0B8Tr|n~VJ$@V<;(qO8 z>zp{Tw*3-J0?b`Xl9ImX_z2~}=-sZwZaNxn8v15#uNhv%$y7H$lfDoU3V3G?f3frd&6akHCwSi}3EW|gHMYMt3e>d_%TOQJY z8<1U(ZZFey%q>W9dvMww3OMtGfEj845{TRT9n%Z>(a6z{gEsTEUm6E_J*zc1Wc60P z`|^zC-~b-!KPqqd!q3+3YRd;zWT|^ZMb!bm?v%@eJ^-4^N8rOj?~!wnEK+NZ3$}_7 zW&H5LY#^+sTi?!2lkaC1HPZidy1Z|8R(;)6fXeQ>QEGQ?VW}svuCu1NW z1M)|ZzvquYjQ~{F153fzsHh(MR8PWw{E%?8mSKKpCwoG&In*08upauC0`w2ILuTQ-@N<=8Oyq_G?3CDtNKv|Gk+X4`{^%Lb!7TXqU$By3gbNuV>)>F_Q`et|QaSHDR zaP?E5oyv8Yu*c%#klNNfZmdYqa=G{3THV5(##?^Qv3~r{0cw z3Y^npQA`j(!}A>f=ib-2VBzysXs&3=LP0nHl~TMVGy@rHf5zK9KE3zz@cfpgnb6Ty z4>1pd+(XLXM27RlLCAl48YqVIu&1&9FJ?`^At=ydkVXZALhF(l>ynxucQO4KI3YYi zVFYg;eq|jYl{b8+VE{2TEX1=?N)7^(?SKpq-V&waEMpA?yx;dAoUVSgTnLEWh;k3; z??n^-qv_(`#!^xL#aQZH=hR}VbpQd|VXzHP;S95L%G_np))AiyDOB2`^tj>A7#y3P z4v&}~VSpo$Ukr_&-W;zr8!`_OR0WX5wXQsg5eWKL|9+v{BlJZv^LEOz^ygc7db zZZRMTGXeU8Behc3f*_+bM90lPLi~rE&g)O|JNWj>p9P0ksRKb;a4?hbh?KtP;Jg~* zZ4yO*%h~`*@e&MZh`hPkn}I>9_Dz&#^?!=eY<`Q)Y>0u1kb zYOa8=u~dai0Nf22Jpe~>snxd<)y!xBs0SEbhQu+Z;Ab=6^%C&>P z3e2>tv;(iLzz}uJ2y$URW#79lzfMoipToLgfL;O2>&Vt`QV@-T&x(l_>$!DXsvpiylI0Prps$0k*)2iz|kZ@bqaRNS|;6 zKNUwo>(8}OLM?vxN_avlKDZm;_fa^x8h)zB3J1C zOW-3p_-dw~FJ2caaRjqPD&8q&OQqOhhGjgLz;q;e4Qw*$K?0jh?8Pi^O(yi${NOAG z{G7biBp^8o6y;Ws)@NRFNt#}iaMwwCvztzjv6rPv%RPCTq3gQW?#qy(bI3ZC)w%X< zn9b5g0AZUImr{tCkmo00j=<+UU0kUL-x0&mJ?FuRjP=S{=5Fg8>q6)(2Ag? zD^DyiJ;pq8v2{T$k$5b<5?yattnSY;Ege`YAv%%v>MV4C%Bk{c5Hwr{CoBSbT&|X7 zB|#fIM6+lNi4*^_lva{i#XNs~V%)1Mm_2}h?SEgM5%fN!@nh^M2uAgaY9MAhWeG`z z!`i4g4wx*64fY0oCTh0t>7{C?qiOsmt>S#>%~Nr@G#$V-9#7J_d03uUu5r z(A-?}IT{$X1~Iu)KTx}T<%0pAp9omnzn7K^ubdN+&)^;cF&l)51R|HOo-QH41CL`q zT)7~e_seuj<$=p|M$38DVy9Wq?c7Gi&hXSVx{%-R6?52lNY8K@ouxkpJFZ~UhZR$D$g6aWN5|CbjHUJiwd=7cazADg8LU$a$pkAJ~M zC^F}q`Di{}ZN6-~25CyQHiVs5>Bj9Ey$#{9G8|P{dpR5hQB}fe*N? zWVApS!2#b(d-?uQPhSHM<18Ur^37=Cs28D+Vq5?bgS0KGz40W6v0DX$T;KWy z;87Cmt3#Ex53}+>BgV=y+mc-os>_H8$QIe?D2S#4`|-2~=b^59X{C>kk@j8RN;KMv zlR@`a+Xiw7$gHH&XOIYUAh|1X2YA#b9?T1hGPR?H*tAuDq8h$jKA>eAFBV1`(Wx8YH62|}XkZtY( zM;YbW8uSj4yLes@euB?O|Qb*(Iu#1MT@1$N3gdicYS^Jr)as*`dcJ z)?Pv(N+He3NmDpMwx!qy`*iD@G$}>Sfpzq@!d1Ehgrs3=!bi;zFhj#Wd{nXkm0KgNiS($wDR1JdZGoW6M%ZFQXU)SP;>a#}B-Z%{vrcb#mhECK)10yY$O zmm1Q`&E9V)j9yl<96By+ckOSKo0-B8)ul^z=H(x+I;oZ2XT}@JaTcd@mNl%qEhm86 z8}PVm+!#rL=sGli+$5Lpo+BOuI5^Zq6kkgIAv3mya4?T#jz- z3W-*{Gi=zvukynwY(m&Yu()1SpAsAjiB?7rj9Ua=%Sjn9+8&_$v#D)UP{xb8tt(6s z?X_uuqicF&?m$s)(QV%FjZK`NuEqVUV)g%HE$aH_uWHevtDq#gUzO;Q!=Ir*4vgPZ zh19AJ`C&5ZtF*7J*1y)dT2gMoCIOU$stA~$D~naof6S%PK)Q|C{EQ< zyX~3s81q4oOV|DBMLGk#CH~y%oHzM4jQhAZ2V_&ZTN>CkyHCNsfrh!S!;KqwpP0m- zOk_SyIFLy8p#XifNnwngYN^@lk9G=b6-j>Z3oWE>7k9n}U@x>Bt~Lmz_^Gj5fRbgI zpRjRlVHik^Tt4wC2gFpc*&5eqgt&!W7ZYF3Kh2m}p=1K`X)a85C;F?3C{AeMoLvj}auvZ7z;8 zvwLGFjQxXM7_qSal=KdgBn|{f8k7;jxG7X}3XxXHmae0CAGIu0o?67>#IdFy^QYM< z5tj>MZh|fs$D$wvk2fk+I8CPhllb?~ca(5Dkk%kt9~$!u^>9pBW|YnINY_k*lQEhUM`yCm~i)^5