From 2a44536a5135b2dcc21455b1956bd231514b377e Mon Sep 17 00:00:00 2001 From: Shunichi09 Date: Sat, 2 May 2020 21:08:25 +0900 Subject: [PATCH] Add: TwoWheeledTrack Env --- PythonLinearNonlinearControl/common/utils.py | 43 +++ .../configs/cartpole.py | 21 +- .../configs/make_configs.py | 2 +- .../configs/two_wheeled.py | 56 +++- .../controllers/make_controllers.py | 4 +- .../controllers/mpc.py | 27 +- PythonLinearNonlinearControl/envs/cartpole.py | 65 +++- PythonLinearNonlinearControl/envs/env.py | 5 +- .../envs/first_order_lag.py | 7 +- .../envs/make_envs.py | 3 + .../envs/two_wheeled.py | 288 +++++++++++++++++- .../models/make_models.py | 2 +- .../planners/closest_point_planner.py | 39 +++ .../planners/const_planner.py | 2 +- .../planners/make_planners.py | 9 +- .../plotters/animator.py | 74 +++++ .../plotters/plot_objs.py | 99 ++++++ .../runners/runner.py | 2 +- README.md | 18 +- assets/cartpole.gif | Bin 0 -> 59794 bytes assets/twowheeledconst.gif | Bin 0 -> 59979 bytes assets/twowheeledtrack.gif | Bin 0 -> 146635 bytes scripts/simple_run.py | 11 +- 23 files changed, 734 insertions(+), 43 deletions(-) create mode 100644 PythonLinearNonlinearControl/planners/closest_point_planner.py create mode 100644 PythonLinearNonlinearControl/plotters/animator.py create mode 100644 PythonLinearNonlinearControl/plotters/plot_objs.py create mode 100644 assets/cartpole.gif create mode 100644 assets/twowheeledconst.gif create mode 100644 assets/twowheeledtrack.gif diff --git a/PythonLinearNonlinearControl/common/utils.py b/PythonLinearNonlinearControl/common/utils.py index a22b22b..8010737 100644 --- a/PythonLinearNonlinearControl/common/utils.py +++ b/PythonLinearNonlinearControl/common/utils.py @@ -1 +1,44 @@ import numpy as np + +def rotate_pos(pos, angle): + """ Transformation the coordinate in the angle + + Args: + pos (numpy.ndarray): local state, shape(data_size, 2) + angle (float): rotate angle, in radians + Returns: + rotated_pos (numpy.ndarray): shape(data_size, 2) + """ + rot_mat = np.array([[np.cos(angle), -np.sin(angle)], + [np.sin(angle), np.cos(angle)]]) + + return np.dot(pos, rot_mat.T) + +def fit_angle_in_range(angles, min_angle=-np.pi, max_angle=np.pi): + """ Check angle range and correct the range + + Args: + angle (numpy.ndarray): in radians + min_angle (float): maximum of range in radians, default -pi + max_angle (float): minimum of range in radians, default pi + Returns: + fitted_angle (numpy.ndarray): range angle in radians + """ + if max_angle < min_angle: + raise ValueError("max angle must be greater than min angle") + if (max_angle - min_angle) < 2.0 * np.pi: + raise ValueError("difference between max_angle \ + and min_angle must be greater than 2.0 * pi") + + output = np.array(angles) + output_shape = output.shape + + output = output.flatten() + output -= min_angle + output %= 2 * np.pi + output += 2 * np.pi + output %= 2 * np.pi + output += min_angle + + output = np.minimum(max_angle, np.maximum(min_angle, output)) + return output.reshape(output_shape) \ No newline at end of file diff --git a/PythonLinearNonlinearControl/configs/cartpole.py b/PythonLinearNonlinearControl/configs/cartpole.py index fff5cf5..bbcf99b 100644 --- a/PythonLinearNonlinearControl/configs/cartpole.py +++ b/PythonLinearNonlinearControl/configs/cartpole.py @@ -3,6 +3,7 @@ import numpy as np class CartPoleConfigModule(): # parameters ENV_NAME = "CartPole-v0" + PLANNER_TYPE = "Const" TYPE = "Nonlinear" TASK_HORIZON = 500 PRED_LEN = 50 @@ -10,9 +11,9 @@ class CartPoleConfigModule(): INPUT_SIZE = 1 DT = 0.02 # cost parameters - R = np.diag([1.]) # 0.01 is worked for MPPI and CEM and MPPIWilliams + R = np.diag([0.01]) # 0.01 is worked for MPPI and CEM and MPPIWilliams # 1. is worked for iLQR - Terminal_Weight = 1. + TERMINAL_WEIGHT = 1. Q = None Sf = None # bounds @@ -23,6 +24,7 @@ class CartPoleConfigModule(): MC = 1. L = 0.5 G = 9.81 + CART_SIZE = (0.15, 0.1) def __init__(self): """ @@ -76,6 +78,7 @@ class CartPoleConfigModule(): @staticmethod def input_cost_fn(u): """ input cost functions + Args: u (numpy.ndarray): input, shape(pred_len, input_size) or shape(pop_size, pred_len, input_size) @@ -88,6 +91,7 @@ class CartPoleConfigModule(): @staticmethod def state_cost_fn(x, g_x): """ state cost function + Args: x (numpy.ndarray): state, shape(pred_len, state_size) or shape(pop_size, pred_len, state_size) @@ -118,6 +122,7 @@ class CartPoleConfigModule(): @staticmethod def terminal_state_cost_fn(terminal_x, terminal_g_x): """ + Args: terminal_x (numpy.ndarray): terminal state, shape(state_size, ) or shape(pop_size, state_size) @@ -133,13 +138,13 @@ class CartPoleConfigModule(): + 12. * ((np.cos(terminal_x[:, 2]) + 1.)**2) \ + 0.1 * (terminal_x[:, 1]**2) \ + 0.1 * (terminal_x[:, 3]**2))[:, np.newaxis] \ - * CartPoleConfigModule.Terminal_Weight + * CartPoleConfigModule.TERMINAL_WEIGHT return (6. * (terminal_x[0]**2) \ + 12. * ((np.cos(terminal_x[2]) + 1.)**2) \ + 0.1 * (terminal_x[1]**2) \ + 0.1 * (terminal_x[3]**2)) \ - * CartPoleConfigModule.Terminal_Weight + * CartPoleConfigModule.TERMINAL_WEIGHT @staticmethod def gradient_cost_fn_with_state(x, g_x, terminal=False): @@ -168,7 +173,7 @@ class CartPoleConfigModule(): cost_dx3 = 0.2 * x[3] cost_dx = np.array([[cost_dx0, cost_dx1, cost_dx2, cost_dx3]]) - return cost_dx * CartPoleConfigModule.Terminal_Weight + return cost_dx * CartPoleConfigModule.TERMINAL_WEIGHT @staticmethod def gradient_cost_fn_with_input(x, u): @@ -177,7 +182,6 @@ class CartPoleConfigModule(): Args: x (numpy.ndarray): state, shape(pred_len, state_size) u (numpy.ndarray): goal state, shape(pred_len, input_size) - Returns: l_u (numpy.ndarray): gradient of cost, shape(pred_len, input_size) """ @@ -190,7 +194,6 @@ class CartPoleConfigModule(): Args: x (numpy.ndarray): state, shape(pred_len, state_size) g_x (numpy.ndarray): goal state, shape(pred_len, state_size) - Returns: l_xx (numpy.ndarray): gradient of cost, shape(pred_len, state_size, state_size) or @@ -220,7 +223,7 @@ class CartPoleConfigModule(): * -np.cos(x[2]) hessian[3, 3] = 0.2 - return hessian[np.newaxis, :, :] * CartPoleConfigModule.Terminal_Weight + return hessian[np.newaxis, :, :] * CartPoleConfigModule.TERMINAL_WEIGHT @staticmethod def hessian_cost_fn_with_input(x, u): @@ -229,7 +232,6 @@ class CartPoleConfigModule(): Args: x (numpy.ndarray): state, shape(pred_len, state_size) u (numpy.ndarray): goal state, shape(pred_len, input_size) - Returns: l_uu (numpy.ndarray): gradient of cost, shape(pred_len, input_size, input_size) @@ -245,7 +247,6 @@ class CartPoleConfigModule(): Args: x (numpy.ndarray): state, shape(pred_len, state_size) u (numpy.ndarray): goal state, shape(pred_len, input_size) - Returns: l_ux (numpy.ndarray): gradient of cost , shape(pred_len, input_size, state_size) diff --git a/PythonLinearNonlinearControl/configs/make_configs.py b/PythonLinearNonlinearControl/configs/make_configs.py index 984df94..a48aedc 100644 --- a/PythonLinearNonlinearControl/configs/make_configs.py +++ b/PythonLinearNonlinearControl/configs/make_configs.py @@ -9,7 +9,7 @@ def make_config(args): """ if args.env == "FirstOrderLag": return FirstOrderLagConfigModule() - elif args.env == "TwoWheeledConst" or args.env == "TwoWheeled": + elif args.env == "TwoWheeledConst" or args.env == "TwoWheeledTrack": return TwoWheeledConfigModule() elif args.env == "CartPole": return CartPoleConfigModule() \ No newline at end of file diff --git a/PythonLinearNonlinearControl/configs/two_wheeled.py b/PythonLinearNonlinearControl/configs/two_wheeled.py index 8b79c87..93de72a 100644 --- a/PythonLinearNonlinearControl/configs/two_wheeled.py +++ b/PythonLinearNonlinearControl/configs/two_wheeled.py @@ -1,21 +1,37 @@ import numpy as np +from matplotlib.axes import Axes + +from ..plotters.plot_objs import square_with_angle, square +from ..common.utils import fit_angle_in_range class TwoWheeledConfigModule(): # parameters ENV_NAME = "TwoWheeled-v0" TYPE = "Nonlinear" + N_AHEAD = 1 TASK_HORIZON = 1000 PRED_LEN = 20 STATE_SIZE = 3 INPUT_SIZE = 2 DT = 0.01 # cost parameters + # for Const goal + """ R = np.diag([0.1, 0.1]) Q = np.diag([1., 1., 0.01]) Sf = np.diag([5., 5., 1.]) + """ + # for track goal + R = np.diag([0.01, 0.01]) + Q = np.diag([2.5, 2.5, 0.01]) + Sf = np.diag([2.5, 2.5, 0.01]) + # bounds - INPUT_LOWER_BOUND = np.array([-1.5, 3.14]) + INPUT_LOWER_BOUND = np.array([-1.5, -3.14]) INPUT_UPPER_BOUND = np.array([1.5, 3.14]) + # parameters + CAR_SIZE = 0.2 + WHEELE_SIZE = (0.075, 0.015) def __init__(self): """ @@ -78,6 +94,27 @@ class TwoWheeledConfigModule(): """ return (u**2) * np.diag(TwoWheeledConfigModule.R) + @staticmethod + def fit_diff_in_range(diff_x): + """ fit difference state in range(angle) + + Args: + diff_x (numpy.ndarray): + shape(pop_size, pred_len, state_size) or + shape(pred_len, state_size) or + shape(state_size, ) + Returns: + fitted_diff_x (numpy.ndarray): same shape as diff_x + """ + if len(diff_x.shape) == 3: + diff_x[:, :, -1] = fit_angle_in_range(diff_x[:, :, -1]) + elif len(diff_x.shape) == 2: + diff_x[:, -1] = fit_angle_in_range(diff_x[:, -1]) + elif len(diff_x.shape) == 1: + diff_x[-1] = fit_angle_in_range(diff_x[-1]) + + return diff_x + @staticmethod def state_cost_fn(x, g_x): """ state cost function @@ -90,7 +127,8 @@ class TwoWheeledConfigModule(): cost (numpy.ndarray): cost of state, shape(pred_len, state_size) or shape(pop_size, pred_len, state_size) """ - return ((x - g_x)**2) * np.diag(TwoWheeledConfigModule.Q) + diff = TwoWheeledConfigModule.fit_diff_in_range(x - g_x) + return ((diff)**2) * np.diag(TwoWheeledConfigModule.Q) @staticmethod def terminal_state_cost_fn(terminal_x, terminal_g_x): @@ -104,8 +142,10 @@ class TwoWheeledConfigModule(): cost (numpy.ndarray): cost of state, shape(pred_len, ) or shape(pop_size, pred_len) """ - return ((terminal_x - terminal_g_x)**2) \ - * np.diag(TwoWheeledConfigModule.Sf) + terminal_diff = TwoWheeledConfigModule.fit_diff_in_range(terminal_x \ + - terminal_g_x) + + return ((terminal_diff)**2) * np.diag(TwoWheeledConfigModule.Sf) @staticmethod def gradient_cost_fn_with_state(x, g_x, terminal=False): @@ -119,10 +159,12 @@ class TwoWheeledConfigModule(): l_x (numpy.ndarray): gradient of cost, shape(pred_len, state_size) or shape(1, state_size) """ - if not terminal: - return 2. * (x - g_x) * np.diag(TwoWheeledConfigModule.Q) + diff = TwoWheeledConfigModule.fit_diff_in_range(x - g_x) - return (2. * (x - g_x) \ + if not terminal: + return 2. * (diff) * np.diag(TwoWheeledConfigModule.Q) + + return (2. * (diff) \ * np.diag(TwoWheeledConfigModule.Sf))[np.newaxis, :] @staticmethod diff --git a/PythonLinearNonlinearControl/controllers/make_controllers.py b/PythonLinearNonlinearControl/controllers/make_controllers.py index 74d048c..d5ec8df 100644 --- a/PythonLinearNonlinearControl/controllers/make_controllers.py +++ b/PythonLinearNonlinearControl/controllers/make_controllers.py @@ -21,4 +21,6 @@ def make_controller(args, config, model): elif args.controller_type == "iLQR": return iLQR(config, model) elif args.controller_type == "DDP": - return DDP(config, model) \ No newline at end of file + return DDP(config, model) + + raise ValueError("No controller: {}".format(args.controller_type)) \ No newline at end of file diff --git a/PythonLinearNonlinearControl/controllers/mpc.py b/PythonLinearNonlinearControl/controllers/mpc.py index 766973c..ddf5840 100644 --- a/PythonLinearNonlinearControl/controllers/mpc.py +++ b/PythonLinearNonlinearControl/controllers/mpc.py @@ -1,7 +1,8 @@ from logging import getLogger import numpy as np -from cvxopt import matrix, solvers +from scipy.optimize import minimize +from scipy.optimize import LinearConstraint from .controller import Controller from ..envs.cost import calc_cost @@ -61,6 +62,7 @@ class LinearMPC(Controller): self.F = None self.f = None self.setup() + self.prev_sol = np.zeros(self.input_size*self.pred_len) # history self.history_u = [np.zeros(self.input_size)] @@ -183,6 +185,22 @@ class LinearMPC(Controller): ub = np.array(b).flatten() + # using cvxopt + def optimized_func(dt_us): + return (np.dot(dt_us, np.dot(H, dt_us.reshape(-1, 1))) \ + - np.dot(G.T, dt_us.reshape(-1, 1)))[0] + + # constraint + lb = np.array([-np.inf for _ in range(len(ub))]) # one side cons + cons = LinearConstraint(A, lb, ub) + # solve + opt_sol = minimize(optimized_func, self.prev_sol.flatten(),\ + constraints=[cons]) + opt_dt_us = opt_sol.x + + """ using cvxopt ver, + if you want to solve more quick please use cvxopt instead of scipy + # make cvxpy problem formulation P = 2*matrix(H) q = matrix(-1 * G) @@ -190,12 +208,15 @@ class LinearMPC(Controller): b = matrix(ub) # solve the problem - opt_result = solvers.qp(P, q, G=A, h=b) - opt_dt_us = np.array(list(opt_result['x'])) + opt_sol = solvers.qp(P, q, G=A, h=b) + opt_dt_us = np.array(list(opt_sol['x'])) + """ + # to dt form opt_dt_u_seq = np.cumsum(opt_dt_us.reshape(self.pred_len,\ self.input_size), axis=0) + self.prev_sol = opt_dt_u_seq.copy() opt_u_seq = opt_dt_u_seq + self.history_u[-1] diff --git a/PythonLinearNonlinearControl/envs/cartpole.py b/PythonLinearNonlinearControl/envs/cartpole.py index fb190e6..fd70d47 100644 --- a/PythonLinearNonlinearControl/envs/cartpole.py +++ b/PythonLinearNonlinearControl/envs/cartpole.py @@ -1,6 +1,8 @@ import numpy as np +from matplotlib.axes import Axes from .env import Env +from ..plotters.plot_objs import square class CartPoleEnv(Env): """ Cartpole Environment @@ -24,6 +26,7 @@ class CartPoleEnv(Env): "mc": 1., "l": 0.5, "g": 9.81, + "cart_size": (0.15, 0.1), } super(CartPoleEnv, self).__init__(self.config) @@ -112,4 +115,64 @@ class CartPoleEnv(Env): return next_x.flatten(), costs, \ self.step_count > self.config["max_step"], \ - {"goal_state" : self.g_x} \ No newline at end of file + {"goal_state" : self.g_x} + + def plot_func(self, to_plot, i=None, history_x=None, history_g_x=None): + """ plot cartpole object function + + Args: + to_plot (axis or imgs): plotted objects + i (int): frame count + history_x (numpy.ndarray): history of state, shape(iters, state) + history_g_x (numpy.ndarray): history of goal state, + shape(iters, state) + Returns: + None or imgs : imgs order is ["cart_img", "pole_img"] + """ + if isinstance(to_plot, Axes): + imgs = {} # create new imgs + + imgs["cart"] = to_plot.plot([], [], c="k")[0] + imgs["pole"] = to_plot.plot([], [], c="k", linewidth=5)[0] + imgs["center"] = to_plot.plot([], [], marker="o", c="k",\ + markersize=10)[0] + # centerline + to_plot.plot(np.linspace(-1., 1., num=50), np.zeros(50),\ + c="k", linestyle="dashed") + + # set axis + to_plot.set_xlim([-1., 1.]) + to_plot.set_ylim([-0.55, 1.5]) + + return imgs + + # set imgs + cart_x, cart_y, pole_x, pole_y = \ + self._plot_cartpole(history_x[i]) + + to_plot["cart"].set_data(cart_x, cart_y) + to_plot["pole"].set_data(pole_x, pole_y) + to_plot["center"].set_data(history_x[i][0], 0.) + + def _plot_cartpole(self, curr_x): + """ plot cartpole fucntions + + Args: + curr_x (numpy.ndarray): current catpole state + Returns: + cart_x (numpy.ndarray): x data of cart + cart_y (numpy.ndarray): y data of cart + pole_x (numpy.ndarray): x data of pole + pole_y (numpy.ndarray): y data of pole + """ + # cart + cart_x, cart_y = square(curr_x[0], 0.,\ + self.config["cart_size"], 0.) + + # pole + pole_x = np.array([curr_x[0], curr_x[0] + self.config["l"] \ + * np.cos(curr_x[2]-np.pi/2)]) + pole_y = np.array([0., self.config["l"] \ + * np.sin(curr_x[2]-np.pi/2)]) + + return cart_x, cart_y, pole_x, pole_y \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/env.py b/PythonLinearNonlinearControl/envs/env.py index c8ace4b..4f63903 100644 --- a/PythonLinearNonlinearControl/envs/env.py +++ b/PythonLinearNonlinearControl/envs/env.py @@ -1,8 +1,9 @@ import numpy as np class Env(): - """ + """ Environments class Attributes: + curr_x (numpy.ndarray): current state history_x (list[numpy.ndarray]): historty of state, shape(step_count*state_size) step_count (int): step count @@ -48,7 +49,7 @@ class Env(): """ raise NotImplementedError("Implement step function") - def __str__(self): + def __repr__(self): """ """ return self.config \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/first_order_lag.py b/PythonLinearNonlinearControl/envs/first_order_lag.py index 7da07b8..5597a07 100644 --- a/PythonLinearNonlinearControl/envs/first_order_lag.py +++ b/PythonLinearNonlinearControl/envs/first_order_lag.py @@ -112,4 +112,9 @@ class FirstOrderLagEnv(Env): return next_x.flatten(), cost, \ self.step_count > self.config["max_step"], \ - {"goal_state" : self.g_x} \ No newline at end of file + {"goal_state" : self.g_x} + + def plot_func(self, to_plot, i=None, history_x=None, history_g_x=None): + """ + """ + raise ValueError("FirstOrderLag does not have animation") \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/make_envs.py b/PythonLinearNonlinearControl/envs/make_envs.py index 4b1adf7..253f3ed 100644 --- a/PythonLinearNonlinearControl/envs/make_envs.py +++ b/PythonLinearNonlinearControl/envs/make_envs.py @@ -1,5 +1,6 @@ from .first_order_lag import FirstOrderLagEnv from .two_wheeled import TwoWheeledConstEnv +from .two_wheeled import TwoWheeledTrackEnv from .cartpole import CartPoleEnv def make_env(args): @@ -8,6 +9,8 @@ def make_env(args): return FirstOrderLagEnv() elif args.env == "TwoWheeledConst": return TwoWheeledConstEnv() + elif args.env == "TwoWheeledTrack": + return TwoWheeledTrackEnv() elif args.env == "CartPole": return CartPoleEnv() diff --git a/PythonLinearNonlinearControl/envs/two_wheeled.py b/PythonLinearNonlinearControl/envs/two_wheeled.py index 8be0d36..43f5f0c 100644 --- a/PythonLinearNonlinearControl/envs/two_wheeled.py +++ b/PythonLinearNonlinearControl/envs/two_wheeled.py @@ -1,6 +1,9 @@ import numpy as np +from matplotlib.axes import Axes +import matplotlib.pyplot as plt from .env import Env +from ..plotters.plot_objs import circle_with_angle, square, circle def step_two_wheeled_env(curr_x, u, dt, method="Oylar"): """ step two wheeled enviroment @@ -34,9 +37,11 @@ class TwoWheeledConstEnv(Env): self.config = {"state_size" : 3,\ "input_size" : 2,\ "dt" : 0.01,\ - "max_step" : 1000,\ - "input_lower_bound": [-1.5, -3.14],\ - "input_upper_bound": [1.5, 3.14], + "max_step" : 500,\ + "input_lower_bound": (-1.5, -3.14),\ + "input_upper_bound": (1.5, 3.14),\ + "car_size": 0.2,\ + "wheel_size": (0.075, 0.015) } super(TwoWheeledConstEnv, self).__init__(self.config) @@ -99,4 +104,279 @@ class TwoWheeledConstEnv(Env): return next_x.flatten(), costs, \ self.step_count > self.config["max_step"], \ - {"goal_state" : self.g_x} \ No newline at end of file + {"goal_state" : self.g_x} + + def plot_func(self, to_plot, i=None, history_x=None, history_g_x=None): + """ plot cartpole object function + + Args: + to_plot (axis or imgs): plotted objects + i (int): frame count + history_x (numpy.ndarray): history of state, shape(iters, state) + history_g_x (numpy.ndarray): history of goal state, + shape(iters, state) + + Returns: + None or imgs : imgs order is ["cart_img", "pole_img"] + """ + if isinstance(to_plot, Axes): + imgs = {} # create new imgs + + imgs["car"] = to_plot.plot([], [], c="k")[0] + imgs["car_angle"] = to_plot.plot([], [], c="k")[0] + imgs["left_tire"] = to_plot.plot([], [], c="k", linewidth=5)[0] + imgs["right_tire"] = to_plot.plot([], [], c="k", linewidth=5)[0] + imgs["goal"] = to_plot.plot([], [], marker="*", + c="b", markersize=10)[0] + imgs["traj"] = to_plot.plot([], [], c="b", linestyle="dashed")[0] + + # set axis + to_plot.set_xlim([-1., 3.]) + to_plot.set_ylim([-1., 3.]) + + return imgs + + # set imgs + # car imgs + car_x, car_y, car_angle_x, car_angle_y, \ + left_tire_x, left_tire_y, right_tire_x, right_tire_y = \ + self._plot_car(history_x[i]) + + to_plot["car"].set_data(car_x, car_y) + to_plot["car_angle"].set_data(car_angle_x, car_angle_y) + to_plot["left_tire"].set_data(left_tire_x, left_tire_y,) + to_plot["right_tire"].set_data(right_tire_x, right_tire_y) + + # goal and trajs + to_plot["goal"].set_data(history_g_x[i, 0], history_g_x[i, 1]) + to_plot["traj"].set_data(history_x[:i, 0], history_x[:i, 1]) + + def _plot_car(self, curr_x): + """ plot car fucntions + """ + # cart + car_x, car_y, car_angle_x, car_angle_y = \ + circle_with_angle(curr_x[0], curr_x[1], + self.config["car_size"], curr_x[2]) + + # left tire + center_x = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.cos(curr_x[2]-np.pi/2.) + curr_x[0] + center_y = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.sin(curr_x[2]-np.pi/2.) + curr_x[1] + + left_tire_x, left_tire_y = \ + square(center_x, center_y, + self.config["wheel_size"], curr_x[2]) + + # right tire + center_x = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.cos(curr_x[2]+np.pi/2.) + curr_x[0] + center_y = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.sin(curr_x[2]+np.pi/2.) + curr_x[1] + + right_tire_x, right_tire_y = \ + square(center_x, center_y, + self.config["wheel_size"], curr_x[2]) + + return car_x, car_y, car_angle_x, car_angle_y,\ + left_tire_x, left_tire_y,\ + right_tire_x, right_tire_y + +class TwoWheeledTrackEnv(Env): + """ Two wheeled robot with constant goal Env + """ + def __init__(self): + """ + """ + self.config = {"state_size" : 3,\ + "input_size" : 2,\ + "dt" : 0.01,\ + "max_step" : 1000,\ + "input_lower_bound": (-1.5, -3.14),\ + "input_upper_bound": (1.5, 3.14),\ + "car_size": 0.2,\ + "wheel_size": (0.075, 0.015) + } + + super(TwoWheeledTrackEnv, self).__init__(self.config) + + @staticmethod + def make_road(linelength=3., circle_radius=1.): + """ make track + + Returns: + road (numpy.ndarray): road info, shape(n_point, 3) x, y, angle + """ + # line + # not include start points + line = np.linspace(-1.5, 1.5, num=51, endpoint=False)[1:] + line_1 = np.stack((line, np.zeros(50)), axis=1) + line_2 = np.stack((line[::-1], np.zeros(50)+circle_radius*2.), axis=1) + + # circle + circle_1_x, circle_1_y = circle(linelength/2., circle_radius, + circle_radius, start=-np.pi/2., end=np.pi/2., n_point=50) + circle_1 = np.stack((circle_1_x , circle_1_y), axis=1) + + circle_2_x, circle_2_y = circle(-linelength/2., circle_radius, + circle_radius, start=np.pi/2., end=3*np.pi/2., n_point=50) + circle_2 = np.stack((circle_2_x , circle_2_y), axis=1) + + road_pos = np.concatenate((line_1, circle_1, line_2, circle_2), axis=0) + + # calc road angle + road_diff = road_pos[1:] - road_pos[:-1] + road_angle = np.arctan2(road_diff[:, 1], road_diff[:, 0]) + road_angle = np.concatenate((np.zeros(1), road_angle)) + + road = np.concatenate((road_pos, road_angle[:, np.newaxis]), axis=1) + + return np.tile(road, (3, 1)) + + def reset(self, init_x=None): + """ reset state + + Returns: + init_x (numpy.ndarray): initial state, shape(state_size, ) + info (dict): information + """ + self.step_count = 0 + + self.curr_x = np.zeros(self.config["state_size"]) + + if init_x is not None: + self.curr_x = init_x + + # goal + self.g_traj = self.make_road() + + # clear memory + self.history_x = [] + self.history_g_x = [] + + return self.curr_x, {"goal_state": self.g_traj} + + def step(self, u): + """ step environments + + Args: + u (numpy.ndarray) : input, shape(input_size, ) + Returns: + next_x (numpy.ndarray): next state, shape(state_size, ) + cost (float): costs + done (bool): end the simulation or not + info (dict): information + """ + # clip action + u = np.clip(u, + self.config["input_lower_bound"], + self.config["input_upper_bound"]) + + # step + next_x = step_two_wheeled_env(self.curr_x, u, self.config["dt"]) + + costs = 0. + costs += 0.1 * np.sum(u**2) + costs += np.min(np.linalg.norm(self.curr_x - self.g_traj, axis=1)) + + # save history + self.history_x.append(next_x.flatten()) + + # update + self.curr_x = next_x.flatten() + # update costs + self.step_count += 1 + + return next_x.flatten(), costs, \ + self.step_count > self.config["max_step"], \ + {"goal_state" : self.g_traj} + + def plot_func(self, to_plot, i=None, history_x=None, history_g_x=None): + """ plot cartpole object function + + Args: + to_plot (axis or imgs): plotted objects + i (int): frame count + history_x (numpy.ndarray): history of state, shape(iters, state) + history_g_x (numpy.ndarray): history of goal state, + shape(iters, state) + + Returns: + None or imgs : imgs order is ["cart_img", "pole_img"] + """ + if isinstance(to_plot, Axes): + imgs = {} # create new imgs + + imgs["car"] = to_plot.plot([], [], c="k")[0] + imgs["car_angle"] = to_plot.plot([], [], c="k")[0] + imgs["left_tire"] = to_plot.plot([], [], c="k", linewidth=5)[0] + imgs["right_tire"] = to_plot.plot([], [], c="k", linewidth=5)[0] + imgs["goal"] = to_plot.plot([], [], marker="*", + c="b", markersize=10)[0] + imgs["traj"] = to_plot.plot([], [], c="b", linestyle="dashed")[0] + + # set axis + to_plot.set_xlim([-3., 3.]) + to_plot.set_ylim([-1., 3.]) + + # plot road + to_plot.plot(self.g_traj[:, 0], self.g_traj[:, 1], + c="k", linestyle="dashed") + + return imgs + + # set imgs + # car imgs + car_x, car_y, car_angle_x, car_angle_y, \ + left_tire_x, left_tire_y, right_tire_x, right_tire_y = \ + self._plot_car(history_x[i]) + + to_plot["car"].set_data(car_x, car_y) + to_plot["car_angle"].set_data(car_angle_x, car_angle_y) + to_plot["left_tire"].set_data(left_tire_x, left_tire_y,) + to_plot["right_tire"].set_data(right_tire_x, right_tire_y) + + # goal and trajs + to_plot["goal"].set_data(history_g_x[i, 0], history_g_x[i, 1]) + to_plot["traj"].set_data(history_x[:i, 0], history_x[:i, 1]) + + def _plot_car(self, curr_x): + """ plot car fucntions + """ + # cart + car_x, car_y, car_angle_x, car_angle_y = \ + circle_with_angle(curr_x[0], curr_x[1], + self.config["car_size"], curr_x[2]) + + # left tire + center_x = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.cos(curr_x[2]-np.pi/2.) + curr_x[0] + center_y = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.sin(curr_x[2]-np.pi/2.) + curr_x[1] + + left_tire_x, left_tire_y = \ + square(center_x, center_y, + self.config["wheel_size"], curr_x[2]) + + # right tire + center_x = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.cos(curr_x[2]+np.pi/2.) + curr_x[0] + center_y = (self.config["car_size"] \ + + self.config["wheel_size"][1]) \ + * np.sin(curr_x[2]+np.pi/2.) + curr_x[1] + + right_tire_x, right_tire_y = \ + square(center_x, center_y, + self.config["wheel_size"], curr_x[2]) + + return car_x, car_y, car_angle_x, car_angle_y,\ + left_tire_x, left_tire_y,\ + right_tire_x, right_tire_y \ No newline at end of file diff --git a/PythonLinearNonlinearControl/models/make_models.py b/PythonLinearNonlinearControl/models/make_models.py index fcb29ae..fb628ad 100644 --- a/PythonLinearNonlinearControl/models/make_models.py +++ b/PythonLinearNonlinearControl/models/make_models.py @@ -6,7 +6,7 @@ def make_model(args, config): if args.env == "FirstOrderLag": return FirstOrderLagModel(config) - elif args.env == "TwoWheeledConst" or args.env == "TwoWheeled": + elif args.env == "TwoWheeledConst" or args.env == "TwoWheeledTrack": return TwoWheeledModel(config) elif args.env == "CartPole": return CartPoleModel(config) diff --git a/PythonLinearNonlinearControl/planners/closest_point_planner.py b/PythonLinearNonlinearControl/planners/closest_point_planner.py new file mode 100644 index 0000000..291aff3 --- /dev/null +++ b/PythonLinearNonlinearControl/planners/closest_point_planner.py @@ -0,0 +1,39 @@ +import numpy as np +from .planner import Planner + +class ClosestPointPlanner(Planner): + """ This planner make goal state according to goal path + """ + def __init__(self, config): + """ + """ + super(ClosestPointPlanner, self).__init__() + self.pred_len = config.PRED_LEN + self.state_size = config.STATE_SIZE + self.n_ahead = config.N_AHEAD + + def plan(self, curr_x, g_traj): + """ + Args: + curr_x (numpy.ndarray): current state, shape(state_size) + g_x (numpy.ndarray): goal state, shape(state_size), + this state should be obtained from env + Returns: + g_xs (numpy.ndarrya): goal state, shape(pred_len+1, state_size) + """ + min_idx = np.argmin(np.linalg.norm(curr_x[:-1] - g_traj[:, :-1], + axis=1)) + + start = (min_idx+self.n_ahead) + if start > len(g_traj): + start = len(g_traj) + + end = min_idx+self.n_ahead+self.pred_len+1 + + if (min_idx+self.n_ahead+self.pred_len+1) > len(g_traj): + end = len(g_traj) + + if abs(start - end) != self.pred_len + 1: + return np.tile(g_traj[-1], (self.pred_len+1, 1)) + + return g_traj[start:end] \ No newline at end of file diff --git a/PythonLinearNonlinearControl/planners/const_planner.py b/PythonLinearNonlinearControl/planners/const_planner.py index 5806c62..a0569a2 100644 --- a/PythonLinearNonlinearControl/planners/const_planner.py +++ b/PythonLinearNonlinearControl/planners/const_planner.py @@ -1,7 +1,7 @@ import numpy as np from .planner import Planner -class ConstantPlanner(): +class ConstantPlanner(Planner): """ This planner make constant goal state """ def __init__(self, config): diff --git a/PythonLinearNonlinearControl/planners/make_planners.py b/PythonLinearNonlinearControl/planners/make_planners.py index 9da7f31..9f18e51 100644 --- a/PythonLinearNonlinearControl/planners/make_planners.py +++ b/PythonLinearNonlinearControl/planners/make_planners.py @@ -1,8 +1,15 @@ from .const_planner import ConstantPlanner +from .closest_point_planner import ClosestPointPlanner def make_planner(args, config): - if args.planner_type == "const": + if args.env == "FirstOrderLag": + return ConstantPlanner(config) + elif args.env == "TwoWheeledConst": + return ConstantPlanner(config) + elif args.env == "TwoWheeledTrack": + return ClosestPointPlanner(config) + elif args.env == "CartPole": return ConstantPlanner(config) raise NotImplementedError("There is not {} Planner".format(args.planner_type)) \ No newline at end of file diff --git a/PythonLinearNonlinearControl/plotters/animator.py b/PythonLinearNonlinearControl/plotters/animator.py new file mode 100644 index 0000000..8446229 --- /dev/null +++ b/PythonLinearNonlinearControl/plotters/animator.py @@ -0,0 +1,74 @@ +import os +from logging import getLogger + +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.animation import FuncAnimation + +logger = getLogger(__name__) + +class Animator(): + """ animation class + """ + def __init__(self, args, env): + """ + """ + self.env_name = args.env + self.result_dir = args.result_dir + self.controller_type = args.controller_type + + self.interval = env.config["dt"] * 1000. # to ms + self.plot_func = env.plot_func + + self.imgs = [] + + def _setup(self): + """ set up figure of animation + """ + # make fig + self.anim_fig = plt.figure() + + # axis + self.axis = self.anim_fig.add_subplot(111) + self.axis.set_aspect('equal', adjustable='box') + + self.imgs = self.plot_func(self.axis) + + def _update_img(self, i, history_x, history_g_x): + """ update animation + + Args: + i (int): frame count + history_x (numpy.ndarray): history of state, + shape(iters, state_size) + history_g (numpy.ndarray): history of goal state, + shape(iters, input_size) + """ + self.plot_func(self.imgs, i, history_x, history_g_x) + + def draw(self, history_x, history_g_x=None): + """draw the animation and save + + Args: + history_x (numpy.ndarray): history of state, + shape(iters, state_size) + history_g (numpy.ndarray): history of goal state, + shape(iters, input_size) + Returns: + None + """ + # set up animation figures + self._setup() + _update_img = lambda i: self._update_img(i, history_x, history_g_x) + + # call funcanimation + animation = FuncAnimation( + self.anim_fig, + _update_img, interval=self.interval, frames=len(history_x)-1) + + # save animation + path = os.path.join(self.result_dir, self.controller_type, + "animation-" + self.env_name + ".mp4") + logger.info("Saved Animation to {} ...".format(path)) + + animation.save(path, writer="ffmpeg") \ No newline at end of file diff --git a/PythonLinearNonlinearControl/plotters/plot_objs.py b/PythonLinearNonlinearControl/plotters/plot_objs.py new file mode 100644 index 0000000..911cb5f --- /dev/null +++ b/PythonLinearNonlinearControl/plotters/plot_objs.py @@ -0,0 +1,99 @@ +import os + +import numpy as np +import matplotlib.pyplot as plt + +from ..common.utils import rotate_pos + +def circle(center_x, center_y, radius, start=0., end=2*np.pi, n_point=100): + """ Create circle matrix + + Args: + center_x (float): the center x position of the circle + center_y (float): the center y position of the circle + radius (float): in meters + start (float): start angle + end (float): end angle + Returns: + circle x : numpy.ndarray + circle y : numpy.ndarray + """ + diff = end - start + + circle_xs = [] + circle_ys = [] + + for i in range(n_point + 1): + circle_xs.append(center_x + radius * np.cos(i*diff/n_point + start)) + circle_ys.append(center_y + radius * np.sin(i*diff/n_point + start)) + + return np.array(circle_xs), np.array(circle_ys) + +def circle_with_angle(center_x, center_y, radius, angle): + """ Create circle matrix with angle line matrix + + Args: + center_x (float): the center x position of the circle + center_y (float): the center y position of the circle + radius (float): in meters + angle (float): in radians + Returns: + circle_x (numpy.ndarray): x data of circle + circle_y (numpy.ndarray): y data of circle + angle_x (numpy.ndarray): x data of circle angle + angle_y (numpy.ndarray): y data of circle angle + """ + circle_x, circle_y = circle(center_x, center_y, radius) + + angle_x = np.array([center_x, center_x + np.cos(angle) * radius]) + angle_y = np.array([center_y, center_y + np.sin(angle) * radius]) + + return circle_x, circle_y, angle_x, angle_y + +def square(center_x, center_y, shape, angle): + """ Create square + + Args: + center_x (float): the center x position of the square + center_y (float): the center y position of the square + shape (tuple): the square's shape(width/2, height/2) + angle (float): in radians + Returns: + square_x (numpy.ndarray): shape(5, ), counterclockwise from right-up + square_y (numpy.ndarray): shape(5, ), counterclockwise from right-up + """ + # start with the up right points + # create point in counterclockwise, local + square_xy = np.array([[shape[0], shape[1]], + [-shape[0], shape[1]], + [-shape[0], -shape[1]], + [shape[0], -shape[1]], + [shape[0], shape[1]]]) + # translate position to world + # rotation + trans_points = rotate_pos(square_xy, angle) + # translation + trans_points += np.array([center_x, center_y]) + + return trans_points[:, 0], trans_points[:, 1] + +def square_with_angle(center_x, center_y, shape, angle): + """ Create square with angle line + + Args: + center_x (float): the center x position of the square + center_y (float): the center y position of the square + shape (tuple): the square's shape(width/2, height/2) + angle (float): in radians + Returns: + square_x (numpy.ndarray): shape(5, ), counterclockwise from right-up + square_y (numpy.ndarray): shape(5, ), counterclockwise from right-up + angle_x (numpy.ndarray): x data of square angle + angle_y (numpy.ndarray): y data of square angle + """ + square_x, square_y = square(center_x, center_y, shape, angle) + + angle_x = np.array([center_x, center_x + np.cos(angle) * shape[0]]) + angle_y = np.array([center_y, center_y + np.sin(angle) * shape[1]]) + + return square_x, square_y, angle_x, angle_y \ No newline at end of file diff --git a/PythonLinearNonlinearControl/runners/runner.py b/PythonLinearNonlinearControl/runners/runner.py index 0c55bb9..4ef0c6b 100644 --- a/PythonLinearNonlinearControl/runners/runner.py +++ b/PythonLinearNonlinearControl/runners/runner.py @@ -29,7 +29,7 @@ class ExpRunner(): while not done: logger.debug("Step = {}".format(step_count)) # plan - g_xs = planner.plan(curr_x, g_x=info["goal_state"]) + g_xs = planner.plan(curr_x, info["goal_state"]) # obtain sol u = controller.obtain_sol(curr_x, g_xs) diff --git a/README.md b/README.md index 7bb14b1..bcb9485 100644 --- a/README.md +++ b/README.md @@ -5,8 +5,13 @@ # PythonLinearNonLinearControl PythonLinearNonLinearControl is a library implementing the linear and nonlinear control theories in python. +Due to use only basic libralies (scipy, numpy), this library is also easily to extend for your own situations. - +
+ + + + # Algorithms @@ -24,7 +29,6 @@ PythonLinearNonLinearControl is a library implementing the linear and nonlinear | Constrained Nonlinear Model Predictive Control Newton (NMPC-Newton) | x | ✓ | x | x | x | "Need Gradient" means that you have to implement the gradient of the model or the gradient of hamiltonian. -This library is also easily to extend for your own situations. Following algorithms are implemented in PythonLinearNonlinearControl @@ -61,11 +65,13 @@ Following algorithms are implemented in PythonLinearNonlinearControl # Environments +There are 4 example environments, "FirstOrderLag", "TwoWheeledConst", "TwoWheeledTrack" and "Cartpole". + | Name | Linear | Nonlinear | State Size | Input size | |:----------|:---------------:|:----------------:|:----------------:|:----------------:| | First Order Lag System | ✓ | x | 4 | 2 | | Two wheeled System (Constant Goal) | x | ✓ | 3 | 2 | -| Two wheeled System (Moving Goal) (Coming soon) | x | ✓ | 3 | 2 | +| Two wheeled System (Moving Goal) | x | ✓ | 3 | 2 | | Cartpole (Swing up) | x | ✓ | 4 | 1 | All states and inputs of environments are continuous. @@ -104,7 +110,7 @@ pip install -e . You can run the experiments as follows: ``` -python scripts/simple_run.py --env first-order_lag --controller CEM +python scripts/simple_run.py --env FirstOrderLag --controller CEM ``` **figures and animations are saved in the ./result folder.** @@ -147,9 +153,9 @@ Coming soon !! # Requirements - numpy -- matplotlib -- cvxopt - scipy +- matplotlib (for figures and animations) +- ffmpeg (for animations) # License diff --git a/assets/cartpole.gif b/assets/cartpole.gif new file mode 100644 index 0000000000000000000000000000000000000000..0b40fb4032b94037c6465fa1aaeab76e0910bc9e GIT binary patch literal 59794 zcmeFYWl$Vnzwg^egC(nP^JYtH72mp)#pa=kl01yZOi2zXl z3=cvAU?c!V0x%?iKmtf4fcj@nAQS*b0ZtP+$lEg@B+C zFcboXLSRq`0t!JwAt)#WfI&bo2p9%|!XPjh1ObB}VGtAy0w5qD1O$wLKoJla0)jw5 zkO&A00RfN@5E24LLZCvf(&nK`=NN28Y7nFc=&GgCk*Z6bud^;2;DX zjDSNCa2NuPK){g*I0^v=kZ=$Z4o1SENH`1$Mxv@QD8IxMT4MdFcb}iqG3=p0*XdL(I_YyfT2M!G#G}4!q6}n8UaHi zVQ3T#4It1U1R9J$LlI~g0*yeRkq9&jfd-Ih5E2bWqM=AM42eb{(MTj3g+v1=Gzf(T zqtH+k8iqn6P-r9yjY6Rr(S+*qI@+?*8uI+Sd{`KN1;u!WjZFYN1GxX*1OHkk03I3$ z{6hmi|JWCT^@K@BAI2yhiBGJMiZ@dr7fbqF_iIIi)u%*4@d)f?4Qr+3Cu(JKB5oxU zDbMvjLGhc)RC5Ge4kyQ+epme{9DGW;lESP~1dhMgp-w%}D3^yQh!b2FEmY|@Ij)U2 zS1r|<55~}`v{WxQ+0VgECR%D%TV218=c%;Tu66qSI9!`(t^3v+ghfcN+E%|g81Y{e8!lW7mP2|RuHoG z;%f_*Crly1Kj&0bcq6~o=qmg`4jJ8BV!ZK!V*$v0I| z9QS%1Y?UC6dGI|!7MFuDiI=r#5svu$$xhiDNI$a$>+t3p`|At~h@8gRRhDh$qQPA_n`XTa<)eYk`<;E|@`RY)O zlZt83AD@Nys((zqj-BM6kZzB2n|Se5?Z=ShH1uj#2G>586d(99F5dzW2?79-^%D+V zHVc($^H-~nscOIhnqmObDps7J83UlYfnxM6Su6!qEt5e0B#Ps)pc`<$p+WW0i(VAG z`m?fn*Z_we77QEE^8XVn?t^ZM#%AIO6P{Ie;T716p4j%C*@)Nom2QDqs&KihNW7A^ z2DuS`L!3GLowR+c^*il4JM}y3L-YEd4?S`5zZiX1=YKi*{LKHy7s=-VSMzVqIycSo z-lkz|9Y2y1!#3faVb#xYxxd>lue<+s+YjX_77qh1WvEtQ5ihG5AG=fx((j%}zQ*2qjE>wNWS~xplHq0|Nvs%R zWxa?dp|aR3^Qi@ziyf_jZ<3?+Qv9$1`WgnTb#M}}AYJ425T&>X?1QjpTfD3~N~BSQjc&Z97xJG3gn@ss81-EM|*ix}&}+pQVFU;-no7etY^u@|*Rn$ii~5DduU$322{p zElb1WaY`-$oqhiP-88W#q6nH*Ci#MZA;A5LXGLyX5sUN-n-Zc>E@WS6B3diG!?W;d zCz~pr;qWUH&k~Fd4)tlKxx8N^#S&^NU`;BW->EuETzMSHc$k{m3IbU?kVBQ=h4~8B zv@Az%c#tQ2q0Syrg~s62AK{;GINhsY2s_k?FV$*RzOGShUe9UK}dqql&bYGFH{ggfjEF3E&!IeM!IwOIn~G*W_DdXGBbRP1P;IV*V84PPMcf!_;!iwT z;?`DmZ`hhkPs2im7>sX{-O>lCf36FUVLoYl^)0+O^1-ZGUvm*z3!V!J!+=nzhI%L4 zO}uMEyCuK+qof=5V!0vv9@^(4Lu{hwm84r1wFksZALj5*s;f2$TyDp8ryAc>sBRK| z#LF zd04o_9c~^Y+sfZITUv@Uz0vcX$Ys4Qcdj`yl8u}o$IZ^O=Q$dvFs!fUy>T%WUjev` zgomc~YReyyuqq}m^_O|owbG?(+WlVih`DLP@Hp;e_50dsA>=w7f7)B`Cxv|6+$>ge z;^JYnzKto=L+4lS-D>oFXZNTb9YFKWdvO{2TYRrHsmt-y@Aa#jcilhZIbF2B4s5Cm zXQTbMf}M+PMEX$?L{ovU`z&hx(!os|zbNqH{*UFyx`=g-+cDxM{LXQOXlSSz~zC~DI1!tB?V zk^6VD;d#eU>YK$UFRvSP15Q3{iZlkiRcZTOdW0d<=|JD*UAAj@#;qs1kzwQ3-${1p zMWMRd|LbN*<>}Fazu`P7wDZzXZPJ^zZV3_MJ(5xS<2Ti7rvZJl7;KSVW2Z=|@x_QX zjNl=D5x->?b-$=s6HsGa_pqws9ZzG%3}M{mI%SvL^aIM={#^QVWatk37+rS42ZU38m^~^k#hUg((*G zULmvvOA6i}G~4UXKUNnavS9UPB6Fbf@z!t;RMiyP4V57V+a;!8YkLs+cuFZJ`Q7LR z2Db*@d6>tr`JAFMscSZY|-&KGn%Sy?-Z}LQ9a}z@D!^o&3VG3M-wa zA(d`91t%-XygWfdB-Lo=LwZUIj;5jwtCS_ko~u3VS|5xL%2W;a#nTL?+YF07ATy|Z zX*%`_-#oYw5n#ib78@3x<`BuVoFOfv0B^$ia7Cz9FT(-KG(d=w@L9b?q`a?8r_ahz zwab1(!SDwMASqBJ21~7^U~6Kf8wICx-KL@i0*Vg|O64T&<1%nEt!Kmx!b;3$T{WXXr&^hd?MZKua$=PJ~>^>c{kA(YTh4}Jz(d) zN=pZ-`v!T32N8p}A4?qEQ3ie+?FBy$3S8SHA@QZXWibjJ!(!4C>5G^7aFABCV zdTCcE+@T~ouJCfaa2MZ@*tg_awyyM{>xWmR?3^W%q5@pXC1qP58K{eI5hZB`#nNdd zpX|zp`-?5NiuG5@jNg}%bmSR~Cnyk<;vwxUvooy^wa@TB+IJL7!8Ka&%fsMhZSAGu z<0`J0WlrePip$h;uJ&@V>+)#D$^nZC!SBZIhh@=@rS_v`E}Z!c$)SciM11-ZhO*X5 zL00JJ{K010D}jnk-daic0v`6c0~)+St;tHH zbwCut++c}|?HuHnLk)j2QQ3tH&oeB<(n@u=vI}jJuK^U?v4sEFC}373-gnevVWs3m z)}NvG>_Im<4~BfZ;N?ArZ*(ZhCk*o*`Bl=z8W~u4nitk6(lo9eHhA6Eys3I&`o56A zs_@>CSYC`zyb5gKSFGMx!`IrNPS~7JUBTcN_&vHMD+L`Z8XM!KjJ zXxG`gG2W2#skL*j$ZWNRbFtags8uwyO|ZPJ-L3UQa*Ntgo6YYw>xp8g-=%JZhAuS8 z$uZh-zui9OyiKYS`0EU1tB6vujx1`n!rv}oRV5J}b$$U2TuFIiTCJ;ZC!A=?#po(0IzP~KsZ(^%=Xh0%wKY{4~XfwC}{W4*Hc0$BM75!p6k-6>fbc6%m)wJ(;)>@BO-g$=*oL z=I%~o7WXbwnx=0?uLKDFyg?Yk6Sab4GI(*Y>!TOuVO1=#L`DUoCk(HaIB{a+y+ zchYqktI%I?;d2D|8g=B1M5zaL6klJYrVNRRDgS}MVc40ihSu-A3l+LJIH5#eMAJ-Z zvvLh&$I1|gexIg|+_3!z*GL#-UK1rp6KxlpM{ZkOIC%%>^19m+ZhyCp-L+0Z|4{HI zw`$_(BGT=@^BJa32_0|<3W*SO9kd_Gs^`%ERD(ONS3Zcs?7~zXcZYh3(Dtnc8?11R z<7y9kDUV%Vm3R?MguNK4&@6I`8}F&kS@auca$?nHtAn7MN8RHP2FWY6&9WHFP!Ra86QARpHw?9seXQHGmY2&*?jJ^;;+v{(bEr@$5e}^1N*1VD93tL zqcjk5)F-kjvNK!7 znNzHoLpQ5A%1wvLB`x?{V8v(XH|gqQjnJQv$j9d_$FaSlqtvXK#a)9CsIe*WERdXZ zLFjZgkBfNb^BX~nEOAm&bThwczFfIaeKB@(8uE7iBWDmWqd7cva2$T7Iy>mKcy>ES zln3Hkd&zSG@;G@55Y0LB&&^ydRQtWLHc@FJU5*l1(BPQ|oIl@JF9y2L%WG8~Ya&(R zsnwiI->kW;bqc<>?tZC9_coG_yw?@JmjZNW$evPW7>aE#B5iE7jCPFu7^+d_$Gr8K z`{le!6W!cHX^|7GKv!D%rkZ#%aXDShb!E+U!(gP+Dw(MD5~B$XhL+j0Np;62;hTE1 zvjJcer~fsLMJSR}xAkyw2UJPB;f{~!_gUA$H8;sDD| zZR!Z?#aZ9-5efR}nD?Bi>~!y*FwyEfK#u5K;^5i0Q*t!M<%-;otbnEOj~Kp>*M?*T zSYJIk`gJk0BxcYwmyDR}Zc+k&oKyTZr&L$}Z0c%Y?n=ewD&^_5+_OdfUa?DNYnC3d zM)m93t1D~CYpv%u!^KzXE;lwVSJ3Cz?Jw7SXEOr^v({UGjON!rdhs2RXGj!bEQr`Y zw+a>PnR=g2F_3fXR`|`G@uyEw-H5W($*(5^KZOuj+4$UF)8!U(&A#^4+ysb!;y~u# z%PpG_pPw`1(9k=mWPfEE+qB|VX_WlBaJ$N+yyT~&5Yd%wWF8E)9d%$PT3#nOVZcEw zKP4_(N3A8+bfJV25MR)9s&7d`)FsUi`i7{!Nm^u0p(V*rkN;>=`Z4gdV_J^+rHo+U z<=(u@6eMhFaA7I?MyAmvkyd-G#DG&uZC}9tUo-pzkwsKioJId)ik1$=Sw0Bjr1)bN2vS8-@c`T1^ zjBPI{Z2 zhkMlag?Nn{JwLC=|8_6`+Tro%2FL$r-A1490~+3H^17{F)@9xgxnFd(_#v{a$Sai% z`JpgzZ`{wqZrd~dlCctMqRkFNSelW#k8-Y^RvOSw(=B;4-umm^Z11n>jBf|3g#(?7 z9NVpIHU{$u*^sC^&%=e9m!z3jzr1o1!dIA?AmT!=7Rp3sd~jB!^g|X;OKBDrR@<%$bY|O{pJs@#XUiEPbw+z?J`g`2 zMq`3VM)$MB_>~VEQSn(M*fYUAVj?1_+1Z=S@^rxs+9wXV(gMH)sX%BF>O7wz@17N^VSp~ zN+sv%{HA3WIagj+c>3C(ci!(jXalrJ=NP(6E!0dsBhw zk~8tV^pm`d`S%X^f7U1#K3H&#l53fUb5;c6nCe3)7zO#vBU$KuwzM`M zotnhGSR^0j(cAX2y7eJzw`Q*t5ZMWZO21VBP7G9Rq6O01ZTH~KB0EnpgqN7$9h2>h zuS0b!H)9foL=OlFOZ5+8^Ll?(q6;#w|M|BuC*=9wZqO05a zhQx`wm+R>R69{~e@7vD8r#GkZCl;N12_<}Q&g`#Q{kd`pzh#nE1++M7XRX%IxJ4DP z`avUx%lJ6PpFhv>nBcjmb?^_g{0-@o{YLBgjPZlg@wnMfTCXvaBHtSeqqpRj$sZBj zKeIJ%OtyLI>0L??PERE6!XN9=o8H6SbL{w$+ijz}kVJ96<5r69hHm4f9>4kiJ&AYk z14WX266$f8)-J~=z8x=qJIlSlVCm}VL3!8x`nun|NLTOEDv2qI?So@X@r#^-#D;}I z3gc>FgGgAqv@JHouL-B=lSjv^1AMgmsBG??9A0na&d~?9R1?&|tASsY8ayZZ1va2_ z@!zFiOskvB2@RqK&P~23NPIQPZSkz?Q*#QElH0&Y%IvGGnC2uxJjKh{=VF%#^VK%i z<1%j!&y04kUs^4Eq$Jz{o{4o3rDdjG7#*apg(*DHCL!t~Rd{vE4s{}BruWl-=~uvx zVWdA!p1Z~E-LCd_sK00hrbX4u(&vU5XUr7Lf&-W+6C_8|d`os!@=lU@nexJX9n}6J zokP)NFnNQ$be^>Yi3#kAAX`X_vD}BOJ_G+*tay z?2<%8I-IdxtB9~vX+%iZBYP0Nt#=?y!r*B7+ftz7$bvH^i>#L-N=J%O}eGC1e1Ot(-U8M^2K1*w4&tLLMNZ5r+%zYz}*hF#x+K*DaT`*;e^F zQ#<$lk1~-f2l_y2(Hx~hm0E0&7O1|Go28$=5sJgXT09&qgk8im?3i_x1>s;EV+tA? zeV%-v4EvkezNv&mRK_7KEub{#Ys&{2t*l4=3$?s=44CgkbqYyva|zd+%!WDi^G^jT zLgl&l?^ovfScQ`Gx}DJ0kJ=z(E6~EU;c8`uoMkiT^d?vF%1de^{hpYZh*B0FizhjT zBMDy3btg<3CSpdT6|+qr(~gPVsv0Lw7h65rPh3VwjW-kc>u^eHEIRS^KMCozPs#H@ z3ys=`C6+p7;(17-jf|@g(>tG-9C|>q;9A5dRgPnLN8V~@aJCjnpN@ovG`lu zv--56ug~Gwv|F7_nM21fE~0;AtZ!&$4nD?>^Ru9}c(j!H=~cd40>(QTUhq)D~on^?0`c z0N8p}kcHm@?}~QjV;(N9FlcQQaibf?yfm&E+k39RAI4~@d5h}v?8F%asgd)XT9*lm z*EGp@+c~?etghYssL0`|Pd&jd1}p7JBT|E~1Kiby_q}ltypT+fA`y`@mwz@A% zxkUa$KkRuPBMCU9^ev>m0v&3jtv1k)mL5`ZW=d6m@Ddqr+t=bo!ZEhZK8<}?({e|h zbQdhPwx!#@G~_1-t{-P_AzrN#rxpLAoIi6r3z$1j)(oJ=k2GM9VTWttPk zk6n8G)_$T*Z@SRkXAVzLn}pwPK1~Olr1d-fNHi|0&#KI(qADM@`p zDAh8WfFaOF(%!AN5{silhzsh&4eNW5+LzKM`QWQ0;ZPsmP%nB_60t9-bk~QXiNYe4 z!VVM1neTg;D@E4T*EB~v>+u2{OKV~Edcvd2+@UQECP|B(;dUYB-Y*6VeSJWbK`$`C zgd*Q)?;rJhos31WL?pw2>VGUF!-y|=M1;2<)l!F)Zb8b_?#ncc*XH02KK~l?vQvhq zWMJHA0L>sbnB4{!DxqPqmf=VpXl;`I(>5r$-A|o5$dbw=lFKC;Cnjb+@Y}LwDpcCH zl9TwdWEQhZ;Jus_2HV%$R+6ttN*AJlK)?EYMxaWb5-q1Ujkr9N@%^}Tt@3cHzI?R( zut3;wDb1jMNxJCkp`I#fE_j#ks=Scr@EEmNjlD26_9u>qG7|n>lAceb5j4Mki}bqV zxxxk1tK(A{`t6vQd)huZY%5?Ne+nasQN9|Qr5V8pQ&7#Njn0(!tnSsq?qFr+zLW|mqmUR{x3gFV$`0W84>9KjHpSkVzi#8ku4_7T6XvaMW^Kk7WQxpb>F;Y&v} zyArTb5E@kMyY(u4GRn+V$zLWaW*bl4P?)zcsz*uqX(5@<_*lyENE#r+kHjV&6WfMy z-rqJ?{AO?Bk_#ObH9Z>r4LsSXFHN10?JEWu-70rr2w6CBwi>gIi{TY-HA~7UalqiM zo)p1NuRG?Lf(MnuTv@b)Renf4HvOKMESg!P8dSV7p(~XjZnTp1tc0Z* zyUp|9qqsmrmfq9J6_E;FkXPf)52e-j37<>@QW;))wu6hUoS6z}YL!waJc#@9la#pip`&v7%#pvG6R_csIRLq1SqtN-t8Qg_8 z(NXOoMC=h#6`9Znp?9-U>|+hUOrSlMX%2z};MW-Ahb1sA-RBU1Vm~)CJ zyfr;m$;W7pH4iWSmy)PjNQym9aBNCYToi|3l(am723g_)DLGy|o|^oZaAcGsfv}o8 zC^d7YhUSeS6GTZ+J4Rnv6+d@6_2I^Tu}X}#j7>^3S5;Pr@Y54eFzG@_Q`~o9;gGh^ zzZpcImFhTYE+*JV;;uz|GH39qMOm5ThyBnrP;RwxFAe2eu*cRq&zuhvrld3hYltem z>YB|#rF-R6@c1vi#-0syoeQg&YokPd^8q{6z^CQ(inw#vJx5}++R@Q6gd6kt7Gu-n z8gWj}QZc3a_Yc88N#pe2#~*`;U~26`_6d8bgd$8xb+xI{3M5QiCo?Uznu|GZfH9Xx zOP%Qp-2Jo6%&fhCv^GB^F0-;vB-XQi+Ij#l!Gn+^a}@KTmY$eYMgSx%FMoq}?1iyL z9HqtyYC;QVMSik|_3=e!nSQ!wTnios^w7naB$I zuaLfLvEr4%E(o43P7s1qw?P&DX(w9Z9Uf1qS{-4`c;6Be$9y;pkYd7Pa9zBmWgnAo zoiV|iFexvVnkj8tuzIOU(XHz9oxRDa)ifp<-=cEqqTy%a0Zfx!u~K%K$OzMSo$s zY%BToHTt3Dt9GhU#f}l(B&3wW>U8lJJArL{GHY%B5fa;N1+Q(zh;4AXbq&~Brgqz_ zYg?ArT8`dYHGlgJ?v4iejwb64*QB+&uJs#r8#Rd?HLo4r+HYFvI|gMthAlfrto7=) zHYN%-D!V&+_cr=1e8#N1mO{H$3cJ?iWsp-F$c>FHuB|<}t;1tmo0eUtPrJ~?U1y0D zhY!0hUc0XAHjb=zuJm?q74|%J_ukp=d3jYi^4ht*-StS{vlrU){j?|Lu@|tr_u*zQ zP{P)w)-JegFJ#ItL}K3zcR$>AKf-H2(zGM!A0!Ni0Kfpa%>iNHBSz>yNEj9#Ex5j* zKNRmNr}1cg;b0^YvvMxDp=dak@}=X~(V30j1P0j{TBXL4u@rV~IFzC{WFYCKn| zsqAx(u*c!ov8M7j5zhh%=#&u^njd)+IZeh9mD(}VAC>czn-8Z;bpM5fL9FL%|F@B_ z$+m{?BQR!_eAV{Gor%nsPV1BHO?%S?va$4P9f*Uu3hgS>&mGN2OZ8S0`D&dl|1U_` zkG(I&Dj(ImJFbtAO-|pYx;uZKZ4AbupS|hny8E#|S7kQc)BXGBe~W}|1YwigZv^A9 zR&0bk6x!biB~oDD3?tRG-wda;t=Np9_1fS3Uy-o=tysQK?BC-A7VW>s3-4BZPk4Q^ z|26PKJ2|$8M%|y2EakeOcvhHuS$BVY`)k z`TjQtdmn>vIrj^~$Q}0!qgdhlMR7uh`~Np241Q3S>vecgUJ$`~SW%Mhcvx9c20w&X zw;Ue+MZ&iJCla;`KdSAzIXtTC!{s{ui)A?-H;l4Y9XC$?CnU`2q#0>jb<**%C) zBZBL+Z9CoRwEZs<_O=+PrrFbj59Ay^H~R~Rb>Hq*o%Nt@j?Q|42i)iXM#2Uv#wN}O zF_al#gG74J7fx63Y$*UAdig|`;vXa|19~~eUS54U&fR)^Il(u={bN#K>3BR zl0E$YgoOP6W&i(y?7e%j%?SZ_)-U7FZ)nk^TzNUD%QrHu1gRQ%N=WykS|yAlCL(L3 zhZEeDwH{X0J4GE-@6ZT`k@nmx!%!!Oqu2YTl z&U=R^9DwT)k2DF4>9iJ^y*%Eswk}50+`2O8*k#3vi0(e3CVeXdQ0B1ql3;VY0#XPr zjphNS->?zwmARN<3YCJR9;cO}+TjOo+`R3L*)#yh!w0W5FqQT@&)V#hwcI}AG;`I~ zjMQ@QRaNtM{^+z@Up<#HYKyzf`mqRYlG@@k439Qtx>9h0$tQ1+!-nYeY(A5Y92 zlvQ=-;+AsRxZ|s@N0M?*JY`J+OK3Wvs-~-^HR}Y75%vuOk>kC-81k@8yvlH`rqKxT zy=BoTR>^y9O<7uK*KT^Uej$~@|8CayEym3z24VcqS-FpE1V~j2Q%6DV*O-)tC zq{mzStNOE;`ZOlC7ws$1j9!n-uXBN|e|Ei>A72kM4>#RrRQ>FCAw)D$9&zdk-DJh9 zz_{r5gkDJ9JG`}7Ym&!lqF~*0i}kFDC412MmuJM`4z48`{W&{NaOalbjCJra3o2cQ zoe%S-er=GQyAbnacG`z&emy(+YkE%yO97qx;pVA3vQB_8*3^+1E6?)!c`^s#8&+sI z!I?GTos#sM%3tza?mlq-?29;i)ne+U(N97h7xAuf#k70i5z&>41fR)b`k$jC62C4I zZ5@~x9w?2UQ!eTftXxRPLTB_K8>rQdjs$(fTStgpt#)ZbsG6jYD0$cm7* zkHx1x!%W9WdP?+fn_|Ftg%J$A2mS?Y{}Y`zr2KHP7*zk8==^`#6xF4fObSRFJ`~kx zK9Tk}I(OZ={}Y`_sySfgQ~%f$ryJvc*i`oUl0rFgyzbQ)sU2pB77ew0W;3UBg^6|q z4<4kTJJ7yc2+9H@4T8B)HHO=B^+B5PpH4m^qS%F`_&r@o`9k6HCJUIN7pf-S(TCYr z3Zd+#9SlD4Kb1>IoxiY+$#|9=jUr^(n|?+3z`l9;rDLI#eld?Tzh}@~-J`9ycm=JF zMs}fRQzwl@CxN}k&6r!OwNe}{U`5t^?e?=)w-jhuZn~)KDqY@Nbo;tdLCI%C=aZij zt^q23)}w@~^)|n4ZyvIAy12M>p@0(Pt30WVfbvu)+T|3$*X3Y1FTi%QHCg=OO}doW z!5W2B@a-KUU$caJv_J;)vNSV{)0v6M*GMNKUA&JNZ0N`S!IMJX?veiYH~97sHWO&F z!e*Z<@wJ%;Jt08S!RVK@K)(0@v3Ue$`lk{_IYY3ir?L$Db{bXlB`CB{b9u+v+z-AObl`-^rxLltNKfPNXye z4?$l@W{WIy$>9tKhwMo;*i(0Th%7VZ~HxI}m$cgmTTTQRKcwiWRtO_Z(ngc3h!oInZTR@4if zEyKo>a6Bt#JoL*W4OY|LpALE-TiY;GyLXuwExK$wBb2CmlGY2Ftmpv!^kl7tzDJeG z%cS2rsND02zwG{_+={I9;Ro}nJo!%T7Vhx|^1K}jzh|838-2LpX1EL12hHjW<$}sh z8pgNQ({W<+F^fwVv?6Ml!?|qn8G3Se@2sWPMGU4%XioOY4Y=xEN}>`vnudM}d3~-^ zBo(Ub4mbKO`){7s)y*{9 z2Kxj{@f6w5?W*nf|4+cS`DfOQc zZZ?dU7?!|?e=q6(NVo-V&kDN3iOBA$ks9X1QN+)v=k>p=_r_wd-fu-Ulnf`bOR_4N zH?qh9d{zUhQnNb)sT|ISs_fdkLwTrtY6|EKXAVSpEFKoD-sg$*bBhbQgtv; zh;i4$zH(zDOBOt#YMnYvi?@P=#Lk8QbUNgr#?8KQ?1Sj{?+5@#q?vb>LbsT}nFj1B z&WQNy*3+#ptKOS{N#P^IaT6M+Qrf#3vj{H^`nSs7msYK%!+ND_K*5M`?ap**EF#DEU@{I>ZNp5OYo+<7vbWyVj_orD{eazmPwpVkc6;i)Js9#)o1eJznB| zp)mpw%%ntoB=hPrIsWr>5zjFSn3A!QHfP*fafwO{Xvtc?fdBYfPp7)PD2Mr;Ad@X2 zgC^lC0R@$jYtL1^IGz$QB(UmeiZq6s=njZ%n>q1za6AoC$`dijw{6fv8oBYaZi0<_ zC^nsvScI&KY#oJY-O-5I3e|vJ`8Sw1;I*|?TBO_T+|&wO8D>=W_J1l(XE_)Stv17{ym zb!xZ=rBSvu(Lno)X|yiB=tMdqd*0D{QnL`*U>-^TI&fHuctGmNEFq`w)^G?qG+!gv z0rfrjxO>_~;GE1H`%n@Ew;h*3<~z-GAGeJJA_?GlEuS#*vUsLds|l=QOuj#bql(gmj`XW1o&U z4-A_xC4^(zRI&v>*#1F1j+bz7hR(8^^TU+4m0JkvC0A_&eh&c)bhh{M;LZFvGH|JS zhJ3PN)N3_d@OQw_F{amPr(o9@ht!*bUcrC@t>icIAji{g4+?8>OZ*^%tOHZ6? zkdz7hmDh#I&Mv~J)M&SDD_=}Q>q@6st1#t{m>lfvaSAq;T1nyB2EEzr^YM`qCeuQd zx|F@#`-u04D;YY!RB_%Pdf&3f_vT2)mO)?t5*2m4zdJX(TfcU{Get`u%2wr>#dfM) z-Mk`F%i=Z7iq5N(la)F*uCOM0o&KBJzHs-p%;#(_{~Xu=U4S)$NNK@nSKPck3mY$Z zN)C<+SdySITI88b#y5U&CvmcjJjJ9b9?N1%E~7P9BbEggx=umDl#bno5v1{^WLO3y z#OG5ZW}@WTCh1p^__nEu=DUV|OC&5rWb!E?*%908CuG&$JgNB#Z4@bJUyTU$)b%$# z$fxfZ&m$Z8Eq)Am3$hGY+i24k<5np?4aL`bAN<3LE8UXhVbQe5c+*U8h%h zGmLafxL5doihO}t*Bb%pI%k|p#D`fn^<+F%@lvx~NZFc)g^S`l)FtY_ETWtPi>17X zOc^2GI-_U8L0C8|hK?!SvNq!E9N0efX_(NV9*`fz35xub3h;G*A0PO$CBE>GQKzkZ zXb-B*xsO#O4rg`db=$I}N?`Z=LDSL?& z%hZ+c7vkWiLa`UDE0pgwjIit8dxfzp9KU#zb*oX#(!WO_y^@?ZpY#zVo*-Vp{?xt< z0Yb(_3z@|v#n)Irr7Jm*36qWBL9m91rr}}DQ0ateAS%Gl)>@BR=F3E{D>a(;G>erN z;Em56Ffjg|XYu_tWlbRPznU`ltxMq`(2FZ1ApAmVIP&px5|sCgqW-AfW0q}jV~J9N z5{bESG*QsM%0Wyp!{x?U4#?o}HG9*ZN+PLE+@o2)tnOKkIZM+3ElRZMbK=T!!AGS3{Fsg`y%8)d)MHtSO`Lb@IVMyL7c zZJ2k<|HggH_iEoF#PK>G@|C3CsvYQ4F8h63Ya5+9l1{ej%WTnNz+*Oy%q-l9yn&|S zm}I-{HWxl>+4W1|;9%f=3SwlLwV#?wdhUl)Pt3MzR^!iVzmO~FF&E*X!qc^OCs|IW zbcgm=68AgVR+r|&Udb%pNI9cfQQ^C1aXG=1?LdSZ70zbuu3?)hS- z$=U*~NRGi-=GVt$Gks+V)VO*wNlUE=l}Pc;jBLwVci~~j;fe^-I6tBmVo=omuvhAQ zMTIQ2zz=S-_Q*SUAQyC=ms%L1WNnwH^RZAj%iAc~I?>1C)4W|$*G?LlT3g;LCZ!9O z>=be8*;LBtjp4lZWKq7z|^& zBep#6^lwT8hyu9DyRMOc8O^LF>+(F9IM&O(8}i13ow}8+Pj?_-o=)ZG;v;;t$(J&Z zv+gW$67Kfs^$?XmPpZuxY*=mip*=2=4`q5FViq5|$1>7W=<0Q8PgmOwTpXL_m5N<< zlYCSNtqj z@+(RC@62|tAG4yhZ2ga|Q@a@7brvN!-#k!zJV!n(pLj2Gk~>j$cgA+*dxW?!eEs9| z4|?rX4((J;_RF4poC;;{P7M7JCdo;kaVL(cs;Zz&)*GBRH`5gXY#97|R8P zmw?x2`MqR_y{70vPbr@Y-sUr6R=u%4rx@3Wl32Xvz{nYoB2uIrEFg{xS~DtmRI1RK zsY)zHA<9&uu-BJ`%^UdqwJC|sKzCZ)3ol8i76}tx27T=X&!an>YfFAvNhZ$3%E8=^ z2|8d+jJgEc*|A2?pA-tBqe<>@YtO?Tr0}_)vx?Euty){Q=AmZXYuM?0TN=maokJu7 zlBFmGvp&i4vV{EDWM*t1$RHvibZ8RbYejql3AkR@FtxdA> z_$FLRF(OJ@$?c$CLJ=TP{z^vr3=((zC&|CfMs$sNZU5!-yxuMuW7Y0lnMI71or zb>+i(JoWN-)Y8N!a7g&!qmz(NN#}{GCV9;ICLG-b^e%8~LcD)_H3Npg-ela8@RS|JKCOkNqI$-%1E0EIy{0 zsj(g>;!#1yxRl?X-<=FpkgvCH10(5nN1pLBn|$P^OHcB|T;8JdG!!Y#mg9=oS@*Slfxr*qbG{^Ul4A7Q z@c-J+mJ|$JjeHDZQkEz7BW0D!kEW5vW{RA1rs#8D!}vlFkI7O%%7I3P7W-fzuuFV& zyTL?MguA!2ahzjdg?OQHum*{>FoKRq^f7jd7EVK$ZUzSXP*S?8kiv%aqwI2quo~cc z!VRczT~|@;SAg*#c??)RemxRk%{GokeEhKehY2VAc_q?9IuNsPFMo2uelB!-Ia$s< zs&VLhmWhPnvQzU8%hN)k=BDA&tlDjMphaLL+XZHehJ1GvN@9|RKX2FjCVe^FL0+CW z`#zs12OFOO-p;#1T-`&mt)u)xdS64VhJl7n6#&=cb7+0-Sa;Vranz{$%(=1UsW?_Wz^bEiS?ypn%l#-(inKp9yKG_S?TV(ljWK!6%> zaFG-%S1b8~7u|_)o%QVyOEQH}k8kw}?f5L*#i5nBzgRXSrzZbF!8zDZ?X%O7RL*IN zdrNgb>1jjq>{Gvp6dks6n{4YE6{(=NuP<%x8>4eWMk-x9rsal;{AEk{p~JjEy+@-48r-9z1f5}W`yZ^mgq2wa;GHIoElfzk%U(eZKGdeN}!f z+?6*n%U6msNBlWgYAS~ihm&?M#&}A=y0Oh>33dr|U6b-vVw2&NMe)L#o%eDPTr$F; zRz!24mxrBTK1np?A2mddRuef)^;;&za2%Xrxe;c0hg=!N8@r|i6lKs|Knc46EUWlUb` z*~&+5+Oe5ryAL4)Qg$j_`ezArCEMJ0C>wb2+bc_J)XP6r55+~%#Vc_k%I^S)(*vT( z7I?ZrzYZue+^$p)q8CBTZ`x{l>jF`}NiDgXh~y!)T16 z0c0BJe1|*&!kzoHA!9KTXV|MSXBCku?JESXoT|@RP_<%8nM^W?U5hv39rJX88m@|E zLI9;dK9wDHlD6On9n}_`N!#_UKJkO9ro`!H?c!>r2@lm&p|ce%-|G-s4d~qQe;m-7 zzLsGkO41G5Quex14M!uYEOTKXu;!ryXQ$F^Q_XIG#qU|i7t4A3r0Awm`%g6Zz<(t- z_U~%u|CBx`j=z?|<8CpciWbHCpFC!yTyB^7OU)!>{mW~_WDs!O2a*8F{xV%G`PTE= zYu-jfe0QJMOVsG(bp?^_Kr_nq;t**p9;#ib@;Cx;vU9So;RR~lg;1>mtg5Q5~gWzEo#&6I#FG32gqHWH?kDVKaU z`OpYGD;<#+S_HoP&7i;`C&i&XLdy~`Z}mQMPFKt$+r5T-&Ed*?`F1u zE}ZfRAE*e&<0?jYIiuuK@H(Rm>CSDb;r>Ep|Dl9nv{{#$g4&Ge5pHu2xjTjv@OdS? zLW45DTBNFcneQeX@})UY!10_wsD*BX$hbN9x;J{?k91BThM)>JtsS3~BHOG(zQ-Ww zyy4kS*fU?yD9|Kc{)raONWSC{1%~%ZLAljf_@r+F*c^H7z|ZpZcXr=lgSdyg)q6L_YZ(S3Gh%H}XiwC(f0~63_*?_JS9|9@ z2G>5N24EOE-Z{6W;-CI79X`21IQ%e*(<#@w5s#Zwtj17la1%Qd8@mdov|Os z-yD5G$Q~1jmny1xK8=uVHeVnSER{OB5MBp7%nOPTE|e-f|Gu>PqW~@a8$qUsr&&fo zrr)1awa<4!ZXE#1%ObmMF#pqt{oddMi|&pE5BswI7C4nH_wz*K4%bZtOqA$*TY2dW zR>_?ZP=<=?n4H0Ktp@eMjU8~b#OHGA>y`6jZkBWy>AecjPr5-ik+!%3Urtlt*$|a0 ze=L3zPf2UtFt2pm&DBFneaD#kdnC;r-gc@Ehh@nep{?w_ye3)4^m~L;wi=B zUkf+1r4e6MQsJ30Rb>&xM;mN#(Dsx|5@FL*J~NO%CP5A-J0uUYT0w}1hP4LL<5kbV z0TlTvdINfic7920TKW0tcAu=4Fv#sv-U+?SV{E#tt+02;K*s0kG~S;M9L9M{wk+TB zMm1|Ba>w2{%6-e9Os{ues|xSK>qTmq|~#gh*+A-M&s>me_iB?4QT z^A$Ds?iYt@0}C|2$LM(w=O`^h`LPPk&ml24e=)Vf$6GP{)SB@~^$`o!HpyK5K*~I< zS{G*9R_W`>T%JPLQ0FiMa-DG_$w}b{8u;Ldh)tWALnYA{gheyz^J>$VMY6kOmHEXY zC+$FD1Ckp$)Z@h5)Un961iNIzvs;NOOA_WnfyijKbhaFqbUoe*rUky+s7XvRO|O71 z5PwQm*U!6?b}dXSW^vgCl5sGVQ$40S!iN@-HlC%pFCpASq)oQ)T^a@-n9CsR?%^V8a~$w<3aFR5*4&(}_FWfbn>MkP zW=6V~2WYPp+lDD9P!0VJ6SE|xvd$qzKhM79sUHTv`Q}R`uwx%(g?DpLp zFpU$WW4t5YZHFRbxvbGrwK_=hiTBV%cB~quCbXr)<4H@B6cY)p(;PE(5PA#!kQSD zDP>M&F~W2*k=H&mtkg~vOt5Sf6t9bTBEHb*%lC6nqN_f!q!*mEx>XB9+FUXSJbeZj zfUSlExKf*TrRN+K?_zU6nS?`689_;lsR1y}3Q+Fo5TD#l$p4UwrW`RWXm*ll@}`2} z>FBUX$Vrk7MJ3Z~#K^x`(^E;1u>a1Qene6APitDUiidG*R88*mKdk97l-cROSkn~M z0_woo2P5@z}Ug?`d{xa`kN|JsX-@Z>YLURP39HM~+!HcbF-<0zM1b^Y_HGm18~yE;t&}dqZtDF z6(6!_0N5ND2ys#e+Id+Zb^Q^1kyO@Ka+lH5C0`tGDhDmsMb@iZJ5#HDgtQf;fjz2J zPeBXk5i}ZCATvS;5@{QjA}~*tu25&-86&l%kd($Yh-JQHxY;c8dd=DkU}uBJ#n(z( zZ2XY}uICPH8Gx~BFa9i*5Uqs)QH5!Cp9~BGWgB-Ujv4p+bQrsMv!g|J7Sthc+#$VX zGqH)yRGz31+bnfCr zh>FyEYSlBM7f5b+jv$8Ilu|ulj*OpE3&; zDaLMEhWR~~l`lN2u$QOcuBgJR!-A)7nJpV|P?pBWu&@jxN=5Dl`G15AGkB?~+5oCP zs3v9xZt^WA2N|)jVQGQmJY|AJmz>FA!~68q8c@1w`_w+kf+E91rlLm0f$Id$ic*)v zZN09B!^q+)nPuFPvWpbMTAQQy5?A<2=gc@?6p)54hS^(s&ryHbv{;3=xR&3b z^-IrQKr^;|3@g~zl~BI|lB`!bk{B|6rf`H2Z7APpd=fjJ8ebjTl_zjiO4pYI(_EoZ z;VqPRn6-797Z0 z>v_@vEM6%YtW@IRUbW-!)46r!q2xop$vq+{tfBmGiaI*Z>_fB-da{<9+WahEVzSUm z%GZeI(~u85K5_he$R0GM40fWlJ+H<6d*+?C_a{u69`JMtQnW*QU0-i8w$XgtNr`{l ziW)(i7NCZ$SRd87f4v}wDzkjncah zHgi^b#iu3CNFPCUG5hjF>l{S=f@iTSg_z;i*Uw1@t2QHlh@qwxv?lkq>n|A@C@__ig^%Yv#4i@40z(gB8b;js@zI(;pG$&jOQ* zN`K6%K9&76Xo?sU->9-lwUT{1B{f==m-TIdoV~&64QDqJnCN( zwilCSs!4?Oe=0}YDwIOml@tAfPS&1e5UV%baHn!2oATBl9%rvzm8`oO0~Gn+O0$aD z@orvvIA>tFOsHTV364j*P)nAfm<&+$y4pmK$DNdJYa~a#5_Lt~?hXi5$t+Rn>B6ie zd5KePH%xC^M7j*iRkN-eug06=J6S>lxy-6U>}w>i80}E6u-T{EpBTOEVv~ra&%4EH z`$nVizA1#6p6tJ+EC18J+$H7wROjb8eIE0Zo$1>Sl|;8&>8UH!X~F4O6|#Cj^XKq~ zlm+YXmMU+zCU#3qW2Hd{Eg=tlJVy(I=)87ya+Cd5O(LXG+VV?!H>Mfq^jbUnVH9AX zI%o~_;wrdUnVWCLA%@hTSV>p-j2wD4wpaF;;3HoV!FmF}l~&|YjSW1>16LqyKUY(N zILDr>CkQZ9Q`?aOxQ8DM2j9#iHZM+-nf^#0rt>gA=(YetA5Dlv6_pMb*BCl|75tH5`hx{M9>-& z(>%MFn(O6C%;Tuu%ZLtcjA2}5K;wcoy}pO{SSAJ?MblA}BJ`Z1mmztqN?lx}nTDz* z*?WBPpg6wFTJ7qEB0NWRa9M2e_0E9`=khmxtv1J@t+*qm-UPZr1k9yC`<-BRLDr$% ziUt44qKhGGte>@y*QSgv@U=&lN+&SAtpbL|+3j@Bqhk)NqeO-dbx8=Fmcjv7e%R=P zmf9udoM2X%{3oDp`HKa<4ZbWLwb7PWO%jPB-E8kj`Sr?{-OB7qA_9pu8^-&|%={6hYE$kM zO(g10T-fh#3y&C=P^*o%+ydFAHTPVbOe|hKpMy2XVrcV6e8zUVlpKDrQVaY*EX{+~ zwzJw*SQ9{{&1gf8vf7?&wx?E@Us|l%FYwA9=y8Q8T&zT0zonkXH zW`icmGuCZ^3WpZFOjz^X_IkvrE<-TO%0Jhd2m3A&nAH7?$@ce(OU_T?40=D(@3qJ` zC-JJt?RU#4UVWke!Ew1afiF^VY}v`!cNWfj>-TrPC8;35OIiMtaVh=xeIFseMcTsl z0@G%6Iwk^Lepx!4%~_@vI?NB94N7ty@|c=k6CwJ6EXR);X}LaGMfDTO9Y<0pml5zI zUXhs{-}H#eh-5}zQH2~o=AtMkQAZ4b3XY=%G|S11M+X>sk7LA=%PE`?gDlI(v3K8; zQw5F=a$FwA!6+)IRpJmsJS->ii2uCjbdxLSYX7h9xtplr_8R5iu zj%8Mk<=hTMT`^8OXqF@5{4b!YX9!}aDv=H?HFZ^ftOq%T8 zGrZ}Y+FFjmP>vksr`H>HT1J{RjXiy0`rPn@3ZpUgWMlAtH4#J6!p?{CcwUW``V6sk zT#VMA(`P+iPA^K`V&^|IZrI0R*p0z%)2q{cdHmWp(fxpfVJ7^=CJn*J2?Ekl=WrC= z{)5e~Org@F46lKY%;xlONMUlAK6-P}wbg|Z>#rZBqOSQ-&)5gnb~Q%$g3P!B-xndB z*n}@R!+){dUy~_1y_(pnX*SOHB;b)=4PDD-coazNy1))4+fh;Tba$C62`!G1TC{H3 zAYKcr5{6W`waiIvI(E%Ms1ax4h%DhFY#R~?yC4QolY-kaUGT8q^EGZ$F+B1of#2PR z-ToMZ(a;oGs#3;dLQ(??F*x4L+a7wx5qM`$NfU`ZUfG~zeW292MvxxH0MgEiT{sFf zi%J1b$x^2iAen36fz^vBkUp>sqGwGCRu#HIRxR9bbsqyrQWMYxG53JsMKpNM=`~(7 zXSp!(beR&pE^NCh=yraOZiB`yhNHGDSxDx3h>>SsgKmhwm)YLktNLs5AWY=lqttVAD8RJIgx8aE&3HIo$ zsh~5|UiNYGf(P&&uxcLKo#`6vOLR@@oo9u(_VtrtL|aK-5;)6u;RYZDqDZF}Pav6v zo4h$<>cJpfSkp2U1AA^e6xN$n5^`!MC&n@W?oLrJ}K$U-VcKP-N7@ zT?6ha-7fczU>dK2T;A~r73qV}2s>O_PfFIAs`|tmtZ<=wq}V9=W43+<(VrA$3myr> z0Xp7G%CWC?7ZkoTRN-CE;%yX87Wn;`e6B;a+;Pl89R~UEMOJ zKL~^n=MJ^}y~Vo6`aS%1A*&QC`nAfIyX@0np0;OEt#Lcj_Bmq)Vo=}AzROYcI{TNl z5b`%q5ti4;^B4ZSUo+^QNL$gpjDlKCeE^LqKlK89BAwH zBjrS;!+XUJ^%@Y_4MQyA+oJXQJ*zktBX@Ya!`qhIWRDJvI*B`LV$3scf9wXZS@lhz zMbN(`oAOXgz37m6)A=z2KJHVKpG{Q26Z+j$VOHBEY}bsM)nVax_*6DC71-*-$r%C6 zFvkNm(&IW+kAL_2tjRdke@jIDkK2XeyH--r|#&0w07Hk85m+VIcD} zHR^yXLa_`4nRXy`R5PM1{gFH}XkDN8qYO1OHNF3&@d>*CA>c=+uMwco=1e1&)Y)V* zTx^41R|rY5Z3ibAU|JJB>me}qB-oLjdmwglwwNvz`80tJk86?3;6*vuA&PVfQepzA z*qaXjG`C%y+kCf27ewh0J82A_#_a0XhO=SFIAxWjkQN4JF_?dD_2Cew4uud#NFbCoaY zVyT4nf4nvlbd~unORu(G&SFpl-6@!M<%yilr~By7024yDn9?^}NEv2Uyq`XpuY3G( zEK8WTm#m+UJ_d2<;$7pg@>J-+Rivh#3LMi~!qN%TNDNR6eiOEAuQ!D zyl$>m0jx5+w<5bo+Re7m!t}#}s79K%iT4*cpx|CXRUuBE5^RsNZzth^C{k}Kn4s9Q z%k-zKklewo_a9}owU##9x+<@C_&yPjed$0nZlyj`kaYdj@^$E`_^;Q*kG1X{*hX<= zyqPfOuX_c<398CR@vw*M^mNX2I6b$25$=C3`B9MCT;To-2hGP3$FB~ah?*-0yqvW| zl#hw7crF9E{v2K2(Fnb8l06~BiuNo;ACnRH;}696v|LiOqxSlrE-6KR@wNWSVghfd zdgrrxxNfNkx&wu2N1Nd3bp@!C6}a4rVJ}brRw6CI)KE=7m$WpX?L1ii!2Ln_ARBRa z=xCoX+gAuIX=W^be-QXqmrNPMqdlIhT3iF0!E~uXtx|({ggydYV%E>P{YOg( zM57A(KlreWWvCxE#%5tik3V04&_UvvG#iUFkLjg!TOa_TGdj9KM^p~hHkmuYTF9$n zw6@+WN4VaaF*sf$1E)+zaETG+jO(-I`xh17=H|G1@Sm@?e;ii?N8JDHMY3IdS{IF> zy~BYsK3RjO0V5)35ooeUfAt~>U_N$HfNQ&(UZgK(BL1b(;k{t}%Dw`a{dtzND4s?P z0w1jE>btL0!cjR;#9~;dAAgT^{Q0;Tzeb!uyB+?vH0|q=Ly~rlG z?_o5Vf}as!2RiTcpAHfVan|=gD8@|ah#S^#7PxOPIx0!~AI!#X5$f&*#i(}cM*`jr z+2tUXAx;_`ruoHwOG`tXS#lrM$O-|9GNpMGQ9+C$5j0h0-T<(kZLCCOh^a#k)iTJ} zj?dsj2_9~G&nTwix}eS%SWw3aZ>*`p05H!(=G|7O3Km@Z{7Fo#)F97D>y}L~ood=r zp4wV=Fl^JK@Pf!Vb^Uqx+#&}aA_d_`>m!+T&X=TmffcecN6q*bxi z8!2U+8KCOHd{r+^n?_;1MW1=e%Q_EnCO}nK;&H|!&>7bQ$JD}NI$5$=R4+60bJpgs zL_#$LK^tyf!&xJ->3UZI7i`^O40Gba?-;_q4*3FM<;5Rj2t*2;h+2h`*uUN88ho3s z=?GL+VwRc}rOL8T(*D^XVTQ~z=W}B3xR*{~HY4YYzVp6lH=wtgt`aToq{3Ct_RD$4TSJUl$iwc(mj`;wx8d=% z(QGG)%~sTVf=lB!Tab*H-tC#E^t2r-H|h4QrAmiTN4c0%|BBc5=X!q1OgTNf6l}Y1 z@PmOtEx1L1RQCDL7aYCRU!Y6TR|vF1?4lj5pzJ$<)ai>h@GY5MQ=5~ny=OIL?|8eq zIZ&H?uignb@f7Nj?#nqpFS|&S!oz+`r($=swz~OG{VL>uQjWYv1jYkUkN-um>?eUCguwP(v0?*AKglTJQ7eVMEEO zzxR?ng1M%r8An=uxr=xXC)y491ZO|`JX&}sbthDJykcLV4l!IeiHN^lZRf6B!_1(U z9mzcyqRZ2706G;kkH>;`j75hLAgl(#JNiiGH&gq_tl_f+o9R5ww@urQZ&k?sGdc&H ziAHX=+cTtgfc-1ZzJ<=D6(Lll+Boogy`ASM)rV86T)Gm)-1Z-57>M5&?xQRUn)Yr4 zym(p6VJ3Gl!6Tt-Bq)^NtdIag3c86D1oEA658fMl&2gA%U7`{~2SI^&wkMOP`Jzqe z3e-6(2E03HvV|$T1XOeybvu%vcMOqd|Yp zsH5s3K{JACN~dQt=PghV_j_g=%)U2NxCt7mZyB`wT~c$tfwK!B{2!O*5h2q*;EaF$ zPdGDNK_L;h7-=R@XES|0i(%v329 z!aUCJIg7s1h`fQbWrL*cNI8jqYEeV0;9R3bIY-v=w>8mb@}80Bqyc3LZG0U$!a?T{ z?M{b?@@$eo4?vIST2AzGmyqc*{5`d%M*6RlFCXbERzC}Lw(d*mRODdoskKRoUtl?R zd-`=VE_y;+JG7&HY=ZJ-DuGKQ@0%yCdh!%UCg)0#5)tVV1rm7mHDxZTj_xcq9{d>iW%PaKq3(NS=?hl@>s~-awmim0j30 z*O#vGq}o$=y(ahQ=eeHldbV*%5OYj!fgQ1-8X6c$$n;2kb4uM>t6|BP8-8Ld2@1#e z&ok9ILOj6Iako2BYY@Qm`WYDc@HSx7C^%YAa90&;9{jd@6ZQ$uC07_85^otTC?36) zinq8w2mfm7uM29RKgdZFcs0uqvxf(;4TX9mCj(bwE;5yfrSoV!H}j)8RIDM#t0))_ zV;9(nSG^qnN~^XqgD4$Xmb+;CbkzrKrK(?Rt`jc|0*2RrKcO z30-2t>aJ4+{N27tAg+3ZU6F=wznPq$CUMP$L+SzCifOCKPw5ok5^gZ8%0w} zclD7%D7VC@>AiwY7O&LUPuU&nhD5T??Qb9Qo)Lj&!;W$5in1uAx-hOLr*T}vds&Na zI;(bVg_%2YxtoV2y)KR$istTkSH0|@sO2wc(g2;S66|c4dImKLm6&my@@%Y15H!he zm~KO>H9696z2hsG$74UP)%fUQ&I(@W(cW$d@EFzmcFFd_s?GnQf{x7!?x{NEd275@ zlg_G>!mwOGy|_Q(??p-78^}lgtGpTcw}}SDD~I=7s!8+^6fRfS=5-V&P3$b<)b{2d z@h`|{I3VLm|BU@(nI!ivYuAUdJA2CJ(vQi$BeQJA6aNAES^JR+HQFEw>|c;Ka#D&Z zXs>$HtcJJ9^YbgCNrk19s{-qK-SQK6@0#rHbNBH!zl{-LSs6RaR?oFB;Y*C0Yt4aU zhwN-^$Ag0wwD+W*=ZUMlPE+?GtT5?tCO9!BI%<_t&PO2ekojDs^;HDQ^V@l1t!v}YP2>378tLB?R56ehADGLZ?GrznxbE_} z1d)A-Y%FwkYN?q$ zisLfq0PbyL4CYukN{G$>Ze}QesjdV;lsIbS4$Z%74x%~D8VbfkKyAX*vQExrxiuQ-b~}Q!i3JLMGe2f;LLn@m8*E>LDoQPM7Jx>BiVi#gHWjFv z?oFc!>yV1n0%qtis5e20vumM5xC(aRe4`5Pqmza*KJB-bDLGS@aozZ|!TXni^p92` zzqnJIoe?83XgZmemrUQXirrIFWXzS$u|P2Z21jfCO0uVR)>@NBYRAe1_OO5=1a?b3r3=pCPekj%S105i;?+#&aOhg zq~s;Eq;|RaQfMQ)WzPM#zKyPxb#p7uZ;;4bo?*8c8$`^0z1!x*>F}My*Yd}2smJeA z)x{FX$ic$TNg%m3kE97bx^;TSgo~Zs*@sIu3L?7hZUyx9eSBSRF5Np{|3g@Cp|tWI zxZu#r0DIK*IC|bsLeENn5@t<#*M_-q<(o!phs^9}vK{j)8?*qY{I_lihj4w4&?5cy zX-@6FWWPFD5Y>y?Hf|~VeHAJbehr9b`;^1j z4~$BEM09)IGuEhk1=1QZ9a=^}9Mnq+#D>!2xUL!UUKaGLKfX%hBEc6>YDjs2F#TC{ zscn++I=$|;r8zhGjQUIF`6toR1h>`=@|1rNK8aMQvZ9=RJbI4}bP|?szeaPvV~}bZ zlkh!X=QD;xwXrxg(a?RgrY3Lrr}%M#$Y&nPIDwIGzn>&K-s5F?mC+-rM4aTN!VcW( zX1sirp4!XH%kc^=d+SSEs_PZ6L9)PTDPcQS)OPU}_hUrqep~uoZZNn{>D2(CXGZYP zV&d$_W15bwnOR|Afl}Y$Q7wlov(H;ly`_Bq_6&jKu<9$!f0KjxcXlx{qc2nIlj#DR z!{0Fn!(+U0aq|DGYWfeMA?BRp?*mN#G4X(L{<<)FBQ#LqAP~HI0FB{zQU387yb$Qo zxqO2^0I9eO8M~`kok9+2m|!^aW`HTr{E|a#gdy#%jE@dRADgpmpy(lAc_0T<#cCjh@*h;_7r&%Iq9|p};1C zhn;-Ij(=Z^%>xL<0Qea-8-gvMRaH8*^}$@2v5@=Ut{?vS@hjk2Avpd=!tdwyee=&0 z)4sg$&_y3^{ZRd)8ycRD>AZ=yh9k38{Q7@0&g)$?69WP!pxs=|4-#^RtjB&XFhJ4A z{&@tNlnfu7wM`*hp2Kh_oj@XpvoYvWON#CxK17$=(A;KsH6#k}!MYyVCEXM@iE^w0 zF*g=y1mKd8#zwGo?PMxlvmH$7;h*~3B0*G=4q8TbbeY=bcLh`p4P$#g=H}N2rz=ksiAFi-gU9`(|BYf96o)Agnd9CBmkg=VfcOH+g5QIj7j ze&ct};_Kb3gDW-@E+v+6x_Esk&oz)Ug%VHRK2)yckQ=Y9{VeyX<8?{RL?Y;r9rs*x zJ9F26Q}Tg|-0SS@p~f|@)Tul27k6q zudCP1a$^tQg{_f(enjY^?tO3X-o>jF!)Ls7gz5tDkL4Ox+7c-RpUV|mEb0v2XpA5&YSF(5eE7wX3X z={(Ddc7vWj8-gjOc<3VHJK(Z3n)aFrBeUS)IB&4t^YYm*U3DXGf>n}PzZH~B3qU## zTg=kHvOX z0Zd3?12A)b`|-29XvhS?k>lY9XnGbRUHa+0Z6vO)KTZ)3-~ip((5=*U%4m1dADFb( z>v$MeFk6EtHyeC7#L~|(mkk4N(@k_$_Eif-F8}(DYqm^yFa=yxId55uJvRuk>^XR{ z5es?;lD_!by47w@htKuBTLK=60c*6qSz4Wa4v=2haqmvq2AllK=#riIh%#*DYjNG})tm zt<`H#Wp?6zP@)9@zw&6l?(&TYo!RxMT?iaWnAj4>yw(j0Kl<@r^p`55 zN%(F0982UW)VVyOo3w7hPR%mN)?HbZfl&kGzN`CC-Fv${?nS2^EwwiU&m2xW8zE+UvSq)Quu+r(ZqtBrVyz7wELR}PTIqIE^)#+?_-7bgQW+ZUN)1K@FB4VZwe zZVDNs+d7r3!W0u3r=VhPWs{%fklFn^ip{XESh6n>QI4tKAaMgsou4f-eo*isozX!p7UkDa-R5!aG#?AV zJ4Wwlu>VjbwYK+x7+|<%KjUUlGZKIS5uH5y-JZ^%{9Z|3rsRwE?kl_hQq%?3 zaWh&HnN*d>zYR!2y}j7>&)ye4j_}93`2e>7^+b${%k9WgWg9zj%8Uwe5wzJU5XSX6 z}GMOvz0XR(yOL5X>LA-Phjx=%i`^=08RdiO2+9ve|UFCIN%OS82NvrIYzzLJB zna$A#>QO2b7P~d0EmFUgpr^9=>Si}?T(YM(@zT3o34x)V;53V`ZcDFYYco%!RDvSR znPTtxN(xYIKNdofFvOkrS80jH*f*@MoV_lYMq;B#*Ne6;^|2RYLm`i=5GSB0sDR$_ z<3!C;4!ne}*WT^k6nLAaz)33a6!%O@-c^1nm*?-Bz_!&G8s(zB#&-@!nRoGxnF1FO zFeROAMqZ1t3ldE`vdp_(k}HD5#*p9eDikW1ML;1RHGszrp8==vO64Hz(KCgn<(zkA zJKn}WNawz#H~y_1sZB<8J9p!3bM2DpyKu%@i!(WEkJpYX^?clw6+G!YCVb<52*n_SU{HHAqj96pn!FWs`cOC5 z67s##hO*HFPha4^Hb!ZW&8=zj?@MN4cqafaz{~%J*Bt+{Gs=f^()g>@a?2ChKD^N% z!L8pAwom;?18OeUQiS|wBcFR0+0{7qtr8i9en6JJ)KRCFg?YdSXw6EVs%4Deqv@4| z3)PtjuhNkb^w(IM4yxf84eBNu?PfSspsgvUxe&s3Lyf?7gAOD7t0wcnMpLxSPco|3 zS%(cU;~v!?L`|b9F5#NcD(ocJz8rLJboJU)d?%rB704CS)^U(o%H7o{NayV`Q>(B1 z;go@7`|V2`-*>{Hl~(4OZ&6beG}WGqc=vwrT?k38uF$5vHhN)U(>U-750UT?Ew^__ z?(*`wPcEO^eC&1bV;zz!4~xWA`zN9ojkgUqhqvCVBgR{&g$oa!aw>tIXA|hna%UBK z9*WD@0DkxF82AAd5o?w|^!AHm2xaNG4GZ__^}c#a(h8HTM2+POU=@&h zgaGCXWYXPpQH5MZe^;<3mJ z@3M&1cl_yLvh#RT&p#XM1KD#Ze4yx@=Deb?y_t0y&I~K~LsJdTwC;LM|7e${o*xdo zxt7f?vzcmRd|%LSDg_4YZep=yDy$jER;Y1h9Mx>1GwmO!WgQ_hy_#V1H*Tw5uHyQ9 z-{<97ps8`D;E+v8dqG|WTBNP6@sSf1iBXDUwj8)D?ho*@#>HC)=O@#O`)q*RPP7MH z^i)nLuF{e5cCP1(goc_bpE38kC^9Lwr==1|%eMBVJ+yJs$TL=-J&+%}Rg1W*<4gRL zgPTby7L;h*(WXjW>Zc0VC${p%b)q3{*?}zzrhLa@@EMRrYa~goTg&K1!FP^P{v`LL zh9JWxj*`_xO|pQPbTzC3jaO5}Gj^>muJ^q?NMl@b^~C9Ym2bUbM%rlHLYh~fTZVAa z(qo<(lZYRFI`<0+(LnrkVeHc3X=9GFB%Zk4l&d$zqj;*5B0aRJYpD0U=Cf-$`&|E@ zZ$B&$>v=Hb^BG^Jt$$>Hdr`||S;&sLRPe-^y?gi8#{dxkQMI{rcqhCeq$<}t3*`P} zEkt!NFNvxVP3hTLGsN8O5{0Pak^;$8LXYq?)j|wjniF&s@NvrMe*Q>Viaw$Hxzn=g zN_;Ea?2WRvUcsXO@7}Q1JF7cgCgPpOk7+(C))dZio&`B^Inf_j_1~Gbc&(W};C`N4 zn=SjByyJCUJBG2Q^G#rZo5cqUbjfAgo@p}gV;8Gh>XYxH!kSaXut`Rt@1`Q8&+$v) z5*ISW<6h9(PxNrl^PF~43@uU9(&-hS@Lmj96W~ldb2cr{WP5~k7eWB9acU||&`~cq zxmA>;TIL@%6)!wQ8LWznPy!6_&?{nH8s$@s+)oomYXX@~g1Q8VV5ay7c3NumfTuJg zNdmU^K-&Q&Tzxv1XBHQVAZ|cwmPFi>qMwiCd#3z5%)`PYy$z6qY|ruMbiN{PfTN=f zP0UV&M&tC8H=AlWWIx(W{+4TiuL1?IU#C- zJ=b~IBN}N_Upko_g&-7Ec~pVq`ji+@gPsQg0MUp+f?DBjsg9)d=)?opyE%qH7_e%; znnFGPt-Io|4;yaAOkh*HdQyyXvlmH^W za=JuJ5A*-b>jtBz1>NF**8;me{DyLKk5?(fZf{-|B^0Bv9(qyf{>$=*cS}Qr;cD& z5Ii=XF2s}^Zr8W&&ej`;^Wm*$ftd@eU&dMqWj*atuvn5TZIrPC!s`eY!3Wf1D|0g0GZS+>{J(S9hsox-Dx&5L#wH$f_ zHcL(Sd9Ov@Dr_9R>WT^-{?PmUl~#SVS77O6ul6yq%Z$#VqZoGICw#{^=ofQzk#-JY zw?!n;5-~0GRCtsN-dx3C;SACanvE1IH(0ir?N_a3(2)ynoNwvLVBz{++yoZRuOPp+GLvYKS0&rV-^WNYD>gzEyQv&*{BuHbunUIBmY$PUNeiopCZZ zbzP@9sSF+_^iZ`7{Yg^*Q{u~p+j9ProI!=mezmzbXW^y`0DPBHb$R-6N>tnPdg>Sk zHvA-_61>(&y(DUx@873up9j)+XZ17zcx4d6K$1>h#0+g8cYSqCj}S?J&u5+@_Awxd zN_s^ufS_kbr?Xug9@Cf__>uUQ)uif!Pp|EdddVpP!5OT6CFWEPBEhRo(9qDsE>?`r zj@aAKUReK=W@q2~_*{hTR-~m)$D|5`zt=r_2=7AiX5NLI=^560V4N7URz4lx0_*<* z_R-}UyelM`eNjc-_#rVkt5E-^((B54=C?eN@=Sn18R{Z$GCm??lrWD!6OK|?0(gm- z1U`Vw)5ZEz0@;WtF>(Q_LlJ^^7-rPEu{3;Kq@Y52GUWb?mNsqgYu#Lx>sV5 zzBp1P%0#}IeaO*IUhkS@IyFle>~1~Ig5Zg-kFgMQhcS`twst)^$9TEd3C(N+AHe9^ zy}Z?**-dd(w|!I{5(MX4x4W8T)Br>PhDC+H)MlS|7T@A|(++~K3LxlHy*#33*zJjU zsnx!q!t68>e)=$WMqjxYz_?Vo(qqRS!zD5Wx!1U2==!-OuyQFgD-70SY$D^+{(kzr zEWX>Q{YZi|97XcEUp~&})G;%4X8V^x0-ZTS+JliMt=pwz8U5A&gSEE~t9sqqh3BMO zx62<+#&kctz z%>ITh6sJPT|Aa0`{x5UzY&EMHK34eRy-J&GQ_dc1!81$n?}#xC@ED*982Wd&`@{xL zRtKl-mvxXDg^KB;1}Ur#s}}XZ0bzNCrU;GTNGiD7UF0lL0-%F&e#*I*DkmW*bRcDc zMn|&v!qzEo!J}izwHWspqiGfDVULrBUXuk^&XwyRwuoTR#7I<2Hb0;1Am}3wc?b?w zW``aS*D;~%8R|82sMZ0vMh)#VY?LaEZ!UWjE=w1BLQ$)KT3@hah4LLnYS!=^jUg$_ zg_d^D5GNNaTof6OLEYagiyGca2h6n$%p@2)g<@$HA1C^7*g5&-6pI1!y=T@}SGMPq zX=Lte6g#hnlnow#fu0zcea*{Z zH^HwfQdp=>Iuq2+8b2?ea<$xT%L_)j!_QH&MrSYvU(o7Id2(8k6ojL04w5^Q5=+l} z;-4^S*ivEao$iaTv2)a7*Alwl` zLl8a^6QFrq-YljU=?Y)g{OEeY(u!K%oI=m;svyjB{YIxiL=mu%<+(MuYvK8ZOf5QN zUSTR`*io`FQH2^=n!R{tal)5t3DGvnR`r2Q4ZqbBeJ5AHM6o!b;*DNWwnWEhVY$c+ zdN7gxy8qENgV!4jmQ>4UVm};ONF$l;wIQnehc634)2a(oR7BR>d((&@ z909KSML~UzA{nvUCsc%0Ty>ETw$L#xx5* zsv5ikhGp{UxTl_JePDZ>7Dq)|OqR!^f_WM)-XFE(Q>*Lf(zK*#6QGbF5jp9{J)Eo< zn;_smWuF=w*(tX)5)<>F4|0^o!59Xsa;sz`vfNN7y6!7}Nj2U!cRL#7sR=6$|Fx8$ zElCaXq{w~>GW}9ld(Rn;r-sz=Y7P%SJOQTWY}0F03gk@{j$YWovVQF0?&}H6gx|8= zFgaZ!8Rd*T_p%>L7xu+Hx8R$3Qr(s!ri(IewU2<82;T*0{dxnkevo38u5&MeZ6l80 zq)sE65<5tT3)Un%KJ18INP!+BNh8ScRDqYw9vjYWybf}l%;|sBvNxYe9^`wDb7%I_ zhj#qVGoN+EI?zIzB1vsxAHLGGQS1K&tZ{?M=k@@+ehk>!>S*3M3A*lDm*n~=vH^TV zTf3o(;8`vnA~t0@5H})jSJoFsi6zX)t_$dqYsO|8@WLh}jlt1+o=277ImCvBiy~Q# zxAejPbzG*@OnGh;ZMgsax8$Y=!t%HE8=O%CVX0{7MG|AatPykXHgK9r@RSo=Xi7-w z@QN#*u|Z$bXt2qj>Y&Q-ke6tRg%9_yry;4m#_|_?H;(mDzF|RlIM6zr(jUQEHgsn~ znAX(bu`B8Ok5ouWLa+4>+kN0{-qR^D7CVkE0z}NQI9@yG3{-+|--}7&Kt!8M?D>4V zIE|8@DN~k!u)G!bUrGJ5^iO#cj24pMqJclHb4ln&p2yoYqpygs^+NtsUdfK~BtF`l+h=v>L zWs^;saRgRXF&4Gr$edeHTWmwUQW&jUkOdTUizE202UavN^qY(5A;7LfkE8g+ddadM zcc0MM@9IyL6$9 zfrQjxBHPMB4ntW|noRCa?>XY_B_DcwE4%hVf6X<%yma7(*Jd=LNG5Rt>Q@C_S5LKJ zGr&v80gc*};lXxx07{>EUgD6@fs&F0851}iIk+f~xw73xIZM_yt26+4l-i8M=;6Ip zd$8m(4{O?S zG~m-44VDG9U&7R(5O(^B0P6_dWF*0_ekv7RLK<^VfNTyoj2ZufK<3;AN5}R)F=tJ zp_^NCCUqPO!*Cs=Ut&ENjqCqG=Fg~(QNFvdh=!*XZpI9A^|3$S#0$K1h!5S{(*A0 zAlmoVoN!Sx6?aCMAt;oc^axtiv2x>Rh~j`|i$&KFEe)nc`>@O;nI3%GT1Q7x^7@Az zfn<1cO-McK$|uEPQldAL5%nRxAJJ+CcZ!Sl@|u`B=O9k#*$l1$^j(s}sb>`47dra{#~;H8RYK*&9Y z)!06gwwg@yJ1YhY+(XF%hX2(=;oU3!De*wU87|*QH{ex!vV?IqR`fmzs}w+*1yTg~ zKd7l7jX=yGDO@3oYL!i;j~K%*lpuGF%neBp)VW<7P2_ic|eP*~!w;H@q6>&sRf zd)w)}FbOt8r8&o~B)tUz&!3B1OpOMt+GV6(9J=Ed4#wxRi!@8k ze11p1`Dw29)x4LE&*^5iw>Nzn8(E`Eq{V;}Pax$cwEdZQn^RuHw~0p9TD6xI#7z1N zE69=$sJOxW*JpqN)MVehTeIA~<49)tpMK^y-;ibBJlFLO47p_3Hw4^G!`7Z=U}r9g z_urB9*&H4&Pz8Nf<<-3)+0F+pWvuVX&0A2Mgs=f*iRWJ;- za2hF1z=x|7hTGke?AxowE94j7RKhFs%t%4ztaDcd#-v_ly%q6r42F=xaXdM2fr0FU zY;qCZGQoTq;wz@3Fi`{v6vd+D=4}xAhRu;Z)m_ni>3i~Ala|ED` ze)#F2s+7WuD*YMG{A`a*k>r%F_nT2mgx=Ra`Yaj@om_C}mwco&`|Hwqb3HXGX*`SHlG_Kx9AtEP8x zCn}89G)n~*>EqT}aELa~e$FOuT0jLh@OOT2R%XmjrbM>JOnWR zR`(?r^!y@{c(Is>#mZBQ(DH+51+E;?XPhJAha_pmAd|{? z>UhY)1*}YAFg21^-~~an=skyCkEj-e=g>t!UqA|M05q^rww}dVTY$e>In&Sd66?Vl zJ|UHaM}_;T_tSGeR1Hh>Bf4HR$*9!S<#Y9t4+*dJ;Uw3r9Nc>70d?TH_hX>i%UG&7u9 z2~e#Y9fa(?d+<}f4p`b3ZbSe5ZwkhKs*1e0A6%39XlYIR#84Ek=!BB-=c`)o3TXagu=o?9Sd2y9(@^Nv?vf`je*%V)E5P&1teY(f*C zUNLW-1V!XSJOEbYK8*x!3)GzQ~VlfJ$RJF3O#@I;3B8p4E#-VTI9LK1hK^+Qz32MsMK`9n2Q z=@dVl#3Z>rXPF!(f5bM+5l7aB|HNhNQ)Buzl3_Iu?ARs#Ytv(sq;d)MM$#`Fm}NOyBnlik&jV8%o!BHk1z6 zcWon~%y)0~3>?8eGZ9_B`}$G4uUH_FbIjJt;~t7L8m|}Cs)fF_d~Upo06dPu0! zPI6;!{VB82%x9~+ryK1T-w=O-kMv(bI~%*Hx~^R-w}nsU2RO|fzUn*-k2)L9ro+i| z2>-LV;Kj5&bM3{<3qiPv|6g&z?+YeT9G8n08IG4rHs!UK%hf}f z3co#sKU6k@{#sc2d&skqR?)eyz*<1Or_#MsR4YMw7wK;ZydrG-9NCKb_I|tp zW*?Gcu{ZQ$#VdFd2sLM-pJOld4Ng?xVyPh!bh=;Fb=V#jaawF65%(sFd*~L3RVM7 zrv#DV6Po~fJ+2Fbd>o@6TOu*K(gm_64sU^qk!{Gq_#1+094MNkCZRWmq-06y3GK&u&2y*UwxXR}9mXWwqP1a;6ut*r}_7yvQ4P-RI zWc&&N2pWx2dLvT~Qk}3(&iZ81l;bGW)us^-(p6=jcKO&}Vyt1{8Fn@?u*-Hww(8X5 zM39=+H0ViZB!wrYvCC>x%P~O*1o$dJDUzl5fbr*qTPCe^`W#ZC)ZZbBYk_I@otU*u zxb28QyiYCkcZw-pYIor@6+d!iz7#hb`cJi!J5uD9m2_u+$$6qYbQC_sIlHX(v=+HS zsvZZ6NO#q!CM8#TF3myul4sylZBpgp<&Y+a;I0Hf>AlIH^NDrt~aBZ>#n!r1wUVJC(Ci( z?4)Ts-Rx#s*WK*B_WpdcUl7H4dr*?$bbDA)UUz#`)AqU3!R>+ghyD!mZ~R)n3MdJH z=U+kQkGJ*bGN4r0B?3!;d}EPJ=p_tmwMk)XFo_0v837C)9Y|(*3{wQ*4ntE}&FLIu z;AF#DLXT#iT=SH_47v2eKe_qHT$xQlPdx6MwqIZRA_ap1gWpO$G{-~>yF^ZfT?ss4`(C@6M2-pR#N?^#(+W5zU!_-+g@YH;{e_$?~%&o*s6gIoL&kucq9rmr<4D1`J(1 zgXg<3nYa(K+mN>U(Q%#%J@XCTR$CFyXn$?;ZRfrJ%SYh5i;JKoZl{OGLCK|FUmK<$ z@zuZS@eeclgc_uWJM43LaM*@50X@CF`HF3kqJq=>?frwn#l1WsJa-Z&T7Q= z%&==<@Tug3=&q$-uQUTw1@hetl_Vhe7~Ji0gk%k6X=LV<0(`8plD~b6s-}EHzEUsa z4`FC1dPKoqpEk8l;q-QDw0f;PwoVDRw)@R-RbeawW$>#HGyeAVGua>5Sm*1QdAf)m zT_kl6ODY{Xld3r|4L2+|lPCcgrenvrdxc$0*U0UitfZB4dFR^oviL1SJ9SwdpVfaj zm`~EIX}&*IPAi%GNs zY|0)EBZshN2G4^0k%Al%z%E67#>j0nEfp>Vl1bdCQ2I_;z->5`DiKCKob6#3@-m@Gh3lDp|Ef0fWm!CV z;X&v--5*Ro1_F}nW5SrCDqOzjp|fGzn$OR)%{S0a`6c)6&;6y2<0Sl0-1MvLn@>N_ zI4zPmdu>iK6QogZTz@E7nYLc_olMul4GKLZ>2q;owZQa&&(a!eBY*Xn_ec0wZ?g}N z2i?ZuEz6@S|foD4>I9cNCeC z;@+FgeS0Dg(T4Mb@P+k91UUjuWtWr9AO)-{>JQ7VCm*UcLvc2;nT=!h5m%|vOkf+! z2>z+md8n$%zEk682ypaR?1dUhM$%)Uu z9+=6Kqeinhn$W0lU~ys)V}HPER7k@s9+;E{EgwwRS_a?Vl!jPfcfA|gh~gUc{w z7Ht7NbkXKbSfh56;^iR-8mFz|ojSPC7r7!S5hrWEh{H)9$~}%lOiZerxVC&~PpV3KwO&tMQmJ_fwb>xMg|-$Y#&~N|)CS7AoFpR519BZU6D0$|vFA3*9-AzE|tJ+Uvo$cYBY6b)aabi4TX?nx-lG_n*-3%RagE&+LWxrBWxZ@neR@+%Q(`-WkP?>G()xZU17KS;kcxBb#pWlVtnoo77Q4fMBs z2nX;8zyNUnE28~M^!{Ld-~u5;p`7x+7Q&70Hzwq@Tb0M7hmQ~o`eE6gnM%YkU^8)7 za9Q?8F(DUujJPn22XUiLl#rQNO62glqW~IG_hpI^B2ZY4W|;e-vZnYJu^Kc}X+rc` zo+4*?v8pw0zM!_9 z;q-fY$5pM^TUq4CWvr^_OT%*Np9!;Ro(vm9@S<8)VO(qPGkhb|}b-!H3-IP0ozP5MoHgw^c+>H0{k}>QQlGxAIFE3+VJU;lunMI&^ zL5&}v4wY9$+!$B?3DVb0k8Sl?2pIj09_A$OyvhRSf9kN-4EV8@vE+Uk!C(S7qb;2! z4whlr{Es)zt~HH9`S+d#yg?6t+kXW)mcQQiudXQuHvUi4#v(XwL!ro!NmKkj1b~BZ zb1-crpGc@+CR*9F+n>nEkr)pL7)P^(+>bs8x$nQvc}|6Zt$1NJSwtK~XE-{$Jza*K zF4-#FS|uOeTk!TZ+ILpXA__#0)oc*kL=9q3k)fUQF{t@@&s)PIugcXn`Qt!KKawYM zjfi8!h7=&jk1(|TqZ4}~m+kk-^h${}K5kQ^P+t4>4`lRv6Wroq)XLfJi!&AK)kfo; zt;Y)u=3{VXN!aO1yZiC_cvst(PkmvSk5#(c&$owD*^MW39ek`do(#M?1cWbrPNx(H{dOy9;Af@!?;U3JfA(*F4M8?; z^+gc#+NIfy(NreT@S9;x;eaGqY1P#zm*6~jDQxDF4wks3A95b);|IhvTfc<>@v+hn zK9)}dVDJgp;cpe{1xSt}V%f91v*k?aiY$JbR&%)qT~#d^o)tRz##wo%=o%G$wf4?h zhHMSC2I=7O^@J?g=k-kAPmy=}jn06saDIqbmQcwiLxKd13Qf>$sN)5yejuq(@a#C@ z<1naDQ*-zU z_u4pU>hhje^RfN6*0Ma06PaBjr!!BI0uDrKSb+y>_En}cP@v*<5N;>mrquyaOX17M zW%HB{3MM)QAaWFzf+%*3SrtD{ulCf~+tzE7@Mv10sd&2e3>tMIyQq{z%C9m&*EC+N#h!JVW42Td(L%a^8NsFo>|$R@ig*lGie^2T;Z`ZCU;(q-Ae7BaPL zd|+~LE^$`N6hucaJw?G?#R5McpFE2^P%N-7o2>L&0uuJD0*Oo)km96LHRBJsJo~d`XDEfuIN^VI=K}Kq> ztvXFz?9I!CEO>hNFfTafI9p)W;=OOZlEp^~)CwXSIZa#B6Zq^?l=MF;?Qf48-gEvq zX<2akaoWCL_v3T-)#o2y`cR+#JR2Z!{&_ykT>n$UfLmozGWLf~^0%DdlX5QjL>w(Z z_wUGHBB6%T_7k&Vs^DFeBbJk&{5kF0P<=K#hQ-l>v;>-`2&9>KCGR4EbSR{(E=41; zB+={@sqRFvbVYgI;oWoxaZuZ{2oPBn2I{L=y5Qa>? z_+_)n>ZVNjr?!LnXwoq;^)+FmjvAO&|2|8o#i|i<4jr;tXxVsOpzBPWdCNb($fN)1 zgT0^Y*3?01MexH9Eu=hww)EC@kx7)cw-M#pyzEs^vi5w;QK( zgx#}qu);+1dqu$0KI>l zJl2%mMqelj0S-fPvZGmEIx|Vw1n}aW|RCKp>#hXrJ9s57EpOAoAf4 z28YWqs}Xgj+74By6Iktv%-1NlfeAvX+66!hooMNhISNo!U$@5<3Up=OPQMo^1_uQK zt(WN2L6-Zx;?rQ-ib0E7;ZJh<2^KGI&Ln!vV?2;8Oj0MhbYU_JKlzF7>{FY?($+oV zQ=K*m))sGO6|?}F;LRT2M^EnCVQYX(J4JC7(QD_3Q$n7M9>b2lty#oHYBd&MmsiAg zHS>qMb(7m;pd`Jq6WGr15aC_aBi!GbBFyl_S@E~TxuHNJ>=K7b^v{Mrl_J|B=da+3 z&WS}cXi^%% zr4ta=gfvW4OSu#Ai)vD{RR92G*^aW&=_67ktNyHrZu4MQo*=~u z7yLp7ia>VlFu)a=w3^Ulc3%_%ip7FyT3s=a_CbBy!K+WLV`O`2m zirjssiQ`JU=d*omvD=G-8M&|rl8S(h&*$**z6Zm*>$4N2$*`B=0X^R5+hc-{Uv_VN z-@Mh7SpzAc@#zB|I0jQ)ksS#QL+;Pt7s&pU@G%MP=JqKF8ZGQa(vEzJAG*s-5$k2q z)z(cBMu)^pl3Tt^XJxfz)Ka~@-j&g5YAsD-<<_3c1iQvS;vMXCEnnmMj%Z~*Ox@tV zb{>y`WFsA-Ygp*YYFO!6@7-9%S*#v12Wd01Rmku##q5=CGj^6(BsuBrGNmtj73Abd zMpl-aLG7xFN+F#kC8b+I!mRcUFp=V_R?e9HGIZOjVaoyblzy>arPA zEnmn8f4h_7@H@%#*PZ-H(q|+Q0z{+x2ixU{gP9F3{7&K!aUuo7x2eO)OZgnG8cRk} zS;Sz9BVP+^p{z1*|KQrmfhT;cBhBTL`JgZiD#ezH>0j_h%J7Z zW|CbuIgNyBf>DN>Cb`z(Vm;az1`^nnMY~mIlNza$h*c*9G!G-X6{uY8k(i{57=zh- z>c<9ttEuMac=uKsd6MdO;Y=^QcgqL|u;eI}Aj$sGQHS_K<)iX$5mdy3|G1#e_{$TH zALU2OHl;&vSV`Jc5`1;tFO<7?kJcnpNR01Y+ST?y6cx-xy%)=8tPO4{rBz%&; zC46sseq5bxkLADYeRKEY`rGlR$==?F2LKAoMlcew%|-|sQ^iIomcYSA7_KZSmEGu_ zfUbJQ@7|FGcmiMrxc(iN;1vr#&Oa1yuuDOIf<>h8iUq!;4zF0?Qnhd?FZi*l|Kh3p zC3tB5i>Iz^{J%cdkC0vv6SqyZ#oKgsLberpvdg?3T}f;FYwY$leDeKq!#5=>^_dTQDzX~6F!n?2c2mM zRB#(xncLo|tpt(pIl7Ri`~-`B>flP&j$LZ+)I9YP#?#7=jQ-`wP880g#-50iC>yt} z=ZoouAE6Tg!b=A=&Ph+~7cF$>CYzH8$^yki?Y}X8$-e8(-Ms>INum4(;Y-8gHyS_# zeomIZDpb-wVmOw7P3I8x=alB(?Xkbk35!O8COPD^1os8FVMiho-H=+tcMAF<4ck$m zgf+QzB1702XGi#qSt64^0tLjD!YWa!BBv712Cf|R`n}ST2GRgI07>xwTo3=xNHko* zf6P=E4CBI?q>#}C;9rO~IhK@{DV#;M_eX3M1;9*-W=G zxkLf?BSKPl>%r{j|90^|mV=8Ga}`^w=BnW+#@c9W^+LVLyMIAR;kB{L_GqqBTisfh z&$pwsvHuL`=}OW4^t{;UtwA+M?QD)!Ki4yuaIEZ1w-g26(lW_oAa|cPx|FerVav zWdAkMDb*b%4b9(mzBJq(G{7UcJ*)smBsjaHiG;oy7K%+dS1?BiHW8i1Fqm#28kK;& z#^#K6D3Kf!_Ln>~0PrLT;S>A=1L41o1OWcNtp)<(0=WVC@E<$?f{;nuEerYqCI5Jg zA!@`hKX{=g8G=m2)G|C>C>DlCq;ev!RtO5k6oeWGpP3JbvFSE_KvORp&p?q|Hc|H;SYpGs6Xizg1n1)2O--GbmAjQg(@KP(#f zp@sb+UgKg?4X4?lUJX4f{9}IFK;E_ZeH^j4-H8oX$#4QXWgcZmlch`si9%KQ;WUGC zqM+gOhZt~KU#=)Y*-tV;>**v=(k)i<#evdq@1yt@33r2Jjzh{?#c-L=raufWC?kee zkiJl9t)ykBSY>ArW!KCzILco$8{|j3S3BytpI~Gagpl`op8;kHDb!pAPMR5E%X==0X>eiLJ3^0Xy_G1N`oe zB;k(m5kMP$N1J{G-Nz;jD0l+`j_`4gm^)r=j#M2h+1r%J#~_o{$IX(RgyeVP6Sp1_og)f1i4kG%~rE zji&9pGK^l70*n-zxh7zz-mIRciFPZIAw*MNkbXJL=evl-m^zCDk1ho{XSU9!aiTf; zTOv$1?%iSxTedWIuHRnpFKieapbs}=<`0kb3qL|yfsZ>R(^Q7(lmELvCk|3(K;!|C zg(1?btU@+6q(a%4VGKS^C2%t+Aoy8L+r4?1K}PY1DF@O3L}LV^=rqF77)itmX+EXOFHQYbH5DBQZ6D~5(XW>AU`mW?$R6Wx+_ja z!sXBFrK=Es7d!v~zri0zH{8sfKg?_}0r;c*QtAY6*8fw0<=1%AKf*f+UTF8P;PHES zw?m?9-hlq?cq#So!dQ`QUZenH=bs#^SE^>I6+;3~M00$0fwNZed9u|%1MxWLLmLfMx1JSz(EGjk&7Oq0ENC1o7YCHG#Kr|2^ zBiyE8O)3#lfm(EAig*n2h@fDVg}W4#MS&T*bAY!!6b$$~dYSJzEo4a{6|JpjbFJIrhw8Ub^xvW)u4RD5SPaFHq3%(ov6M2 z)O09`N-FP3huij83b*>agK+cyc>c36YK~66{f~vJsalRAt;ciq`tO)H+?{6t`Ur~- z2eA4LICkrOf$gR)#fqv7^B;z`pTV(P5(k`?tAQb;+WeidS6x>tpPIcNP+uAaTo3P! z6&t@4?(x4&|I`*$Z+Q3f$N6DWM*icVSNB$ouzU}ADo>*^K?P6c?HHqJJh5b1X!RZ% zEcNvkl`A$QDeZPlqG%$8UPm)PZHmn7Bz(4FpSWoh8j!(Qw&PvVeW(+J_H5>(L@sUU zl9YSUN|L1QuD2ox-)iqbUZC(>q=Hc{Ez&f!bhTsebSoJ{o(>UhLro%Yk`v6JwoEeW zd6i{4wjyx$dKW)iS_8)+Tk90h^~!Q3-_M8TiLWjhcJjmh<`{D$n5qtn;>k&Eij$o# z4phQq?J8f$(fJ*giMt(D#^p!qZI$q9vK>`I=tfeio~FbeRa2!rC@|Hu+zzryPju)V zmv)j{(6a&=T!|!v6fBPFhS>zHUv#iCNC5m_p_??#1~ODjm3*k$fzA0Xv&(B6%B;4n z5i4@a_NlbyI_^XL_Y1`pjz4$TCbA}XUhHAcMZ7bct$X8gd0WWQh5`tOOvEgOnpxoh5l8MKI#QyH&c0l*$7+PiCgWHur%<8r&o(y zI(!S1ZWAJt!|s!;52AEa$weXeZ{@t zPmX=L_zVJ{xeM}hoc>@_FWg#)2wVFWDHH)dY83puR&X=0 zr$@bCP%^=%NR%9=xtcWQY%Z-`3@EqV`#^Q=F5Wd8C zDbGWo6$O_YqjfQ0kzy^i47;hOb-6Bw%Z-6q*s(r6dLSZ{eoyEceP2ZThkUGFO*Ey) zmb1?=6RW^cwAPN6Zd&Fb+w(_phCA3K?|!K)rhvg8Hp$*e%4Ejl#oLz2(Vp4JkeCW;NLEb=u`MfILSb}9pENnK zy6uoaWH{u*J4>$9@(-5K(JU)+CcZBG;c{H}>{kP20^R~+jyQvvOBYQ0108AhkmlEG zqUA5E4hh|>Qq{i1GdGp6PI@XrvcG>wdDh(iFd6Xt8^>J>-LpINYPga@L2x0nq`22) z6NiTk%G~B-dbTN#=PjJD07{v2z7&K#h!JUZ)_F_$^Hf)tVg+|}Ci<^WjEe|kHo9@H zS;~|`8fILd=9WFhHcMjN)et#dWGxOHt<3UL(w0n!R?ShU7A>+XAXX*0aS~2mqd^WJ z>p4(^D7KWkISS$e*)>~lC80i=Ru+y5FU0WGAfN3@4N?uD(NVo_u0(F`BX)X+QBc9t z@0ot5*|-nnADZz6;xWWd7%2SSTl9ao8GcQuTI{~?VT7?EcFj`bXZDhY=Vddw?RyIe zef%1O@uCs9AD9;r+G;Utv1L@bmHaOE;o(*RBTj?kT?3MS|IVcyjGw{@^Q+zrM${9d z(^KQ9wuUs$zvh(0n->(_r8+)p2g8pR3JeUImLYL z1pMO%TXMoh8B$E6R&cyg3(P_%@;h#iRyS*fnMEZ_47Wsl)u)fdH-aQ}kE4O^8=+<_ zv1?{L^?CujN0*CAt9Ke1lUP%Xhzk#emiMO6Pi?!sHCb=0Z%{L<8LgCL1Sf32JEu+? zSof~_ww|nM=F{))I6udm3eNg=gKdyiOzUXsuJ1B-VPAJVQHhkr$Oq_0rif z>8;hJcDxvI{8_e)iGf#b(cLG5AjKK3u1jvyJzUi;&1GYBw%o1=d2IS;lg9HN#SUqm zf^q)NL(BCtA4ryrzI|UMLHB%>RDRS+{#yJzPNDwuX^PI3wIa@yps$%BDM#cihg)gv zE0lMxAsVIYy+2ien(3|@bVEDT59Qqbyz}RF_hx*p` z=L@9NR+JklK%Z$Sz{DHYXYtT{5;C%I_l}|Hnc>YV`W_^kAUd^q;x^49{TFmGng%gG z58*fi6;~}ryJZrz`{J@C0SUau)soa(^P=kMVix=EUf)b^1wzEEUol^CBO@45M|!;F zbwZt@qXIHLTxGe`1@W+= zoH(}SVw)l*d?JI<1S1~I^pkjk1X6`!ilPZggY6(R5jN3w5s?vQF&9lSiYTl_(J^X> zqIdH`X-KhPwb&V=sE0I$22$E#Yi5=`nefn1CYhLgG`{TN826CqzV;}McgF6#@gXUs zbETM{0Xg0mW@d*rZi=+{W*YPXzB%{{}3SVUw(GrB{6SQR$NJy<0 zSQ6nu?$fY6WHA0g&8_MnkQLiS0e!B+n~6Qv!!5@#aj>USLjuQ-2_Yt;=DrWE5$LF;?w$_4=Nxsk+#P=5z0#``V5H^ z5%FU}soK%$MtF(pHwh9NL^73@FFJIUVvH)KwLh|?o4KanYoxy$hU&$HyWS8QbU-zH zrHF?e=y>Pp02NLi|#C;h~MAY*N-z2re1ktC18uTMmx*5%pv_Tp7?XpX`^LS?2>;uMZ?& z_4|CJ%j_fNEoMqBUP_%}CIfi|qMnPm4-gUgW{9bZh*w0sZqFc-cufy<7^;N2$8a5O zDfvr81V0GpOuG`wSCq>~i*oy(m49WMe;Xos-I0I0 zln>NTn>y7 z&~3=4esV?f=z3fue z6lMz%`kLq@m!BCZ>Vyci}9a0KcKe`+cueVKB@j;2{vWEz1 z#q7fpq<5cTiG{K~hE*DkDpilyQI9SwJA09-z@g~&%*E~cmx>5>lKM8f#IgP*MK|9Pj_mh zxMi zvMcN4btBbfYwtvGMQ!UjVR(*1uimIHC5rdn&HuEBHQAU9ur>n6+cCDxb3X& z62$$YSdYI&>Ai?cQ;jR4g!`p3m1&d4ObdqKi-%2tCp3@aNJEvYAtH%RC=*rHq2b}~ z5r$(*K#l?cLCwZ!kv}fs9=q29xzu4LjVoKEGq zrSw6B+>zXy5e!;HgO(yg%dSVr+>e3Jo$vxy-P^OD5rc*AnmvelgMae#iQK>P!!H_47x+BYv*{+&~Lp zBpeL*2bA(pfc2lP541+2-!LS2izwd4^)C!*cM!t)zi$zRsO9}j1HxW8)9797F1hDF z#gMR-u z(r};#;}4)l8qfxBL?qAF0}#;hTcW_5AT>k+Ch#y4gvF&6JDPzAWWoAvllRX*j1T|lVt~?L9gel$Uw>FM6Kq-?f(~R6 zWs%tI^8%jet`57JKoVdgC_d3(1~~|xGI4k&s8lMN(-yB&kTK{h#n=ljhN+4lGQ8ox-6Ns8%#DD@a!~jvk6dYWsiUh(GZDb>& z1Or7X8Yx<&j(|Xcf&y|YDk{jR(qeH@+M@nWa5UWC?dN{-=Q~c`=lMR*dB*pg0}o)- zNw;ZbUS{~QgI-GLCFXbo$6UWjMj0addXx3>33e$eWnDXq6U8~QW{(nu*#xTe?9BVI z!+XaD1?qI?qA&kVx_bgULxD*h;sQgKiftPF7da>7sJuF;Co^dkTvns5whCX|pXy@; zN+aIsB!5F*TQZ9fBXNC6WF9x9BroW_X1k*v^*(zg zZq20cdqQsh_UBC!=TfW_){#0;>-&v;aeX0ms38#H=235ZcGG#yZXYt%*JfS*&c{86 z40WS85Ugu;zM(?9n*kWH=tV|sn!Exx8(T$REZpw5WhrH03zru`c48ZA>;s#owHKez zj_Ff^e|>5v>&Q1`eF-m@R(1*1Ro5KUC)W0yK_>U9k1l!{X%qIiNf84hBA$FD=m@L@A45%NPQ zGg($rf6sIb%yoIQXpAAyPz~GCWh?8BZ>9xCa$M6EjS)1(v=?U=?%cCGu->kRLqXimOUu}|iouckJi^Su^kJiH~= z=RB+C6yibg_^^0w$BG@xY|n=XFsuDkxv!oFw8Xwen$!ozhhJg6-xu0jM!I#A_rsd3 zKLTxeZTOj>TBH3hAC*AZDauImigCr_=La*`3_dAn5qedX1PG4sX4Q!lp{IvWILquY zJ9|{0k_zglJZ6r$b@BxNrQ~K2KCnLSnLUYpoD#d{s=n_|_6aux=u$zGURCt&r$z=_ z__V)Etu!D&HRua4TKHlicLylsA`v=9XrkCF18wSk(n?x+GgHaXPuQGf)|sKJ8uP0j z(X9KJ4nEcB-oQlne{b*a{X;a_nKKuW>R7hLYW>%kTu%>uMN^lLstExqK6+qrR8T%n z2E}(AH&#ru#%j8S4)=$*=IWsWLiZ0;wP&&j30sC=a65(Ocu)5H3-Zle%CBC06nC&5;m7=N_? z_+0@exKed=4?nFb!47%o!Slzy(xkD@YexcXwqH(p``q8vh5qnHeD<{Q$^K=L#gV6P zh4Q~TJ1WGOL^XxXNyZyu5dr>XL8HtA8_eGsG`pp3%M({vFgyly;su|rVG-NJkJxsT zW7}1O=AMpL9>x+W;#MJC7t25sWh-;A%53tyEryY+rXCSGEUNDM%D_0-sClEN5eFUC64QFf_udRk)_ zj>B*Xa9R?v=QGHFJ#K)lf*~Occ$Ypj0|VZhn6@499>#GMiCeSPOmzt8rQPgLMr!%d zNI!N^`>SL^4DLR5mP3Nl@%VS1t`{S`Lgp0vEPs3TO&{h7ZfigY=!DlKhA-JP`#l}%$=*D%mG*UsLsvJmZ`H`BOKp%WFi zaGMW>ykG8p*>zS*5b}~Obo9z!(CojuU4VSJe`Q}^YRDZ*v-Rww!qcd>se@A6_RqQl zu#)o?H5K`aAlyQ_VAyH$a0{kqKz<{_F@)Ha|0z*Z8?%MU#KLxgEC z@A-E~*!C5ON!ia!TAU2f$;Ch}0PEZ2&SrKOAS*VgsgbqQ@;wC=&}v{eKyVcV`>S=f zBt&Fo}+c&8LVPc zl>vhROO>-fmdWv`mxgNe$U^FBPy`O40xS2VDQEH!)kUr1i>+8 z>@I1zXNH=&cN{;FE(>t3K{s8Y z&{P7fkF%*op82ekzntpT*BJMYtAqFP-R!PK;Jgh18 z>el0DXh$&~5qr@|Jm@%4Gmn?kIMG#NxY2^WYJl7;a@HIqHxF`|5b9sSMW8?DT|r}Y z9t_(1jD7}Rs79bB)^rDOQp{ARwak0Yd8rpDh4@deZ?x`1Ju+9nT{=iXQvSw5)Qt+qp+K;9Y*9 zW7~i?DSHlA`fB|^30;MJ@I+Gd5BwU(YuDVw&t;pGhw-fGyRC5LHc z?}5utAKp&-QH}OS@_5w$;$2L8=%Fi&OK?RX$Q_f)BB}eA502>}%^HrU68Icqo3KGg zE&nN}x+4o_61;_JH{O}4=ahPKehIK`@Z=%v&vtNkmLj4C%eQKhe4Xd61WO)Z$YkSBY|t9noLH zEJr-Zl?3(gWS)f2%&_}k)zT|TDYbAn4u7zijc`MpeLXq!6)UIhD%OE~_n7~-)S2m| zxK61}UqN5poLO*5{N3REkQX!FExRqBRPqBSA6-RULLwGktPB?f3$89$`ptT`=6ks% z>+4TUloYE+_MW>Uev)2(_-xTj+a1w&V6K4+Y)+FbJIj3C<=iY!J#RA|O$EOPS#s0Qr}z_@sALp3Rp&}} zl{brx^4oED-&A-IMX?WW1w0L9k)<*&2iT&3{XVfX!S>~Z;e;n%5LmhMfpw^}EZvAz zVBT4vwzm3zvNKHz^%neRAOCpRdz;%KgHcImol0deB6`>K7Y%dH5gzlGsCSBYz=XxF zPO`0n8~0-_4F`w=rG|K0_5qz8_b=%`#ukNKn%rJ;P;-23=+-2E8Rc*$f~Zef7vj&l zbgp^d#Ql!cOLK2l1BSpYviceAnXL`scf_XOnN%7yZ6Bui|5eF8AbI|v$oPw5nO5Sq z0>#kkL);HeY(%$!xL;%@Uq^=w(H}|YgwxYe##mv_Z1~MgU7K}|%!^$2WBLgDkvcn4 zSBB{ZogzK1gjK8*luRhw9nn?d5``4yN~dTLdF_-@-ph#%VmeC8>FH){{~6c9>4_l1 zluy22>6eZzTFbWNY`PGGd+@sU$McZ`_s_NHOy4UD9SgRpxRj8dei{3&u-^etFT*y&YbDkjeRR#OdL+Cvp z{DijLi>i@pq~U2cz-RwYlC3t$gvSKTG&qc})^vqKN=rwjV28>Fxf_KHQ>}K^ov@pd z3K6oHI(vFhz(xgcL~Dx&D#O&h>3j!;6r2u{N{!Fne1WpK4+Y*JuEut(7OrZJCD$Y# zX+NTE=PW7fukI8YX(s%Mwm0w2AgO=Z-rUIb&al~p+#i%EVV7F$y49OvH+Acnn?G(fWW*{84VeGJ?i4{+s5XW+SVx;JW{3fN)hi)6{^^9Y0*Po7C-_$X)jL9Rf~E; z64zRcSqLRd!(KTZSR35w1Svyk;P2@6JRB7#jlRywXo~>X)KY$lVcu)JqvQoTe0xxc#*PR*@iWQf7S700>`u}Arz zL#y^i57atnQY&K`m(qLlX8w@&`8LEU$FYX<>H`EG--S+6U!QA-QV{PPo;v?RD?6-u zOV!qu*4l#7{kGkmvpcOi^Dk^@IevlV22JM;ET%web3^NEq`kK)!^#O+JmoE89~J4arsTX_1} z;R)chjvc)Mhm=PQtESP~6JIF9FQsTiL6u-N@80e$(a?$I*(OD9v;2S8uvFYK-9)ia zJ*(7WqS@&iUy1#Nw)hi;#DIKw&HNUAz;9c>U#ULbFr8@2$w$LQ&VkGCtou>fVW zm)@-en@zj}OXD?pgt-AIdy)Ii2N9+~qNX;YRduv28yP}p>k(T$GiYjlj$Mgo)(LbF z_Ch_`8D;^6?%8XVxVb08*s^{#Ymf(JshRrWtff`7603h;U{gJF6#XCrW(Oio+#(=Z zp9CnU?@7g8=>?ww`HvNtf4s1mzOI5PL0Ir^4JZVmXC>k)rNgimkcMJvNCV_^Rmcq7 zlnBs?qpbs!b~K{EyGz6c>7DU9oHQ|_HCGu=ySkqf-j;`^W3T4ek-CrLT;8f!bIjAS zED;IRKXy@igjAaoY<=03m;D-w*~y?retVgn^2D#Ki{idwR<0Uhl`Vg$N)l!=**(bX zuMS?q9%sNvKnf)ACp;jRMJdn)NW2!K&X#mD3t_4jS0gHFhY0v!HnVoDRN z`L}ap7fEnb9L+*ZvsW>v3SC9jj9i`nmxwJcjd&T^nImz&PFS@$oPE^E+(Krhk<(tG zyQgIYT@>|0<$q)_5D4jsU?9M@gU~c75#$5P3-~fAu`Np-zm7bAp^uS?!_#mOFS0FD zSKXPg>Se^*LjCo}MkI}tA4`^ncNUe;Qu@-JcOkn{3Zq(=8leVE1+oQi50mQ|#1OJ{ zw7MCY86&1=!?oRtnx)|oghxe$GVMt10v%HF!TBVz*HP0?LE3Vg`x*La?4FG(E;@jO zPtr(trOz38H(9lb;NLYdu!Yf3jooI&97T>A9ApHBbcEi6AvK^6S%YgoQC<`<+3U(7 zdgf_4#KbjUH2)!6kCbqa*%Jxk;?4E>&6Fi7&;an0mk)uP1@PMmoFgE_lbgXJh%Dq` s)#YekZd)GC&iSCL?|4TZL3{T(D_<@%$CPwxh~FPZ`&bD3FJ|EWe=Hr)IRF3v literal 0 HcmV?d00001 diff --git a/assets/twowheeledconst.gif b/assets/twowheeledconst.gif new file mode 100644 index 0000000000000000000000000000000000000000..cedd5da532867b170379fd10c5f94221100b6410 GIT binary patch literal 59979 zcmdSAXH*nlqpw*+NlFF@5}OPX1<6fra%{3FQNTu`f+Ru7vB_DGOp~F>83D;TG)W`} zL2|UU$N&4DyXKrb=gxeXweGB`PrYhYckK_=&;IS-eo9SU^{J$F5cYShYi8i@0RjLB z0KfnM4gg31Kmh>yUuQue00IJFAOH>mkRSjB0?_}u6a)bv5C8@N;1B=_0Z^w8i1n#BpN`W0rWoug@OPm1c1T-C>($y z0VoQ9q5&uXf`UL$2nY%TLE#`M5(GtoplA>jfIvYIC}3c#Qs z7!(47!eCH142pz7Q7|YP1_j_y5F84DLt$_z91caop(r>M4Tl0qCL0f8f6a0DEVK*A9yI06kv07wJ~ ziGUyxFeCzwL?Dp}6cT|(A^;QughD`22p9?hMY@1i-)m3>?590SpSjpaBd3!hk>+2nYiMVc;MP5`;m4FlZ14fM7rn z3n$!W5x@-a|NRX7^EUwq zFu?oY43LxD?hiPmY(}PVR)ugva@AylsXXOqDna9w(puYrcw*Tw+(kV*^+ZzbVr5D9 z!jU9FlK~iEeX&-SnCrpl5ap&;?$h9(R7*+hn)#5}KSuP)`+6lRP*qu?%lx@=(|YIC z;fC^s>K9+49%(jKEY>^DAfAmhRxUTWZ4T#XHdU>*`J5lDjx<%Tbp_!NGif!~tbd81 zDDM%b3Av&t9qwuo$xXbQX>STXW^Ij$=kjxYPBet)7wt>kfRYlHJb#q*Ik?X23P z~>||IKOYV3XH}3Cbxef5_W_!&$?dJF}8FME1y>8jbbwJQ@=lSQWm*#%tG%wAI zew)5q09WPRFHAOe-Y-gbh%(K!rblq+#|AF(6y&8!9egf{8s0~I3PbFd*9>5Ie^emn zoqtp|bAIJ5D{FN=s4B%ScP{UuSbkO8PV|G%phf)0Vf~~k-w|@wIJ%^65dRf_(YdtREq<9ey>u>H;<>$vMzKJ9TgE-mb& zhk&c%qyUY5=-PdwxKiD;C8g!wNBYvgwt(3C@boK7IRDuoNN~QUk0!UGc9@~WQg~RX z8eKQ4mI6B;d%9auA8~bfC>qFrZjmtZu!*sLN=%pWViY1V#uHHqN&o-~xCc3pp~>&_ z`T54_DA`6BHh2QB0SDl*jvu>Rn#Z2hP`H96^vTO|)#5GtWQ|@-n>An(gJemt6z~=7 zMk_NFBSw;aG^2mb-fTvxjW=(_89un(N;mm*yPfGhe!H6*-r2JEDe1x8UTNB=yZs!> z%8N9PM$tFeu3vJ3=5VY9^e5Vvd!<*qF^~OE`bb^X{`1FlwFj{~l!NOQa)T|ph{*hef|;_G3w%J{&^S3wN=V!;*j`)0Qq^9Ox>{PzhY z$ph{|y0Pg`f(XR&1P0Qm>&W|F6SO>1Xk@`^CJ*s`kF$0yUfT1(ySE_h#&!*1dlCPJK~rbXlBL9y&wjHLPM+A$>}iP=A*7VT!^zCMhF04 ze7|G{lqw5 zMo>7tH@VCop`^gWP3CKYVg1&^@LW(4@B8UuO=A)DDt`_$CY}+{R9&h|2>W9*su8Nw zDW|@(LQWNRtrt}y$pd}*ED5)oV#fMuZASWn1&b*b29zrE?GB*NWn&cDo+@Mf_AUf$ zTGb)v>BV-%Pm?6MjRLo`DPM6&v`OZ>PS5Zzw!e%xE5l5vkJsno)V+-SUZyjhESf_g zz^OnvtP|E+pZDd0EE|_d52J_7M^|tMi6EweEs+Jcw|n4)mdQ_W!*C9lQbqM)123z+ z&vP&*i={c0b6#eEMV6Y!RVkkk=W&db_vmRVZvQE1LJN4b$&zuuZ0pjnaD~bdXL0BYU*q2HY=O4y3#L{F5mEn5)5kGk~ z7rxOiFdYR|gMt!BUO?D8Px~v(im5W z;YZIkv|al=6PI`$ZEZLkQ2PSUTjC+bq^sdq-&Goyo}{iBAqBe#vi0DneX#XaaU=f? zmu8>GLYx^Z)6prt40(IQJ}!#VFZF$Lf<~LAD_3cD-GZ`Q`c0c zBh~2>r(uk-bL^Mh2zZkejjwsdYc~0cwMrIJ5p&T{&^hFI5skAtLA2S*pXgSpC?34u z`YG98k_|@(W-_)rA4)F*!fyIwhZ|4i~Jxaga=k!k`tlRt}T+fMcamF|-Mfo?j z<>DMfomH)#@7!+>#((|h{Zj45&fD%^&kj`krTDM~uSE-TT)!Vm$DO@yc43Pf@e{S& z=y=!cPw^NT?C&@Ghx4Xe;isOLXM4LVX8P&CuY3=F1OM$TgoMd{m}|Od@%Fi73vXzd zr^mI-R)L&PhRQc&^U})Gr)%pY@jB^6UDF#{f;!U~=bnbXZ3pbvl2f&>&MHN<5w!7l zW3Q^TOQL@ZI)sB}Cz!I!Hs^kTatS8Zt1g>M+P*tex6e@zt6t%yeIMrCCXoyj`i(LffGwm8S^TfzA$!`Q_&|4I0`tYmV{tw17rK>dtqNVKbo+Glz#C43l@nzf2Gp!gc9$!5h1#^ zer}M5M(LtFPa|yHBb-vg^HX5 zg%wn>IHwjuFjH&hE z4fKh-9}&HHV>W-IfkMUIuZ_L9h&6DGZ_$qnPmGy#jQazLv$&2Kd1^S#9WQnhmqHbf z??iTi(!TNeK-$7^2Z1o%bHj0p1a9LW5>oD$CaBqZ5u4GH-wG2s!8sx&*wq7h$|RV~ zLeM@5!%q{0TO_b~l054YdokfjM4pL9gGsLnlA7)%^JgS%%}4!)Br`}R3G6>bHhXKf z#6j7T^SDy*HH!smK|xpPEoIb+bPuh{lpW3kgX#&r&xs4WU+NCLe{f0+zDa)lF4I|^ z+{GzJl#?x*N8Z~uixR`F3QVT^NoLpG`fY}0?cGMVWuzn+nbjt)gUSXCCd=(a$LwG3m*rK22p|yyc<8K_*fNHbhY|ePXGzK!rwNPbMF&T3IzOO&5J> zBf_nL`%zX@(TI7uGF?g2FdxgiiWdnL@aYE>-!tq($n-^3DI#gp)}P;edf->pge?vtkY8Vv zt7O4i372-gsMj#B_Qa~MOVGBmsKnAVYT<2^8!k8hm2b%)pyTJ~;#Wxa3jXQ`jB6x{ zgfLU&Rby*r)80eG8$NxnrFyw6Ggo5YP`+Y!zIab!TI-QVFMc(}GPKxR)W0!>f3T?Y zX{`HLEiEl(&Eq8%A`^Mbto=vq&{N=c|P3YpV@pw&>D@~QhC;lo7HB^ zSDNG(6W!WsrrDhNs-#9*2+3gc^%qTXc`OXkR`jY36VW=!$2IiBYR-bMf8^~VvEV|q z`Klky2<8=Kb6eYZThq?3M;*VKx`^9*c-pI?E0=%e)n&!5mD8-Zk@-CBn6T(n<*XgnuT=N7j{*NbpF!pq+skhzvCx9G#rtj5QB>bTfj=-2r?rc=1RoS99< z9!ZGyCI7%qZey6LM^a!wBI4PC=ajATroA7#R#^p&VAA5*yBDN|%#;wXYAWiN=I^yv z$S}ox6dw!i^Bs73cy0bWs_BJ)*JGL2f24bs$=Q~;IQnTh!~!L zc8_ux5BYG-z})~-QFlLU<(LK8AE^N<%b|nx&elUvzwhv2)^OVNFvZK!^s`}?W{X~u z_P*>0D_Hn1NwSIIkuLus*|ecH86D{CX!)>i_X3)4B{rQqpND{-3}?1gR4rR7fI&%nn&e_;6FM1fZ!n9Vj5DDyoS89r zG{OJKE7)jiYGq6#mNtlT=C|k*xz#DTkKIB7;BIv&YYqn8&9pnz zo;|eLw0<)j_^o6~+IDeaW6^j0`MoTf#_t(ABzi7KUkiUPe>|0Ax~V_*{95*?TmmCo zs!W|~BJjvAVs0(Aykm8V^MhFrYz20j<4T^&61u`?(5t~vWw-UIGkDdNb@C!bKgbfMjHg~mdFj3L zj>C509|uVW8WoB=>(5`l-DtEL@*F?XlgKKV4f?o><6jd>#!D_tL;3-IX=|@%=%!VSZk* zfC8;a0}*pCMot8Obj23*0<-C41wC%a&uce4u}?ocQCjfI*$nCYd9!fx4KvmMR)Wl{ z!|8G}^7~3)(!QCe(yZO~_a8h)(~}pyq4$|pvrSKJy03nUgfW_( z*$sysEw*OUoeLTO53wD$sV`PS8-8^hBHrGH1k%Qe17e` zU6NLKzT6+ntoBK!#dc#jN50?Js0?~wQDQL>WuQo5aYO+@zl`?tF-TtqCFD^;yvh!% zt-PPh%DvrRTwiO-?fUcQ>gKj|K?K=*SE><-YMI%=PwQ^DA`sSG zC3ncujuM3eK&^Gg5tr#jF2zC02-n~&v2;_%Z`hh17U(z>(G>bhRX@r}%?nrMpFmHK zK8Y2pg*@FYtRL^+LW=6j>PC6!%42Yobr-QY#8hR7Rm3p*45UyaA@MK%$)k|fiaK4$ zT1DbCpJ)!!P)h=@L0ebyH?l)akmJdmp1uoGT-74cDr!3lkc4=I4N|_TgcdnkJnJq?ZG+MY<&K;n7W1dJn zd()=q{mdKZ$K|tkyDFY~zQ^`y#{So`jjOg_IA~wI#+lz+gb{wb`W{Sc+-x2ED3xX- zBta%+JzOv@eU0&QuG#k4@5_g4K1!S|a|xP1QEE*34vV_*nSP&*2wP(wjm)nNJ`Oqd zJ9Nugk>Vu8lt97zX8Vc zo14*4tFxh0lB=BSwXZKRo|kK+oxjJHb>#zd)8Bsc`|W2G_+GaB`Z1UlF|UK zXCfY)D)1uS4=?0}X*ZY1I#kHoj-{U_2%!3a{DPq|;D(q4)-n;dP6S?3<`Nq2NuJXc zh4Q?!CgC$^r^qMs`N}qENKr#57rOJewP(EIE?_^R7WPvEu~7s!E3

MQRz@P=3Bq z<}ntIGAU%EDQQ;WbC`;@oVB6txluW~3{!Ma-lUsLR~4_C68Ig>;xRZ$6OY0sXbmPN zl|G9edC|wTQ%|6d-IAoBQwR^n1(Dq6fv7NfB!s~1K$Mc|ss^ZPjvaG9HI?;aoV@sR} z9%d%iprvbt^Uywta(Ypw7uQ%<;E(23QCZSAhZ-f&sPK?v;26X=CKm}lD$}$bo=&v6 zD3o}@!+eZA1HUpVmMh{>amk$dY^nj&hcnhDq?~4L!??$_oQ>=ZM$?Z4M^h*G}WgdVnV zkxBAywbpT9p^Ddo_3p_%Y~j2Ymj`{@h&){@{}4Q~yby(O@T;QxH+TgY!CN1`BhVIRAaF{#*T zWj0h3xgw<^SV=Y!@Bc%Y$E}2#lFfl)nBnEU<$hL+QV&-xr7+`Uy!h-t@Dg_hiMEp| zL}YD0r_2!*Am%o2nR=<5FsRo}qe|5D`@6?|8+rqo!n}wC#dk~kPVr=g3!zS-mNAv9 zax}}c_up0pI<>o8d8zUtRgx_AEWg@fdLJ7mfW6hwq}mL)zy@^$Xc~w1#7iTc(p^NU z{ddhrm?S%KVKh~@tr$jBet$)fae<(LkBn#Z7c)iab&1zfTmrnej^~J`S#!qiBj`o? zQPJ8~@!Qwtxl*fPr}kZ-o?8UX zbc*<-6n%&9%kJa{Pu_l>I2CfgcNvaig5`PR?LX5N9HKn;E;@P?tYt#dN4#hpXq6%S zcjT}(!>tP9fjEc7x?wzQ@)~)y)~_;GuX)25%omk*%%~!S6_|gJU1fE>!2&iI*uC<- z+s8T&+oo07FLQrjggPQv(XjpUxe14F?9ytZG!#J;4JC|=su;ep+WQYJlBKj=TfDMp zpH>rlzvoQH>TCGaXGoE1N= z7xuO0L;Vo;{)I>zA?K!$?W2?_X%^dDW@-Yqahud$2ICZjp{V#X)GFk2&=Sn$GcSf=Qsf4&ec zv_TsCHVGxme(5F=_ayjv*R0S^(&5wB69HGZtjif`F%|8rG5umOEicRVWHbWKg(fy@ z>qE^b1`mD_8to8-F>&6>)OWK_=0(??)Kz?}sRHMjGc?*pixDm=c6CSNVFQFGpO@Gp z?9mF@3R4Uk?)j(H5&ZIqbFh7blt$ZP4r&}?Dy5Xk+) z{wU<&adh8c%e4jYV*84SlAO5z_%5L5TqA58TcN(&iEPaeuB9D2w) z6r!x2tu+L1S5Md)N|_zXyBI1%4CRXr7bp)G8Vwg|4S({|$YUJN867I68ZI#!Dn}1# zSr1ok4Od+ZSL2S^b^5|5d))?dHkc{@U*4T7K^`zI>LdX~@d2Ep}JLq2y1RfE91@OB8Hb63#<-Z&V z90Ep2&5NM-1Qv(@X1$FiP!9;^)2mrUe>KN3CCK$cDwK$3W$4I|5DO7sdeax@wc|8E?K(dOFC zuW)wFPg*T?+au|sufC18)bCE@DMd4Bw<7mvN)5}c##$SGEY#SJe9~@f{J(J^&UYsZ zG;?)2S}%W~>R+vmceGs}fBzDVVb<+zzdhfZDStlE+41Z8zjYwK2jS819J^$;p!$Mw*M4yEg1jBoeW|E~_j-bS?00QY8$*u3Lr?7j8U%{ZB>z0G(q zK2M$==p$l1$2Xtd+1yMzO(-`2ifUqi1^oTRSu)~)ULzE|(oOStV zIbKXuy&rJaulm3X!csk=(l}IUY+pLa`G#MErvfHO21~Ep-IDU0Juq@n0-B>;@(3Cz zs+GYI78Ps&1lDMK$7wgx(@m2MrZ9jg;PW&h4G{u`=*(`K?^T*5ide3~r!+?>oA}`e z92cZ?qZ+4zpB^)3EAz1_Z3)!_L4I6{U5xyqst+`=z!W53GxPwpO-69JWSbOxM0hzv zPnsa9)_I!bs8x&%cp)RA*!5scU(pU^`Fhq_iUcnUMWJ>G>rC$5K;Wa#k`MqgZ4+i}NEasuC1r%DO2UcbwFivw;_))TyF5{O-hg-_)Y z%e_&cYf>Dp9eT`AyN_Wxtlz_F*d*d9g7>QQ6SBnA)MJt4-eeF42egB)lSNg?uz-Z1 zi#tx?Lz*o36wx>UB={~9ERH)XExfLaq_Tk2;SDVRIr32K4$O5}#|ZItf$OW{y8hJh ziv7yUiME8S6bmfrzxH%jB3LWzej+CD*m|TM@+}ooG4CyyGO7W=mV>Upuv_utHf~P{WOKJ z1;Hmv>Jbe#5g=mh#t5^smztu3oDw{6hfuy`N@0#}J+t9(J%jif7;5c`Izh+yB>HXg z9HEn$OaM8^I>okdEy{SrTJk7aB}tJYl>^V9`N7MImFK0!>SNC4=b5O{V)3S-vDd!m zS>H)Yo_q0xt3KhobpGjPv_$TDNO2xZ$+u9#PC$yTY-;E_jv+Ee7Qq|+}UU^ zv#7AK|53~SVio%ztiAw}u%7)}EhBsgsmbg4NI=Q^-(b~olKE>q9wzv|#p*_5CgIWg zzp={o=5f1(ARqo6YX>>Y59>z%LoE}i&1GGV(*NSiiT793Wdk>~MqTJWuLOFITH3BSf?Dw! zJbtzT{(RMyD8#F1pb~^7*tElW`a}K-&8~utP1f#;z4BrCpqWGzttoAB^J=ma02J^m z@8giTwcP8Mo@^t)0S~uVImrAJ#K84YU_M%9;U;z1)Ob0kDF3OVV3+2=XvKU*&B(C^ zI7*-pX8jl-gnbY|JgF}yYa)cKS1MG(Mvi8SqkfSN-=~a$e_a`tfw!V|7#j6-{16R8 zStMHx3WP9g%_SRhBw>>sdc|p`YXxJeN8y6I;-+-O(jKa(S-yH9|ML@ZA5EnYW6k%? zs&X2I;x7&D)*B9DUEw z#Doe5+tPlJ@0RLqX#&0Z)wk9f{)AY0M`0e)_0;@?2&G&+l|~*iwh)q<%^VW-aQOQd zKP_$k0_R@7VAnGZf3G%+TTHKq3>H}^LlRsOfHxAx%91)Vjm*y9DT;sSt_e_X38(qW z3A_f_$buog;wYA<6Oyjs*pmwcMSI<3Y;G(+S=1!Og(H;-UNb}zC`+zPiG?c1`@k-8 zfsHg=zaU|KmQ5$N@DHxGzQK(5M1p*OnXeALpOXIvan#5V*$3PeGpOH|qe zEp-Q5CA-tKqd-lhjmQz=iKo44aQF0b4pEi1VaDbMn)y%bDW&&9GFN)*W_6&)cJ3Sp zc$9G5u_8|>>u){+SxUa4KaWk^`U~654-g2|zWN!WN=G%#rRmHoWT|$gv&qQPeCt(1 zO>8CXrRMUI)zVdC^H}9;?~&zicUMi__p98(HCHz1ubT(8t31+1R(7PWTP9qLHR*nnt@d4DNV%xH?l_69_TSZ9yIV4m#1Iht z$CUFo$-@C|ELN;Y;2)d$UrGKyO*tPiO#h1{uO8VIgqHe`Bu@jw%X0wyME;fJUj{`G zI?u0c)&G;^1*fU#sleq~>VK2Gd2;e(xp>(>HuF|$vFS&R{ePyM$i~JO9YnZb3X7}n zpK>(4Unyr}!8p`e$N*I4`;6C4p-olmU!>Vzt5X1j-3`_Y8t$Vff@4c2JSS$l) zUzw|8wH2Lg&y>+`6dLo;?mCBU@v8Dj*N{STtm%do~nGp45zp-o_N(_^j+j{gGCwBMq z^JHzhAZSeN{!T7q?Nc&sLaISMYbs+NEPtQH4ca_-7>L`*_|YxgN`X8>PtQs9fJc>~ zs&V>l)|fin`>N(^UKCCPKBsH$0LFJJ40{!7m#)XNHKFZ{#S$v;i^ERWvyMiZ{7v!B zu325>DkWGt3rGNXlISmpy({R;1u}X%ODfX!@N2XwB4N`+aDq9n^~OVwWtZ~bSb02( zKe;I(EO$q0KLUX6rJr35KX)q>vVj^iYn(OZ;f~U_#No1zEWV zefL>3AUH5(ntSMp+85&bWpuQ#e~N zE}0g~aD^YQvOv?vl%>OIjMR=;Fwi?TMTevI%(@`-l5UM(x9N$H2M(5`WL4vWyAs1R z38&q;$j`F5UJmwHkr`a2IBBIdTU`s76sX852MbVM`s7J?8js_W2Ik|XE%a2jgE9Gi zYEWxES7^;Gg^yod49}iB&|=DxNiJK}OMZT%`vv`@LArlRUY~|*?Mq>|ab>C=OndZA zso5azK||d;?1lO;YZudohEx!$X^r!e$jNAjv?Qyq7{()^5t*6y}w_sj)12IY2mN)>9F93DmLS>X;i1 z0DH6i&(Ne#(r`u^hWjGF2A=ONkINRFFV@E(j4#=zxlv+}&VKhjLdJwK-jM>p6)6<3 zFhJ(q&qDPHA!1|f#MmbX!c^%Ir_W)18zHExfu#n0nK%4abmyo}*7?Zz=>m8joB%RV zMi3LKRmc__swVSz`hA3dA&5(TNW=UrF@3ar3)!kWIH%YNjxcaCK{dxMJR9ScC!SM<1n zKbK~d~bUc&+nXl`Nh zXIX0_L*fISXvVWV+{=SWKsh7y^;WLKeWT`SU;dE0Do{jU4*uqs`S{tnB=3HNp~O;R z6~e3hJzJqVZW~!Iwg}6A>1SB5T7abgmg?bTtbd~aM?W*`==$$|Cgw&nDkP5mpMGZg zbLBs8bSW&>{q1KSauI$x(3F8qT&btJcb=2hcGOa=hvE6^*ThqfYLQdoeCoLA}V za;O09@_`jEIOjsWBPssUjN{ExaakX_pW9MBZ zujz*&P!J`&*Y~<+JDJ-Bi+qpvB(?X-+=VD>%PFWg%}`Sd~7d?D)|EDUew>&v+t{xRk~qmtv|_ zhc~C8HQW#}AI&WFa>5e}G^H1evp8+YfNQp!3{Rup|7ODac;5<;!E#Gc@K;wTvN!g) zr;JU)t6V6L0Z}KVD}BCT&$Qj4HVPK`!_LlQWx#1<+}e@;`2+Sk7f1LT50%0cnE;xp zh`pRtGCOuo-_-ZaM18c;xOm%6043c$fGl_21da>XIXRjCEyE2X6#igZ%qWN(o$|n9 z9YtG+sGXbV3RyI*lY&PutPrP`RcC8p;Z&*+yz=P6St$!;t0^t!5;++)UPpga>91k! z4E({>i(?By8LU5>VhceaR-G@)!Pf*^TUvzfAFDt|Bt}2;^O$gF3~LAclKhGX?98*T zwI~T#-0sY|+E>1@4)IvUJ{M zjuLK4yqda_Cv#z+RR4U5eNX5lO{Tj*o-Jx5g3r&7GzVBB!AZ^Mnk`s29+P^i>`$F7 zTLdcW2L#y)Gt#gkWXR{o)=@-=1T1g?>RwXEBq(T0mQZD?5rbn2?VE~C8pf{ut;;tZ zQUOte)yKm9D!F$Ssy>t#mc+_n3P^+^K?Qvo+@~IOBGljmdVV8>>AlTBkXn4#doZ7!txP*ZxEZtQY^>N0qNTp}k)NoJF%1DQ-^z=FdAsl}TO z<`N=I9J<`OP5|Sw6K+oqB}9e8uOjhS-4^?>>Gl$waPuBr?+vyyO_R66@`Ef;A?cm$ z@MiU}k9@+=Pu!+r*WGGzJqlCvFPhsDUBaa){RtHgJ1HqesA9tT=variXNiX0@vR_? zj7fR+a&^M`a=``GR1$1oc*gM^Rh&N(@inLv%vM0{ouPE$$pa#l!h$ZNvkZcwN3PXi0rk73 zL^i5!&KyXAhW*|Y4ZPUIf{tIR;fKCoVl}ioIDykY= zxP?OHoj1Bs;0Zf@T}x*Zjc;?!lr%1nfWaR_6iWg~HBQ1HkU3`CiV57({l5L)gOqlA z_ue8!!(97M48GWFxX0KSR?5=_2f)0=JN)Mg%kss8F?{^IXR;1glTC~;X9i!-h`u*( zvjSq)?>*yl?V$cfgI_0+t#eMeO&{$4WRS`KJ03VH^yas>o^)*k1&uG2?>1xj;l2c% zs+YWP-4oA6F_lUNuh=G1()|fsjr-3zvDZ>UI9Z^))YHj#ln4EbK~LG{Hs!CtYH3mP zEsifduO6!9no$W~8YSt=60Qoqc7hfu;5T|ud*Gfbr{VrBt&3&t)NwhUeHAWC(^2f- z-%981e5dD!J9iNusB_d<03OKM-_^3guQ5w}&`|pMeaHhlQo|G3CBt}ZZ8N=MA$)LL zu`1I=w0p8|W>TmSKIUp$@sHyTP3)LL23gLV7H6si90e!anvVx!kyMHB62?47A}?rp zr(z~wSt2$dka-1543VXpTVhqD09fph)psx9d6al=6HNt~Z7J@liGE2RGuYCVTN7Vz zR5eW$wQ^Nw4inErs`x_mC_&1qplw?M6h-V3|*B1TDd+=3Xl z*(=RT_dCg`T8%#x9FykP^SqPd!N8{ZP*1C7vMJxP9jE~^NgE`Of#Be>tgMK7)pAmb z*%(S(p$$f`s8kj@CL59nYAqSE5t-gR{FfR=m|r=8s>AK@k5?7cbQ891h3<0`t4ca7 z^wY7TnSa(XJc}LfC0=YDIAyYWEZ`M~)OAW8+Rvs5>UkdD*{EUL;BGC}NWF%bVXt`u zuYuIPAj5HyVohQyf^Rq~3aR!nq^;`BHCSW~`&{I5WIR4xTx5x-R*XRcBEIuf+09A! zpCuE`NfDV5px*8nbSaD*zZv>vU)UM?nCP?KYmOZozUv3n-Fv31&E8jx3b&*ZcxCNW z*s#SnonE^V_Ou>J^`z6XBwv;*=oJ}fy2oT;Wic3I8`5utg^Xh&kd$tl_~(vl3Rq9a zIPaRkq1;ETSp>=yh1SH(DOx@7zn~-$hUckd;h^HLj1JO}K7xDUMj*-!I5!P~EkVx&!5yb;Z$q@X(oVo5 zEEgFgXO>Er7NJ_;7Ak8VQh-=WSAEnO5$C8t&a{bLF6(PA;c-#Ga!-9wk-knQ{Qo-u za`BfnbUxG3%ie>5Bxn8>)IZ6?dPx4$;{FdnhNT3^{TB-2V-}VEy-kPLxHSFvpKUrE z7&gGt(;LG=_s7psmq;znf*_ED&cja0LS5$*Nc4nuBumi#lNQjO+MOcrz5&BiE*S+W zCgC@z4e#m16`ChxE+JB6^E4g>uJj5QPvz@ifmmn8Y36~)^%P=s#tt7q7KMFJhR!RY z4fiQ=0l=6GgCdkPooXupJJ$nLpJ81dmr-B!nuBccWtW&}FI86N`N7;LVmX}+O3+MIrUDb@ z^4R3{hj<*6ROeE@tjHrtPR!%i3BOK_eeZt~pLoW%fSZ-6QFa9Xeft3rUzC`r$q9)| zKJ8;r{q;zV61G5%%vC5n0rdp^jcF{(Gqqex@;ojI%;tx9CnJgsSVGUu8zUslmGClO zQiNPK&<2?x@c=559{uzU=gP~i&#|l2PiPdiS*fRDSJlP0z!+TBYz^F$J$>cbT3Y)z z4C)F@i6rhtQxGm9F#~L{*!5(r$aF*kE*3EVOi8#Fl^=kUk({m2zp6A2E^Lk<)1d9S zr8KEv+0s>5fw1Y>d}T$FsZr7xWoyn=s*{-%%9zi9|AsDz5WR2NuH)5-k!`>yMFd?D z@qGb3}?<2`4j-w=Zc?NiaPn&X04UJx8$a;6tY<026`)6*nR%3`NZ9A+m*|9 z6yro*x36Ws~EO+GIgmO7x1pH2ww@I1bX!lq#|G0m@upS85*Vnq`C{$e4Q!jTqbOt*66-bfsGK9t;1YCXE9GYViYP?q5!-vjI4;~?Yl zYUoeEjja6LQ4XfKC!{XjKi5m6^5DtCtZxz4Te{v4?val!+pYb6j%~1FFA)}ZRAgwE zv!v~=-9T^tu0{U$*98j$7=?)?{w?)VEy;aeq%_y`W4J(84aba?(*`Y*T1( zfB)x!Su5r{ zuh;v0&gb>Ie9z}xKA&?r-*diy!u;^O&EtN%UvIa&qIXuek6OOh){)q%rIUFPvkiI< zVy$RWMYT~Du`++TluYL#)cl6;!Av+c)3-7%Fi~fiJtEiuJ|(dkuE3sckj^jmVWe2A zsU!JGt7F2ojAqSxf%96^BKB9c4Kv!*r6JNRnJ$S3TaNG0tW>!{fj@SDg=>#r71{T1 zt!)Tq=OC;RBu6dF$`|$4zq*db1e@cnRgMtRo*eNEaQ}SzhG;h_URW{e^hu^pKJe05 zg0a96od{|1Xn90udm1mm^{h{PLeogJc`-B**)m)-JWKgu<^JA#SG^< zq5UQejMU-@ieJ40nZIeGY71~L#j+djxJNGVn&lGEy8^%kv=mwo_gMV`cZyY{l1CAM zS%bM#rydzXBfP=F{<zEKW#B6>D&vlcK2O#l_XEgQXsCns#CMmeB+klMEwl~D#=u;tDHx0GY#3p*1}>%%vqV0RAYH?9G6F1kiQr_`&5 zQS0>8^5$Hg(lcoi;IueI1Q}mT1o?+e>^++e9&^3tSN&r2 zfb{MX*(FPYZO28nM|lZ=XipueFsTu>H}i2^|HgK=cR!uAmx-#HNwCD-N z_gb{FxJgKu$cOWT;{UV+cDLSyi45Rl0|?};prJ@W538OIV#{+H(vj-U(4!^F%Lck5 zZKZiXa;=vhtmDqU#ENpUMW~dD`mV;zG+|MHbB<`B0Z12k@DG7tqVvWMeRX{KC)snF zm|CJPO{)j0R{4|c0ojQ61`5$N&th{nxwuM?&QO7~1TV#QwzJzFonQV8kvrjNRywtw#@z#v@ zj3WM{ge~2pe05@gTpy&KW9HF#ZOxUYP|jm9W!#owi;r0AOC~3Mm%9a!d^R9^CA*0! z+~=p4>h`;EDiVSL2yp!t)srll_r6UUx0aanUpe}t?&>?Ca}vxaNPFFef*J*@^S|I@ z%daI{Gf?R_2j&O#uQ|y1v0h*6q35I`b@CP8kACpMN;9FB9{%xxapYaduODZV@*cj@ zt#@$xHQ2nxKaaxSj-GN7THWIc1|N@p@ao>s;kx~Z-svp{wW35;AM;#K(_%k%<@B0h zr{}(Yq8`%e$8dzq)c&!xFXD9$k>jZSt;NL@decy#^Xz%)TwGj-zxi_Hqa!UI;InvC zTI@;gz7H79pDJda7Z6c)8K?9-Q?E&iqgcE+hnwv)mHLUL`n*B}J2foO#dYnwbM`Qn zouhdqQC<(E4dv~*L3Vy(qC%GQKCb3L@Bbc2xq(fOAM#O;M6Sm;ntO7p>clYK^OmoO zE6}Y9`js*zy!R1lMuho)qx5VuZ*7$N!Z3=kx-00gRGZ$Z%0dnv*p{D z823PqE=ZixkBR99=WtM#TQ~pb9xpiQzLii?kN-M97Ascxt?jN44`ghGpmarB-jL63 z5ZCDC`G~>C&Q8`@fm(U46MQ&0W9p?~w%&s^->LSy#v3$5ECfxCn@cm>86iLiVK`Y6 zlnxC-Vskf^wbVb(5BRCtZ3rcKOMOLCFbcd@w?X_9ttOnz^Xj9&2eAE#ECg0*TbRnY z7w^+6&_um0VJ7+2>QMYT^1Jxl3w81IIJqhY4diVDK{Lg@0fbW7Q+Z3K=W%we`(GS_ z&+RX0pSyG6V_<#QtjssX!?pK-ZK7|cakPUGS`UrVJOOgPlt5U~6 z!df*e={!^MU3+&lFQmltV6vVo%#XOBDL86yQ?s7fa97SQg~_!#lc67ZLusIt<3_L6 z&)sjaD7G@Lh*(TFLTEbFt)dxE+s6DuY#FdSq<26RZZx_#XH6oC(=ZbYd$P zc!PPZn7^GwG$D*2cZJh?Y{CSa#v(E5b%oKl%gckWu zkJNg+r_gQb`1G55fTgcAy0Z_}x=m)`G1Fcib>_0tsycc@Qs+spAIUyu)0P=3lEcfr zcz%g_XIZ0DpuH8DF;t6Jl-+p!yCr_nI-Mtc6{4x=q8m!J!7`C)zh_i-5X=r9F& z(DwB--2R|3Kp!L_*g<~i5#jGY*&1f$v=Lzh`f{dYzcjP6%5z`h_`OB?T|~uHneVSs z_cTH}txij^Fmx)C`8+q{;Js40M^}8}GkwXw&Mt@00SZP5Kf}JxGw;0DsgKI+zI85b zl8ZFAVLoH$%G?WgB&Y|OTc1%-TGH5`*G-4*aE}$C2vN;_*XZIUt;2-zIi`*r{*N;; zStlXW-rRb`*>Iq>+%5^hL7Yf{&Cqq;p(~w2_*Y6>nW$BW`xR*-1a)T9TWie3bmFjp zjh39D;7SZK#mvMzjDB4xnPq$3kij2+Y#VEZ?8W<4WR3w?f;)Y7b|1WkS|c6uUa#ZW-@$caNn3-qxGw1pA|C< zYOZ9+S>Bubqjr}bVB+cvW zO_Hl#tNQB1x{2EAX5*`gp8iO1(K^ZWab9v(qB@slTCwRdA}_nZsNwPoXGT2I-#l)w zLucQg5^ofea_eKqrn(&+Pp5kR*E+J}m(_hA%=FPj6Nc4l=AnVsL68X{03aLCDCnVfOo$Sb3#7%udpS&RPhk*5Hkfe(QF zKR)um({Hzl*ZwB*2teI zf~3a`j}WZ0GLPoj-rH<2H!Y<#UVX>5)LBwcjS2KaMxtX6iKD&*?52$AeJIoN2^Guw z`KL@&_QL7l`;N>s`~XWPysfkl-DSCy__)#aSwW;jP{H`w2?*X>bzwl2v=ELz{mW3Z zGD|MBbtWw>AV`1uUBe5RW8RsjSx6P<%vE!>F22`|cg4hoP)ZX62u2xSOP)t-Jul1O zj3o-ip$hI4=#@V8yD;%-m=rAv>8JdB^TkD%kBA&AV&Mu+dy**EsZ!!%_eWzp$;A=M;JLjsRr zl8~86;c7I?hw2az6@X;0aQ7~u#ddJoh;w?DmwP60%A{5z&+`dFib7xBe>x|4O%O-qe6ZU8f~vkZOwJHS{iLJAS@09U^yXLmq>XJhuLTeQ&zbF z*Jwk*ho_L_otlnkA*whcmLo7VfJ);B&a(<@J9jf%XuGCB5N0H)Hctq@r)R&! zbs-*59CWzV&e}}K5w8z?tNaTF6Fg>uK;YP?ljZnn=9W(rH|A>{r@#^MQF0>?Xm1;v zf3K~Z3q6%yX0|}VFbGIz;|1VQ6JnNsQ$EvyEBH*I7qH5JOT@)THMe$axEy7NrCz?1 zQ}MHXG6q*L;FkUPRX<>KMM#Z{ z;Qb&+Ze8Jw88nVNHK$bJlnB#>Ojd%v50r9d+r++`ipGZd}# zHSVh(_FZ%n^=kF`*~HwbuCjB+jfr6N)RXL%@T&9kx3dPo3fqPZ`0+JyZRPv%_izlR z#mjL$SGZRO$SSmMF;NKed+A9u^2Z~(7$ZstPV($czCsaKMJYx8B8wxg2v94t^P9QS>g= zmzYDC&oT0z60ag=Ho2sYP38II#XC0y2%p><;Yiq)N-dvp^-efAiwgOCGqU^bH}?S9 z5$8U)SNepjzyM%3@+a+U9K&C+ctQ^+sadW;3sKnkSC2vrXnL2hjUW{m z`TMHs(TXH%UPQSE{k-aA9qsX=)}9qlL4~$H;OLRzM?skbc!0E~J`0mp65X}mpIUjz zjar;ycl2cH7vGSzTKo0*KMg`CHq*c8AM*+pXkqQOh1vrNkHM{H+zW>sWE-I~c|~FQ za6wQOx2rFPQns-%cxz;r&oA&Sgfu}}O z)#FSXVL5IElHRddu!DUy6Q1K6ws2BJ;A0Up$A!6})UkHaZRJECHZDgO(C}qKR)~xMBpB(FMeoJd|?C zo8=UtK9vuNIA*f8?C-l)4Uu*d~YbDs4WnuxlEXk1Czm|6pyudTt41{kp!WjRk)ldrj6fV#$nhWt{I`uLK+9l~yrczJbujFu`?-nZ-e!rG;x7M4W^XwK@7OSm}aL zbp4slYSjCzcCs2pKvyp_N_! zd#`;obGsP3JT_Bo$Qlvjxl#N1PH1HtWVH>arUwyA_8#GoDN7${l73j!%m=e1-;*e` zfOi=TUqjOi-yWxxOD4|L1J&#ApYW&g0P>@D?ZvIYEMb)bV?DUm0UkT>j!2c!)O(?m ze!Id7P|8zmJI}fDo*;)lz5F`zfwzo(-`2pn@PR7;N_g1l-02*8UMtzYvmtp|BmDhu zno;G8-S^cKfHbCl&BQUxY2ZzwL)#wn74xkcdl2?wOwD6Jp=e zXaynw_)Y!U>%*zwb|K(vso{Zl46AlCl7tjxM(1i4?XF}xUS3r1xqN!$^^pV^!nKLF zk?n2)*U#Ez7x?B6o19k}y3Vw-%Ow~~|J7`fdGpwz8|;1BmIO|U7$r-kTAT{76n}W> zCcPRT+aoHMVN7j!`bcGO2UIEB1$*tGqO&$@$r<^9lkw(I+uRQ+a(>h0`9HG-6JUXB zm%ot`*Wi>P;21sfmET4{;^2bB8Xx=E2Ru&4euAGC|*)56zsu!E{}YaGj#2@|1Y3d zb{kCvY5oY6tLNS=q8=8GU>PoQwi|6g$~B*POPa4sz8{HuRCJ)Ua{7Dou+C<(-=fL|i}O3_rcb9c+4}Q`3u8^4j>D#&;`yqFqfK>AjQUeAh4vb#za?Dw z-%h;_*{x48mm*vf;`(>X9R->N(7@li*rH zcD;?Ry0!?@m`s-@aZIwzSv?~5dZ|tU=(vYa-H057oW#;Mc+_RpN6BY=jUrx?7%Vo9 zz)VF2Z0LlZRs;Jm2g;Hl*pA>#xEb7_4ierHFvHzDnnF-I)|`=$B_U4*$!OPI=$x%` zyOlougnk3p`~pn%vE?qSH*|e(Bc26ExxEN~`|^uy-uKB=;;i89#C<2n$dIj|mKzr- z@4`==tt>DuZU?7d`9Q+@XG5D zx+OENJ6g0tISCeq&XL<(yi=}Dvh;44IOG__%m6Q}D>6!Nm7AIF&jY#u_X3c)*bKH1Z*85)fKl8D=UmnVnQ zIIxSZfSJfxagNv-=7qfHZkBl|tb8j)LEaJ!02lYR04kj6eD`!X_*O4h93W8XaR<1w zyKJYr5#*3{{Y0&R-kx0mh zB->N1Ki#Stq!5h4Wd8KgqNZi4Ak!f(1^H0ObU61D9vY9zRzSSUx@+kb{l3+v+FR^N zQ=Q_zNb{J`BzA8@A2QckM?N$PYSYi92whQ&pNidtsb84&rdUVV9Q7&QyhE>L%$Ngj=fmiO9fXvuvdsZo&M zu_{HIQ@7wbq;$P3eHL4n)rqtot*@cJ&UQC+c-u3FFMP5^#l=M&pX<6Uga_eLX?78gq>-g`t(E#vXBHQIPOhPx^P*>w<4fz6wT(XktSuxP!v zOLQE}qAMwr5uW4_#ACSmR`7OLK6xLHW1M>HA@%9%+K1J|>5SFA)Kh6+bG{2q2hJqO_n$tOFaL6{7y`1Rs_mrZ_m^L< zH+W|U?EBdRD%>v&YT0Y-+_la4>G|1;QY zSWsa1JnGh8!QPX;GuXh?*kuqI0 zsUwd5%v{D-jkaC`VWwR4YiFL`G(Q%qHJ9aL#sjHH8Iae)t2l-1qe&Raw(R1CaXI2c z-q{@d7sOa$+jS3H&`+;9@}s`HQj zLPK027+)d$J&UWO-R5cQ6kpUA0o9kIkc!royl;_Pv=4jJ8rDURuZQAj5f zQ_eH%rFsX`qa|*1+ix7*VU<#FFOYXm9;&rNX(CoBl7hIy&)0pzT5-N@L1Px{G^t~l zX7Mpi_%QC2^ht(>=o^pP-WvU#MZ;TEO#edL7D-Pal$y9F8G&3bX&3o_GQ1Xl0(q%|sv3dqeJTJzwb)zx|)KOKb>ECMOta)}`=ySF& zLr6Kw@KA5alj6-oLYB}o!5`)xU#v-o@Frd*Q2taUIFMdH83fg$2)+4(H zQ{QWo)`zMVMByYr!dfV5F3B=bD_QeB`En7jrBx#pZ zunV$Znb8(T+0k}@{>2{yGTKR3*+Vgn z(Qj3vElbsmKv`G#!s8?X?1ABTZ;wPnB|lbMC%C2qUO>UHLA8JlYJmZ49SIMwDrzyLGcbnk{#jv=@Podenvz1B1ti(VNm2 znK6+;xl`ILg{xBO^2rU*)^-JaZ_-}1{-cG-o<)N+KbG0ahC7fZJ@yC5@7iOP465Z1 zr?ykGUWu{i<;20+2zM)=Fv8#PDxk}75d<)-+7o-<`gO0dA-TY<_Zt^?_IUuPe8VOS1!17^jUsaZu1{du(rf};&yBc)k>TT#d*BfbF4Xm~xT11}K)gX=q<@N<22MSbpkA>T!B?f^P zHhgn=kJho$02En~*C~3X^h$Z~myOXXSdEqajM$^*O}t`3D~4M?1~zt|$ceY#XsLe> zDeyiymdjVCUhC_rHx0=)n?mYk`FdJDe(<`*XF6R}FpwZi!Cn}aD{QG9p)uX3jiya& zFa??ZE(BY1g`sFQb1?8-b;mH&l833;;QF~9^3lt_pYA{eCE0r{)H2a`TqR*VGMZq zlW|CEnC7omJ7sdf#8( zq8|FUK^Ti6f_O~q3EYiA%JR*&G{w9)2DgJ$bqNMC$#;J>?nEjG7wv*pzZF+b7Cc^l zp8~)|ab(D_G69g?h{37V$zc~VFS>iY_hU7J6r^^s^L83U-NHKL_8uWJvcdBzL&;mc z*(g~xlMOMzGlW?(z>dCl$OHc^&mK7LofIYda^xd`KnZQj0x0BLk!Hlb7}s0V^RC4x zyXjV(s^zWTk7Wl(*_~13J*uvCVmY{l8IX|)UdL}oIPzGrCmDpq% zrDSA;-}ThWYd@K3u>+BVrP~+Nz!>=~3t@`-x%QgM%0#2YQ{mL3bA|<*__~dZdKRQ< zC2L>)c;Xo$N*W|TY?@q6?X4JYyl<4f=+!eJD4lDzz#@x|H~3!G35my&4KDL~__i=j zM?wG}mK7uU2&r@R8E-UCoQ%B;TH1bdAG%^@j8`$&laH@HjeA578kDijbCb9iXW{Uh zj3+>F9Q`9sV*y!b12FlBgN*(d26%+Q^;E6x&1RlAKFoUx-K?TL^XJXaP=-@( zt_Be(dZ$)W)v*9IjY)fGRiNB9Pkn#r?op923Au$)`7ppXP4~?!esHI*y+8!n_a3xZ zX{~R}zB85YIazsj`4%UPO&&t8k^wo-B6}~u($#%tM$qF74tn1;FxcI8eFCp$8Lc90 zTKTc)SC1M!IO#6mj6uw&x@R&Gu!l017+15DB@os|_vl>qrZ@D@JSnea z48546-rCHAmrcGtIe&YB^{03MxRG3|&0O{n{>5+PqKe4oz*2NaWp@hZX=iH60`}q z%`zu?VT8j8i4aWeW`U=JxV5e{iMe&G7%paG4MXs8VLvG+bgW?kCy)-ekrmpDmHjzH zBv*v|D(d2Ne?nY$dJCJ)8GpoE`+Nu&ZJgJ!k~GKxwsPCMUDY(L3^KIq^Thg106g6qbjmE<(m2Th@(Irn15HKL+hTducd!`~m;MwK65|;STOQ6eD0bgcQHX#Q zmkN57z;uA}7o&1&zpo*xR&@G7*cRV!oxr*`ogA~+^)_q+ zD%6ZVcvs+pn``1;uTuSHh95dppQrgpJo!_n#ku&HqsPph9{G4KSLFEa_xItqILk7J zERa4xB1l^#Uik6Wq-o+u->DJ4xzxQ@N>t5Uw%1+!7wHd|hm_t=02VA%J2u6Y;5jGO z5%ut6C)_sJHmJMzxymN+fX-VXjK?D^Qjh(@5VlFxtT=ejivNSw7PkctTF%pg`)>ac zzA(BCJ2W4|;29+xBMBmlU{9u5*o5^T-aU0i{K(Z_PfTbmjU-ui@c!&pubYdO&@?y- z%PGfDY<2#aPS8&#A+tMx9c$*Gb!tZHLzJp{jY+ENd~Y$j%OuX_HbCrh0*(*Ti(`8f zGP|`Mj`vxmVb&g#cG#nGwGzECrRFx4*V$rz>q`h#3G?mT(y2^FS6Ikpa(hdrN z$=xYiQ#?tEEh1S2if!cNdW!P*eiOATW$_O7jA6MvH?nq<6u4IjH}iDvdWOHUeQfXd88I#t zh7KcNa64q9?Sij~prL-tG?y0^$T-uYU8HYniR2l3h(1pb#(;B{DE0juLfQC;8}mIr z{iA`+(S{WCjD1{;_%}ko8t*1g$BU_Q6In@dbWAW)3q<*jyT4BV07F5rH;@j~&YoyJ z(NiqPjEPa!^FR4X0o@NtOOiWY#OnE(RAj*kKK4{eE~3AWPg-~hgA*$}0_n11xN(`G z1?OLXu#d{v-o<&SIny9VFn7mUETNNL8(ibFw2vx9|4I)-d>+7I8}=oABOU~G&+1=X zayRAz9hjZ{m@5;zp4yrGB*cIAwqEhqD?;(rcV34dlMzRrm)*a8(&0D#sOq|sf=Xz% zI(Qx>QXMM$L_$Y7bi~z>;`%!v);~>FZBII8cF8zA|M{zj-;e*GD>@3M@BDda>^AN) zcg#U7dLX@dgKcg!91)kfhr`Kpbu6ND$2HhP$SSAUN||&qFQNJ0qNEH;SuA^B@;&($ zEuU1%=7D)7H1jP+OnuTn1-9zZ~_Q{>NmltnWmz(mRdNwEBuq|N?C^~gC08IFBh zjL9gXs5aM(RN+)xy=q51$Lg$jzQYdQI*eCd@M#s(O7N}=KK-aRSqOH2_OW(Fb3l9R zgMkN*OJEE_Cjs&T`&?owbK-$>y3e&WalNr>{U>rhKG2X1wv|`8%FEGLf4HYN+p^B2 zm$liijSAdlz_GP%dc;zqB#6;Zf?w6wL)pfD{VY`6q2W%Cw%Wr*RF zrMOPV#jbDyN92~hywXmD?L|py$*=i~YvI)M(vrP5A3poey5%D(B;3jO*#&qAM15l9Hgm4Tki-Rrn?-kCtUne( zgI#Vek?fdPcuhn&G9kcNd>fy!Y}t(y=$D>BOQ_$5+CFVF+KFEfC|9J7gxQxS3Hd0OhUHERM;xk7jIF z;sx?0de*Y##$g+Upl<46D(sj&YN3wvyr4@hhQ5E?FwUKLHRL)wYcZwQ!oeD=pvfPE9+&Z-gWNDl%tDzc~ z-}zmP|5J$Yn8%HN`P=WG^f*i1v)wGROE((5ESUd7%uQeK)y_|quP$17-q*1Rewd`E z6NiA@faW!oF_%1%Ba?o{@dyA|`9i39HNU}B=wM|t&ppAI28uEvaqTEhy%Ooow>8V( zGHL%qf?x~>2T@Ow&X&g9w)5zq_kMf@J1a9pYrJhbFZ)gz`Pe~uBlKW8n_+%LsgH@$ zV^|>IfK%%=ahP7Ela%|c(TDlCBv53XQtfr!SREGbSAK^(K2P?mi|jpY1GW+U#|;O1fMQF`lycA zd*|!5))_G_cAG*nqCeGIHups$@MMRuW`9>1cX~sVE#@WPP^Kn%>XoL0t*L*&L8|$x z)D7kPasJfHfr8>a112hL2+Rz3l1*5wDXuves=AzN6L(f{KQ7~b60eS<;jq{uD@jRv zAHLAiXX5w;Q#i9%V(cky$stqDKRT5bFPdT=xD%(wuzV#(Map)dUkvY8A$d+SHYxHx z^wh)Gue2|w+l!<#=-C}$a=8NT#09RrWkP5~>@=qTRRyqty3mxCS#9R>>9Qx;u<|=? zz+I6Yf7x$6({%Si$N%!|KZ@zQR&=#+7mE2bWKGt-f3EOBCPA^k@7=$bdR6`>9*PWU zBrNUp;Cj1ZO7K`&|BlrEcl)R(`e~Y;`Fp(t^a%#-Ca}4UZ;QUIGW2gdrURf3cm~k_ zdmrOJQG&n4U77wZ?%M8W3M3%^>SHXG0|0~8KW$q~uDsg}4JDA&Ol?hHgn&tz=+w(J z+jg2oasUEA1(f3gYR2pM9WMsum%v9N92*l(UTxqVuE#m2r@ge$gSOJbVD}PtKcJr0 zNBOQkne>Dzns2bI#Vh_X`W*Mz8^L?wtAw;kxo@L#+jk>Hk6+7k(3@}_Jk;s9#o(g2 zo+60j55u`Ucz=ofQc4 zEMDLhTHgOR|Jb6#2Dh^=)u;a1r7oIu2koZtG<27Ef=ViV?i^a~tbcm+A=$CLa|t4t z-Fx!9=eS0rg6~_*a8joNeX+qq7m$^Y0D;33?ypD;LOcQBhc1wD@2yn@vRO9Iub40`?XO52i+`e!-7R7&Bgq@hC%u^0Z{bWu zCZq*I+M=!2HE?~q<7N6I7#3e}&msP9WO|U~9r^J`WDPq15X)%hX*%=mK*bK7l~2>H#ou7)lr{)RdsAco)%*KY98dqIpuyv8FXSD%E=plIm6nNs z?ZdjipfebpyqmBa7&1;wsM|AT3!}-c(`9dK0gebzvxuXouPLT6Q00s0eIXbj_iI9s zST()i=bPBValsDWd4D6d_J-##V=I`Og?o3K(HCo? zskx33lw?51mqP_(K0D*nZfEt;F&kL>tvGe`y-6;z6vgE~BVIS&43@|=ngzJoF0fur zeE84vz_O%*?s4<-PNjD zr6B4NYt} z9hFDNK2qNgFWjI1W=})hQHl?3K7DGhnsrrmaavw@^7$bvjJBFPX!yW_jD^L zd+o)Kz^xt-X0%bA{_>ojY%Apaa!Bs4iMrh3hh{|dOBP+bJqyV+K26&Q%R7ctzCz{C zW-Z^X7J7qQ3SMoQEc`aZONElf1k7h9?tgJ+{o18x#%S^u2um0HLJ#M%embmuUq>`g ziAh4Npv3TasmYo?)+8-tI==Q}!>xEf$pYYtd@o3zo@GlL1C5J?9K6iL&tuxxdEAClyj1QAW+y1COF-95wFdYnnWA6awl)blP|Ol|L6lZlOGr|0 zbQBm|*HN0NFeynGZ;D%geGc7-4H`&E`feq1X@;B{h-Ntn!scs0|D?8&HOrL$OL_nQ zNgv~*qNI*L`xxE-6Vm;^fD#NIzPJbNBd`4M^dUV-|N97k2UJD_)7kzZy`V3m|LSaH z;iaMJjV@{cRMu;bNHzll0;&mf>)goRG^ta1pu2ZL z0@1b&_(gi z1em^zFk~Oegg#k*7hXgUwqom4uxcQ4zY{-5t#rzy&WI0nMOp9aZa;d@EuWZ1W({bIE3+yyw$uTEIh$mDJoHU^zg!QoI!Dmd9w$}1o429&-T zid~`~8h2%oRx(!;vpC=k`_lK=60BY`Y3cZ*K66Ra77#@kbH?yzy1YNRlA4G;9b@Gw zBHoT8f03(P(o{9~ERxgVAh24AY39wFHF5`1P_EEsp=@gwf^n>w5YtB^C_u`!VHD&? z$^9@nNOV1IF;$$iR?1|8!;%kpFxSC{i>O$2Rh(KsrZJu%F0#Xl`Mp7aqh))thmCY+ zJ{rN}G0Pu90z{kLZ`ePt$%tpOpJtFNL*R6SQTW|0bmbQmzmaDWJ~{7nUb6rbw?f}5 zk(Bs5b9F}e^H4vP-P5&RB(w{F8`~c-!xQEXC^uOuo(k%VI3&WsOxoHHp}hH@%WgC0 zt=Jd_^AWZ@8K-Hkj!m-|^UGEEFF`Vh4E^*-~J3R{tkGHb9f*bxlnVN7>j!cLL z5M((4aL$6!`Ea`o*Yl64p_{qP*UEXMO>!xj-gz}^e6y_jb4_zKWqPmQSf-8W$@-9+ zqLGX`yb{rU*;peeIh-#;jxt0!lT*vPGy92S^J4tmzTYKlS%NpB=WBt}cwL@(*Vod- zMAL^ESpSIN(`a*fnNvW4D82 zDHuln+w_C`g!8XG;PVzfrN>u}kvu5)r;9>;4C@to6&s=?OpO2e@iur@oS5!Kygaxh zDOCNciP#VPVMh--f&9`e@aOx2wT}|e6pF!8x*>>lorhLj5N)EzEH4$%3D{teeVqX4hi`R|>noCUM4qp8q3C#S5>;3=L0uqWO)VF*95Agp( z-f!aw8YD9aylvUOvdx#xC)gWud^8KtT@3UiGM&12W1s!(W*IsADi{xmY+)%e z|B!yW&pT6bQsHGVl*xzzzVA|pM6rgR5mc?Z+D}nayI(i$(K`;I_Hl3th<^eepE?e` zD9~B?sz`&@Ga!TRDwGtPwRPZX@2a|GduaA7gL)Xa7y!F z{ihvxFIs-Y&@b;VYUD2wO|AoHq{(u^)_KDztL@@W+NFYr%c!$k-4!>~`?|RT-qpB? zXi9GeuIW~XS<_yNOVW!rToXi2U7IU`1-Fgyx{hudEU**k{Y)A^kH4HJj1i8Il1!w# zb;|*mL#AWwgV0tZ+A{9Br_i{XTSMw2QsB6IF@jXDp|fcECvNx4ILw?0O!X~>2vV~a zKe-)>bTw-Am6kfs)2Wk+)z$-#_=FyI5wZ$gF-p;9jQ3&)){v5;Ngu6Gd{*aW5 z;l(+Pbg6vu6US2IYQ zDPP$dwJ(i65S%_dUMk%~YjxUmmYDtEzyR!~ehj7BD`TGKa4IIL_e`#EENjP)U1&*B`I?-QY0gZ-GFoOaI>m0{^$`+rJkCA|>7@ zy&gRCQyTHLZso%J>O!vQ(X1%ek3XP)pR8$ro3srL{2%fMp|byu{_D~K`;4%Z_@DB} zJfjCLae18zXZ3}k0`y7oV3QcTX+I=3odRPatm7o!CbmL5=Gr$Z-$&Eg`p+FIg3zH# z;W2a78HCXsTM7oNXf7j&e_>W@7Sh0rg=@b`peNH>^&fEBiVqzsec{8`+t4D2iDqM! z*mp(R1xkQ!gR7eF_>}M4A-TKl=`36VB%^LR9@gd-ohryPVjmOa65sZV?(>Ya8yP`P zL~tKh7N2eOO{5;zoMa-kxdH?`U2Rpx_;(Y{8ploS zQEmP!)Jn$3w`@vYu3Zl*qHeL?{`Df^ia8_P?S03unEFn=MsYtL>mz!oRkhx=>Ck-VG;Cdu#F7C zsigyDNor3jpVVDJiboXJRwYxa(W^)>Q&ZIUO}s9PW@u){B_nMkXoNw47jchm7y9JR zlTcW3|Iw&X(EcUa47tLvp0Ce}7`S>ekTW-p)mU0KippJ+Ka+z&Cj?2B%s7J-wYR~i z%L-bLcJVJO&rFjw1SA>_q3MNdjjaNV3>9w~#4DKKB*+gFKgjt#V$$)59uC1{UfYa* zso<^@h)HBIBX$9uUa}zwWad}|wq!fK)Lf9HlmJ;YQhR27KvvIHmgt!>56!_fK7gPc zuc4Z$5wP0}4!W6BACAve7#vHP`E?DjXOUopUY#8E>)R9Ju6PYM3&N_QBw4M`?_Q>1 zkYS6W3D|yN)u`y+m#XCWVp<|U9pcwk)#~jsWy*|Py6+|KNq?e$6~Ysx7^bPjuQfW2 zSVMO`Y_^w;$aN2Wn)@}@Hb9GC+X#*}c!lsQpUH5@@d#qyK#f8WgTco8PvO$*+pN$k zsk&=7jzKTy`v)&aWc@yl;>+;7s#QMwu38U?dNB9ZJUqk{q-#cIQuK^ukQNw|K%#%! zQE;ENrmN)zI_cBCNrEqmvglX7{PG@ z#gl!G(sG&pzT?RU#R6IY4b=SGj)!6EuW3~)mdbD(Lfi4^L>72Ucl0)jY0`Qgrf3<< z<<}8#EpV>NHzYboT>V(TjMo1WahgtBsqNfaPdYFl zr9Y=trB=I{A&b#+r>o#Ja+d7NB9P`~_5vreHLmHyTXIfQQ8eS=%i%Rs0M2k# zf*6~Pkj{D#HuKBF_$6ux%(G)Sv{}6U@ipTFUz;=~icE1mR!nJwe*u_-#Xh{txP?&! zp;)MA<1dAvm!QO}A5!d`-md`|>E`{hOF9#?VYY(CmZtVmEf-MmoV$jt7jWBQUjSmk#2hhS`4qn#G@cRCE{;icfzM0uHp z@xaWy{shKAW{?3t+!hnuarYX4~uNFp%=E5ouH-u{MZV60H>9{2?BcOM9R>ZH}c7 zi1m*PZ~hqWv)8T%N{TZhRVeaGLp5gL`@VikCm@oF@?}t zAzWvE^7`Giu_e2w(=Qrp&jEN}ZATFINLA-$1^}!9RqA_6R~tCl!D&eNoTD<$+hb9D zy#LTt_}->u*JgIBBv1fvT`9>w)G48aubFXhJ%?syyaG*uiyd)URzsEib<$k&q?fT=@n`NB%}2h%#S7DT|rsgx(ld%Z=R-p=ydsT>ZpJ6kTKWnl~e+e#B{OPe2WwqD4_+ZyEsC=-G%=b7tTrl_vFm; z)$%REEnUd!tjgi5S>=C(z)L}X01CkTL!g)#kM;jGZvN*kOTmc7ix2aduFlZG={;VC z?;!zD!^WCs0gK~=cNTy$ExXM66@qHntgOCRaJfEzQRY>?^j!;j`Q}ft zxdvTh#glJa&e#J`N;CLsx+m%B4IYf(Y0*AYxV=wUk}TOQGQw7DA11)R#m8*k_ig;< zXywO9QbpjqX_^0rx%Y5tdhOnRzX<^eMM4No5Cen`(xr(c)X*XHD!q3R0coLw2%$HT zj-Z0{q98>;K$PB#pi~tVML-2|viE+T{p{y`XU@!-d4K1e{~+JVn(JQoy4Q7mpe6!# z8lKAs^GKWN>*pGSv;?Ex%s^lI;Mg0A5D!}uirNkT78X3=Oc<^*?%2=Uxv0$T_{RX+p`KFsw$1&pDn1U{^m0j{49JN?##iQGJ$^AjRYs3U6?1u48mFW9N3^(<&r$_Hbx^| zB^hPR)LfOR41#TiX`C`_mr=E-Pzmr{4y?vs)eRKLcZsM>L2Z7Wt3+D?Yqn9lr#Ch& zXvs;zF-OKkUYA_y{K0pH3-nn4EG~m3N}(5(PKoQ6uW>9t1dXFqaw)zR7P6A;+lsvq zF3si>fi{9-r80R<>F9vk;4O+421?lE$qoJN?nINB+OX7zMiAgYkf4yP)8uo564Wwo z`sJF_bhXCazDx%@fo;78oj0NOCe9!Or&L3#jWkh8WDl1dqkznu`Rc$BzoSe#DN-kc zw=7oeGgzIm*qQ@H4#Pn*ATL4Z`5o-6L*{uL_fQ}#Y)S0XxGT8h9?&@&u&od1pR0!= zlK{@){;`XvEdEh9lZBjR{4=ny4Sqb!6twrz_H{>|h7EnPpH0@&Agmz4S5I?4N7a*# zXq-JqdpD@2+>aa`?=IE!gL^Te`0&c;VhcAkPvUm&9FrBHVVEhNyk0sgKc2aUD@tnm zJZs46Cd}~FwS&OwD6Au2H$&?bl|Z#`!|>iXl`4C5)@GssvUi@znG`Dgb1alH#ChT) z2q^!e6kz7%*1Y}m$4_-?``6A*Yh}y`r@?^Ytk$(JiPj2M*a?Mia+00*zI`v(AXd+B ziB3!fzI3kn_2KrLHvUO@(5bHma=$ns^#>`oKmNsxYQeq$=+a?7Rm_ zpgtv@Q~7_e5!3Mhok0DOM-NXNqUI^laY$p$Zq%z{U&sDZhnfEJ=2c4O!Em&tgCD7n4T|CN!{h5Ap57RlOu4-^jQ0t$bs*x%M}>ej~Gzxa4eSzsXQkC;7<3UhHh z>DI__)@0Uz0-!Y1XVk-RE|m;kZ6D1Lg3GHyGNL9x=s^*ZYyGIghs0g<0V_-IMXopj zR$QywBKxneX1({p4udB(jM!-1R%2Xtb!N$IGP>ZJ$y1(T!wSqxhb+5#PwSY&AwM0o zmQTMau94}Jxy0qy*$|K!%_o`lCqW$NEVEKtXS!eIvbEOaIoUgQQi_B^fPRUssYL3< z-viR0w(q5|1*z*QNMj`K*+jk(_WQPms-v5`j7{Et*U&1i09l3o5bd`T^zr!7^yKYS z11+zA-UVr&=iqLA;y}{kY*5U?BZt)UQCTK<#bFv7izQR1y9ea+OI+i>dfuUFoEg2x z7T`;~kSzCS><>UfE&1d z-s*NhDKDUQCdUht14HI3Fb@oQxdJ-Xn5!^HG|jqE7F*K}9*nhe@AAQj5R`JFKN%%5 zoJW(8qljUxyu*1-iZu7iVsO2YUu$fbE$nV#oq|1IQAWCyz()(CzENbBN=CT7s)VMK z)hIyRiHR;bJXEliaIl8}TAzUmvF%(@RfP=KJ$rFK*2aU?CKPNTD`1g(ks49hntu*R zqtXi)dr)0gGi8z7npK59Q*DcToKSXW+}?u88E%@ts!2lBA%&tO(EQ)W6j$U9*dtv{ zR6VLLQ5jdnMxi8LH!bg)ZRfbYZhqj+3ns}?veUvIMrfDyD=(X)s<3b4A{iEr|0Fan zN+Z+1RtGC|GS3>Lop%({?5VcumZnv=(EL`bv+jIBqQ6X0OmqI*V{qqkp`FC7B$UfC zBop%Zm!@(7!a%y;QKjNXXr?ZAI#>s}47-JZS<&1h_)f`>;@U`Iq%<(6cWUZy+<1tD zSOgABXi|~Ct^wl%LzLenAle#_ETVZJs_l}Cnj^y;*Mi4I59cRS!)luyZB-n8Z@xjj zc5vYwSgo^tiq3kA`q)&!F!ak^hk};=BWum0{^He1tfMX2&x{mNsyt<^7XLCn{TVzrf2;D4gYhF!X3`Mug-7BnAAD?0~p85hCus zuZ*IB9*XSAppx1kt5jZ2qo0n^`1D%!)}yq8?n-bjY2D9A>sd-Qxt1TL-JRX3cKsOk z<2$6?I_Pwt?QT0KAo0L=d$212>9W=*e%55tV!s^o>gIR7GD(bUJhi?kk>gmdxqlPv z?Js)!gzNJ@``i1bk-1_v$Fw(=GP&l~ZdDSUZZc~><}sWII1F=v=`*!B*kPtYup*UT z|mTtr%VC6nGIk3UwOO+vYq@^V1%fg=qs>ENCAxe;Ll;h0`WA zZ{)*7gJe*!`Lc@QhhX|h-IXDGJ-XJsLId(WXM+&(xT7(vUC^yn^k_(a@eQqw2Nw-g z<1AJPG7t0m3sfXD7yzO@b5-=sx`QgX7e0S6-#B_`(`aT`Ha#=xtE*dK&XkEsLC7cRO zPBv=@K?my(5Wckj7R*4c@C81PMx%loHt9KeB0Yvt7wSMB^YLqn=r??lx>ZrK@C0_g$Ag7^nEVA*tFfVc_EO?3Cn}` zeJ;FEK2)e9U$|*`@fVNfZ6S9yL#*s#rVa_!1H?AJ5Ok(9fs#8fJ!t(SZ1Ax8g(bM~ zYS{S5;LMhHHnBYu3yesa>AT!Y7dKZHmV|6{%RJ>y;(DDwtK}f?txjc6Pe1qpQ!JwM zsdOvay&(I!|D4~`jb1s}Jt)H{k5wz_1rhMZTtB_tcQmDN%TLmvhG`tv zHzu11uEtWziyT;#Iu2<1t(|kr`DA~H@5#xxQJF6%-^VpXPY*3U7FN|ZNK%ss2037 zes$qDtJa8`njn`!G7eO({!a;MCrOALp!8o70{QZe8Nzh1iHz|7ycPsPd zonUfamUiY{TO9GzY2j$L<1-QIx%0ZqVlKw`;$CpkiD%>PurhgT1}=wYAWw!(%l+ol z!(Dv$m4(ga1tImNYBCn*-Cvw9hegfKTQ4uz?Ug>Ys`EAv4e*aGjk`1&BHuRO3(zPK zudXD^DX+dU(s!XnSJYPWPf$NDy0^Zb&{_cjl&z31&~LBJmYBFt%P+y4Ag*aRnbNrx zrHA=eEvG7dDqUT}Z#f(Fzj~!}`vcO}7E#G^Tr< z9>wJ;O3q*IE?jx@ZMeKLgww+bK-=A@T4>5jBNs`s_mEd-0tB2{HS^8kx)~Rh8F?4x zgEP}vCQz7-c7wQ2?g9vHx|MPrF-?NXMo@Kw%l#y5_7LeZM0z1ZpXCkFdwRIA7=h6` zw+IS11o4GQl?|<^eDHodK>-9Qr+M(5_35N0xg3j81{{%CqjC%$}Us( zn36X0_KcvH`Nek<7~(38lh2vFG!(KzH8?56 zSRUx7Ub|cARa#iDu0{GCJ$F@gS$VQsFe1i_UEGZns$6)#0J;`^o)0YAcO{H>oZ?8q zS13bo$t>k-SI8Nyv|m#>XUZ-}YI;s%rp>i~6!0$?q&H{`x}2X0hG{qTJ{m<4Er%v8 zYS9Y@O@iFU)lPUw`jDb^df$D7`T9t#-o$PCd#`=F?)T@;qtCy;^qdnt`P$Fy`~P1FVNs6SALqJ~X^kcs{{Mp4k{Syq zKoY0{-Thk?4A#1%|0_D+pN)k^+Bx#GUw<|h|7L>6R#3Kj$bPT)m`!DDj}2> ze=)%+PSvP-`qF6{E?*pK7MgoP(d$F29rW1ZiSxvL#z(CpOKtA!b$7LI)!DS&++WRp z)F%42I|THFRwuaLzDkH_p{50EnErza9uacz4%45__XiVP(zTLChB1)cu3`HRcx~(P z*nNa1l_qmPRcy)Z5}E&<(bu=zz5q}0M@*z0t^M_vcetP>dgO(){J{jLL)e7c>;63c{_%QIhhjej@{^Ac1%kQR zDWBuYvcphQB(B9!DG!yzo>zBUk7YJZT#vsHBx?|J3CH3P&mCZ1mOz%A$CV^hFwd1t zerCKB@h21fKk!<`;T%{L`VV-mvw*5q2xU>iMyA2jjSXKz(|A#ua0=aQ|9s+qmxRBi{ z{rzFS2PJ>NYt2oyKGZ1kcubX5{~KQW=w8(uk4Lxj4?{lIv4)KN39t1^VVjW`E;*9g z(ARz_kE*bsZwUQ#&toAz&vEQ?)?U(7z|+U*&sg!PR)g>hlcIZpuXZt$lm{YChXjnl z)0wjeKIOyckDt+BsInn3jdu?|Vf7+Hzhpn>Rn^11x?=Sp1Qw_Ixi_iNut0cf%wfk_Y5e#94UG+NDrj z0_2ssFrs`B)r+<|Ve455WFw9qW_s9HCZa=^ggLaJ+F3zk=EN>uhY_!tI`dSsH-@)$ zXwO($ugN@b-L$+yf>lCzte(7)h+gGgdD!MN@viRWWtVhf*yZ2Zg(#TO`?jOY1||S7 zuIEY9U~Bm9d77ZwS13e@;mdH$*&ST3SurrGu*jiED9IkY3gCoAI1lL3eKVSuxEH$6 zGw1Z<6>ABke3e>bm#|+`XWVL~dwhT@7&y5Epa`)d{gB8Ut4qH-&ANztqR`i#YfPhj z*^8V6jT@4bkg+R-El{<4Eo+hpHeF_GBEg&)GVAT+!iYP0A14-Dsu(dr1%>ESF@2=` zh70C*6d8;YPbpO-+VT@jr9`1}8|(Gs354H%Jc(j7Q6d=tfE?}j&6v0kUt!1)xIBI> zNF3`~Cabn>bNQxKb9#>inM5?IC*lPsm!HG@c_Ii%a_=?~n0v!3 zya5PGa8HsrP0u$h2ICSMn>1#u3k%W2+U$~!H7php64K|F@gc6R!=;}Bf&`>$bHu#J z`By@S51G%Rlan_V(2x6G4tCZHVh^fX?+xp}?r91kH=*1eIZ_Vi1u|(@rbTVBYO+_{ zkw;NTuj%~47z$BR?y|G`YlK?j6%q}qT|aml*MXQ-9`|`MY_Tw+c$1(r9u`?6C$oBWmK1QaDpv+~F&g+nbydYR|Lu zjqCah0~m@mn>_>NLA!0(1VnUDui`(xS2MBCRDO_4DsJHeT5PAAVY}y+c`58e`casdZTz9qR87{L zX(`)D9U`}jZs7bV@bLxu>{|aratptxj$jKGA8vXOB_u3O;`*TXqfnThrozF;IcPbB zmFO}BEV==zxop^c0lLa-pq;Vn5}zE$kb%>+mI>hJgax)FFcmzA+j($xcNTb zA#}2QW~m=FsOQ%3rw4ge1I4Diagb0d0CLd$fNnv&xVyi@4#EYa$+Wlg?xm9G|2b)8 zzN&orL)kZxP>nJ9#LQ3WG+0qJA@OB?gh|m@+}9sdk@8ex@br}Tzi5)%bL@2l<4nyZ zEs=O2TFQy7(3(1(AjX^ZBt*in!Qr@({k>Up`cDlBfKY$_vu0jy7kvwF9#;TOnPLIc zgzcS>rR8gPcb|U~xxpY^xVtKVxuTtc9OPTtSNAek1}A!>f2&Qp7~1GYe+j!Kh+YEJ zVS_Pz2_;Kw8XxM1eJG3*6SP_rOCJ>=y!R8NeybdW%!OefUr(=gzNaVNxb-6Pn^TsC zOIh85*_ie78s|+RD4dAvQB%lJK6t`tXaB<(nTRVM0(A-k=3;ll&CT1znXf88N0ov7`R*JswVj z+5I<@wd|^F8n+Urjz3omxW6$lPLS2{gjUxw*w)^jgDybFG9r)5nNrWpHUzqP(Wn>u zE>C~QzEu2ZNxkv@m-r=GGJ`_+jr-zIkSelb{mykI)$Z8HT(iraPhQVa3e_>6mhl{Z zd0tGv`Q4lK1a-|&h?DoYmf&YP*;VTfynlSH;6&AwVl7o4!P0AX*4*A`<* z2yYc_F|}+9h-JtTMw>}!@(FqE=o#?S_5ctE2KD*}H~r@0c8Lw*)@}(t(Qzdb@zXz~ z2$Z+3;u&N373oU@6!??m%5InK@R|1pVr7Ju`V#b5fQ_%BlSp~WiLlN9ywE1y5|Ef4 z%$v0n@abK&hk3HB1VfFiWKp}?o?%oVJf+4YMw>CY538^Yzw7z#JdOounG+0bO4jyI zVRoW!GDQZ?bB!MJ^!A1e8Uvk7kSFbFD)ceVelvYh@)}6aasNmtPKH?87*NmNo>nF zL9=rs9lpTLolco3W~#Zso9vX?nGrmdff+K19*VWX$q9a|*6=rm9oc#GKS(4@W(#dz zT11Cg{mlC6pZz;WIUAGR6CG*nh5 z`vs1x$9@Sxg|otwzIwe$QVQ7RpICq;{M5Pco;wnIqVjEi-Vf19=N2|Ne_$^%77!9#g$=`93)p_()=TzZ;-+Aod_$a}?g zVN31$Lz5D8$lbi3GT+*x#kE8RP0|wA3_mx={*?4RG>?-C#(ayFnT%6rQZBzG3oDP3 z$o9``Bz21Kbj|Uu5)CCi2QY`l;$!YAa{Ed=9L^aktY>=F*s_YMFVHqr?1_uu`|9$? zvVvz6dUd-B=Nedc?ae(Omfyo>gd}BG5tEd@@k^|5ixyE5Vn_nZTrD!f-D@E65nmPk zi)k<)mQ@fzCQeHh;Bsu_cO>~RZ7OnkQ2wzXUs+5|K9vV_#59zTd4S=OccXBMyAkNH zd?mkH4a=7-Cr5e3YG+&ist0{%GVj+m@#|)ftTSj@qH=kwn9Hb2XhTCo4ywkIQ8t21 zRJ%0>Om(hYP}SfE(@&E+@hpp^%qs)B)x(GRv2|t+@ zj&k3K{#Jo&NEs8W%A-9k?%@pKz1E=RV1h?Rxs>!B*Pjf>f_KR=zQmD`OP;7iP(1w- z_dQAElvo^Je_e6NlR&Wh2J%i8k-7dlDnWnad;!D5?v{EZK|bGtM&125+;kkXRilhV z$&`6KM(-XAr@P6=l%8uI++flK!u1$bEBNRFtu-KU^&>D6spmwOBjH^qIeU&>d!%%Cp``_w!7 zGs)@KOQn;S@nJ)a0RxG|&Y_g$Ap<6{)G(j)tHW7dLdn*{dH043!Z07H2V**iOTsEk z!iGz&N2eyd3UVYU}!{Z@acgf_{lk!)coveHKez~PV@g`Gw z0Y60WsAt^h;Jwk&&e1o^?jtm>Ukkq;qv4+LdOfw=g($7Em%Y;3-o1o~5pKbxCW5iBtc90(OyN7kJ zO}mM&{(&othU&VodSunu@zpU`&;+fG8ROm?c=!ZE?ZgjuAJ!E{$NVwm$^`0kLSSz~ zxNGvV;-uK!N$#SK^TY|^SA`-~AUipmOA2?dFD26}6g6Q^VJbG$fz~l9doXp8X^pOF z)zc~L$~3Mv+TirM(Zw0c(kYYhY15(^vy~b1i?e!NEDyQrk>#4q-f^0s(V{BO`Wpi% zk3L8L*SgvxR}G)jX9GfPK-<$-h}RrspWc8kjstsE--KCyjFhpM&BvbRoOn&#o1qsD zoxjsHAGeN7U+H=mv%oJE>=W)8t2kfwdY+9lgZCn${zOQc27wGv&KJK-$jZ#cUkT{V zcq;#Z`rE9owoHc&SN=-TQ{B|(7w4Jb%SDRIec|)N;mZSem)RVayLAIzx-E&~aV@>C zul#uSOPHR`o8cu9)y7Tl5T`>CI-jzoo3U1#u~GDjZNGeRWmPbp|A$9H&}#_>{9xZs zXE?jaXz^?K@vQK;?kJ=G+N+Ci-&|ag*Q;QR2=engDS0^fSmt;F{$@oV&F zNVy9s#PVq#LpH$|unM-!jARv2&Tx)Zs!++7OcQgw`0=!7AzxNH`O{y*Fv#1p9I9o{ z0gfS&zPCr#uw5|VJ7u(RMTNu3^&S$(+VttnNWxnExu>8U*wojpWbsM!tXiE?N9#=J~h$ zy@;w_K0n^~;-7_aJ+l`$qd5)rIu7V*I$&1FO;=T{rvR3Q6m%{5anTD71iq&ReR@>K zK!v?5nZ7e+2J;x%7G8xNG`X;7_lQnV$!fuI2D{W4id_Ll)BQaSHTZeCwedcL;nYe2 z2mRP)JcuyZf6XcV zfMSsD-*d|UJ$CMcdzm!xhY7`c2y!c zv^MZ;IA@DArz{_!HcqaMtal_fwP=p$BayBTS6@GC(|iT3JozPK-TKM26@&$Se%A4Q z8{$mm~>$#`O8apSAY9<{``HssYQJG zoGWy%e&M^mkSM6fG=h@1`mK_cnCgN`!$K3e0j;3hdYsEZE4eLmDW9DXtycZIElZBu zJHvk3<5}g;;!bH05DJ}alb#>+?yl^j6T84UO-wqj*2&c>QjRpI)NJ$ysbUT}r_Uz< z=ShAks8q;Cwz)jYO2Nr5k4?Ri+-?bPk>k#*GC=Q|mL^`=1`7>>Zj__lzvV{xxo*|C zDmR>FsDj^NSkQ4Dz0g9DNXw4xGPS{3t-IVek23D2n1=FtRao<-d#~<83%#%Ex$ahL z^tD2PLYl+37*3HI1Fu#S;yg!9^C}A)Yk|CzHtb8+ubO}s3QwV`>gObib1#sNRcXNU zeQIJ^4J`_nAZH*grLjCJio&7LsOGhtwo7+243Y_oNszM9hZK7<%We)0Y@a(je6MLhU;U~u4EimKBB z8B+>#?&Afevy-Ved1qc5nT|@{h7H3~o;-z2Bl$sT3dxikshu>^6gNhtnRU%ah||#! za4E;L@#o|#Gg*%Mr=ABhF0?sS8Jf+GX(%7{10*IiJwtrfjhp<^h=hPZ+#DiK@L+mY zxA1VqVz^ZohV~+gUr~K)s=>7yJNJW5MiVIQzgbH&M=-u&mfOD&XZ9SvxtPv?7OS|r zix7BD6L`fekGZ0LvzkF#7wGXLTN=^Rq@TfvJenhT)@;`qwc-H@$5-ZqAp;H$1KP)P5c9Lf5dT?!E8ToW}|dvF~Qwn$E>J^o?1 zXeLxh2!oY;*nSH)d!MYdOzhvC?KsdtX9icB?IyuaEcYMa*PP|ZL6#sse*WYh7g-wi z#7F!?nENa*nQ(+C1XjH1e1U<(AZ8V6#t#o6kraee*0Ji$Mbsnz%3N~egvRU2TqP0C zi2r&33@=N_CIK78m+q0HvHNr^n2kN%>&v08?XHL`^Teyc;!d_XT0+N zCt~+!Tc7@@^}GAXdRuGm>Ee&N;Mb3Aj|5F*Pp9I-XdnMOc0cj%E_~BMIT-@^&ofj% z$P17F4F4nVYiPR>nmb-GMBO2SAbr-4y~bG*GA+v5%^mDtQ?MwJbw9KQeg~q#wzc^-!{AEcyyVXLAy6 zgvsja9f{EbRpkZL6+G5XaJIBI((ipMHFDEA8dWO>&!$whdlcFIj*3E?LL^GWp3inb zORVN)eKc{QsbzCBrz45FugmQbN~O2kvMY;Vwr-2NL(5w!6u4#^6HRsxbrE@EI8vPT zkQVu)t)>E76#_KjRW}iE!9?Pa^_8IOvQN5Cfu!j8vLiRcioyKGZbMZ*8VIiz}0PMZMJQXnSJZ%lo3Lfj*FjwWVr-Z&X zFTeYF)0Cj-m+sG^_MCiYQOS*GofU)MlYQ@Re11bu0s}OT`?IGWR-{&QUNMv)$;F&1 z<2SdWSZlDE0di#i23-cKw;5(F`a#A}87z?G5O-mAurT$obGl4fPm9~6@K%l!9e^rO zuedFFIV;x}uDP|E5beQRoRA-4ys1X?x{2~?<0S8ir^d(9n>l?Vp3A!}PIV!LYcuiS zf|*<;OO(<@UIUvOlcUX+x>qhftx&Q;mh@ZWvHn|nFX2u`soWsXG)Oo(?y>TXGB<;G z>C=O$nky6p)$51ahrgRYnw1cPXCe1q&ePNwH1#boGrO zLJ!k(saSXQmmn|=pX!BnaxLcuc*7H-aq@k;vu0OP);$(OAy7+z8?{iA4~$EJ0ERN_ zxXJ-WwG?<(qTz!2)^v(xu*sY`*BykjlO64rQ>T#bsJ&D4X0~z5e1!T#R~VD~cr#bW z2cfvrQu6-DpJlh$td+YeuhgV>y)K##nDcIXc5A!#X!YH<$9qR_qt0DEUW;Y+IbKiX zt2=&|BJ=t9JwfC0&y6fIpP!p~u5~}R?%n$QbGszr@~@qWT%TXN)eq`^eR$mV`Paw# zmzRHkYM%4?pM9LR`?(YJUxxF3kR2dR@?8GYqSXBd>+$QQ7k^=q{?(uTD~3+xkN&LW zMFzhS#n%ToE-|3>Q%e}XfFT$u?#gkM6%sWDNZjO=+F|J7jpiex;Rzw3{>mx>NeOj$ zw}}#HZaj@8W0VPCRgp-m9dE3crpXEx7-_ABG+|`a!*_1H;>D3djTSRd_%VpnqW{5D zSYnSU5iX?Xm6n3&hGN|-+to^pVsgm{NkTXL9dNiXtp;iT9mB*}#>;0jvd}101>c*y zJ7TrN1FhCCa@?MH*hgoY2(`9c(e#T+%JiZo$Vx>)aK>~xI_mZx?lee0^Z6m>|7<7! zoGCFUZ~DH-6R3j^2+8?b@5{O*uh%By702#nT|G0MkzMEf&nAeAHS1 zUgsraD(?&%hkg(Y8GxXGt;R5mx7yx>ovMuBxx>}DR1d?<%R|3~D z6x8=KjvJfwGwZGLFbJ8aDjx5amNrRW&7EG$ud%9hjZtpJnAkp>8gp);TnE1VX`XOb z?B~#jQ(^|3#UdGoecLatnOo*^LZ;vv^EOySY9`}e2jO7s%4@?*1~nA=gUX> zMc8(RD5)Nlcm?Lxc_~3mBvd|I$&qAhMn&;+&nq%Lx{&;^+4F7r>7Lwa489Te#}b!n)6@ zZun|GV~_9mc{k_jRG+~R1sOPc98WdYVeY90N=L)t2b&wdaBs2-*V?Z?!~n|iya^@V zgq?iF+Ge9Bk+(OczUj4v3>HUHWZx!?lZ%+FMRX4-5bTZKRLr~Q4hS;Fm1s7^bqjch zNol-KPO8Iz{=sA)0@;%a{%^SHj_-emcWIFlWXja;5HEZDv*0)S(BMpRG}pj}Dgd;$ z2lDg4NU04O%>^BVQ4E0f+E?ZO?y6VXP2nQ7Yqa(nFD7%bnK|miP#F~nMaV#E&XK|w z%=g-xoulK#rXJ1+Rx-{sAZoQ>l(D6dKfT5p>VmMmTQVfR%$MTz7sO8si(L3xgFCJl z9TXGiIr33*g<4t3Q|psJF)h;>AEIhLaZi|6H~4st7eMn$p0r7R!z>}_wDEGmhe|j% z>9b5K$>H}4tr^I$r##KBWqDSYbv(=^mAA)Krs6H;+Y}d|QQO4xCG6-&FRUCw^};Od zqNka%&#`#5U;Ol*nmUpW8Gh0;17?k9aGhgyn)m6_HJ)Yys19BQ!FwtV9Ewb);Q&t4 z{5lxACSxyzMj_W#Zh(*+p2HyEtyhJY+JrUPT}n#_%FtFdFM6JAw2hG7F`WzKvJ`tf zo#D)g#i{gxJ{ahcwF;dj-Ch(kRGrKN?~@$I8P8W@iU_+!{7yo;TY2xZw?bymXVONf zasnKUhtw|6r<%Mz%4cMoSk}!7hqPtV`qTG}QA!%P-Qs zWb@k%F!3`@Y*k=J$b`~0MaCWru`XtA&t?#PA{UcIGx6mrd*S! zm7WnD%IY>xf28tF>Sd|%`?UpBtmg-{WAk+eljJ>eH?A(qj^ zX^2&Hg@MduEP2s6wEOu}qf*}+H;>2MkU{NG;5nz;Dlf+CK;MLMVahy-Zly^LIZnQo z=C1zw$SN+fK%r>jF9d|ugweD$|yl<|FB|s_$;~~rF`|oC`SPdaSPT62`qM1S~Os8H^n)i!8g2K zK(s2Wb^REzW2P=bxbXSU#VgN+Ws*;G)W)zZ13DIlUIBA@Zk&g;~XJ0xp_Hj+Y$P zmz~oe_6v$A)_OkST&QxgnZTy?LYidW$HO*QLf+5J5^TPSQ>1fc;dw!cG7eQ-Diuzu zjv<$x-YSoJnjKWAJi6}+yPGJ^Z?B?pjdj-UE+&LAoLX9zG3?TPH%`Ekg)z#`>NTNV16fZ5k6#+6NS2E1IsrA&Ba}^4Ufl05JMw@fUqx37J>Q0MZi`kU!&QOvpg6 z9aSUy13DxIVy~~vT3A7D|;bil(3AeNtqCT3YZT3 zbA1LWn=%^mpjd0oof@3rQ(E!lg6^wv6vKj}_7fjX&|KDV6*ExGuxVnf<>uXxWb1_W z7c^j9ael??6_TA%pa_?mwds~^876u4#8J;Kj(UPsIA})dF7wP?kXqI%ab1#@OQbAJY}P#zE~W%_Gh`0JZ1b}-=bs4p?@;a zRW#3&oUuDFPSV9z)N*u4{QY1m4QKRUb4w(?)VgN8I4Vt;{Gr$JD-HlDF7WU%pIsIj z&nd%5}ina|GIqOIZK`^73#V%jq($XoYMFI)5<3k&Tg(lsu?sJ8gdpX5A6@ z8Hj8ZCL@&Omn!x!Ff^CTc9_gV@`Wt#V;9R6p@6YM^O3%mX@ZrV-pSnOo4e7DiXJ-m z+Z+^nf=V-_+{B?~FKLn_Y2Lb?)sVbo$&SU>jUJdsH+*zA>XX} zWGd>UKKds$dDFA`8r{q;LKFPw(nX?@vWspWIJ;T|urD;4-#(UZE56CXK}r~5Ob2KA ziN=vTXn;yg=@Ta|x|Li9cc_d9SJ|s^TbS>~m8)n4L*Ct?{_&DcEeTT2m2@tIyyq?t z*sn~r5Yki<#^|3op$IjU%8vfLsWBJ{wqKY~a(tcRjDZe1O^CuqTIk)(@p4t@tuFIL zrS|;cNiX#7&izCnad^@vSMz5@L|jHdkhrWkCzF7)5LHeUL2rissz)78ZtA=H*fqcT&Tu&*^2UzrFn^62W{%yv-Wo>W|!H{h$N8e;YVFA6eT)>o4dY-)W@u_-Dbp z@OYwuy4h{=3F&3hcik)r2D{IauzMH?#4V}o=&dq^G6D-gXOHO2>1|!cUe zei-;`T2mlzFm55oysAf}P+u;^y8`rq=d#_a6f+^P z*z7wssC0V(%eAAdDnG3!haq1dxruOZu_3g=s8+AjbZzPfiSpE|iO9(JXFxndo%t~G zrwnEWdIRcItWT8HhYiXS$O$mV0=La6#RPHn5hfgj+ACb(hY0~^yPLF&d2_c_ILg$8 zhrHrdC?5AGLoiejZi zg9RFpm2N+d$7Y!tHO=49E+juz5g@w@=V@W;S;~u6yKs86Z)Vd2wD!~7ZrB;^kz!C~ z$}@M=ZRgf>&*@}dAB?o`h)0b6x()~8)y}A?EPH0~nsuK8vH9CCUv$VtygB|-KN*=p z4lwm(1YxJ&WJk2-X6f{2 zKO)~m=dv3iOH~V8rBOS&g9B?~HIM_3s|0V3DGFSk)iQqLzqysheEL33q_$a^iuFDh ztNm?ikq4z%J`h!Ig*Ftm_hd{n7ANF-pV>3dlJ^&G%b&|_H^2C$|gS$Qc50QwPupDaa-620~$>w>fZ1gI!c z&Eo_in~&hGDiCrF3KG&uGa3c2Ajt1B@I|4l7NslOr%fN3T2&BG0_5+eV>J!!P1Ea9zLm*nk(6Y;tihj)JnF?RuefDeaq(}h+&TnsG@W^6*EgkzM^)g zxD)tj#>B4nzvzB3^5qV!C!mn$bdJCkGM}Obixa4XZ`_V-;oXJk@KXo6SXvt=F8kl~2X~A| ze(+qkZHZI6udlsYnNRAa$5RzCJ)|(g4v~;WHRvDH9)YfeP1VC#9#EnvRevcukf#)N zS6z_A7U+T0>uN&RSm;#_AG5%t@y(JsrqC0&O!OUTl%sMFp^Do_lK|qwcqTVjV{YD` zO?HLyGj6D7u9jngBbtM;n#<{27-y-8EFd1CsUqfX&$rl^l*7pCVGt}jaqFRCEAV?Q ziKet;J0;;^rD>(rL_rmyU0JWVbOfe=ZSxbYI@+qB$TPFP-abP(u7mt=(k!SH}=atez?1tbQhp@(7wl6sS=Oahjh zVNoIp5;q!C@{OFacql-rOK_qVuoAc}NS+ZjEm}#>0C98va$Uiyq7?;#Mj7L(&-rpR zYq)p<(CfW=Cr4@1!&RW*s*AxAJ^HaWGG_|;ZR<)k9^`||4!Jxpy5YsiCmOO*>(N(b zKj}Hk99Me>s)JLfW815kvb&X=tzR!_?n~Cm4ZnHD3BI zG2UBypj8bT-mkp-G2$Y{x2}#q?YT|9c_lsU)SHh!9I_(A;YZHOm*GW;!H(a^+YDp~ zldJ6P zabu<#V@ok_$mm*2u85~Q)0$JZh#0$Wd5FCuT}l&gUYKXnK-P#Cyt~* zXbcpfX#MTnQ2r92{1nbEKv+?Ug<>PvvkmQD;hl^}g!!GT2C|qy*oAlFTUaE8_sx69 zqFgUh0Ncgia}RZ2-;x5DICLP^L@|s!tO2>cSH4Jnb4X6nd^Xo*d8gi+fzOkg{qDvzMq^q0O|Yq8@Oi zAkIKYU(tm#$+e3QALb1mHV``h3xcx!yXPR8*TzZhEGcjBKYyBCRODahLg}B64#vU0 zWoq$<6kMJBhFa=(H6v&d!~6DwX&@l0c}Jg$fG@mK=k$N|b?yI5_y7C7*<_A0=9J{H zjnNP}C3oAHwmHxFltT`YiPBMF&eCCK^kp3JX%| z$2NJW;d#~?tzuU*$|3uED=e1jeVi*~N47hsM>j0GB<>keLvagdd@?p?`LVI?Gf&#p zK-TjVDu-GRHI1dc7S8R&>f0=Q^i#p7-d4VaktbVpT>?sB!p^=H6DAKV?~KvQiJbZa zHm~0)^@U?Q3W^h>KVsH~ob?XR_0n^H^Qz#U81w6v$FqYu*;3|Lt-mggWp#m>rTTAm zivJvig`U>XYuy+0WWdyadCB?&A@5dEy9*t@b|PcsljMt&$>F__dKgdoWPeQy#b7u+ z@|jK1nMW5QPsN!`q(S1fm?$Bxd5S2DF?Zb~e#i&z4$im>k3Ap$O4SY^caM85W7%xn zDhcgDSA4(x@Q?yhPmpVMyAO`l)c4dpC%xL2hr38Wy4eQ=FkTS<4N#;Apzi@z0EkJb zlN*A8p8zpA^_f539E*PZl!~(U1iO(-NYwbj3TdYRFzV%i{w9%&CAiHtoi%_%pg^x4-3pZlqKmB=p`+GJ(4s?5?}HRb{yoc=V&-JRsU7r5hAq%mw+Bl z_C+fUeHpe~nsl>x;utMxjh_$D+P_0TMCaWZpCyW#{TFwgWd=3=Ljax0K7P>)dnC3u zY57y;zt2R(zb>tD*FRpIO36t+1~*pN<|vtBc1YN9@1?>d!4j*D+WqObsN3z}DdEIK z{XOC<8E%)HvdzL{smDgNiUHkZA_VRp%3>_3BW!%%YhqcYD*ShS3R*)9ScN`n>>9^4 zb5pzQSG5n(f0Wr&O7nc+5wu1ysG+4&5Hl3yXZwv-YpxYo%s(q0{N-FMxIHif6Xoej z1ez?CJ{G)xWa!=qw0_R8cD?QYAW~OcAbDJSY8bljGCHutcpD&_ zo1@!N7dJ9o@!0wg_3W*2y^BhWnAs`Wh}u`}P_n>f5oYNcBQ7#ni>nMtmsbVe97g(! zM#w%X{s0J{4oc#e9)*c>cH92?$f9oSXFA*VBQk!MGIHe@F-lR=Up;@ENtiZVpf4Kg z%lLyd`{3MNxf?f#^g?LC?JT{`Eb5PoN8!gbjU5| z6qq<=9mhU9VK_GX(dmel3+zBsyF_Y{OPG;J`94E??HGUNhzrOO% z`tkd4&zNG(SckB*f6Cs;O9Eic?=r)t(djELsVTrlQFyD_3hK{S^@owO-)n(EMmi;m z_yy&`)3+c~8-3$ByK+=0_Z_i<@!KddM)M8T_*wEL>y!5MNhY?(Nz9WbV|DHKv3fZ! zRi268*AqnUMl@S^brG_h$0V~C;`O@AcEb4R)xSkU4|SOE&Z*(2N(|FmR}>{?j0cj5 zP{5L!AL3yG7Rr{LdUruFAK~$BWE$39 zoDLN#;XmsG_tnx$>3grv#W3oi(sHL8EoQ1a={t`cJ@?{3(;brY14-2*k*xCVIIvoE zQ5(KqctHES_1Y4??#8@qoyczIWyj}?d#=QKj&g8>gh`kb?HMEd97X2yc}`LtdKn4e zC$znHEm9r{d_LG@s1W#O5EUySB%X6}AC8T;0z3A2+f6?i89%IA(7Mr%+MzofB5uyp zv9&3mcTI$&Q&6e*2L>iUC)R$#OX6gJt5Q{Qc`;WSiEO^$1`su@5 zK}>`w_&hFZ(CA54w}_UehzRa@6Xm%HFJ!umX;2?){X&zMa_Cwmvpn!J69oX4upGHZuSkf0ajvqHho}a3h zavEq=oxIG;jjI8wLM-^*uz(lw7iB)GXrwnFX-coW>KlFzER^k>TbI^e?VECCs`up>* zhpr(N*@|x@66E}7DiME>Gkp_OiS06Ba)-fno+D}JA9^$Wy3JbiG9d+EH*o3EKKUH^ z$vuIH@=XQPMBzkXiXv|)VH$sv8M=x3$un#)S-&xX8@u(lKEV-%W7QRQ7=DYZwY{vW zTDF(g^o*%Cso+KVuUX#%pUfI8SkG1RyN25om?iSf z&XE8e{qLTzzGJZorPrz6tD<>=H8c>k#ppXPIjSU@%U~u@rnh_;M5_j5di>&JyWF2F-i$D{vhL{c+&5HF{R#(mT>zWB?|qh^MK$<9y= z{x3Lwh85;dnbE5(=&MMmp+0Df3VxidB&YCr+OWz2Ag{MM5tXh0jaV_UxQz!6^<4Ix zEMzx*ss`?Z13!~;K8H-yfa8VsZIyb{9X-(B%6*2-?mifTonqUtK1VP{wUUv2C3Dog zmg`boUDzVruJJjXDZR+bhA;s^dSSkLUVM|)e~YyNp2SI?9#Zsc18`g|)dv!t*Z1jvs&?FA3pSR2J^XgbgZ19{<&+{{r=Ao&TRW`%|QX$*}>+ zL8GI|jdR3gCDVxJtoYo!=MmX=x*ZTsb?TOvoR zi2UttNyws^%Rq-jt;XRF)@V<5n6H#djw;GM)4oc3OO#qzIHN8@yV;v&5jX?B^EC75 z`%mviz)3rId@T#6Gu#zC3fA1;bp^>WfTvfUN_M@^img?Ep9-YX#$=NhH{4pEOs-=2Dx^7 z_i=g#1|D-1-2lt`bn=ddtx8Kph9fUU!q*>3DRwmoZefd7Z+NRu-AG$kUK07uA~8$z zZ_8YKB%!8?D0j&+k|^Z7{IiU?Y5S`{+Lli*%X97Zqo@%k|AhRXqnYmojELrC2*1<3 z%-O=Ub+w;NMW(z_G_NR*d+(ekHbNA4c{^GD=6TU(O{hL6zTXXxBD|z3NDdYobv@pl zoJi*ZaAsFkuNO?86*}R3stZ*gA)7E|EV3B^a~}lwJyi0nr{UCENKMa)*C0BQP@)pI zlZQz5WMlI$rCdZ%`S<zo%AP8}FetZ0_DZj}5*`XsZWMnu~6Y09WcH?a7MV zqEl+vtl^GDQPWr_z9dsH4X+<&6v<#fU1Kvl%PBrt$Q9$NrD~e?jl-`K4t57Qoca4f zsfWew%A2CpYLyrg38Lto@2KgBd-eK`k!hFuf@R&_>-VRTU=z3lCgAQ#%r;4skC zk)3y``s?=fGxB#b@t{nPXYt=qAB&T2xYh1}X;Uh&aG!_4(%9LvBAFbJ3if8J;xu6^RTnTg7V=53Q{MNG+YyDy zYotT&^XZ}K;&~N1!5(+RT?}~4MwrN!DULh zAsQ&Q`zE!2g8IEv`ftDf6V!k7>vHnMvLeA#eDVhW5MEy+heX?CtHjoWXZPiNgR|rT zJRZ!TI1ec9jgPojXhc8NTxrTv6m9v9E$TG}lJmhl6`4uaoD!A>Y(wHB_VxssHnMWC zOhvCOcNcBcM-zr(x%BmAb@JUXM6=}B739RiynhL-N7#%e0gqY_zQb&FV9h-0@}U>A zOXH$uZW`7rrEhuP;FXWxZ6dTB(GU0M`6>Oj_nab)k!2M-07G0#@q&GcmF+(yqz*v* zZ!hU7ODv{3?E2tnd_(6=DuA$5dMkx`Gl#^2eJFABO1T0VYG&)|GYsgNuJ|lM4;K0$ zHM+)D8pGLf=LKYa?em-8-r}+N(GjPT&dAhpF<-V_v=G)%O6td5FSIf9&F~ERe1ATG zsJVtLf`FM#zZ>DOmhQ=r8ZPuM+)FZ`$_P z^N0iq=&bS?nOP5413}|?G7Yk@trXvl(!rlf(mLkq;-b-CK(qS|qDgoYuzJqOpG_Lu zue(O7aH~RV^&Xk+RMy>f@5zcQcyDHyi0wY%9T~hf>BAvPgjnuP5c~bei;F|_IUOz} zZ+^He&Aeaz|D@zN5$cA&dXWYWA(g_P_;TobN(SeXDJ&qwfFab3PVWMB z-2OAAcCq@$n!;@pHKF7XE9OOqeAT5qnAL|%E~)jbzUI{rFK>B?c*v-gtAXTH7#X=K z+aqN(lUF{_Vd)7tU6r99GMlj9O9KVSTryi33uk#@GY~_1!G8`nLaZ}+2FzKbQ?ym* zP9H=>V4CXuTs`(}Md)P{<(-OOjpnKS;tGJgLmak-U&P?x^m_Fp(zN>FU%ihnMKJ*C z2i))P%_bngl%mJUM|?mNm_o9rM))@MkX|Z$%W5@VfDCltJ0=7V3}0O$?bI^|9qhQQ zkW!*_Y(n__CfFDDLLJ34>6en1vNW104+GGIX#}q3M%dVf?mHu)edw*b3Fo826tGAF zO5F}d?w*VmduSGtCQG?KjhCD^Q%=FytT1sC^j>u=I+k5wkC1@aksR_G=j^{lg*nix zSIw3EIv!T(*n>Z2PBI`Z+{tqr3YuXD$QbXEz2N?F9*$zXs^i3O-ZOZ_DRrJE+E}pu EALYN7TmS$7 literal 0 HcmV?d00001 diff --git a/assets/twowheeledtrack.gif b/assets/twowheeledtrack.gif new file mode 100644 index 0000000000000000000000000000000000000000..0575f433517323dbd5c7855e2a01b2e2356595bb GIT binary patch literal 146635 zcmce;XH-+~zwNt#fK&|~=_T|cA|h33LZ|`~I!dnrMFByP-fQR`=_Pasz4zV(A#{+A zAktAHx%_|o?!C`G=j?Ir7uS?k4GpXWR0GiQ`ll*A>>eR0=tE?I!v7X$#H z000L71OT7_01W_`e?Emk04M~2LjVK>KtTXB1i<|BRR|P-LIF4wKtKT$6hK1(%s3V@>k1PVZ*05l4~ z{BwE;8i1k!I2u5p0TdcQqXEo6*95@;Pz(Ua00<0#!T@Ltfce*j!XN+)3c%n13<1DU z01OSlFaQjIz#tG96as@oURhGEb!00Vjf+91DeG;czShjzz(-XgC%F#{vi}1c8Mjuy6zxfxw~= zSTq8QL0|zC7J|Y;QCK(%i$GyfC@dO<#h|bN8Vf;Vp=c}|jYXibC^Qz0#$wP|0E2~K zuuu#Zj=>@@SQG|}#$YiREE|?Y^SSOz1v#zfB0|D=IJY+x+iwtv7+?VeZr=m{dQ1R9 zEa3B(0s8Apr$633c3lGmn_LJHxl#h*RJLLS)dRhy;%dwO7!sLa(7cwFO58n-LPZIe z{E_$v`u%XC+Cueo(Kq{}LzElpU&Q@>QZ2-DsO3VVZglAr_Oyzg!<1x*&vU<(8q_*0 z57(8>RhspLGpW^=&DYvZBTYx@%NHBoZVYFtHB>COc%1Gpk2F-ScKG6vFsnCKt@ngd z^1m`^L|T@pusti}YZBQSQ4_T7U($VVJN`l@gh0lvc5k9cxkxCgxz1s(?Da^rMtb$( zV&nTCD`PDUN2{FyBrKY(jmH~<@%*pHTbq6km2$)q}?U+}$TUh$D`Jn#C&z4^+_!UiCvr+qp(oCrT16W=L29hZ(6J(+maz*sve`hrxnUy=K>=zz?V!?S5EWx?~AmqLdkU-j-~ zx=rabFrCe+`ly_vt&*KC=Ix3;Gos->hhnpDK9OB6y_;Kp9ObZ6e!1dxi9Nhr)vMFE zTs9ie5T6UWm({o&VN80pflwCuy_xVpKzt+Ambw0W+H3Et?UVp-)2;ku=RbSJMVj0V zejm0xH>y53dmQ9W-!vcW{Q0Iz0RXIW{Is!gzDJ#<&aJ-XD2o`ubYSwX{2?G4E|@Rw zgE{{@uYkA!s9sFc=ztSI_tDAE&<)=lUr%0vVq*j4e^FXR{5fvW?Rasy^C14_;^@c+ z3-qpHL3FY= zd9asD@;FQ@@;l|Ka_*KBJI+1_^l~9Nuv2h?8K@d~&J=p)axjO2t zS03XAbUejpxyu&c>n#3y60)CbIYI?&pNtLYyLQX>? zCKqu@EoTM7e!tap$G@gDLbiot@2gu&#;5k_T8rc~soRUir*)3z4}IqX^FndibO={v zA+kd`fwAxFdQ5knlgHg_;*EDqip&RrR`*V@hcQo)V7@K(9$ok^zNJU2^C+TR{(ddu zzIb`aotl>WAMf#lsCQ>NdDtCkruoPdi)TcdHS+6(e1*eyq-=}EC!(k_xf6F}6;*X? zaJaMSnbJ94+~@RrD_W=-u@hc1I9+BJUnnkUNb_bPCCOj8h(obNI~h4sh&(HyQE*U+ z#hcDniYk8DjfA-yGDf{fet-}`S<7gWuZa9Q)|#y8KFG`m^aI+eaf($5x-&1i^~ z|Cr8qDEP8}Zlh4Ap-R#{*H!bl+)k#~Wo{ce$WV9go4c!h!0r$4+lw zN-ce*(68tuW3s}o8!oe#HL3eoyeCSUf1>iC8Ly?{wa&27dfaS7KiLD10g||%%paN- z`hK=pIdU!_^{pBTbevZssyao2-CnEyw7ZNjI;Kf(UENCbw%_tK?SVH|Au1=hOHTqjSsG`}_7irGuXzUp93Z&08a{ z4VyJdE9Xg_-+X9Uxzc?6ZZAsHs-wm98-aEwmWkJ{!F~-CLe)M0&Pj6Bcy%FKyqcxm z$t=}lCz0vo%7|RXU?S_Z}?UTu@CFp^rPQ}`7nG})R8a@3owhrGt#7Q zXv!eXa?YgmEECo@ujd{=$$q)CrOYi^@3Xw0acxptJ-$C(M16v-TI6rYYA#c+;C8;d zmB+jDq0hL&HIMf50WQt;4yOFvR)Xm%HICzAX5V|@JU$peD*-&2>BA>Hy3x+Yh3Wl?c=p!V9?~&vf&WGs_@JY@CY(tJS0OBs~f1x$I@x>Gh&F) z`Y*bB_=C<^$wu}}FXbk8ew;e43gvb22HoRFP4T^x<~e3me&P#OT~BWK zhl^~^f?{a)SBo}Sa5s3g2fIPSr9bDnd$3%c+2BQamuD*W~xpH>ch0zyEy-n%VCRR`fMs;H1+ z1HQBSVgHHWMHN2Ym1W1<=X-NfDy%pYr+zfWK0e&m5-4lFK|fj^d5&Tq@)V#CPeE+= zLm!7UIa*3w9L&cRAT17l+8D4sM?gF1fA}GgyI5ZIz^r= zNg=;VT1rvHJ5(X9;e{lXN?eix3ARqbbS6|h!Ad$%)x#sqA|)6L1bYt3WT2&zpdl$& z_w3M8#B{7CwscpI!N!yRcl`qHXv^?dhqUFnTienTo0B-BrF6x>$9McFF7CZ33^Q_9 zI35VMyt?=PDi{kkmw+gtJQUbBBgN08Lp&5dH!2+dBAK&Om?w;Uk{}=Fp|F`3>Q5Ig zp&KosXuX9}AUThC0wEGBP)I0NFzq#w-28mi7>$?Xon{bj-WVg{8j;KXp81@X1?^9Z z1KOU8ytGpv(s%w{EuHES26XyNZ%}I+&@dQ&{sxMjq;+JvA2;YV|t&?kOw-=55$%L`iDqg?X0!ROs{`{MuE1w}j>>HD#PAx%;=~NaLrqlJ_rd z!u4Gw;yvLFsV-gOA0)z}`KhvhNU$$9(S?LsR7rfmog&sv%Kprjt|D(kWkmZVA&2PF z+(HYPcl+%~n`UTIqmbJRQ=26bwJu|CnD76VG-fb>0 znvrr1(~OlA9e9{`E$X*~q(wG8XOyI=L^6)i)0z?Z-TPSSj8pXJPo)aQ7muQHkQ(j6 z%SaV2y1)Czc_GO)X`(;x_}TS;Y(SPWmsZ3alN>7txZstYrqY&onyZC_=fus2jUvc? z(6;qdc~zJF#ZD2Y`vy(Y=g_JsjfG_OKx-d5(w56+`D&L_dS(l#8P4q^drr$0NNCBM zyw;6uOz~_wH^2ts(mdiy7Ya(p``j8trF%y82M+ao3*_Y6*>aTibPRN6Rwx!F;-Nfi zJ>J0Fl+0`TIty~2$$cbu&2vM)c+Q7Pr}3G_zf!zN=*%uq_+r(8Sv z(yEK9Df4FXrA;1wA5uTjijA<$(WxZ-K!6DoV*OHm`C79`S}K|wq$R!d&C^|SLf0+Z zzK&2wU<+eB%#o3$70y4HrWUJNTiVM?+g~qe?l=mZHq-9^ZhPyP_x`x4->)iOnV8(M z!?#OHH-Q$j$eu*f>CdL{n8Y=kyJgkL% zE>RxZh0;Zb`>rPHU8U!JgcMazVEu87L#6_j7|&1jWhPAOv^<#Mjgj8$3>k@mfqrQg zXnIw?Jxx!~(3n77Gz0DCHSOue;L_*_3NxlgSv8&J?#7kp7CZWlRNFyyRHMv=JZYR- zQej7WBvpNspLF8XYvRqrky4(NE$UH9ozXSYA={;qmL)2AIFHjPZxCagzWv0RKr624 z0Hl?LS4z6?+MEB{gZ|0X6(cQk8_k3XOSvq;xA>-y_4vAmtuV(nw!c$Oe&!DohI6o9 z?*b^B38%vEzQOXracOZbzF??OJAPI`|mH)F|` zI!9ga@088_r72*VWha|g?VjISW*8~Y*>HHZgD*8!Au{?lrXa(0b?3vX910 zs}o-!et3tVKKu!-2-WJ9dI$$2w}gJ)c@&K$$j|ie($HbquFSg8v7Za^Fov=89$sXN z;0*9{`IYV99Z{YD)836k^#0ho9*zQbWSlgbUPb{vdo&A^YG3$vtW~|zVx_5Mo2H-_iu!G?~YH=)XLFUD*{4Lme`msid3PDZ8a&qQkaIiB|xiCEnYLb*md z@~D9d&enk8&Xpq!^P0~I$v1_pKSF4UjvvYgGRdE*OUTrXCH6lZ@Av&RUud70icZ`* zBe5OZ7kfc&=|tm{-6--ih2qu|Vw0Y>w7*yCIgGZd?=+{l7bn~PQ|W5!u>9$EN?Zu( zIdWG_exmM!;apNwFvCO!ZY2-T!BIH&RJbtX%lo5com8tZw}6Ks)=$r`uXY~X<9_{y zMr?-Q!vkc%)bF!uk0Q-q4MHc|1hs)VKM0+xKSVbak6fv@UuC?iu1*$g^PZU!q}ygG>}gFd*^FHe&$v?Vau*4kdzLJj)FrDxR8y$RsH$H354;0@9(3$(L_ea zkFB0@Tbk*DE`Mg`<98-<K^kRbn5O{NkIb z)_Ih)sY>H$h*Vi_4^k8Pxzteq3b*RH{?V)U&wp>ouJwPJbq6h{fn;sW%zC_-M4TB7 zPhN+_U&c9D8=l&XXUg~xn9_2sOgc{`DIGSQJR2+_A>hLIO>kVO!%}yzh!|ZuFGo0G zZ*dLH1I)Q%6IUQK0c57?D~tau@2K^ZCU8>Z(_LxdTEeYn z;hvy_`(XLI%C%Yw(=T#12A#9sdNuJo}I3nj6@ zK#JFhmJ;sq>AiMrs3h6YRn`nLdp*NMM}_}`QdKwyc}yFh zzxIYraD?i#?7CYzev~CD@@=0V-2PDc8FqbYWcd$M!0Uub>Xtf0%FsGLf%~k}ELA-z?B_cPfMIJ6@Xft41Z<1cxS=?~>nPYOJNj3V5Ib-DKWI zG{Vg(3Efx<1?wRM#4b944`&Z7$;dLCxG=|s znjh_0o-1jKpE=wd6lg$j-TFZ9tUn2VqHlL!jpj5({hXN8bRlsxkL!Fh7T6=2>rORv zADVI@)>@?}at#J5kIBSNdRB0kCVgfI%q&0E`&7XIYt z^KjlR*KGGH%eyI(TjrDZ@!IS2(*NxN|A6xQ0!d3(KgAi(rpH|4AN3a8 zb&#XT-VS^z4qE65zR)5NMkR;3H|8;2yuAbU?kd#loqXef`$c)-m;`T+>rr;8(HM}93c41Kd_+k6CZVN;G*IK5-6R@56;8CG`M$a&Q|{m)zAOkAtO6)8 z$K!-5f^uWh2eqHSQwaYtRe5>c3$mnyxl1W~9&<56zduGmrm0xqoS zJSK8AP%xg`R*>xbFBosmgbSx`*pKTF5P_{=*t*jb+>#|{JC7{j2Cj_fH?+pMt#%5$ z7ws+^bSAJJwZPq%>jiZR)P(>L#z$$xSd@)5pWB#OZeQXusm-fF;StTh8|ke>k;ETP zdrwj8?|0bx9^5>k?<>|wsi{u%q_T|oq?*HV7(pysq%U^*&>oH-^~wp9^mHl~qF5c9 zw-jtIHHcPtJx32sb`4O||E6ZqG!wP!@jhGYI{m>Ueail4!j5ggC5$@{a6>vtV>5*hp)6Y8UNE3B_ z;YaAdhb0wnso@azHIOnDflFu&rgWlA{9>fdz-V|>o`01@kMB}?@DJeR1#prS@DR|`Wq)nDClMxbq zCAuaQi84F*Rr}_;&r{#2qLwD6clS-BzR z7W(n3e$9+^synFJ+WN=kZkdj+HWua@xZIFIg8MX%hnl`h7qZ#b2>B<*Q$gNi$oR~I zb`2?^PxbDpwtCVAwN|cE!(!Q~3_q`K)TcM=O|NE55U1gd)~ht9oYzusJm*>_R+dEz zPsd(=`eM9#@A@d#-xQABWqh+%Wb?55nW=;BqGDiDz@k@f+OJ@K%o_E8c;Dl@mi~)- zX1ijw&nsceA85J#BqTSQT5|3b1W$bnb+`SM=3^T+=33QCLDpZf-c{=|H8D5u2uzajL;=lH-~MdO>=R-sfmE^~Id!gBVDqfcuOetrmEjXyBB{P?}@sYe$r z#fk;8muiUG@CmxV3eHQw#%YV80 z?E`r*AaGsu-sHG<;_p!t3+6Zid$G-p{k?Ac_FO7RJ9WStvo!&}N^bgnI^c7&^Uen~ z_Zo|>e2V2KUF%6(=jc3=>inh9d1Bmof!A?IUH0UmEP-oBElwv%uk5tARNY1g>6t8P zLVIRj`#ne(iKxs*s4RyF^Br|L;y_tixExJj*Zl;!0kvl_EvPndC&gx0?qU~<-;+d+ zP^a(&vfo|Iit?^MWFx19cpF*t!Z;qOCWJeLLQwL5rMf$0nSJ?ES`pkg#e}>DPfXG~ z>09N_6nY4x6&|ZAVDVjhXkDvBOnQhnN%7?F4yxeBQFORszKr)ql|NY3jEX<>~f z8X^}lV8`1lc*fCh@7lr%5)UGz^ZuPmGt}d#UB#T&|Ms8*o%h^7uE!|wxog66H-P~Y z6J@bL> ztZSH2WtbX5ovA&WSFXbw?tqLk5JBS@2fKCE*R+Ng>_(`|)EXm42T&u!3F@t_qemmE zv`fQvCZiL9BokH)Q=qZ0z2sjN@6U*ieKQe$m!W<%Ia1QAK0K;El0UYX(1&)F{iLfg zd#2IEs)}`F7+r;E&WMlJE}_2bj(6LsFLaItpw*i)H0E1J_E8%9t(tct$Mp_Ix6U-b z0jOqwLQ3MiBheQ`dm3BWLP_jYO-)~Ze{EOIL;XfUewV%YlYzRPnZRtmxITD+Ihz3R zCvlcv;0S8r{++;sO@geo@SLk#fQuyB*s zQQ*~^UO%RinR;bBMP;o`9W+Ios7+fiMN>CLSFX+2Hg$h_ig8Pu3I8h#wGIpCSEisA zLJ(Q3R14&7j&@xCX`oIIp*o)hd&m{xU7|?Pqi&upofZkrp5wl7zLejg^6>!)aZ(cT zFQ>7h*3*yOrp1D$pCnF;7fegkO-uGoOMRP`-kO#j%lQq~_RXjdW-JI>se=AU05g22G%wE=mI)PtgbLPFe$kG9?xv^I z_7degYyWxnapJ5)!7SWb&uMGcwr$oKf9}~|JvgVn-SXt*u2?{}Zs6Omx=T8ytzhN9 zl+duMg9PGTfh4L}{bxD)W{D4Z*B^Z{h$W)0?vCrFr(_{Zq!Ku<42+V-{`rb;uGH?L zfjzs%C*>2GZzNPv7wiX$L#Z40{q+6!zzYd+YZ%2;C}S|M;lZfB87?*CIoa@UMhW_w zAau{e?rM1zCZ*p>tPqIO-n{(p`Blbw9+?H9Ly`myO{~ts-v!m3Pvdi5&5z#Cmt<=0 zo#`je7=7YQT3vs^dZuz;6 zHfBZptD(r#9c5696&m2@v)AN0teHN-h}B#^d-mCs=`-GYo#*81or`ZHa$a8*YVlEd(;KyGm{Q5j`l0Dz3n^;>J|ZJGSEenn$$OtWpywQV7`ZP{OA>TIn$Yi)D0W&O(9%*NcR zaND7N+p&Ke?yhO8w`~(`V|TIT>}~VLTi8i#=e^R7tKN=VFrkaPt#k0s8!lV>q#YNV zolpHcUb8!&-8Vl}*!tYv@wmI|L$hnNxf7tY8>qJ%B&6sthCF4b$9wsD`vo@pg%#*@uKnzay>KB1WRe4;>wekne);x( zMR0`gKS4BnVgMHq5C${=3f!0f1kvyb8KG6#T>&5*Kz6VyrzZr=p_&1$&h3k!d*rY* zSe-Wz!>SN|(D*igD4ypf(qyQnU?f@CG8e^NTR4_3{(gUHsJ3Y0i);WflPaosDi0dZ zXF7~3nJ&`GQ_WPZL;k-BqK!6IZww$f)Uwo@YPLpvu;weHO|?4{*$NTNGJ22pri&xe zG{>6V#=liqj$~=H)ZYft=DWxLGl=H$(AALv@g)$z8L z%cHfP2rSEs_SWC0yVIqwC)(StFaNhev^8H4joq3bAy@I5KdIR6S^!vyXFZTg&u%@4 z&Zc-hn9+TA{eKOj?S79C?&sNv6rHu(h!X!^uM$lV*S!(*RN{`6k0{yi)dx!da}dpb zE78EFWGl%ei^nS2ESPsY#VX0(M*nqI$#xq2e+r^)m+WMDUF_|A@g?Bf%?_k-*v$zY zH?YcWo$uy(!ztsy5*PPxK{Vu^yS?)tLtI>~eS3$@Xovlh;zHy;vaEi8|38Ch{6-Ng z$R8E0HM$O!odo;`w_z~HgX%%9(u11O{~?Ixcvy$FDLt%Ta{qDIuole!vvJemw`0?8 zq47o&S6yC(=0SS|to3Bp@lDv-O6gJi{q2zlx;Hl?x}CVRk<48Lw?VXS(kBPMdcev8 z$Gueg@Z&x@+p_B5T<3#_7O~z-FDuyZeRCO7jEy`Q_9_`Y84(^B{V_Dp1}_+EY7(d| zljMFf`Ain8FidlgH-B=RE%jpJfouy&>=YZvU+qaO_%CWoCql7KQOou))<$;mG)5*{ zOxJzx)r+ySXR?ZcVq^BkRIU>QIZO>ox{Dlsi%NJ{oXcg3ur^ozY$d1qsq!+VCu^Xf zzY$c#DrPVEbwu;EaMKa7AV5WYxKUA8;ch2QMB#lDkj{O4xr48*5iYM6z%052K&vHx z;AUn4fE5_!u_3#N+X8f~YMj#m2O5)y<##j)03uW^{pqVag3>^_m8;}QwVGaQrtTXZ zsna-7MK}J8Ptj7pEY*D5(gNd@!rRW=4{V?6k^;ZL@ z3AWGvP7S-&wG2AH+%;%QT?3DC}_7g@-uj~iqub`M5JheAkfG$X%Dt5 zfBX8<-(D48bBfKCs*`YsK!Ue5HuV|F;wc56H54T+gSM zDmm$!qg<0&JHs78V>I8@m<2Y5(CyXa(T+;f8-EgLTA$I7IbuX#qv>|REu3epwRpQz z%;AX86Q^9Npx2Y(9$Jw$x>=Tw>=f|+Ol`Bh&v1KWbhZE;KXt+>Xjx=B%LmkqlV%Dz z$4WHc_)lm4IV+MSLu!Sn&g9ac7eh6WI?2N`g_7qbT2V;dBGqq5qjRLe7*elc_*;c@ zUC}Et$ED6R?HaC`G7AmW1}Jeg{tN60DfvwPJJ{nd zkf_xBSJ)3{sQmv8`;1*dcUGuG=i zbvzp@_aCX_{|fu<;*DtOi`|VFSpvh!2l6!bo3YUU7WVFYTmJ$3?NqzM|A(;WLhj~9 zitX?Im(($GuQ0=Xf3GMzm~X#0Kk0uD``gs<_CK(vviN@hdkZ3X=`;;t)TWa*79&}q z{@wkPR_J!tzf#Bj{70>4vyMk?SKFmW^51_tQp6JAENQjeI4f4k-XWQM(?!Y+``L4E z@l=@CxR@URZejnhU!T~7z88x*sT#zh@Pycj z%JphmO+YLwJ*#r-YVsN4PkVvZQZVnQN6# zD6~3C!IfHom1*cgtS<3zqU3a13Fhp$IiVVz zTIR$g%=hUBsT;P4yx1J(zXCuY=$ASxKb|~mhB%m&)r{2P{ zOK_D(;R4;GHc8bHkIBKlU;uY%aFA8>IFjJlJXbX(5ll|>7S|4cO^X|BJX6ku+w=wZ zu?n$<1BKfm0)%5LuD}ZIVL2a!(8$gAXuOTn`dmib#clxB0Rds;*Gz^`DNvnvkF}j)04pPf*K5ErD!NFjx05(VE+{nYl;Rb}{*%AEdBS4DcHz9UG*@>0*WFaR(XHW1NT4txu6Jr z83LLqmhHGeQ6nB1dx!;O55x3~}H@VPQbtF&eg6@v$T-o}A8r3`j`I)3D;>(!aLc5O-nSXuPDHI$SO7?IW%w2z0%&K%?Saa(ar1$Ys-H zRE2Ai+VZ~9WixuL!o6W+`RB*WmNl|Uj{&unleEj$U5(0*b0aGk&6jPzqAI<1)K>p2 zT()10ReE2Jtls>&>;UdoSvXuX<0|wvbzEz{!5>{CkhqlDuI{Hql6?^@)4U7m=r=KrBZ7*%xED?{kX3I+aeEz)kHGPxp`F7iKW5n|V^ zj$19l%*h$V>U*n2~BjkBk#(; z2E1ASdRvNlpcv&IvmljbW@e7#nMd5Y*Kn&vR6Cqyh6sx+0LxcV zghoK30YXp(QZ*DR+Rn8uXPnR78HHDu7bzvh6$%cZn6b06y{)SF3d%wzhb^A`;ph|% zgHk{&FUuMYoL?~SS-*b8D*+DB(9mOd>H=Qg*N0PVYN|3(Ty15%J2udYwsP$=@a+WQ zK_#T_CTa0gf3>$W5~4XH`IztO79%6Tg-0mt3!09WN?C~C`V2tGzvpCAaHb?ZRsm%B z{iiNs*l~e4LRP;s?7S^&r5=&JC+_^$G{2mSKa_wU=%tpmEU0Tq)|w0yDNA@8c?J6l zd`OqYVHHcPL~n~aIr@S8>6~Q)(?MVy9s-~M5WQ8pWAqHpV8S{vr~0#+nXM1ysIL|= zPF}QTk@@Jjqs~7o94ck;n#6&ke;jCLd+LP=f&1rr0xxrwazgfva8Y>bWqts=h=l)7 zJ46K$8dBIN;6qjDL*Uk^lJZJLLL-gnQX)zapqbIk5xgTvVJ3uI&ygy46Ts?!0mU7i zUc4fT6je_zBac{is;-$dF+Te;go}!krI4YE`Ir49ucp;j2j8 z#xDTnMfWJLA_Bh9~pV4u+!Duc`!(gA#$Kwby(mc8WXun9>aipDk9{t>4 zzgY8e)Z55B#vSN@0{6KgTh?r1`9OR0iegPY|K%`RueqgG!Pov53fg z2)D|Rs?kYY%4j~w0b7+3qXmjc zW0J7Wi-sQKKNNmV7|s{Cxc`YUVL$-K5XbfZfH68BrkUMeEdBqoR2ctl%D(qew6P|; zEkW4w-==KDg;6YfZ7p}I21OhMO5r*(_K&4vbo%AiQpt={W%WhM0tPsc!L-L=zRBwU z*6s5x?#R7yv`u84YcL%9r`rdubBLl3B$=!DSGVt8F9U2?uKf)@|EtlfUDa+avZJjQ z>e7+^+bO&LO1#`?B94T8`=dMSz}W4Stw%J^o7$7tP?4qa$=$K2zBQaVlNx@w+KIP% zll-0)2H=rfmA5kbf^@p_)RKSPKb)S!%|~~q>zS#2H>N~k(=^*#EsG0?ZXAQYRSg{N zk}WLey0!kkzIxIBB!!`~a2j6*pH=Pxnv?kEH)rvhqBfb>q?!rJ# zpTvEaP5v9(*@UhNx+eA`&Bu^+LpYAvYKU;ZLC#CUc@7*PAEnFTBFc^m3lt&PGY`KL zi=&8pvFo8F^|dkHO8##h$7aG+PEo!r`S$MO2Rs$ZK!`M#B8xktj(wp+%(+K_jIq;> z;YZxJRxgA*K^8BJ@F+wR!aTF~c5JRCu3`koIaBkM>HeHXX#m?F1;)r3xfH5q?f~SU!F;egcDa8Oin?dVt|%S2r#k zf&*pm!L>Xn2?OPZve(_UVs))mYM}#ULF@mXSmjD7AECjcfS^mPEs5>ojZ z8*m~jP`~2v3FQYpsRON7n$rX8jflYd6k)CDCe6Me_9~Yf3pcA)(vZh|a_Bk>wYZEwc)tzt!ZsD(2?^A(5c5IVqf!&>~xWob(caHnGH`AHQVUXO&e?gCk zbqI2{!R2qO`7%wk{w(fgI%(b2vyYXKFj0OkUJdpKd!~Q%2^Mx3*3#x~w2S$1QVP;y zQnzDf@M5*?(Dk%$bg~_>9IaGediI)u4&@kxpzN9*=A5UmC_hRzfR6i@3q4QJJUZDY z_Cn@`^=G+{U(T;D#x1OKZ>t>>so!Pj&mIAlnT4@0-$+I&dz-V;&L8=*+9S&As}jkm zHU04SVsOZzU8g0_eb!^UwZsglS0L*))TB9z!PCS?z>%{N3xw~mZ6n$5^n1BLY zhDO~=E!FoqcPT|Oh&)FEP>VTWto95&%d4O#6olWwA>xc}S3g4Xrp73W1}TaMg+-TD z(RPf`KB4jA$E-8#*4?|$+3xPJXi{-lK;_y+g27MA?dQ4bWtAmWbE1vcRQPRn`kxBr za|)m3vEI+^mHQXQKq_pM|2@V|;9xW7WupeW57cY&6*$!#t z)hraK$=FpdlI)Qmcgww9fnB)YCd_DhE>Ol=wHDdjtlw8ia#H_Nj5AVvqW{8|UN_`S zdQjq?WYT{%papQu|Bpi-9ovm$^|coG8T_sgNUNS*I(_V!6l+>;7p%6Jst(92b2qAao$L z%TnJMhkrGplOcLv>hI3pHl+X6gqFG4npgd0Ruy(@K%2N%w`E4P-6fSuskt?v_5XN{ zxO4LkxFw5_{mYXGi|{1)iTwR=bMCeY-OiAH$Tbr~DZQ-GD*k;%x&T;fHU#{;ps}h~ zPOZ)7tujM*QHdbgxKUha1NM1i&|cDy-D$PMu*p}K5I^&~tph9BZ6`o+>Fv;0@FH-y zYhcRfPHfkV{oh+!K4&>j0Q0W&g&>~YWwwg(qd?WJ1v5VFjdypP&!f6exZby@iI++k z|8B?a){_8z(`N;YInTbz;7(qWM-$ZfCj<%;G-XHPyWElGS0tW^7X7(L7AFW(;LM*_YOTqtY2COy0=gIE^{fVqr+)P@Oi zci#RtfVmchpRO_Zr5p%%Fe!~Ffe-8p@=cSSl`nNhb%AOUfUm?u0JlXkfP{2qTSIGvBx7hsEeaDnPlWynV? z1}C8F9}uw1tWr;1(h8)_kxN@vNLLLHv}mB2+SL~pxifP(zWFK&X}KFi+83A zZ9Ym&T2noxju*^lEjT|$mqvTYsm+l|AK}C9$wtg4zoxjttNZ$SvFnQvCt!tfzQNG2 z(I(5PK(mW;WqGU_z{h!Cfaey^PRJqRuZh+G+QIAtlP&K{|2a!tJb;Wd%8%~)n_~T3#f5{(){mMYG7au>8!qkbs`B)jw z1Rh~zMp6rA5>dC%$;vJ##r%OPv0FGgy%=T&{f3czyrn0Q`-k+&ujSYMe?t2H&(U&8 z^M9h{bvXvT9p^9h=%v+o^tQH%oSdbh(;Z0xp9CGcT8Ku>jf9&4td@Q zMn1h-2cELIxApOrIT>^-_H^F2_iQavj;nEL=^V7%hLF{%*;@gWx)aJB$Y{AA&m|jZ(_%7oimM;uO{w(hjqs52)WUX z%79jQ5m^{p5b5`VeAJ4-d)f={lpgq&Alb>iV!I~a+Lb??H01@5?BMq`eFf5lQoN0_ z`Q;thfT&&qASS5H@y}qV`a~|`nDwU%gD4h#BwpW*UXDzodY53SwcZ9xtdZEUT-38yCh59n7|^$4y0?B1qXk8$6FeI0F7q--XvPU&J7tQpR)K0AFFwL2KmkMo9*IKC z5D5@D`_AQ`0fn6;;2^FODx@?^Sk2b?^6;V%U)lp+=)%`~&ILfFQ$3;}x8OJ$?x`UaMM*19~NxEh7|s=K_g>Zz6#QDwBj&pn6R$7_22{GEqi3 zJb2%_hyL%k@0lc#zjB;BPzo|R;FEbUwL$w`f*D_-?BQGU!Yk1(=Qdo&t8I2^`2aiC zVoxh8ggfDk>Z8jVE|UG*Kjut->s7mXuW=qbswFAP+e~!h*6?=1l!VO%PjkJ61M5|X zohXvL$ShRK3;9#Xc?v*aXQj%b5_n{uF()AbrB5|~v;?ecr|-sl1E?-Z zS0b#m^!K*o%PHt@jCh9Y!u5OPZ28}N3xZDNH>?MzW^53J6%p^&X1^+h5S#a9vMHVN z<9E-`)jj{keD;=w1ENl!#W_^(O!JQ!PBriBG=qK`5x?>{rykAI>Ii-x^2@4{L~^BX z9u7VZW2LGd-DtHTnS%|emAvoO_oxfj8BptoLW(sCEW%fl&?VV!Z`zCAl=nH|vZ^ew zD2esT95fb{z2iUdD7D`HBy>>DnG-|m6_Vpi(?$7;7D?sqmGMuqHxm%6n?!Ub)#`5# zJ@u+*8L7nFG_4X9IO<;f2$=ekY3}6nt7B5C5j&p}ob~oq%%fZz`a(A9vkN{fw|i>a zA)A&oAj~61QW56PJ^Ze|2fG0KU2cNXAv>q%iajq={_b8&*=Sw622T9 zKHd4fVl}JI&~?4~+q3VNx1QD=+8k7R9`|z$@Aj*Xuq5>`K_)--yIZ`CBHg zi7Ts@x&28f1U-)DCKRBdHwyA=kW4H9t_)$+!b^Xab5%iSkZIeFyaJ-D>#9vnBJ}(p zf+)lJJ=(e9b@ztX;~^*=z)y3ha)bpNqJtX~kG>y*R&xnrTWs=<7Vc~qxFl8H%4P7@ z4Wr6TkPfdwB$pt{rgk_BtTz*Sj_8c3E+bi=UJ9!6v^%@fTxYI0hxri&cT=frkoiU!}6u}x(H+bU}AZ2jjb$l{fVRJVW-zeIi7`d)u@xvZ*!HF zbm@uI$%QvLJT`w2bGQF<37-8<7>1`d3}xa9CRoJ%7-Yc_Wdvmc9>9()l_9$M7K?bQ zf&>t7))>Y9*aufSmnwpv8ilTCu`7UL-uKlaeFHvttG@ib*3KD9z~8W`$JrVSBKyd| zkri35CQECY+QCVX?mqtVg)`y^8cYR1)Qk4# zJH2`*Py{Tz;&nw@3qcA1GOjueXfMeG?vH?5)b1Y%_i?%e|MXub&!h?et(u zIHu;8GNMrI^DhLdvNiXg5hAITIhDxfP~SKDliV1X@c=bxRr|_Piu^G( zhOSTu(xdSA)zm}$oZiJ?LUZy_%pl1($9SV9>lV>1qF$%PRQlT9aQJ%t-UcwXO=w0! z&WLVp=CY$(bReTQ$OPXpd5d`H+R_G5<8Df+^`%5o;aB7J7WRvii)2y{*kH1GO}&frv+3LFw$) zvC{}M>WN83&@;`H1ZmbJD12T~r>fADlSA`^%fiX3^>0P^mY^Uy2XynllxIT z5@_rCC=E^VEJN*jmF-1ELv_LGb*HpiNo}Z|9od9BP-(0nvr0Qw4L_3-q=2W~u;l~! zlKWv62mYZ7ZmQvO|NY{mfs{acfcAd^%8K0oaKVw{zO%4zlEm{Jr0`tdO!=O8uzj^P zyww>G^6*t812jciS(!Eeug6?67O!v|jKHyiM^t5Wc05Dz>D|@ZRWVKzS|dEc#N8XAKMZ8D<^EKz9rL;X zT2>nO;h_5K0SKOlL{+bTUIDEYJg}p^^zi&`p^qJc-?oU&UKu?r<1rCt$FBJ?fExsI30LlJC*B@m9gPAuSZwR~J`41DAJwD^N5R8N zGm!=*mfi*o*4sTM4`DBcO^`CI4-CiIQ096V;J}j4-DO9 zc&myyNd_HFmjD-2V>;@iW{-jCTpH2cG~h@@w~LLY!Pg%z5H?`|HDqafv6TD8^9bgo zhiRm1l1U68FmcXF26!8tjto1)??feODs1N%G>5gOV=1sV<9S^KF1pbmpx*LGMRal` zfDN`o(qKR@!4yP?5zF|olQmafnT=mHz_fh0)~$fMc9jRpS-?4%$gMV1fd!WeTtT>= zbO5x-&sA0T>F+}fq?9K4-WAU8QsjU3gNkR;9WsEurIz9Np>SU-1H<-i3VvnWgn}`= zd`=PVPH($hw93yKjAWvMg3jrJb$#)^J8yH&%@|5&RVUC}-w@WOqV3ae2LwzX_q7!h z%t@%nE0|~{-d;LQ@aaErWalTIpl-+|M(SM<%%JDDo*Bv&(TIjh;6v_6(YbUiCf#Uf zTpo@luj^o_2RTJIOql+K*xVf$T1ZE5TI|G=`8lR@{6_RG#&NLnEpxJkh-Sfy-NSgM zsa&U$SM5y)Wx^PzKeob8ty)!s=;ki%H~AXgmam!KKWBs}{L%Wd`VIJ(&H6bZGHfN+hS%Vs#n`WwYPE)bclum@%1(m`;%w~H`FZhMrzC2dMpC|y5KbT zdF&mlKg6Y;k*p^joe6i2vAO-JR^P7o)KIZES#WTBEm}x{y>dzV$MrSCxsALF!*}Ci z;u9VpD(bONKzGNHtttH5V^5s7J^jzVlMZg4#JDewJ`#3$kYX@t8Rd)kF#jISYepjc zix_Z^s%-9eZ2Zsf_@74=z!CmunuR}}_|NE~!1S?z1M+=IyaxOz>8@A(s$?ctoG{CH zoQ{Mhn(5M?D#FR!naawxy5S;W4tx(KN?;fQI{R~cuuYkrY*w@L*HY`7(MG`ckOD5c z{(d|b{-yVt=01D6BcDcb^WtJCpiyx_F+(Mwmg%km=_y5ARkyH{lSCU2Lr$TjFCL{(u zpaRi?1n_)&QS$zY~ObKr9n^6movNf&*MAS|V`GU=5UUubQdnhzcg4<6$*k;Wrd zDi*{GMU?3%+S1ijm3@cW)(KU|B&YA%_AmS_*+b+b_*%&o6LovtWD1;+(m>d^+!Q$wV0Hp-?q+YmxNTZVVBgUivESLv5q$nzfsqW&3@nE+KuFm7o}->I&IN%k zZ)q4h{WFD59y*er#3Xhpu#1|Nd!_@Mpg`}9QA%bPfedL~3LQKQaYd9_%aiFK$jwsQ z#o0&c9)?Hos>(wE7=k$5!;+!+Ps{@Pfc6AV6w8JB3N)*a?rcUju-%}IJeqwsWLgC5is?4{7 z!7x92kNFB*c`E!)5iMUa~-eUOU zjJ$~qIE_xrFDQv7=Y{#@H18qH>kx%AN~)gOWDiGqoD~~&YEAX${<3`>&j-8W$!mJA zX2OOHk?8;_)nSmY{nXt2@9Vd6u@v(&yWh!n?&~~NOXNHG61oR48|tS>oVzk21KecaH56LL4m!rf_F0D7Sjt~N_ywj|5vE=b0d zW&ebjwt7{D`XrIxIHqVD6KlW9|AbFK#lI_6LLmQbrO~;cIPrh}Rl}$8x7GemC(E$f zl|ewdl!m_Ng9>tWeL?Ql`{X!R31)i>~0 zbX&bc4sZMhDr2O6%!>>;T7HeC;FxCH#xQYnUYtn6waK*K`r-YOyBUxe8psvOV?b^EPbrFsY3vIW*4xDdx zQ_S^Td)ZaONz2${sD>+XxprJaQ7n!3dJLwZg;s{@QLBXxoK>4FYty4sM+M#6MjH$0d%z;|B;I;`+6W& z-w&BQKG3&#g}5eak!L!mz=Hd$Pe6}Qfw0tqupbHiv-ZOJFNJ{`A;^_eJlFYTl&K^i zQE7$bvwO}OEV+y&fakvF7;`551eCFdULd14jLv%7atCs+42y+DJ_@CAJlvjHk%|;c#8}$CdJ;_Y`odd z!FF47W!x?ptyiKEBy9B8zx)aHgX z0g%_u(}cHI5#!$4kV%LtR<~WCYbd@|p}4T;cBN^&G{(q-!dn-0H^xV(4cIq@m`AeOT7%Ft*O$z#W>|(?6 zyzv|JN!iO80LI)jPVwMnCg`dzvyioSWyW)7QsdIZ_ZK8v%=fq#Ly9>LN|Lju4olCZ zewB;4OL(m9lyCf?rPUmHsH&kbnx>Ew<=?eU&9tPVN04CLjR(IMASD(l!5(kiM!JL2 zS+7rSPMDQk@^E^3&`yHrwXttOOm_Z&maoIJd{lp4VVbq_BR%hch{XKTXM(`;6Yn93 zjiM>2#W84u7pX8>+|s6HPrvj4pd*EZ&)&EgHkc94R9DM2w8v6m?tI-Y(#5M*$_msx zRYSt92k=)+b5(L;sqUkDdwfH5Q28dmB;M{(8dgj&PZwI74(gj-Md*8cu9kY7CVoIs z#MvK3PknK=;NQ7_E(im%0}TF?`-`cdwvPP`C>AWGf7TsXlMw#jU347xe+r`!EEvn7J$z*%`57x@I z2TbNDs77KV`96PG=?`zy>zp`ZEu{eMmQNl?3UkwzbH8r+@T%d5Q(qN5qQzg$bwaD0 zmHkO%+TG+Z?}UrD80yw}){Wd8z#s%&`|53?{Y3Te0*FtdP4l$eui7m?eCHMU8F}~O z%6!#^^!;H=2fG)a>&kQ53LrF^YS|+1>uc=G*7UBT*W#6 zcX&e3`HIzo${Q?=X8{~i2pvTrc|VUyr#RJRn;*sz@MYEvn9|BGj^A^|v3!kPS)-6@ za$Znq2@nU?y`5`(uQYv3yMP}8LzL~;x98>o7HsQYz)v7kN`$fL*q}~F;o8A4$HsW@ zS?=e?&CbHijrpgA6QaU?{ywko1Jm8@57l0%hj5@PKH5 zGKcQS#irSm38#K(B{psa3+AQ+09C@63J*8E2?ypK8!&R-mH8H~>E)Klbtl$IS;nXs z!b0PBB&PnLcvJDdZFT!y$2&$TvBw#V>41(X4(i&g(+{^9_h*2bFY^i3riIqzN-0#9 znP_I{31)dxNZmtw6jHC7(72zq*j4O#Qg_tqJ>k?foKLV%zm|tP^_7Ord)n^H1DYP_ zgJMxR7YluoDoQ_#UbYe1pWZom!t^{^^HRA&9-mMxI?1fS-w&UCH;;rKTt%HiP`)OQ zdgYu<);~36qy)v^?5H83Gb&NvpOAk{NTq2*55JF;XAt!PvYN+4aH2LV77|X@wclPh zHL4FIg2$_DpHfFzK$?gG+}_)pskHn03po__Ct`%lPiLQ$JEoaq@t^sh zy`cM`#Q%vg|3hE+yHYh$bwB&R^FNN)SX;;57*m^F{^e+&%KnA3=Ldj;(f_Jc3GHxo z-tOmDsEmJBs=()vVLw>Mz|C%d=YRI~)q>;0Bd6OxNwodh_TE*P)zuLeuNbU{*f;lQ z+xx}V^P`RRJTnX7I)7KHMkIc@PG0Z6mvIY{{HIdYny<|Hxp^8*@3l+7@uHKTzI)D1 z+4oC#Zal<-#jp}BKZ6*m&F zYne0rtnAE7Y%^;H`MmV@=H}|9m$FA@ejm9%BC;0Fj|RQn0(iHi&$gRG3Fqzz1?BjI zg9|Ev=CF|~v0#^AA5Tcii{Z08wMy>6ux|l55J2tBd^#?%aNhVr)vZcGyXx)yi?LeE zPWIEa+?2gpg5}=hX|X|NRy-@4c~KX>)h{x%stT$ATXGSb&JUHu=D7uyjOHParXvbM zqHn*jN(mh;ydUbBNPT7EAyt_VR6*pnRZ@2Wr`XHO zSj+umbI@gXx*bZkHv`q#UgQ^Fyb!uC=Y(v2QoP_)D;#_cRAr7QZ-hLz3rC#$++m=2 z%pL+j+}V~(VaVP2Oq7dTS$%HL%H4rb{i(9zB*aktz7Li=lN_#08Ow)EW9Ltd zz3GLmz1y4*)7hCca{nz)R-*wtBsDOuHUD)p(A`uDrgIO+^e`Tbw4T^{p?|afmrl=g z9QCF;7^3k^d&O)&J*nuLRf*9CYfM;=3Ygx(EROr#Ccw~W04()zzY!H?8WoM)%;LRw zk22->{%hQE1_}9A9@G^=0zjlCaJfX^Ho!Fc{VTqpMyK(>Lu>o4I544K(LeZ^_99;r zxZ^-989k?Xp;}T~JTnf_JCr~pq{N?C3gICWl;aLoU%~d9d*Hl5FW;+qqgqr6G}&&< zKu;rpJ|fxc4WN6A>#+UC9B*sPcxuuQ>90vK-*!83WG8zt63OBLp~=D1-(;xX?`@jX zst0IjD3x8eX9&jaeBL?~TzgfObF)D7F%DH~ggcykZPJRlT0XBPD#eX4J_3OI`lH{J zJ8)TE?w0+BuA60r`X6x*^V_3B!H5d;^uiKA4};I;y2WKJI<3BJd%Zm@t1CvsymTcz z`E924`$I+%mP{#26Ey?}lT!r!uA^S@9t~|hQhc*{ZGa3Lu2kqEB=c6e!$;-42NH+?R2Z^Ffi#mf_k*1^_W~HK4sz0 zSDlB-A`hQ_hb?QrnT#rbuY6`YPtn(@R?j&9t*JVThrTJeY`p>3Pmozxgc#MEq^>b_ zRoAQ3zq$QDQ$`X(8>^+B)mtpJjbz7glTAVmB+HNbhZyV3AYuc>b!fD(le;;7slhsk zGFCdhepQ!SsX8+>cKQFLQWf)~(Oam|?J?y=Yw3@sV4FtwmqRZ)I)5~uxYX#$P0n{t z|G0kkS>w^op_dPS{N?{P%X1HXseU3p)4z2KWC}rRC!Ocb`Vpj?jNqY55{R0GiDHN0l}T-2gF5j|lxo zmG;0i1=;@TanqkS9R$|#CD(&%FDU%|rUS-EB*+tF(OWmMN9<*SWf~^u*B3MQ)Y0Y}{kj3$M&8B+uKTpMbho&23kOe|y;# ze|v?jdsgpckUAAR32mv}LmXvs-*m{ntM|F5@B>B8*?v``9$tUo_3)9X?_W9fJRI_z z7QCc=BTOVr$vkxU%j(;&P|k0?ZAiv0kzZ+-#T~}ipg3>0_1}z{2)4M>?g(DFy30Ti zh%j`K$0b;fx*l6sL9EaU5{cw1F&|HnEDWx;m5$@{_Spgz`W)qdRzM3wcPd_Jukb{X*E z>PJ3hlc$Ob!#b25vO6XNJWZIfN?qL8k59l!@VO7~uFyvHt`e9nfoSd;^KF6|^z0f)m^ z!L#4T6wux-;EI2Ee55j8yQJ;~obuWMgykv)?MT#>W!l z!&rv399((t>GSLZ)bLMVX#L3X%PkXA8kaD%@+aO$|B}^wdHyT!>|7H+xXV0b!x{-g zBvcCc-h-Ufs_R1GE!Bw0Dko=+SFqIs+8b)0CR1PV`>$B8>~{G!#1hRaHzEM@wg$8G z(QKoYsIz6p58Y<6)xRtU%v=m2_N|S)`eA@*8v)Ca(G=P}iO3g)hETP!vw;G~O66AC z{Uvo=Y%w&5Jaj-%I5ub^p}r z5N-l&hJLP;0Bh;@dX@i3e9ibNR{~eo$TQ7&Pr!C%7lZeNiVW-Gg<)z`Gw_?UkLKLB zKl}go6VS=y{?VZ`=%@6vhQVla13{OHmx^3#&l=NJf9MsVQ5>qaGVZrD+%t%+w!U}? ze#^Y`ssJHlfdGIB+g&h(2AX_gLj3B)=j1R3> zmAR#(2ITk=bV663^a)*or*Z(nxkq-`Ecl~4GL}P1K<`!rslX6kT9ckMF)Ll&i*5WwpzS{G>>?f3NJqD8G@vh-#JtFoLJ5rhY)q z;2J!nskJND#|sX=VHC5&$dJPgR;yhpTGX@8aW#X_=(Kv`1XDzMQSoU+X`cM@lt?u- z=?Ut?WB>PAK^FAyHYX%tB|eS$hMVw*$e1;&BIa8;W4@2ic8ji8%2ka#!WNq(=|{=G z>a;numok#!zWz7v>kR!j?o&n?rRz+b&Hrz>ALj8%*-abzF9DM4F?4~%xB}!q^n(8i zZvDe6G)?W0<<2AIdgI|#mC)Ic#y6;E>Mff38R27fmr_*7t?p+xH<8~9~-5y>&bM5Ltr;c3`Kx6r; zj!0Mo5A`;_G^=-gDtc6;!3r`=U_&}i>-w8AeP}w@i}XM6FNKT8NTF1*E;Ikp2Y+h9wn4Pl!}Q!xN`tL5oTb z$9dZ$M@<%WWnf8h0TMK0cVU!df%cG;ygd=%co&##=GRzb5}5Bsub=4jpE$5_cv{-+ z2F5JpFz{ zn4Fg_^4HRvMjhoff4zpwp{*u6la6-xHvqALKAu7ClB(~0%fp&o5V{~xgUN3-DT5%b z)g^h5o@Y(?eAiw1O+r+z?coKu=~PzRiMaYeRTum-2_YDQ1mpr}%C6rI@v!!DzJZ&Q zZ8qVety==t+b1pGU$3Xg3#oO3I7Dr=IKEV>Lz(-Qh+dxNt^wnpS5@QyQVTfP#ihN% z8tu(9e`C}`=$@Fl4xhX|V(fGJ_=EI4bx`GwV*Vh{IIn#MYP2&y93G3!$w#9H^WO^l ze&1%u$2-uwGgO<^3S1%a4+UW>gs@tV!TTSFFA+wj+QI>1Jp*4Ixh zj1QZD!nj80-Q&L3!kdWU^1iPEU69s6@NwxW|IDL6@@V-GZt)y}&RZPT)8Mi~iMNvL zJ7UWK8rI3QNs~br+sh zZt8{e8SF?!9o2oOM>KG`CZBp2WwlQ~cQR`tM+qv@)qQghvGx6uLr+^8t-}X<1wJJff+M(B;RXN-TlT0k?Y)i`OGZgM5 z=c}GS?vabh<8H;k%UJwd=KQp-c3@y1%Y3K-<#FEG1XcXzz+fr%$z{*r8^>*^L0a#$ zNXVwgwV47Y{_slifq15j*!rVrYIG@S(lcQSQY~J`<=%~u_lU^j} zcbh8VN7uEDeEeS6g-XXUjFnvq`N$ok_dLI~Iq#K!zl=&W(#h3SrTc*=MQZUn=UOU$ z{q-Jtb$_@v?tH=oC~dDj?|mhixOecD*YV(Q1zn0(0Sf52CkjONN&fkw!qYGt?TN#J z{OBv^)}~rZfE5zV`wXYW*NOPBl4XvRlO%`3E`~nkfMcd_x6aa!jQmH!9NgD&ovVO6aEv2oj=$`&>-A7*K82Y>=IY^&L>MK=aJNwng-qzW+*!R zYF$|HekY~rdV9Qy+-W<56`b#k(Q3!X9P=;0J|S*69+YNJ>&%~ThI9La8IsK;y72>` zfrJ#~VUPxdlt5+(0PXE_;UfQ{Et-f;l#UjXS+vs=ZNvciof;9^VqJyl0A9ZL5A<|a`X&!d`Pog7c1lLt3!e+#Y)V%52 zQr-34_wdT5<|9LgEqOWHE4R>G%SVmoRsoqcP$adaF=2FVO0yY}A<;bPs~rK4-PL-d z{%7c$eof2LUDUCY@?8rrh$&_s=O21M<=;-6qbfd-y50%$P9z0YaD-8-+?l#4?VJ-E3HXe3CQWablgZDMx&N=_ZxAdnu zLtLlTyFVP-P!l@#*|c^)yem z?-cy^B$UvO%+~QYy=hV!f&TT}uzG4U_QWp|QohFp4qzwO>GJ~&DSQNoAO<{15f^%w z^ugX|R{*5VNDN4*s?=4xWe2S6Iop?5JDa0XDRG0un_PNUaD_VFP$!~yK4 zx@tHa-@*s>*+Uq*5zlFUe3aWVq8FQ$<@fE1+zjt2iG8miT1f*>=gmY2UFyGL`uKOz zUgBRM&=uQ{?O+LI!K40ml=YKaImb74yB!S^M6TO~*ByC3N{A8F_5+F=bmXMx$x1{6 z19HmYM8ag`9-^3y=9q*Of70&ck5ko>38oWL9tK~9xL+QKPCXop<=@IY4(O-3JI;`~ zW@^~!N&AFO@qDqu$2adxh1X}#@OCIN?R#c%nggrZ5!hbCKd?V z^n{O4TwT}Bm8$}2D4;|i$_}#izyAJtDTu_$g8{H836K{mJq7`gS-}CoX8xnVQl9oa zK{e24%TL}R{JQM)d+mImvE;DG+G}+?-$P5fAYz1O*!X(YB_LzUlPHu0~L8>w#cvKcOWlw8pMSEAJHO z1b9Gk)6ndy@pJ@Heb}CdK47-z``wE3yk9o#^j6MIg{pENDNE~5035X+oNy1(qC;}O zx1d(c(!(DUjwW|KlH<9kfo}QDS<|>_;H;c}pW?KBhG@mfLpN_0UTV{nZr&3<3WDS% zIhAdNijIBGf4}<34U|jbs-*ft1Beym5K`00lXH z*)H_O(BWn-mp#tJDS(az4)Tsv9q4%LF$y~@bLXj!3PATUD%E?X_|B4Xp5-U=S!GX$ zOdl&g%tF`JUBvNdekp(hON~xmGVu<&{rP^HdS(^70yk4!|Lp@Kf=MwVANtL=}QL}SMWz+L+$zVDn%F6n(iiZMRrLWL6 zQ*1Cz9AE2i(gJjt*-+QRO|poO7REoEtm}3Gn3ES{@}4?8lr$PX!jDe(NR)Dj0Jo4U zo1X!@O%H9^HF$UAz!~7_4D|AYnp>~@^<9sR-s9Er$X<~l&<4pk{=I3s3E_{xHK*Sh z9ZayPYPlmZyU$$zBmn>HESSymJ@)zmbb)hk>&Crv-wg(*-`&wrnICz`{I&n=sj=<9 z-icZ*4~Q!?3>6Vy$i(tYCGL%LfG<8LXpnQeXu~5;4k5hBx6IEy%H6ax0DQ*_2%^gE z&@)GW`#pE(NmjBqkVg9Fq%Erkv#~mGGq+IT@Y_%XUwBVJD)joq@VVUz-F}fBEWbI^ zcd?3lV~dPB5LrtheEtBZfm9eQ@_TYoLUc!4B3p7w%nZ$YHA&WjtAhz52uWI%=Av_( z0?Ky0t6U`#z@(GS_D|Y^xnmMAN7#7XNP)0k$Iz^RX^F zViPA3E9)Y9t}Y>V1{*-+GWCQE2TpVGcljw$Q#)UX4EbWVE`KhA>%yur=r^)4Ytdq<3?n7|Pl9lw6}($Uz~~=;@1L zWf7f+j~^2|GKGi}^o4u-EU`Wan+WV*7m-d4ytdLZBvpRko>YvKmv7M=*A`*UwjHbB z*+$Y1a3eD)N>;XQ$Hn|GS%d&2J>-Pr6P%x!T%TeXeUyS1Q@G}Kj$C>VXLd^#BG_G3b}XmY zd8e>~Vm9i(`um-#+sLCaGt~EPS@qm=agnn4==TRWq`igZ$Xh`|!)Cl|eScw6I!c#6 zCoJDdz5UBl1~DbC!mHvM2Hp}mBgMXO>xp>KkTX$0xYt`Xuh)3p^{&jJ=MI4PxIjoN zR+zW)sAK)!kj9UibuMXi9Z5*Pwn?BO2R+3BgEpT+S*5t znkOD`_}e=s4sW}4 z(~s_w`T`0>?SDdVz9;Ooi#0L&xYAUIiD$9$i}`*tFavsU_lq~op9qKBwT3HGM3H?~ zC#>x6>55&rY-4zQY1Cw-T6PPGAI@OEyewgVkofIWjCn-+TuD%OCWicsV=m?TeRzIy zY^*75x8B!!=t~B+5xvV#3ZqC)$dRE4QimC>+>m;A{%?h9q{0?{}&4M@bjHM`@%09_3BMURNA7Urk>u%2R$-laC7LhnOJ=lg@~|=wTel#2*tSTIFx1 zFn<8a&(1bjge+VoBtYIODs9X@3a-&8OjTm=lhp^)A!JT)4vLFLc=T}$!1ZpcfolOy>5OyE$Iy7to#YNTqI1#WkH8+#Mv#N zdi}ob48CPb`{&yt9)%3C3%tss!Ve^tCT&@scgU)UnP8~{6}X>RE+2u>s!TR#-)7fR zzcu)((O6Ua`|D(zyfajMLapp$C_hE6l3e^h9B`iu#i7R)PhM%2eO~{zWi|%-wR*XF zpZy)4ZFyopcwRpolNjjM7I)Ag?L+O;({)jZu~h*_J2y}Q;l*u5xnLsYKP^f#iD)AiQ7Cne&|1b$XX|af_8LBg{)fCGyLtn0BCVw%ePH?&^HTJg=+ns>A?i zslS0XqZVNu7;}hQc*Ef5=<3_y#H&{#ZV?^Z-_Cfp!`_srex~0%u;$$p^sX9gEdrqP z!l+jG4%R5YvPbYzKsfBspi!|(&`_wYTmL!n$nf@R#w9rY%FMf$x_>1+j{*C5p)iPi zY%r0Zx%xT@z!9}XTh0eAxauW-Ys@6PKV;9KzlWS9-itk8!m&>Q6mxgsV-+p)z6lQN zyYwtfe)Z?gVrz59$V3#GaVFh9$(##rkNU&$7fX>Oy{2BXr>Y``kB~VKTjo8C?`nuB zbzTA&h{z#ze#I}IUkIYd4t@;u7j*1#8}HkH{T)u9-($BVwm<6r z3R(;^vg`5f$JieZHa3n&k6d*!Zxp8z6B%a6tNs>n=e0o6P1}{-+oXkMQB~VA_OfEI zy!EB)Ar;oI6pp{B+V3M9}jT6GX2@QrbCfPm5&a$D9Cl*RgmdNU>c zGDWJBHU^XlbaeM*M*0WI7F;UiM?R;Q=9fc8VWHHR(bN->@?H5s|5X~`0&ExPE#L$A z|1SWGW6S?o2h)nwK-kIAq4}XQnfP1= zuo%D%05brDiWm)&ubU^q3Sql|uW0U>mgn)#H1eQc2Ge~r8%A$H24OZP{a4LFWk8rd zp77aTeWh!tLgiE@Nf`)5_WopK&E|(4|T0RfM1X2zlm z3%iW>zSyh)m|;q^_$~-2DO?Jv>1|D=!4?R0(ZMy|E0gkMJ01{{6u&en=9;xv#3dZk&CDE+5sPwHCj@_{|Z;~;Tb4D4Xzfv z4(_f;90!AtSrP1yxWV#C-pGCEr~GfiO0HE|dZ`VemBKJP&!m&+H0*-Nbu7}^J^^;v z-^!o?6ZpIukEz@Pq^o&&g#_~V&Y$EhfW5lAN0m|sd;$Tzis18;LlRWd%|6FCg;}g5Rqo^(nv#^x zHtxvMVn=#9->bQ3{Se!C*!pA*sf%|{Ap}eyUJ#$?>EZj7y#cp>>}V#!oYCx}SF@@j za-1s?&~Z}o)2eoy7g1i4j9o>hf&yj*)*V}ZMUdb#X>zYa#FC1v%O>9nzs%P8G;N=5 zx_|A|y^ui=;cf!yNTs0?;D%_ zIwsWiJY{=ANW#xEKR|DeC+40h+qiT?2gg1j%hnfMm*6$pmkCr0rW|c+}#v)q$5y$+Q6p_m{1r2B_s--Kcy&KAV@q|bz4{A_XO`$uWL$^O^X zb02qZ(R=h3T~HV0ELg>Nmg?Cjzkc#XM>rF>b42n#5P;gWsNz~e(4}0ti9OM)hN=8Wj~PY#=kbkxCHS633KYtIL~O26KiRIJa?QY65{@7ap~^UfTv|zZRlhJe|)3((~CGB zDT?`p;B&CBsJ}{3>J}lnfs=Jo6kHEB;abr-==F zP8t4wxmobvW-8u*UIIkG>p!mNe^?9Lbo4|1o%8=3gWvyaBGifjp)$iTWBaT7xh6d_ zOaV&c&QyTHLXwfSgMdE+0KjkL0XUNszE(`DLwSImU$BC21UN82q#uHntePiSCPUGU za`Ondh#ArG^Bmjd$(5Z5q*JDYGVun$b%B?)1_`%7+U9AQMR=1UDwcPvwylDgcj5^D zY)PfFS%P<;A?EkxnWRnsH# zKTm<6UOSR#P z#gQqbH;vQ4$4&A>slzA4V->ujRUAlFRvW(;Dl^z*2JAGgNrI%74vbRLh2@qRX=+-* zzH$3)w*2BiK%R9L4Gprs#K1x@=7uqnBRM*;6O<^&>s!w=$w1Fk3V`+9Wdf~G@B&b> zOfh9M6Qz0M-+fX9FsQZ8$z8}sv+M%Ey178i15PS9>p0X4X2H-PlG;?jxG-=Jx{55L zn5PB;dEVl46;8i-p2kebRsLV3y@g+sf7}0mZVcGSF-A&kW3(tGsEBSzjcy60yD<3jv~0?7f$|s#_}Z_l{2B0hje! zm92%3NyQ@0KlGnNEXdg}dy>{iIQ^RHO~Kq{gt;yn;e2YiHK1imweHC`Xg~fnaU$z7 zVlPqZve)(HOP6dS-^mlG&=FUdr`-o_UE`J7m`hoc>?3J<4$IX46Vt<-+akXcPq!Zj zj1haLUHq>`ic?B-P%Ci9L9rI$4u)y1;Iwb^0hI4kB1*Z`Qq2UDqqfHR-}2=TaH!ho z;Z@l!*7r1R{K+1j;Xe>ybJN3-PyP<7!k>ajVOIK7exyCZYLx!lgo;rByW`I@-W5h) zrtDe8KPMSA-ee6!woVjtnS8qRg3Bi_D)!;<&8bD$Ti*vdl5g7vOcE%{m!%b>0(6Bo zn6{Ho2M6c<-qv10sYGE7Pftr&Odhu&a(i^c%~v$TG2eci{|4BGD6nN^8>wD&3m-9x z60&mT1UIDUI$mC^Lq^z&!k>B)ABfbyx&=fwFXkHD-EE~84XI2Cyjl z-%ty^@HLjsPXh=G>3s*q!a0$B$t-VsTPOcd0gR3!4@&y=zWAMry19s1Z|M&Cx4!2B z=rwgZx&Fs=f(G+6KKv_}pqF*j^tJDfWLHMH}a$wBB;}e z9XoAwx@0JlGD8RvFVU^ab5tO>tsBKu1C-5aqnR(Rz#R&UdfPeQ*g=SuKgq(iYElm% zBxr$101hl(t!LyVMhg(7w!lQNZ6i7x3x!{$1w#xzD0uLbX>p$&2U{3vk4c4Gcz}xZ z+D=7q+s)R}6p`oMiNzhk&LHUK38(=gR#VdF`udL*_W_pQ>m2-mfm^$qB&+9@v>SLU z=Sd09J_940zT!|&=G)=i?QFAV_-WTCQWfiT!UQu279gTJz#xjDqviNad3D%r&i(V1 zDi4YQ5X0MdN+{dCWURaC)9N3Q9l{~pD!W)A0UI2^t`mT3S=P7RP3g%~H%rF9a){UlAzq zHp^VZk2fJ))wX~zYFPP`7C`9PL9Q0u^a`S8azu*kWZ7;@GSnuKmZ%C?Nt?K-UV6rp zMzyezq8`6&Q{+FFK)YR9#>Ml|*#g#g=mzXT780;Aj#i@yoYAFRJU?9nyzm3O>*Kij zrl75ey{V7GzCY-;2gRP9ucFO-F;%gNXZoFt18BHXx}SCvzu}i${Sj#7w%qw2vAptpAIHlvFE3vzu&eZpNFjplh zk1)%>t8H(2qt%bq|9M&^3#K}YR6G~;BRav^DF_{Np ztA+Y@`-pMvJkP-z10N$s!;_57@fcI`ONLJ`%mfM=A{}npC0cos-fmQJs6{G^%-d6c zrE21b6A9bt_Wc_eUa>AEpP2;HE19X?$ZtDpT;jgT_X;i{AR)z7a(QtFB${cJ7>MK3 zAJ+i9jtZT9o{0W8T;}r1#i?sevbu0bxf!Q#3QsRp;SG6=<`!-jY-onw;mVx+g?I^H z8-45q=`^r_qh#tWwjFs?W}1))T#VSD9uFdZmhRJe3MfwdtNn@09RJSaOgMUrm}#Ow z8-8ou+0j$TET4>y-r(~w#!oQgpUOiog#j-u*`6ExEd3^rwuC@F9+^QJv=pF|J47jv_!8@)VVj7KuAI74K~U9Hmb0sQ;w{*nlutzi+mhXw}^6I z3>EQ3GlErT`&2Gsqay!>hjmQ+FFfqCOs;?6VG$U=U&a5MTty>NK`|B+Owg%>$O(h~ zb}>+siUm*yb(-P-W12xI%sMCol1eyLymP_T$G$U$Rmy!%b2P2ZYzr6kOSm?*1F}oj zOj1d}zDlRtn#KrI(+}XR5A`ym(pE3W0c;Wno5&vosFXv^Fm@`i(kLD;Oz6Q1X9E`3@dNxHHUmz6sf0_CDcN+J zio}-HL7JHa`3_SUz1L!6y3C@vQ+g<^;2bZ`F__M&m|NxB{M$^NqlsFY3XiG$(9H}G zpozdqN01B}g+(K9b|trxr6}Q4a!dQK24+;JL9+njH>gg{UfNG2H1s{Jn20op7c0Dk z5s{mBTHB(hx{rV;JHvMArV|g*?&?}m!k_mO-Hi+;Ew7k?ZD%ggsH<|inWI%dThg|NRG=cnxUggv~5mf46 z0bsXBNDMpXA8`Q*=hjqtgg==WmkMJsc%7yjB3U#tXNa8V)B5aGy*^WrZpHWGU5jw! z3`@3L`g)#p9PsPqayjXYlc(`%jG8AEQf54$3}S#Rh(I$Ul2gz@JUC+?o+=)rXtIXE zIfB?Xcq82bJ1y{d>TcAmIm1~T z*R2sFDX5hk^XYn58LtUSuVaSG@LY(e`H29`Og*8`;1REUm|f&kB6&}zzP}G8 zG)}k?t5ug@3vu8$^Po`%g42f{d>fRHfjY4R&%8t)*Wx+cJQnGHDvugpZ(ibgHV08D zFqV4v$~GF>@@iMzfxd&d3JTv%Lpl=22X?GH*`myFXYV@~4#vD*$5FV`D>vkZTs^^e zY1uS^Rd~Ya0J!3=hkE&?AF<;`7YH8=NkrHhU;+#EN14R{gp0;y6Qd6o)*ZI}r?XILkF`ji_7lob>Gv%@u7 zv6vaI-<%0(3bCy~`8Zsl>~Osu!8vGevVfC(W1Y+0GjrvyRb?W?j ztO-E~w&S?SS8{1W@PZq*f;}ovyP3b8)xdwa47u6YV^WzEa2I;cnT9Zva}xHp3X2x5 z$LZGSp1l1Xi%;n!Fwx~l70N>ynoQ+bsqaitZDFqzQ2y_JBg}C}pOlSCne_`I>iLZD zk}Es>pA~)T9Mb_cP!o&z|CnR{hBiFaxJN9cewF<*v52CuME=tJ%PDhareSh8t>-V= zb)XSA1VZQ={UZ>gUZjT6318k>9n7N&#Q3?#IV+@$e6^-jN`>(N4nYepy;1S*iL%W_ zj;w{!(R>)VSQo$&YH_%P_cYqg-mh$EtO$5XCu){k-G`$M8e1GApo2h$c91*5(0cYyu7$iJ8CMBR)tn5`C1a4jGZ41i9V^~8|l zuj*cqRcmwR7$>`&=JsyE-F-+$CuaC`X-cS>4i)-cWEHecqJV#7`+Y%$02#x>$5m}@ zMw>~`4z8hBb$u#?L|Db3AyQkkSi^Aa%K%HU}AwT&MpennMQ3-xY}v$Vv}(9 z%C>|-;`MAR`hbvL1BZh-dMqs*cyoO*R>ljAL)0-lCh8)v`y&ZT63aQ>At-o(K`|5k za+1J26ekIGBhPapcf^DfJ56BM5D&LLS|owEc`zhfg*P$bFtX8GPUBMXXbh$CL5FTD z8yx_y-fThPts^VS@Yz^k!2vzgypnRwf4WpzsUAZlUgzw0D7d3OFlv1*`o}fIt;m}$ z0XfHD3>=Cg0)<8@66+Oo(}n0LUD=*xYha2(T62T^#zf#8r@k>(DBX`1tqdZ|Ec-4vI+qK_-^6O)Fr3KKOiVaeuA;=i*l{VRCrhNM+((j zK0qeBBLO*&-6;yxdoJzo{D>AXWRqm7Rn~&o`>A{{#6Qv_^q9YX08xnHSO!?drkwjm@Sp_rfW>z#@3Sv(NM340?0Vvbsu`@qMjDuA??v7#u7=_HJW&_^WTT)ry_qWNXf?|!@Xqv z>Vt0w7w9$aT^uFRwNd-K_{N{tB8*#~97j;*vJ4PbuCGeXzdgnRX!y#)+uhyU1^%0~ zXdi|c$RUEG9E3+aI7-E-r?jxiz}3-iLwLAvl`kwpO;95K$(yux>U1*oV2gT87T*fCs<$*1@MXJK1d-X{H|w|?cpnt!liUSwhejG6kYYU zNo5_LO{w*I|2(&S;`frR*sY!Md0wt|73Npgt{28rKBd(N`$zL}9!&8p_qCt-k`z0j z8NP{w-W=_EErg(BoTuNW$L`*PkLtwQMm3Dnl zXeDc$(ZJIuAF}g$jJ7bVXjyfv_Ng?xZrI;w!|Pe!|Ds+08`^Mk{dHg^6(sT(+R%-P zHvI1siysB>cxqzt|K57|JQDOm9`$c;VjWNsb^7N1&(rsBp25EA zR{Y#pMq7dUC8&qTgE+7-xSJ!?6-T52CEN2oy&Z?#N}}{@O?!CUCIPgC@2&RSY~Kju zw~pIhynKeJ_vQ_{-GIB3t@)7)1@fisGiw}E%(%zIi&e9<`hmoG?CG3c6zS;D;J*@j zmQGcYigLuLRJ*3)lsIL(b!}$sUYVLfAprHzGQo8j=O&Y8<^;`DB>2wI(m+EYb@n5d zoS03PSMkzsgYr(fHUe`T!}MgtMjSW(WdoAE#Xb zKfgmplVU79q+FJSFVDDh@qD_n75^I+p2023yN_XXzl|{97p@#1YZ@wJsP}xD2I6>1 z3N!>sEkK_YX@kde;to> z`YBA>-J}gsqHquRzErbog{AJZG!ptI$IpL$W_$gyU(pWf0;gFpVo=t?=zT*&c&c-R zOPi^%UCod~s`*;h$E?-COLIV1k&{(H)^(uYOi6b9+;0+RiKmFTK?In3r;PC9g>3dZ z*5x=1UDa;defPUlYSds?6A>jll0*?E_7gt3WzYL@(Qdi~3tTIbrIKXGxB~F@R&a#% zwE&aBdvt(PTB~QG)9RokBRUca*l3R5Q z#8i@TH%h@ObJUyIK+M<>F0E zQ`mxj%0tfQeBn&$K2S78eznaDzzX6*sl5s53+?w##4Zs{Oa1 z@$LpDh-!J4`EDORK`2d9BsVON)54w+;B<7=#C(`fLDpqVd&jG~39)u+ianazjtV## zb1i?0;oZ+9yD!uajJs()IBrOoeemjuv0V>XU%XQ_j2Qw#;%ooSIoA z1DBH;KyfI%F6o;6D469dUB7F(9)$a(mtUij8*@za(4!Q~%g=#1y)GG_u? zovdq&`)@kGND$Snz)qx3Qe6Y*5JO&6u3gUZPxp6T{J%_JSGCU-|8wUo4|?x^ziX`6RjN(%Z{`;rP#(|*6#O-f{~Ljo!1Mo_ z#@l%zHq6S`|GM6Z-_`pg(-kJ%A-k0-8d?K#X8W zhltH}8b0FWi(f?RW$~OD9Z9ZPEUCDqUDABUw)%y^Zr!Krc z-opE4P7~Pg83FFhE19_C-}IbW^g|^ zkUG)>e?S0oR46BoFhwd10R#P*JME1aQ!tb>m59uqdLW>ay}g=g0#+Rx2yV9(Um?=W zEMqKSo=bLN5YT>NGUwrUR>fp!csD0l^VTXAfb;Z`)V-vorBM1YaRVosr12|Codk{# ziT?F1(cTx@9`gG*m!2bzrF+J^?b8@QkKyw>nGDInM88*kY`E-iNT21Po4$wAulo zZC2}`557}ehI-{xjMOTrRPurQnpPmRUkQFiUQ>w9E z2oKGI)*E`oc`GfWG0`(b3KpT+3O2+NYiJBpN*_7|-Lvr3b?VtRqaF+P$$#ddz;4wh zF+dvT!n{;C-$A2I5^j?krD%bx+$#z%37eWNS5F*9K43^$Ehbyn z%y2#d!3EdW#T^r|RP_1C9pfJra+&OvEL<;)XitNRb449l&y}3y4S%Sjbr-3o)rfJR#!3bKXwE}}yf-YwC%5zSUo~sPSo98~xDhb+0DPcY9kjcTh&eDgGxVUAdZNiD`>^co5$5q2iu+>Oo+Xg1*tG|8_2e8JOzW5TgVvz3D3RuRZ=UZj}3|%FsM85g% z$yZ%Zv)+V|axwx1&;R)r-rdRkLdATq5k`XkHH{PgV;cYa_0In?jmy>lrv|W5B3)65 z^p+--{9qhyP+EFc3aWVH|CIbNiCI&1!~OliOuhfX0-69C?D{VSuED~SFepqw=YLY* z{*iOZ3h{tod}LnD%D+tv|4`rtHNNvr1|FUNFWsp(^1l>F2t(g{|jp3m? z&0pVl1T(Vg-EG-f>PwW=AHMta`^V8d?L@tM&$fbdMXfne!ghmOhz3RqlJx}o;5%$A zTYuz!+fmr(#pZO%Bip-2-*?{mWaUwgcYcHRZ32IAl;?#Wqs8*WAOfFk!&pyo+dY7r zi4{a3t;_8q`QAUYQ_~^T!rV(!UH?+x7OF|2A@47*RR7a=?#_NobUaq^F9q(SPm7WG zzZAGN+{>!kBI_&32I}Wbl8wx$zVk~)79`^f_J0((F;sG#j)hrRNwh$q-#MGRe}33ma4!_dKlEbT9jfovz(!(=1x`M zI?w#Az`gj)e~$U*n+Pr4pOYfr!sXvyy}i}cKocyr8*i5ArO*4*`X zx!8ICHRa@)pgqdg-iN42=KTeYMcuQLk#gO8i*ZG%0eD|Umi=YYl`nOx85@lOA9HSh zdFpmCc(`IA#^}`fzEbwagY`tx{i4|ekw%}D$BAuTpPSYKN59;z@n-w-RCImh^zq5c zlCPad{Yok|YfR_xc}<@%EgRh1o!zXN8|7N@P5##7x{O=;c?r!6Da9vfwaL3Zu?P=ats1D@>l{_U0okD?`#lrVZHO{(?Bk<}K0V1Tiw-^+ zb#yGI{N?#3n!Z8}@fr%jQ9}pKDKMKhjZ&j7B#Qr}O`0Q@S`-$z0Bd-~$4JsNR9{K3 zIN7IVd!S)pgiW}|*JoC&E|>D@n~)t6eoAzlI=&qb#_wdVqf|I(kAAq5J?Y4k4w&VJjkX_5E@j-@~9X_Ifem5yC&enbkj3P5}?rM%7@F3Nj{MvMQFST)wI0YJ+;-f4;xDV0yITGJ2h) zVMtDi^!$p>wkW}o!Me6^dF~Ks7f&c0a3ibSyRrnkDEC%78B@VOUGP!s1Pt5xn-xRJ zb~QT&2@LusGG(_EqRX^Kaexq&zTd&~z<^=XB--E6cfhRUKv`)0bE4z zsuTaBX8Fy_&7>5Ja0;5?D?{2=-(Z}M4gnbw0zmbwD zV52CRqh;sA^bR`S?uO&mKFax{>2a_@@K+isH!70XCyTS9!b!j#4YiD-x(!s=a&dtCis`A*#Xp&&boR+j1OJsr-z1M{UXUI< zkRNVq>0i@+9V7t0Tg`pc+F2t8w2aiIstAd0Dr7mvo&C!i3Z>XrGB4iH3|;E8eE-O$ zc)?9RvHx`+?DiB*8G2ap#Z=FS@YK5!E~36FeObGm>u{Uvoh*Z(BnaVTx<*{87h ztz8_8=>x}1 zaahMIk%&;j6#WW4=Bvl%4iCTw7uVvyuM+S+h-7QUu=&7~;?Y$Yg@cChT@c?F9}&7! zs%bt%KJUKw&%JnAl9$ZU(~&E`Gk@1crwmo(bh4@z~J@m#BpDim@kSX-nQAiOn8T z6AUh@EMG?9k*^HC$b~e40iLNan2g_Rd0pqakP!z~G92=Cm4!rvkehMfK9p;7kP1{d zPS~JT*jlsY`ssc49JukUFONW8x%a&pW1e7(jFg!U0lDx;hXM5k> z&u;R~ZHX3P6`8yEzQ~VBK0f6UCO=N^*3!B-hF4O{t)WCFsT+3h($OYYLOCx-`3Qj? zmPgQxS)F)R`)Pk6tMc-wKF`FUEFRs4>*2+)s$f4(e2n~7-$Ldu)rS75g0 z1oo?7)3%6|Ynd^w;}No5NYexMTGbH6F^tdKH0iOMHwfvOAb&vCYwQX-*dl^P1wKng z(L&hYkcc4%2#T!r_2^6|IGO->oT_AWM{ z4^`NlRuRZ?HIpqHXW&v8dG}mgU@E`+D&l2ewwtCi$5>WBJT1sc-Y`tRH}E=t(t{8n zm2Jl(+9+|1hZnoTKHiZOVTL7B`UNZ-b4ABFnElym-6TE+rqk3h&!W7(^u@JLKjN3W z`EC4$aDlbAZB86fuY+*x9JGTA?Q ziiQa&^25{T)A{M^bT7up>D9r=YkGW;sI1HEI|0SA?$;GU^JS9Gu8Nm@{P_@Ta*te5 zaHFI|#9k%EP0*>b$ll#~+*bvAQ$y4e>629|-o@Nut0QcA>Us<&)2{%fmKTpG35-F8 zj;c0C1YKn-XZ+4_cOb)!@}S(e3mH2j7!t!~79(@I(<~u|qsO?6pVnjHJ2pA1;#@%* zIK=&(+l4}R-cJf~8i=wAOJ4M6xV2;96A96YUKU$6L3<|-^;`C3hE*-+;2!QbnoQ&7 zppX5pUyPP!Ik;YiUX-`EBG<<&G7B(e!>gi9*i$Xxv6+RB&sQ7OGl%5Eq#;FlLF@$# zHMnt}oSCW*EhZ)s?8B8cDs{|3u2`3)${&^-D*)6OE*-RlgEinO>uEQs$E2S-QjV-T~q9(k~kT1t5+(YHtYzX%?G?*IIsVv<3^JLPeAEJ?b_!$XKl8V3U$+;#oUi7 z;W3)8pji9{!exehsxIYLtH<5hlbQ~>iU=}yCpmPm{>8_ND8%(>Mt0v5hN5T?^KE(F zpDi+Wl_px}95#wG?qH6$r3FajydzN!N%$&ox%>eC$n2S*68;}NRb5PHA+92s=6Ut2ioNT@-Qz2~SUM%sTawsKXH z?Yp+CYE_Gxj7K+TgWFWQE^p?Br8UpnR_IB=E4^Xy;<-CBDnE}p)Idz6ZBMcq(yUT} za#LsgeCH{{de*p%KE*s_4x1NT4hKl;7PmDL!F<%6oPw*QeWzF-R5ZaOtoIuXK-EwMIV`aKF)G;-|#|(k4iB zftlDBZnl5sy;%A4VOlCO!}0}!NoexnJ**$RwaV?BU02>6*6F3z195imcxaW1bc$VM|oW`#@%N%$hUyGg}o_t5q zTc@+gGp8&TzC~2U1men@t$cn7K<0F5#xOWvD-{p@$8}d+9!r3jYF60d%a8I)-xPg&^(@!VnP6Zo+g~UtkI?e%$D}7`L@K8ZS))f~cQOVh zbR_O>mai?hu)RLP&-6t9@U=Z-T27_-FCF$=?V)t0A=py&!a$C5losEXsQ6~l*c^)` zrMF_$@bzWb>Ep-OG2u`J-9h$Tk@qzonInmb9uHJgL8^T^cYt@ zhvB?s-v|l7BMZVMUkoS72(*cRGGireH-PhpT`&ds-$U_P7)y^wTg2xIzgs1Y#%a0r ze$0h+MstR4=k^#kPX%3c?QvVFQaUilfs!9&fTT-&S(lrW>FmnCj=c$!9Z$b~arjlR zn-nnjTA*)}NAjrr2f0uv@YGg5^DRq9kC<@U*}7%N>BO*UeR3tZHf04a*VDj%V-s28 zdnRP9DwDkl)oZen&)hdUefF*=jSOwQQ#ZfRnAsIZn#KGmR9@V*%lzO1rLCuDDP!|k z{OqmE=WYDvh02*8N_4a{`)^1J1>76QJ1Tk*7?P#oSyDj7#zO+ByRmxpGjKex05yCC0Yw8})S}@`ECmm% zi=h@h@EC*7E6C4^k2GuhU?l_avwL%0L$5WjpYlBQzIk&UVW<;2u5k?`)01MvQ?QYz zpd;~9yUhBXR7%zU z+kJ7MTLM0}W&*L(CaaoAvTfIgcOSloTj^~>PXio#@Hq`STzEMYS?V`RX8WY^Q(X#i|9I70hRgK+`-#+Ti`}L9VYv98#^3u`pS8N9B(O6<5A9{CEU(8JK(KO|QT;9Opyie`+R>$H8 zF`cWOtHHvr^NwG6un93AZzg`n-`f)?mf6u4lDTdo_)usgm;#`23%D>^W&tb|SiBSt zo;l+Fkh#2r@LfRHXvqY*aH)h}^2) zBjtO?5MGl{28C)5X5NU8rS%l6=U$B9HT`T-XT#;>wq+&u$egd2X=RbUgR}eN4+|?)$bgf>}^K$K2PZC!YUOcBoE9c*>Rb+Y>(qIDa%41kZZ{gf5(w;O(-eI0 zt4$R|rcr^_4li)5-Iv_y;U)@w;T$+@luZ(cFNFr#CVP$N$y=&i=I8w;GK! zrAmGn>B_Ali%O_^B(wsv)_?%i4@_0#<|f}LGHVc$JZ-_6HJNXD)ZK(uoQ_R3v+??U z=AHCI<{v0lSm8;L^bl-v;d3p1sAWcBiNB@CjY`g0kCI8Um3Q*c?yT>t`LwG(L#w++ zzJxR6YyKakT;~JWlCR8N|EkPobLac&m20=xBDki5X<1rCe}|wxaYbrIms{Aj@%7=O zg-WMJVrVm_?Biu#oOMW0^d}YsV}G`+B_s-1$SbGAe8!D_7A zed)DF9=n+?1^4(f*U~J^4qQu;oq1i$f+K@mbIWQzQJiCs@s(Dg&OuEzHLWves&yek z%N{jd>K>k}udO+R$?LOwYGLH$blZ@xWTmg3KfND+X`{SI^Qi_2UfAw@#Gm2Y&g}Bs zSDMlLuHP$Rjak3N_s0x3%I{b3U8s7$Q!C1{x>Y|LZrrOu*l3(AH2M10?YMr4!Yvv;f%s6rStuGg=X3Kx z#oUp*9MKRTf!01qu@pcgeXZzmXg|`Xop)$U5QE!GLYEed^EtZm=6nLIi(=>ECQ_n^ zqqg9ve7d2or`k`6qEDAUSn_gn^F)^122U>%xQi~)n4OOJVH9`FvWzd9BHou{nz793 zOBJ{{7IUTBp0nu_n+RP=tW^#>0_~FaukH>tcEJI9zy!$ZU$ILq3V(-={hzKj>b3hn zU2Xro5>5PfC&It6vHuaf{LRMxuh>Q6+5nYnQD#u|ckJ?)0K4kllRs>1Z8BBj>N-(* z?JqX=A18u#bIm+e;`;dy8~ei_CjwP~UAy=)ie1wB^Mgq{x}i#zAn6sr3mW3cz*Ex(?pfc$cwh4z3t_}JpJ|;zmN96Z+sYO zZ>LZII6tCp_fYHQS&2D#xvfP0n(dvRPZXS-VWH|## zc@dOaCRmK!6`nKTwprIp>fCHexacwcXxDR5Se%yATu-_Ka41e9VZkB*jm&h6a{I4| z(@#Ho?t<$tls`gvu^wh{GI%2?Lzj znm{SC_?Lq|SSoq;bZ=@?y|;>`$Woc?0I*a)$S_kRTO>s?ETWR$EM&6em7E#lv(HM7 zicCmLh9F_T9pnH$5B`mJ2G)0ZCQxKjM;Vy^aXzpIT^PCK6P&So8VVv5AqzgAhl9bM z6uiH!k)l`WfE6mEX-bB{1VtnV^!qeG7h}K9gk5?Y5F>VEZcy&tdN1G^(0$?54EgHs z+pFP8_RHxKr1~deQS=uZJ_p#mKKZs>sZq>kc<>Z{<*1zYY<7uYz9y;i4Gi)4#0hx2W^rp%&NDUO;M zx_vPL(vG9bNKiNqn$J&hrEgJ{zkp%s4d8lgzNE0%=0+`w#Y}Z0Q-oDmEM-og+CcCi zmfGl^j-hrLAVA-u*ag#_xKJ5;gus3g_Tzw#=U^&U?~T|<|43rMuUM%TWcx+Tbrpos zI42fzaZgz`=}r=H3}H|zht^Zwk+THmc2phtu|64CCXlGbd8joBWi{K4>q~-yAojdo zMI4WeVBC{|>y}&l6C+nMh^*fd?m*pMDFEmYONsdOi0PTOtTzl_Wr{h5Ugj<#->?wQ z?j($^46c4TGb9y0dRbkm@Q7MJ^-5Xxa%K{}R!kVa14F?)=GetedMT}D^*a%#gdSc1 zT`meDC8PM=BOp$u1iCYEX8l0;N%|SC2Lg?#n_X*{-G3$$XjOP{MdjDv_6nyhZld2D z72&|#eSZ8WV>;n()(qIXWRYV3AreV))|HqsaI^Sx{ihYC`sh5VEj%D+UK6%BkvFr- zCEVt!V&q!qC(|u3>zZdgANJgl6c$WJumLAnnnGB@OLpceEq*wj-6V{n3X?6W`6|s` z?&}d?V(u1F;UZ~oZ$*+n&9t8+_q20HdM;xm&oXCcDED(jzH>O~K$5U{ZQfMx@Y2(D zymERtXtyDsx!P4jduBXqx3OHe+WpGl%-d(XO||jWo-W$6Gn5&!Oir8BRZP`v>k7HK zgSp1{q4wMo?_NuvZq4=d!MTs;_nwZ%*W4`Ap8ssQ_iSpY#=m)R{!7qa>jLwWfLGe@ zzh&(`|D@}4L%7@Or$9;Dm-r`l*J7tXjPJeJA9`|sZ_pR5kxH;wnGw@;{7I?3(1W74mRet0G%rA)^u zGpA+1e7HWX`St3lI|qZdEDag2bUw;vAG~(eYsh-{`lCYYf$xxSLPO4)&f59egW-VT zhDUp^*Df9%jD)Z>=F{tbQaN!r8l~4*$TjpyUFmR)n9x`(s=KabbvT|e+*qnOw61sO za3Y_jsa!+%vr%?X7otTr{kN*KaNgl$ZNeFYW66z!@u0z)N8hSFw%%WB5dPP(Fm(yv z1Bk#45YK-t;XiP^|7Hm@{JKRf>ixGREPTjbD_cS>&^r7PRFu3*0DHgvQ`H#B!wJot zm>Pa-@IdOpKbA1DU7afH#SLWm)7@fu^K6G&)v$dzlLF3vJPjd`J!K^pZ1BzYf0po` zy<`Ib2SByWCyA9_n|{^W)Fu3EmkekUZ`V2WLWi~7ZvEI=q%Pqj9WX$!fM}97w_=+; ztAfi7Z%@9aE@7hN7T!Ati25`R#?TPIjaYwv^MtyD-*1279KTC#?)Nq~TEHmxe;?1M zwfx-Zv?83%<}$$8cJc;O(k`@JnEO06QI+nY&FIj0_a``ub#vDmbeAVthGO-s5yOAc|nNRu(S~dIf!HoXZRJonWXQD#QZ~gNFdb6NsQ4VLQY= z0X-k_#*2FUAcK}B#sg=|-zDsW79B#Vd`5JfJoWZLqgad%hy`P%4ZN`GFle;M%(p}f z&4n^y_b}btE9tgIST$2x<}*|?ug?1X1Izv86OwV6`we&(B zUD1=KDs-$1R#sLysuqsK`aCImi>GTPfm!|B;$TyCqWmB&jkR>Y<^*R^d0p2u zPW`uAVYHq%C3O9<#xpgl`JL~~)a?*R10kyuYquC%JeP`d8Y@swO>0!pUOsK&mo<86 zK=?+Y@-8-+33c*ddE|8LOvAjJ&rfGYao~KFcS!Lk(J6enmn?J90z+*yvW!!Hz6iA;^M}?5hhG*J5kRj9Q13MzwqX!($hh78^7rL5G)W}5hr!EQ~mwG!qThCz`z?gjNHqp6rM6U(WI$|B@GW zww=D4eTi5`{$)Ch`{Jr03r&rRSWmnUJxNf~p(&5wXSVh_qP4jGkorgXffwwxtyUj6 zqzI*b<_&va5osZoSf>i?!9(OpV+nBg?FjCq1rm0&uE@7WC=uMTQW^Q^{XTsp4jC;) zu_b3T=Fs`*FWW92zwD-*9EiZj*{k-hPzMuTFr!BVg6o@%nAT1#Q=JBfpAZqdxg|)D z&_?+0pU)26iDz5vyVmQP_8>(Vl)X*MmE3dr?4cnVTIlc)vQ!+Ju_OQH@(??vukYdW zhY3(On&7$JLUqgQ=rF!wd;+xSg!Q*%+I~ls$8Y*+!bnM};%`S=j5W@gK1q&sUxGOW z4(N-}Y2wa8pS?CFL>VMnHT^17_DoWWQ;t^5-F&as$nhHGUSdkZMBKEN?{~JGNT*vt zB-Qi}J;v2ay(tzMp_>@G{$e=!qmJlh`xUiYh2Jn+H$@ef#sBR*jq?9~p7wtyCJHhM zGWuC*K2&MeJTO`FpJF1}dWrvkF%iA?RM)?Wi4Ie95+Vpw7^;}aa<@L?kC8{#h+Gxz%NI=%=>4R#l%e?H)!TaCZe6Hgu4>ZSN?t?p7z!P@?FEQ z2uE_|!H9?^=-h+9wRs90^9(?zSs|kMb$F1p#M{4~h<6OY?`m){m?$gxnh-O}H-=w* z1?! z&&u%J$;YQtpNI-tHkKRUzSp;I*n?mSzwIyZ$=l3QpNK9~?zMI(LI~e`iQ1p@Q}z5* zeNtOvo0M9zCnY)-3$I0m_}}0lVnYE~Y@M9QY}<=_eW&N?1V4>f*Q-WrlDciF)<^4G zMt$!xF72K9WNUL`OC(emo#bGRnZ^CoSF+N?sNJC!CS$?^cW%u+5G(yOaY>a*JvhBJ zH68=3XoC9UNyH_6C529BR&lkSbS}@lv9hHk%^IxQRU?CUyl}-YX8g|8`woL5k3lFk zBdbRCY~Vz0#!7~xB^5eOk3e#vLV?9uT=Z{a{bbe2Om5EysTFIF*oD!fhL&VZPu|wk zKp|;^XD|R!{rht7|Hs^WMm5=X>!MFWf(gwKLRBz?5QvBZ0*Z(vAxJ_e^rG}CNEbzs z(5nza6Y0H)3Iyx|3JM6)ktTwGB8p-|@D(_Z-?!HK-o4IQYmYt7kG211@FOFGd(L^y zc@@m2OFJ4fxyyJ3+d@jM6=TS*=jv;8~MCo>cMem9Hz)lS}$NZxq( z;vwURUF~OfWeD*pwQutvj!164Nk3$|dAL9^@Iq~Ad@Ayub!e+qeuW}{S1KoIfL?-1 zZ3M2=JJTimfx5c4WB8kjah+muxpoSlBkbtTym~NMw4oA-mWjykx$5H+cwtO)@9mi! zF*|bhiw|o->#DX{7<rI;(4}9Hrm#N48}fjCJI%`Y z9$VV9`?TH|dkl1QbT`i|kwbs*=fR{2px zFv%^CZBM>2ZB-w7ial1563FL9p={*bMo@WF1(}oIzm>(Ro-|})D)5qwZhf>HT{keJ znvc;`ByoMs} zl5?mqxOCT;v9T1-P#oi1kuVsW_lG?FHMUIZPi)@*aD0+EoapqQy3^lc^Zs*p`mZ3O zk$&5x%75LRBukt!L5Rr4Dmh_B0&vK=6-jZ=T+v_ zNPwD6>3!K&Z}87eqjd!X00NWeYKeRbhBUf2p+o55wA+QLCDKJ~kp=jrC@7@e?sF(=}p=RS`avt5+s<$9M`Tp&zX3s5p#7 z(_&7FIPeo*DW0jz{ig*z;5CdY+!R{UcIJ;4yMJ~#=Rm<*?!5uEof*SImshsS4YBRO zo3kL;3i5NF%%C{j-gr1>l@AU3_=VhdHM<65FIG^f(xLRg2>V$->gq$k78$G5ibtDY z`j0HY0dWRxF5fYdo)M(7IN@rd(g6fE+}v5?2A#1|8Tb=fg(980!5eJtses4&B>z zu*vV)mFr_CWLv+Gr2U@LaS$Nml%{}YUnN<}=i|n5=9JLbt$E|wqp9mz>?R-z0TLZN zdD|;DSf!6??-QRWhx&O0E<6?j@FWtiF&&#hcjntkIDgH(l$XLdCQX({02{U@f%CXB zOmK73wXBZ@)bLW^R_wtzOhB>|HH{|mBMWBQ<9HFS1cn)&Dspk)hABV#kU?@7Cn#{13^Wbx3oZjp*xNkzcntFwll z)~dnAYIWZVQySef=l-t2`SL#na`eaQ?EWi|^Uw5EtCTxU|4sVp|4AFs{cC&(+%%#j zjs7n4DFIRe<^LW`xO6)1Qnvg5(#11MA1c!Ew2Zs%<_e&-v6t^ZS6!M@LQW<;Ot1?; zX)J252xNPEOGrtr2Be=iU+biutbJJly*-in%V4Fg$?ng+Y2Arkj(mhWx*zBuskrv9 zs7?O?6AH4Ie%P7nPd-e9fcK`WZw7BWE({9;V0ilj59N22Q+L376SP_%Ty!5G6W#iy zPACX-KD=bwD;8?mI7LUf2+GCx-~Txl?xw%{gx$3u_o#}H&+GjU?)F-p6!Mamk^MAt zryM!uCo9|>6m3}u-kTi1INnDX(BlY4zZW-H`O>`Uk1ep`N}ifyS;aLKtxZr+TqN$rB^9g138%Hgyein(H0j_Ke#Bt8IqA z)nlRA!0l?ODM=)_&ik>M82J2Xn&L-1gqGFIas?9{O1evY(Fc|#E%UCte|P4Yq+UFr zK_u@5NC<$Ml_<3fX8v=l90z{q9A@|qCnL5D-m&qn+E4O`DHQn|S_1xA#!49zZzo!r zMc)yANvaYK*;8|;)jdV)_6hxBz{DGrVvr8>?pI2w+CON9p7{2hQR$~|TUL}DF4Az< zV-F^|xoE@HvH*DFfo^|rx95uK7Y!>jAmG`g#i6fpgSAuR&l%QstwX&xoY`Oycl$?# zA#U+^%t4p^XT4<|`KCYIGI1xwy<*Tu@w)Bp@PF(-0 zuNf-aK|l{ykCth2gNde)UFOCbpZLBHXzirBV^EaKc~iZ#dezZxuO?4kqMIS*tWqyb z<%;SOl$|)vq~VYr_CQ9bh1@fH;fM5UNwhVf8ZoE^Vmg77u70?F0$ZL=Dj5&a6ai#KSz@s+M#&#LmUv! z^ZN(Ctiyu`e9oPmX6~&S0l6Wrudb9f*L1C-Ro~*T6!4i~rz~`DY;RTmb>MiLjhy(ljf zLM;Ug-|PGY!+s=C^g_h{0?$QCOvjV?6guHz?t{Tfvgj`*k{)tCe5WQz3=pYM046#= zKj`e(cT73dpAHpQSMIX>1s_0Yo@Ot5L z@fS7fW9lag2T~|OOL=oB~+G{saqu)0TE(A`z7vBeKdmQu-Ps`%Y1hrp zEq*z(EQdnb3wdf*ZAgIK=_pNa4KPxe(|L^Sr|Cw)qyXl? z-GBL@%#ki~b7B8Y)+xQc2h7c&Mu~E{^@)L*Wr>JYKM0HI21PQuSw6bGR^91Jt|zYB z1mc7wXpzb>2(N zyw$If_ko1G6qU@cFse+8s`$DR@t1lBq3g2N6Alsdt|FS9)d#Qh-S#lJEJx>+Z3{Va zm)^A#HiL3D7Z2Dsvaz?u-aPV%(8lXDxdZkuiNF2|+kO49qqHn`$M3fIipP~<$=15r zi35*Umk2GqK*5}Li{qYMan~L>D?G>-3mGyQ0iGlUu5MP0i!7JkF1FYbj2)ygP}T)n zEq`LThQz_}pEq~2P|{wx$24y5(_2;)JG?7KBx&t|1 zvH*08Zlb-l`3+lBKL99`OE{aI#576Bwsp}vqt6hrRtKG_*sf5D7=!McYXLpN^DF%j zL`l{w{Jd-jI%Cz@ZMPf~#@LTd0-BInJGWL$=(w{xoi6?|A{-PoWrPVR1soxIX0-N7wXMzg-!O#3{?r zYU8u5xR-ATR?!YToA2RcZZz}JUUtxcwzEE?AO>}gTCd|1O2lUWlt-tkd}{$&* z{ZIA=#Slp=j7z8Xez3~j9#rLy;|9dd zGmTk_=cP?kBG!kDUzfBww78$Cs2NSxI@ox6C{lerBJ{#Tcl>=f7LEgbOTlGd0lr?G2(4x0lJ7KvuGOX9ofoFo1 zEJirQ*D-4&){TmtTa40Fra|ZAa>vbX;oj61lZ{=a6wH*Q?>#Qr;%3J#6W{vC&7AHn zvBop*cUjh|=DUwP2O3d6Z~tC*jzaB-7L~Of{`*zulK) zo4zuU+udCU!@s0B@s*1`qdir*_9fNJuw3G0_fz$IU;cz5?tMplc5LeZ)Va9gpWdKf zGfVg?|2N*ChLw(&ZB81)YLfqB{|%O~0I-CSfIELHVTUflh0wpNS*4E?P%=E6Y&=<) zXs_-kts8Gqf36k99UwNBOUXo=pWwjp5HOj-^${P|d87?2VQCgU=FaFmlBYlcyIKB4 z5shntYvrr^2mq9Tbj(pNMv-4MceVt8$g68hK7A#TWnl=j6Jpo-gnrb?Y~b`7PQ*9Z z+=lCNPsFav+T}*Z2^bFE*l$^=|BS7=X~1^G2EoHx;tqc_dcO0RhpJ(P*R2K|l25V# zdNfeYt6%Dyi=SmfPRMzyg??*~T&GMyCvS`q05hBEh}F$^J`ee};A;s&o1_KJg!`Y8 zhQF-DBDTz0`Yu&yJ3{QpJF~Iu(hHquBL@gIzt7z_LeQV?6Bh+)JE4**1vi=s4W@QY zdJG$lz;s@a+BTl#k?a9%*QFbhY9iu*Z>i`-{VkzX73RmR*Fn$c2@s$`DP*38{<%OPDc{5M?;U{Tv*DDu&|r+nrin9v0aiO^5{z z=rO{1TrE3`&XiUFJdld{sc;kR0X70l-{9$1|MAgcDa!y7Ae0y`dD5M{D(E&qHqsTL zDs=$OcqL{)%(VJUmQI@H`b6-6Hfw9)1wFeq%ie3G)x|)eA)vwxr|(h!`PR5xL~paDX`deM&#JIw!hRh}zV1@Y=zQ;xD6i>5geP;RIK!3Q}3Ex=xciOeuz zj`Wj8!RUMLSHUJrD}$^w(%Tj~kPK5&Bd_Aix>aFn=hfpk6?ymc?d!E(iD-GXb4hIW z!_z(^oR<*B8fwvaCX6buxhr;ze6|%dZ)!nkbf#2OOXE>JiG4BT7v+ zxOB+k*Vp4}G#eeh;PvOX3&lH$Tg97*NGBv}Jt$!*K(Nz1(+r&orC3A5+C;Z@uO@Oi-_5wv zdh3U@s0;$Tl&ZUkMMJJ?_8A2vN7nIo-bxf5woU&ZEMa|>2gCj(Q+&;B=c`gm0Fx>1 zH6|2JE@*XzWi$U~x8Vdy1WbXpe;xIlIvoGsyiZYj#w0b_qTZ^N)GD;GySyj4OV|&YJWoagF)`^k4qo$F_B z-X%r8itNbYWQO-}hSR5g=ylleXByLfDs2}}Fn_h(m6J4yvE9`!0&S3WqJ!nlIE-uS z&495zAgvn$V{=})HgvnCP#)0VnSjK^paFkbEl(5E`S;w?m-h%%6#!?Jaz?bKVM2!3 z>4NHcBW-$yQ!Ku+g%vH_(pivlx5YI*a~1!O^7gF+sGSrl(*m%lH|Mq2J=h*x+1!~x zq^zLlBs%-=)H6IGK;#ZwO%G$5$wD-3ZgTom5yh0$ue255f_B$_E8 z@k$Ji*z_3_REObVhUPF(o|-(;q{_Gid$sr?Mr%KpA@-Of2M1IVvvTk|=R5}p$x6B< zX8WqeWb9wYDHetNXgyN+NRo$0YC+{-${vl6@7SB|QOUbq@>EI>F)goi*>};kC$NF# zB#;qZIOjY}xbSSM!H8vJze^%?_L}DdQ~IsRE%lJ8JoP-#EF|{y@`cIA!-S;!a$? z!aJa<`0`7B$&Y?kI!R~4~Rz!VaeWc-0x@kGOmjDDrO{!O%`s)BK|R# z8A;>*=jXD&7d3*=^TS7+CCqURF|@w}O=D06WeD8+*Oc~$LkIsy!0eL*L?oO=GsWqG z;n*(tY&--=M;;?gvZ={giV)u|`<}0_Nx2fP>NC(1(BkbV7v5|$#eE>>;Gy2VQ#{o} z*Psx@42(nUD>dcvg#wE;MltA*8gL2W{dwt5R|trb5GQE%ffn`EV;0H%b$Yw&{C<5S zPN$wFM~`W?`ZHPfcW1}0#@5Z>0V&sC#Lp|8w6{NQ_t0l>d?qJYbbpB9ns@zUaIGn* z82+3v0x_)10j}{aWQQK&SvoK%;$@Gx`>TFc1gLL6;JuI2Aoi2o0dd%FUJ{|#FDS-| zhTISS=COD!^YE@)<`>>A4|8F5;EceMPEOmo&qa5NHmahPI(Tot%fWQKx@JAacJrVA zwFn#gIuvX|l-uX&=q@|xtMIDX2s;f^8;XTo*BcS}AYM~?3Ki(Zvj6<*2+L|o9%_h% zZf2ei!fbvsQIOISC7t8;ac3o<6y0_+Fi`nH{TUb+O=)q%X3*psfGSJa`5xj*IlBLQ zidKbutN3Lwbk;<(6-2K}9cwSswC#M{-|Fl7MNMjN!o#f5wX#ZJwD@wTge3_;Ba|T6 zFIH$KUbj!rgET*TaPRW#l`EXOu2V&BePywO-Ph_!4;t#tK~j#TqT;cDz!oT9DlZ$}p*O5|-zA=d@)nO3V)amdxX zuMAWVb|{ACqkq?-D>?!5*8*xZYlW8$37_LFXIdM`jHq1w6JmLMOI=oq<^2VjYjzil zV$vjeFg5Kkh!Zb9^LueyWy_J>$9+vGgGR0Art2?!^Qd2_utQ$eQl#W1{L>ERK!m~cIi8-deQ=CopOyi`grAEpa{^ig9!sjFjl8mzD<{xnN4Xt6`E}<-0tO6d!fX)lpE+S&qjkr zpgWwM!u-j8Xo`yoj_0iT2nXSmKx)1Jm;7 zhYzKc=~bz8;JvyULD&0UDj0(Sy@bZPB5z`uwX;PD_W)s%_|Am*B)wv zf(QHtjV~piXINND;p6a+4Da+1#KKxilMrhm6TzD6i&(%H9byvO8s%$xPE&FRPQoBo zsz?2tCKu%L-h>K^J2yrrd`X0!6v?AE0Kx^cM?cYQDBD-%;K@1`abAgRdflaWio0H>mWd`x4;RK6+^Wk17Kn1r>9@WMv7KYq#S6syE?lAO7Caq!nLxcpm#XiO8EDNkKuskThd zQ}DOds*aw#p#OhQ-LjkdXE63Z(PftD^At_!zdP)LOEMBz#_a!>GS(3T+mUwor+wqT z{i*+!Q25V$?1Xi0Fl~ada5GAXx9YfUlWZ4j{qhw)rIAXb#0GW0A)t8=^ zg6tk4^Vu01H(0bxOSx$vwSTx?Ki7jJ{DX+91@mwwg0h#*8ulIuJ++5)orJWxSvDr` z>^Is9%k0!WcElBZA5nypzuG>l{p8|blq}*}Ky*#|eGx;Ku>*`|NYnna8y^n2^}yyo zsolGaBi;{_vsd)V^Y@NFd_-4-4@(9w5f%6hrZt5P(CxZ@gjvlQ_9vTgVKXP^+%L9% z9AiVVNb&NV<~9%7en_;H^cMdP#$>N@Zxlo7_Oa#giyh~TU&7DY+s4w z4@Fqg%ZbZ4_jCII#sTWw88<*W%9*QiG2Q*=C>~`1;k>~R_Y*@fX47$)eMSp#Y>^pQ z)drG~;$s+x{;sRy-qTw_*U+L;)KL&rsu)qO2+C%L_g^^bWcGVZb|0lPyBw@cs^fbD zb&WP0gGIo7kxT2P(9^DRBD%&(ZaG0F`un!aouN;oY!+?BUW~o+KYRsDM_r%G12c{Y zF1r<=o30Zj2^vehESaIi0t4i4bxTdFjCuL|b~uycxYvAv3Dawz4}#w7Tl2A29#0n|{0nOV)JJ zq&}(*4s`&QSod$XLIRf46_fZXx*7HdcH#AR40Q-u?QVT5+N-xbOcYi*LI@N{cDbs_ zhGDPZhvjifWTqHKPEWcPjy06j7czW$e3uNrQG$4!4Vp9>GC=a24Swq(_weX&pRTNs zA+Co8uJ}4=LFufCttY~OiCo+%!~8hdJ|Ix)=kBcG_E>+c{;r5o@0e1Jg;bivU3q#T zWT$=p5`z}BOgbhl@=n{jE~MfOH%Zwa>d1OBwZh zvypN3Y?uV9a>d$xiCglOB+$S$S#)vKQkc0=p7LFc`OW*iR7kq)^06SLrJ|(_9%Oe2 zx#3df{nZ_(oO7q*;GZ=jk9sa!SSo8>ITG97^3?|V!97$na&YIzn04`mlp>J-b$n|5 zqd$?QSX62Sf?2GE87esE;g#G?7C!fjL}MlTt=T{`9>W(XIqY;(;}nc6-!o7G%9QUyUHW`Z~?eHDCp>hQ0s za;)eEH*|wOM&Zc~0CikVY`o5_898)Ljn=zre+ORtW^~e`j#TUBHr2dG=q9Q9;yX0# z7TtHKF^qqQeP86d)BSk(6q_PmM<%u+94(VF${X;f>9?f|G z31C%_JHIM73nRUCrB@IyShKX<02WD$sQ7)io0#yOIK7D^Fk*(y z_jXWwJz)HGSh-n<1kez0en36SH-;6C?dcS_#NBAU*8swbmhy*ed^6EV0))Cr^5co~ z+BJfUjLVdGRbgQFcG#fy3~T{UJctCL<)h!`?ooTVnJ$4RhviY8(v*p0a1sLvdQo7m zB5r-u)j;#*me+!l3M0iHd?uoT&)X5|^o0qbWqK&Jckb;|e|7G=OveEnMw%uf60+M6 z?$`0U2qMqruT%kAgDbIT7M`D7C!NIPNLJA-(ghwqd#~rSU#Ci|mt(g;QeROJ@(dLg zDZL{7z6TY6{60Q}pSHNbxOe<5(Nybb+)nE(`|NY;!ofZ3>Q}EoSAS<{!Sx~1le)TM z=P9d;i>IQAMH_>`NKQ;>QKmLt>O!Ez_iqD4e}2^r!H8vI!eRJ!QNYDV=ZCaaRIKhh z?GgSim8gi$-P0=~+d8+EDM0g|z8p#g_?UZ(?g|3ogC2 zd>P{4`E>oBIY8&g+Iigl8E4h-@wG>xWd;3^;IATn(ATuDQPSaKN84$^PW8_t#k#&` zq?k@4RUS^FRsdV9Q|yc~oryg?I?~=nn^U&hoYA*qkndus&`(bcVOn_68=$(M*x3j0 z4ztg`*SB6hFZ45ri?rnKf%AJly*oRB)`^q&l1MWw`vUykf3H-qe^e@0Abp2B9&;4!sv8eCqa5%KD$~27q|J@6WxGGm z%*W#)?agukR*Q?~{qxThcG4d=dPg>DpqdOPc*Sw*j4F}#4p zu~wVRO&5;!xGxl2tRqJ^wN6&-yQcW~K)w@io{_zSKTfyKa&@}Fmy2eqvAR^IuOnbg z>TPtr%jLIf=yC?z+qGli;&#fRyzNR(vtzn=M78%drl-`7A3a{~RP@50{kv`3b%E{Ow+h!co3Ypf+k5D z;+84q)p4TI0hmB;rpPu;kHMIRHC-Vu(4p;@aHV=>ROu^LdsE+dkEVe*QfBbn8%VXV zV}PzrhL*P4t_3Z+rK}F%+lS)GesQZ3&Ef9`344leXIUXTsUBv-Vs=VO zWS`-e{yAH07<4f}tUXlKR(b-#JQY-A6j}XqT_8!jnEf>_uH+0UT$ncNPQWms+nmz}XQ%yUgT|hJJyh?)CT+abZ2(%zLy}L$4QC`h z+1Sus5_~uNR{RS-u1B|8E>K6_cHH(YGKz0zsf?H3V?O?V=QT`)?^iotdyd>5zgEtO zt-s5|YK(XsU48Hd#1|qN^3-+gg2{zfp|vD{<&r&$A3vSp*2CR?9OahEpYyXWO1r^g zs=U=IXvI85;+Fx%GGYVf_h$PqWY?kXuhq_}vriwZuLz!xkRU-~JC90eLLdE1-;;EVk=Uh@X{0 znv{l!8%>4Tl`3uzfwY4%iX2kw#9w;NRYuq3Wm?1YO29ogS0(2@{kxlSG#$8p>HRP^ z?^;{(_OZG(xsfXPk*$1NjGSeRb)Lk`*F!$m-GM7u&`OU9cy&_E&+0z-HxU~p8;rmgyvvlyHV@g@cyI#a}#8~ogYr8PFP{2MZcI} z$t!I@ye5w8qbD!rBt-JIQqW;_q}PyN&}S2Ma>UqXF6{TPiPz-JX#d=h^Fp$&DtF$C zz+S|=E5zO1_hN^@MM`d81JzOP;5apYnp*5B*vp{cn&nfQ$pU$@48b|{PPy}0dg z1RK#YAL8h_G|8UP;@=v1L0H8s76kK;dCXE|ysKGST9ZL@QEEn9d~&V8SGbd zp~+@*D9p!=t=IvB(k}Me+U&a&4xzEa^JUdpo(xjAbL=9F3#6AGzde+`3P!q;pTxZ^ z*Rcl%d1A%(dz$F2(x4z=L4M@L)pe(h-5EQ5G$HHn{S_{8!h}$F!0K2{r#_4br-2v< zi}DX|eUq-34+CI-UNSWuYJ1WZxVZn>Ym({>cxOdCWj_(bT~PUoc=bC;rLdtIT|g7L z6GAM8M(8EOpzm`<-7BuGoTtXvMFHNH@)^?xu_ATnESnboQ z_I?vYPEQ`6=3S$!s30{t15ts+szP-So7n)aSLKPBNxqo~r6}0QEcHmkJ-S63azZrW zQNM?Q+v{2{6I6SRI0?Mep;O!B7An9nR6r3GO#61#G#9xC-$Ph8R2w4OZhx$Pb8++;*a)~3WRk(k@~fkK;kPy>Hhy6MqC9I(SHjJ zMS+z?8BqEA@BnV2(f?LiWJE&bzmzI68kBtct`1q%JMK`DG2%=Y-54}byLzl% zrrBzyDcJKxAykkLh86O)$TzLbIvmB>G54r_BqkgC}*d{+KcDeXd9|(7I_A z@HR+ohh-*e{^&a*A|8X`2HWunnUnIi`t8ZNu(UJiD)M% z!;r`_sf7U49H?S8DHl3q>j^M8hsTOe^zWJ>*)Q6%T=e=UWtAK}i0{ft6HQ20TkecX z%}wE!5^rs*x3!8tHgdsBKX}*5Wpjk^Cl{~tP|=sq?g%lj!+EI2QEh#dZs(;t#6Xc1 zbozx>aleH_zR;?j93aOtx^QC{#&EmULED(s?wmSoS$bbXf$a_ET}_ah$(4LcOpE+P zjy_7${05i;d(e+F2HSI+ch$~KMSCjKF!#-tc~;SDGYtCN3yH9K{PYH8kYLUy+TJQ( zMH4jcCR|)i{7abXTJ(l{ZZQ$za&EN5@nQBWZ!t%kublv`-R11Au-}E@+C<;eK`%f< zS5h-EuZXf*qZ>=K}iwO;LDcNmda*F8;PJ^ zix$`lOpm*iK9E+FhdvTN{?wXMG1jz$4U>wV2K?Oww0OBI-{0R6m3h!%i*T z>wchJXivTT`NqDOU2sLSzi$=*@X3+>*C!W)KyL53qg49mXf2tw%))i12&}f?S{h}Z zr8n4Z?V&f}>8bMkXQBUS=Fm)*GCkO>H!C0gU=2TGxCQqztwtqL+-(Cg$1-hpO=(Ur>J4BH8H_C+^^YB3VDT;Lo)!huD!*61W_X(C zL@xU7S&^MMdC;N|T1}v-sI?E=jCtncme-ln-pHp1ZT-m`0Dy;Bc}0zJH=xhC=hjSx zQm}pUdTZ=iy+Pb;q)6e^aF0aG<9fI&7mL9w9Z=fJ2Auqk-y~lwxs5+w#5m_3!)qi& z)oRUtVbyQKv-8Ny9ReudP}GnQ{6~o zY2zCbUyT1&Jb9JZIUFpvdd zs}D!Fdc_w8?*hg1(F}P}fWfAr!ESjysr?!NKw!z{rE1lrhDA3I@YfIoP-urL=@PhN zUT1`lFpP#eCnbx5o`a&huR%WEC7=&T$1h)tjCy&M3|?qRnhr=i(?Sw3yi$Jyx`Tsj z#GoxaOG1O(QGQ%MM$J*H6VVplkOLF;p2|})O9Uo<_+#@laMD$CXTtS))}q)MMZHxp zlRIjQ zHv=Y$mKK0H>5TT=^9_3AIdyd`K(IBY8g=7vzeY2yV{gBee*WH&$2 zFURM@)K`8MvCu7O7*L6D6YMlZs*NYC+BKlA;Lz04Xn=OR{EU&#Jq);1m8*M2RycLU z(KKRT>@{BibLV^a?;E2V@!w?S_n;y*XpCvD$tLWa%E2r4r;{|Zgg^>sM(c^Nu4h5qHv6>%fm)_eXmBSSTG*~%dPVTBL5Vx~3geA{&IOLF<- z>0d_oMDbqhR+eomR^@4Snx=2;+r~(BMaQ&^v|me2{qji?vH1myT4!VIeVe*=w!iIb z`IMkNN3YV^74860W*?o#C}IDdR0keGHh=`+=zn_7u+=|D5a$j@fnD1vG&84qs|v7# zb}N(WBSAAonC(z$10G=1Ipi^%pv2aby#+RCY5km|5Eu<>+H07n#?S6eYIcf_Z1W(< zif7Gg{V<#&+ zsM_uuWO8;AWK`HFcO?v(z7&KNleS~Qe%JxyLNH}YIR$owvUf}`J``Rw@$`ZR?AGW7 zH-oBad1|8K096d28q&iSNW?t#SJccFP%*^@%1d!4#y#e>8^AF-_*aq*i$ZJ(dgTns za!^=^ zP8mQd$8y}5{`;^6*?BwEvpp4WOrS9LN20aZjeak&gp0z@;9K1UgfZB~?aIXuHapTDJRBD|PQ)j%{WM zrbsh_QsAY49I8HoBsBi`{E}Wz%sxS-)m53+0Nex=t3;BKWhdPV;cda93Oz4Y8Fgo` zjzl9va*iti3p3HA)svD(e;lxCi$tD-r!eJDGXjSQ1TX)TxiYROJb)wdjCCizvuY*E zCdJ|zR5s4L{!~|F3WS53IIKXa+(Auc0;I<)Q9_Q-CA|!In6>a2YfEv556cC}=JJsJ1%8-5#$x6nDV)7%0;Tsobxapn z6&=zB^$G1U2$24oyF`n|W0TKMrk#;n{gED+U-OO?C#WGC2Vi*Igiuic7l67FCkvqH z08Up^kX0#;R+e;6!8`kLJD-i@Q5B)qw5U{9K(PSq4^H-~%7gMO6H=m9Jkhr{@17>t zp-1ZgwZNUK!K$M1srSXVu7tiTLQafiQyd>lc!$7j-)3XF&q~KN*$2oV!Fd?%RWdT_ z>U!2A&)oq%j&w@bzC9T;m?9n;O4QR?Z!uC*hAy1N&OE4f)PH&>J$=lHJfqU zyLeaoMWdfBxi6uU4D$&GfBMHbwU$lw8S_>s^}LI#Y>><4i{k>seAdvWhc9)OxAylvU)&%CI_4R z@ZA3812Uf6_F(loFaASG0>A%}k2;gG*DD5|g=(F4lEucsJ{+39`>C_oL_9s}-GMeM zy)zru|M6zQPC5a;SvsKpFD&W=T;vjz`0e>`i)_BNdS~4zK4s%SGI4SoWIKtE*yKh} zm*2PD^s-J^oZ+TU&%jA1#eyS3-pt*@l_pW^-FP}s0xq&)pn_huR%XbuY zI~p{q^i716DV9^8K(TffSkMu~SJ8bc+qJ$XfS2HPyVY|#>A?I+UDI2Zr!u8KpLD1d z1yJSO)82}AHx_j}1Oy)o?@=d3M>SmEUgFs-efXG$JbmNd1-Eyx$R0yu7PhBPG5<7p zjr;CF@89L`xj3`_#T-z-{lGUa@XJEvDn3>A^sP5z8R?qZMx;6{vlGj)EgL`%8x0uj1qKDVIuB@Su1cK zq@qJseIL(|ezH1?F~8hv<}L%QFN2m`MqGV_DCNZ&?bf~Lq{25VJI8DgQ5dk}rn;qT zgIlgd3Qq$b9qG2Fj&f26`o5d83RDZG$h>-TMWr3q#2>eNTgNzZ)p9aNs{*(MH|6T` z%+~rt?gZN|C{0X8RZM0SOEaemjH5ODl|hNtY@ubWlJ<5zqty0VyH$A~hgIl-@)M2uhdUQL2iHx1fU9*zqa%Th88} z{hss7`5)Grb6#_fF}~ip*SGBNgGoRVaff=pf>2*|- zF<1XSoKVXm+9~L%ppi!Blm#S7l7YG>9(S8;olDM(Vy4qo<9zeZ2?T_K7X>ZSLZ)J%S_U!IPPVwjyj(W)Xl!kIih)gk1BciXgtY_gBW~U zHuJ9g&G9s@Z@wU>8=-AP>b&KZ>13NNuVRguQ&)&%su@Lv!cE^@YPE2QA^K^|d=_5W zEUq6*HMJ=BK{EOw*V$Um&U_9Qf}r2`YHY~wGWJ-JUs=fIv$ae+o!a})MJ`cX?6*wM ze0k+j)SK_0_UhNys2er>A9n?MpICfoSWHonYe?VNeN&tqnnGeTDFzGl(;snCBK}r6 zGJ5bRCYVH zlJ2k;hTVYy;s%2p9jcbvshdw-_8bDKt|y_4*ar}&$ymypE*IITv&hV*cjJt`%&BE` zvzuIvD=V0r0(m!6=*%a~OaXisYYZ7L{;T|f4!7WQ(WbJl_vsB+MqX;Sd0w(<4}D)K z8bINMJ;iffB;3zY###oxdZ#T9s{x?27R!%zlrPWK{cBNmgv&fa9blD94QiC8`Fmn| zVOMH2ungKRTp++kki@$TDGN*f(~Oa|P80k&A;sEv_WA{vV>-jGR6*}bAJ$*^UStgV z-Ou6kHOJaF1vQ@cMDX)LM8@LI6I<9Oo6t7=@Ww>>PEso2CaN1iijdO!MV8Uf>9f3%Kr^+`ZJx`NOS( zhILU>qnGEV<6aV$WIW0umUDXxZ!&%V=8?`ZuQyF(Znrj;W2m!}k_mHGcND(n;Owu>e5E6wrIo<^@ndIrqditUMz?y4jr<7XDH-8*>bvfk|bqWuY1yp|42) z(PZ<3Z-7Yj6ThcItqO@k8m~-^q=X%@R7FqoYf;O-Xjn$ip{&14rqS*T832(cZ5i|X zbEfX(a`;$y4*JTm#9B%ZJEO1Y-GQF3BO^F(y$F8}pnrWE`%uS4^3SPGk@XD`eOb>$)@TJaf%D2~qgn5a3 zW+$`M*KyqHs%gc~0#}96$mt5AL;~fHj~E|v&bMo6{r%3IFse2e)fh=^MBMHC(CiH7{Q>C#?FzzrQQMy zjNMOiwV3oP|Ni#Bb*cf{GO+xW8p{d@??h(@)HulN9PE6@X+v{#I z*$W8aLA-*Dt##B>aS!2s*s<%#zn{vCg3!Y#2s(^I)_)F_WI5!rmZ6CMG1VFcoT@MF zyThyOH}&?@N>}P}4ZkK03h`Mq!m5Hdd}kKxSj#YemG4T9z%643+Y@_pwx&N6J%vcGd|h^&vUJwdH^Y(dsMCBkF|7uT+N5E!BEQxm*RMH ztY|u*y@?~scj*4u8X`82F-+I4Rze0K7jiR+7oJ9yRd~t;4Lz*)u=2X#Ye_Ui+%Av4 zsHHTJ6?Tg6ce-P%;*8IdV7>;*AooK7A?Q zT50O;L~^Zggd^vgluA}c1^t;1SrPjCy2G{It>ER(V&mA5TK}JXk#`h6%>)wsq(3R% z0MV4BUlC?T%B^u-7^zr)jz9l>=(6Xs9akU-2j&fra|$_CY)FI{<^!7IGyE_NKt+KA#Fg>^+k-|v&j8TaprMa5TMQ84(CdZ8 z)iW;?`c#LPV4_e#-a%K`GXPla+~<6ZHCNwVfNV=l<&Q7P^~xgwlhUx8;N7&?NET2( zCXtN}EhrrnyK_mr_=WX6#)w9SAmRa@c;p`MqM6p@pA1Lp7c>TOv8qj9f{Je# zK;}Eirel7Nv(x#B$9j_!Ho#1rniEJkC!(7TW&+O*rs4rY#zZY3p%Mp6^jS6X^8Woz z(lnzxLvBQ!grp{^PG(pg!BZtrnABft8A4R{&3rpJJamR3&p9)Au`(fs-9%!BkTYSb z`#6(wMZ<=-ffp0pECA4Bj7IARkxXo{zka2!>J&s8r^SgTR`LZ=gFB(9$$cKEp= zTPqEOxg!;8hsb9AI_E+9{h;vpuU?S{PMVbB8ZB@x&BPZ07l3a?(2gw)d8d2_Pt_Zl99lMs@j+@-Ai88G)Z)0i6 z2-#>~{%VwMc}3d3%zw)4Jap-OA>Y8NT~hna z{z$Ql>&nB}mb#o1o{U^=z$M^q=&=$hPbD$v7+9$7-q+>_QKyv$4pH&c5!dpYf&&Q< zy~{8t{*sbsO}ZPshYtC0R8Gbu?YzNfnTg@os&aQqa2H?mecJr!e!85Tsj66VE^qglBB!7I@N zb@3WR{)f(ZXSF-!Z(a#R$C7c#k{XQVIWPOuaB|Z)PL{dh{y^g!)7#p&Sfr{ZUeOC$ z@M&oc<(Xsm)Gwhjfnr$z1jS>;gwrc)6|8G*`}{r?J+4(XU2v3bsl_0`cYo`Os3EKB z0(tBd+7d3B-W7VZFzKiUg4Nu94$lbUf9I5UnK`WXTQCRkIOas_<2(!yjcoBzuXv=q z_Hd+zo3v*t5B@{DMFm#MoM2E)*x zjA>Dx6#^b7l;jjJxUhVP8|)cLK-rlodt8h4^(;m?pyKl=7uR0sJSk9fh<%(UNmpl< z+N}ae^uxS<-N#T|qQc2vPfeBnB%C~?H>t>;^FHu63R6Rg#4|V_O$o^SAjWKfG>9{o z8-}*?kSC`4sZ3bk7APqxC%6qERYnCGwaI z#^=xkOegVt-_Q2tkQ$K28jSNYDh;JES-ab$fD`ea-F)=67g|=|S&^B51db^3hDfjt zZ>6H>^J_8-T_Ar-<;qPSlsu)>zGccK;OP8eLoP3I z$>HP+zGW%|5O}A3Dwu<7&(TWCz>cyEZH8mu)`tDpta+r`V_)1cd;k+Tf0B#)6-;yE zDmZ~dY1QmQ;82soKpK8Gl@Gn({*Lp6nTku-z{d!K19I5dj^XrDPNyv2U+m?rUa+J#Wd zAAj#jPayJop4e}%ljewx)Zw4Z3Awap#m9+j;}r{~viG|DiK3K$eN*zcpI@ zdL-%ZXAxt~QNpNZn18wOnHbfqj-l6MI{dd@52_-6N|`YQ3I2<|6vwCYceJ*Vb*>6> zC>!L|Q=oad)HLBRAhpA4IhV!Kc8*6R z$eeVAC$yEhY3;Y^F=9EcWs|f=m;oGE8r5yB6&2jO=6R2~GCqPV1I9^^JHO6iZrW6= zrD&Z+#TvHA%w<6c5Kw#qTc@Wxf*_BE!Eb=-2#{>PFWEZmYC^e?z-<&Pgs>7Ph)6_E zjG|0}2g(Bg${I@Vhq#T6R;?@USwd?S)VZzt`hYRiH_CMpvo;eZ=- zHES0z7fX;W0xM&csZ9-V;Hv|toivr`Ms^Fs2)OSBxFfpA*HOH9Z=(ua?;n7_Gk7=$*z%k;PpWz{n0oqA5HgG1bMUw&wt1frzh)7eM^1DT3e zycv2>xlUn6op$>n^+f#cw$6sU7A)M?ref^cDK#yMMQw(CmWAelijj-Ont-K#&|ZwI z-rMHrQk#I*2K`JZzO3YVfYu_r7jx!y^?^<9!;IbdR4A?}>ZU%{pqy*#K14Ufc{xOH zn`H0q@G^EFf0{@TJa*ID<;$HQ+MK(cV^iGkUGf$?k>jn^@wxUwB`~6!zh&w`WE#Az zm$gBDq#lIBZ8_!g-roNh@qWap5>w86N%f39af|i{J9#)^`~3B1<(coPQMPaF{Fs6?oyC6bt}TL>ZN9!>@|B|S63|6^stqy+P@3#QVxie? zXbu_pbTZ|jzm!Cet5G%!9a3g%a*(7d#8ioK1v}<`vV{Tcs4Mj)$y+SCMT1eS;sq9i zPUe-|t!W?iY7wSaNJKQfUaX!Z-k%i{g)Q zKDjYq6NeWumLhX@VvVepqL|aWe0PtOQi^bfo{NX8(>B`Il=V zdtlh>^yl2Mqzcu0gb_c7&v|ph73!@6BNwlK&R>bCkSNjYPx@QK$Qa^^7*WudKn?%p z@yEvVFR%W8gU(6z++=uO|0W9j4V^`nYwg$CE{~8FBS&YS`J!3%U zP8gNe;+uEWzPh;8$3nfn4z<;LBr%Rw1VoTtZAZ>=26Rqyb=uaFarsvYx}`H*sl|ZK z*{P6bX#|dd*o8v#MYVHpJQ>hA+p#(qCT@V%MpCdiYOLV!P2eIeF3Py*M&mO7927tT zaFQwo0Y;7;w%qIV!ghMRv2=Oya^r;My#CW;&Z3Obhz*9Ho2YgUuV-N85-@OzrIp;a zRHZBaFG8_c7-RW*90Bpo?&WWZZ5hznGxstFs|~cQ#3L=61|ntHS=p52Sn5r0&O!k< za0{s38BE}WkQ5H_N(J#!ENCQF?5yCD{~|Mpp+1E0#A|_2u%aXYQMa!13t9)e5PCO` zqN5jAwQ|C6l(nC_XJNM#)y+^iQY~W)SnyvVo|8Hq302Ywj?Y*zS9eQ<`l;XmR*cf% z#ZhoZAy!*86AFh! zS{k9ry#QdWZW$z)mDqd+*2joF8*$+AqV8UBdc0m=&%66BwLTh4LE!naekz@q@A z1VX@;nI>3)J@_Hbl6 zV}LG;!SJ%Lq&Vx_U$O4|Y%8A)VOq5d>@Wj2m`cd`g;XnuoHri4x`%K0pdLy_X3?@OzQ1*B>} z9Qhi0QGMH#vKFdwV=}1uLS7kwT(r*wMt`aDY5JyHnule2^c5_nWIvePpaCTDDZ{(M zL8jZ3hSjmRa5M%E4U(Wwp1aN5xv7y5<#o|A}`7{t4YSlr=eqw@wEi~an1 zdR{N?ofL;thE7+LN{iQpf5=Q)RdjPZJ@#B#Ak>{!HFW4DX`ZE^Lq0?c9FdXKPhFjCmBkG-6p z*tz*ELQS&&N=r~`2mM35-4ecuGZSLP#Vt4F#>NQ(>V}CsNh0C}VRZHEnPrqWa{{-Y zLHx7Rr;)daK5X3B20=)>uUTb6p%|-B8jlp6-!VE5v-kRGo=hqNNX7{Lzw5y{p1NoF|a=VOVo`={L!+G0o~ZIr6%BK9(|Sz3@ygb^+znFJuAF1 z4vtDm))&Ht+_N~-13wpF@!Y~LH_Q;0mF3F!G+~aMf2k3^Imoqym8wkNaTpinPpI zDOXCaGFfdO&0Y9XacZQ>?CRiT;rB21FkIE-}!R=l%=1 zw14Q~zsaRmM-QcQwL8OCHedWFa%tB|?O#8#64qZGo<4ba=$R})jRN?6R>*&N0++rk zyj{5kGw{ie;oY5fjTK~h?Gh*Y4vD}+!erJMO+>&wL8hW|Em6MZ?b;osXAEfCUs2!2 z6I5TbO~#(yd%K>BVL@+Da13Z#8Xi?eGgO~x-bfeTVcX28BtXkDt&b&0={kCCZDza1 z4OpZXiQy^$?+V}7c`Q})sC?#jA?bq4#(l4 z?**v|?c!H2#7kOjy*?wKcjk#4COmZ2-#i}kbm^kr@xcx+hgRh%|J>pMT2Z6UQDoBt zL*u}&lP8XLUI`GtRQ`ExOxD^!cbz@vlde5iMhin|Sl@?%SB?a=`$}@smuz?rAwbW5 zn*x0yVlq%;spyGVt1dJ~j>3ECVJ&5yu=%*z1VAXA0-#84`K8>NUoG8C!Di;R7+4`j z4xCo<>GgWU1)3;C>QUYpATayzG@2C@bmIqjD$xAkgTKzTFB@5kZ9pyV zENtiYqgS(RDi0L;^)Er{4Zp!qpuBIF5Yy>PUw*Q50T*R~?>~}1j!v_quPH)_-=06s z(~y5Y&jm>QTznO6*tlC|8e{cs@gpR@>y`{t6hAMp|N5R%Ud*}MhX^t7;q2?&=EpB$ z!EDELm+HHJfIzSoA670NmM#QPis)pDmRNA(0A$83NGr>zk2^}vsX_8)OH_+@A>rA&AjePn~RQm#)Ijs9+@N@u?^}uBfpRS)0!7m{5NYISP5=3&+EB#`QA=?tyU3EWx!T8{ zkD;@ZT@4&*L;UR4C7RtDlrY?V|Es&_9CF$dhyYVAy)sY7r~Qx%)Kn&RKY%c2*KpEe z=MuuS$xtyWm(7DcCY#hRt#rnahseHCNO#r8_G42_E!kb=?o46kZ78UB=fXb?-*NJZ zK2r%%fy&|pVN^wZQS7-uBZzrg!YXu3l5$Q6|P0R0RhpaTwZL6CLNz2-B~X zm3x~_XQ9&;pGEs^s*Fa8qu*JY*5sKyGfJn|Q^mk5mB7-fi7#HYHt~Ke09zgM;z#B{ z!mF)0dWN6)HB0mgofkt(4j7TWXlKW(*o*q@$dpn(TBSbg*S%J@GpX)6%l3URY7)*h zBRlcuyv~=?g}4w-57~9uAzemxR!@34nSBZ$<7qc{i0VD|VG$yHbAFucq+H6ahS$p2 z?@v!sp*1S>_uCCAP}TG?OQHDCs|a(u1VT7M?;$Up@B+OD>>$BXv8%F=h`8rpJW2 zm|4Feno~9dZ2q2u0F#@#T*w#XBLtOM>)$%8j?4VZy58u`seN=!*l+8>T{-G$0c5rD zk!`HGET9iCHT9XS0KfcTkKs1sX}US<)!z$U0@gat_4?q{qydJ#MR;_rG=m3|==Qkr z5^>2M5xqK|a*!nPyyLSTA~M~o-6St%fx;^dG65kyMBeko>+Cfzom~E|!)ONXMLBD( zOIARh9$gzmcJ*u4yZ2@!J>gy&gz(d2Zi!8%K#I7a&oN1lkB>Qj5SjMD^t_gHZ_|%X zpH+4yCbj`Kj&NsIl4-FeY6G)g-S;yvt|Z=1WR0kJ{!I2e@ziIp(-LAHJ?cRK-GhCd z_f&uGyfXF8;>}%zNHfD?FfzKrD~G@KMqgJtXp1Bhc06ZmJbzB-zR0CHrC%w!z4zw$ zp$hEXUOna+m;Wtds)D-r$2Upt961+e6X3CgHc8k(oGqPdpp-pCU>mdA{%5~Rg<>_ zz!KTvE+Z`8S6YAB+wBg#N*?1c`Oso!*#b;1CmRdV@i>HfTD&Vnk9!|K)3nsh1p*lA z64*u;yF=;Y=LuuyRfCdWoiwyedcPlhqCz|F(sc|aESzQ@(^J6+0V)peY*M69Z-1-` zqeu#YSpwa-{wf}x0&fsjdJZu(I@ImJy=fx{oSJ5wXv69z46bK}!4Y|S;}`G`6#J_q z3a=)tq-k3MUY1I>QR`jR~j8fB0 z-8=em>`2v~raveIr7D2oL+z@QN;r=fM&!!@}8_rNB-zlps11B*Ly`n>@&N zfLX+#+#gu5rG`nr&}C1cK*;7t)(zBdPO5J3DUf;ii*3RW>-h^BZv?8y?*WX> z22`X$F+flnEr<#|3=ZdiYEh2!fX&JqbMt?B?rf;1{Nb}kQI^&MWh;Nh%8dGqKP|;UT8nbdCxuKIB6HJ^6_dA*QPlH|XzHx}xo zn~`cLRqS?61;kmxdTS~;{AijP6u5w&jBWJ@?GVh+4NvZ(3V||VmwaIynIfA#8mA=O zr2Ap>NIf=j5OaHmv88RdpiuMyZ1}C5@wA~MjGu=oL^cEFKOe8}%l)QVIx|N^67Bq( z=uB%#*kRQ?=dBIK1WC=yk>dOVT63?a<(4Sx*Yl^{}o!nHAZ?X|5K>ma!K3@EkF)=w-pT|1d(SB zw~$xKlDF-7Y~~9r>zFNzlU~j{M`#ubq~%?njrp!#aL($ku(D-+7G`sogR*s(r(Na& zx(Hfg&Fgl@Vw}jd!E=KR{_|RXjYqL;N%2j=yVey&yn}+@OG?_-;BA6d3r!_T-Zn50 zu!iQ7WKUJID7O2IO7v9fC6pRVXW9?&oE(H5bKu_bg~!S;zr~dySA{GPG{Xk|bp-G= zK|sp^Zt6$VTop3T6Ctsc6YKfU$JlCg2&?&&2TJ=a2I*IAmDAWnGgy3y-^(A>I}K%4 zIAFt0T!m|Pz|Os^SSH>(3nzd-UFoV9y^?rOVchXIYvqZx(wIC%7P9h0YiZV@TjlN3 zyrJa82djEM4ppf}e7M=-$zFZpo$%i3 zy;^oY=bq}ug<}cfH840==rrtJbi%ypND&VYgx0>EOco%OrR{0+LPR)RD?ZhBr zGO?(Ue1Ez_a=xQ>X`%LIHTQ5+)Ft72wC}ag9jcYx9{fxzeRo=Dt{NWsG;e!BaPw4! z@oLrQ!IF)dB9Rr;nMu@#X=p~?IGN;o$7)cR_~|XZczNu5DltT(rQ$7Y_vRdliD@n zL-;r9r11yV3AGP4o)T}oQQxQ-QG`r*z>jS@D%T`c;uUc9fmuGB|8(cP=Z`RAmizG>M3pMetD_A3aRuj<0!S18OzddQ@A| z+7pr7?%2uB-PV6cAxLF8+8te)#V38P+Fn zdfHjB4g4jK5#0@J!JWxkkt4=Wnk2fK>NDqZ9(>X2I`yVrEwAg|>XY9b@*sH;UoCoh z3FNNZ6JJ5Pl^^{GXZd+1@la65QK#`@KtOy`U9Ede)Y(wt+ssJPiHir%2)Xp5I798vJ}7eWpLgsb7k_Kdzwv>*1q5sha+j zpZ!%Uv2M{5eo8I#_yUP(A-SEg;M^pW8Qb@cz=^gP((S z!>~=kp{4>vh0_qeaUe8t$SN(X(}e%oYG0Rp$5W@_6>)vbCcS6FeA*quH-d*oO=LH? zN2Z)cW+F%C3Pu(JgvXplB02LGMMu}pjBYrMzK$GyD|)g+w0>)8^yAObPogh&&%F2& z(DGjN(bs|(H|qyyM5C7PztCqL126OaOsa2Kc;2`e7m+!}Du&3@8mnB2dBi!+E5_$w zH9ivp8#o^k+Jf`$%oC86Y_l65pFH7G6Mzg(+ZdKO{OfDrx@utwoy~(w>!KR zrZkhM;oAOh9mZ(lGc4b4T3Al#C_7tmO$Xc^bg7@QU!FGG<{Rgo)nA@*5o^AnJsWv9 z-0`~L;ZHdE@sn)PF-PS&pQsuO6W*|r;kF1qOx?J7{hYKMpV6=gbCPJR*mEcH+%uW# z*wSeO>`cmH4{k^9)fwb1KGExW^LoMK7pk?0D|6P^1<_TkBX-_wZ&r6FIsY!qKIxe1 z?T*4I*n=qEmR}_|ehH@#9(5@UNsovODDe0FI@ZI^9w3ypiuHJFx`TOL`xII__W&j<;NcCaRjJKhJ|2Vm_@%%$T z!f=E9J0j)ZC)d=!1tkB0q4XFmApGyvM*qN2GHwr5jG(%*f6$cptCG~@s0+UU_A4CUqbFB!Lozh2RA zaU3`6Y};99U?^Sw%i8GuT;spjMo$?4vU5*54?e%0{7-A6b6rn<{rL9z{VN85?C=m^ zky#-@{=GJe=2U-+Fg;|0t=_t8>O+YY_+3^K$MQ>;a+`@PLyG5hXjx4VJc2aG{?4cr zN>oa*8%tDt!X}xxZz2OrRx`+2!)W~eJQUY8SLT)m1;!=4u!TOfG^;iV8UR$bZ4gaM zeU5@{z{TQ1(%|rNcmBd0$s_|*w`V4sU{#5ZNJ@Lo?ZdfABQ1Mdf)qfQQYnwoi$ky8 z79BjuRv=iT_0bwH_1H75OJy*3FzlyguxEtx&dVjpLUF(~KOb*7JupC0$l}M{D?VJ3 zB&p=>9@^ZgDw0KG0NT&VL4E*&sm?#73%TVo2fp=^BO&1?i29eC;zIslMpS;GK^=i= zO|?i>*yG%)O@cN%_`n7!YkrMa4ki<;7zZ6Z0>f~PWkNZp6k$*Rfqn2)0y!3w|49xg zeEYHwT{{7mRA}Bq)yJYNk=GycZwJ+kF>WA|`X$USn%6oiP*8|ccdyn7m}Qd$MmxAg zLLZC=>S6&|fsIiV83||8C^1`5b}lgD=pQ37&ecs5MwThs^dr@73^%mf9YBkE5{gI+ zm`sTYR>7^kaGRg68Yg%DP=rln-R(zaUx=3hFoK#&=*b`}vwG26+gS>h^uxO?J(H!{ zs!C*})#XLK>Kq?Lh|c_pS)F%*{K--I1!3dgo^Y6`4BW@x&$)t4&FOzl zflrBT%(Z6S4CuKIu<63!<40~z>A^{FMRj|d&w{=L^6=b8fJP*kBT53`dp>D8AHIt)Pp#p!fBR|j*)8y*Z#Xq#^qc@oWbflY6L?3B`QAVX!mqWsgWjLq@mpd@YB1q9QLye!faERne1w@WcslG93?jAA}uS)x4It?oLkCk2cv zx~ieGsAmu`PJ0Tj!_ovAJpY!?Yvg)8HY-Y`Eb&w(3E4)l6HvjIvNbTf9$03NX0XTm z2&uJm#c+P63R9fyW#C`O5yfZVX>=j8s=4uFaDcw5o^Yt4DsCxW`wgZ2o{+g;wd?w> zclFF)IWTlxda--GVX39Mg}W?o=5-bPV>m+A1j{Sm93uiC-Ns@1FQR9S@o@OQMMKO~ z9+&<2;#}r1xrJA*QpA>L*s=B28OcIwASzZ&;qktb2E`!A>hyL;qZTadtlIv-3L16MjnK<4lRGoifMew z_3+wrRRx|2REdA@Ys!tM3c@Pri*jysi75kF5pNViPdBU zEb@)cW>yz1FucN|^{pG0QWqm_vdZrGtw(UQE>2^3^+?3Gr-&oUkqe7%2Nzg7>EQ*~ zwZygem8Ue{=&t928M~!d+v0mX^(j))BVt+=&(0ocpxidukPtcO$D1`!vxhfOS_cE> zDGeF-Og3d54+iZ<8?su5Hx(lehFp&{<~%oft&)E*>|@rLH#_`V{n3HeNKi^+!5fn| zrxy=KuZ=bq?hn5?`{UpR=}1#CtLa-^k?&*iW=*96BX13~zK>HqX46y{?pk(a$z}&!sYzu$g!A1MaCH>Sn_G~aUCy{Id*`QB6IvD zPhFqwVD`~-{9iP7)`!xdAf%uS52`oq@W!gBPdWm~){9dA`J8dfk6@wGRl&|xfvc~V=c)Txm6&kn@%nK1FFf*#@>Zu>oDy%cxJ%KGE+h4 zu=!`I6BV~MZ)Eb_p9c(rJ9KAKotoUEYs;D4ea~$epryr&t&Eunm_+T`Ie1o(h5ZaW z0t~TA2^0%-hch6W6gPOBvkx35DEt(3{`nmsIGB&5ALTN{7S?p`u@7vbl(Nkda{S;mqiHbegtf zTMk5t4D3k5Fo@fmHdncuEF}m)X?zw`*%0Z>l=eqc^(BE8N7y?=C#Xn9t5UQk0d73F z_=*F?YFa9TkptVb;1|cn%V;GD#P$sB@65U>v20V{Ybf$JD&>^eToW`uD0#3BLO@4F@B~hlTzcd)B*=pTOTM`(c5INyaeds4Th6Ovrl~*vG`HE23;8>c>jd-(As#V(<7ybl-G*qM0vrn`q+FVWzl5mf!0B$^m82Ob|P z5vzQRHF00-xX5!oSY?22$|;BQVyp)gThaj1gord`XQAsG5EFU32MnLd;0b0E>BS}q z0#JUV3|C8uzbAf%$TA3c$f!^MtWf_JS+e~znp%(Cb&TbkfHFX`Wf$<`eS5CdkSqd~ z4PXZ7y?~fTm}=YZtHD%GjlqI80)iAKEfN=l-YI&KYsoUB+Sa&YTnLdn^5x+D8w^5y z5giNV^c^lbyB&xtwyEhUWzt&EIyF;`zpoP z(USr*+|c|1wW-9$%28*hRiascD9hB50zQVlO=y{N zHO*Da(k5c~Fc8N%FbT5P#0c@5_q3z(dRWu&aKBZl9Q#@X2(UKKrMZFgDOh%)vVb%k zp(?nC3zmRHN!XnRzbV6QA!hC^!d^cm02=K5W?7@tD7Yts-*5XM(>9qSE&EQ$nZ1bQw zj@B#8S=$U|if`yfT9{e>MPPzxY+F*FSV5lW0c41cI6#G(*uS2nd# zaPDHu8buo`E*m@lQo?#1Rkc-dt?n#=JwVS<5XpQaR;_8}Zc=uWy}Lp)Gv;E#_LtNc z*1K0*aCs*xrp^iIg(C2tfoA5VCfkY@A;5~*rOVhfu>*|wv6wXXldoGSH29fhn>TD0 zKJ)xh@Tra%n8yB>W?5nD+`7}A5#!}R0E^|NPcFVxEMe--6Fqm0k7e5O>D}B!u!T$5 zDG&J8@?YY}cIYEK6}WAI2A0zEM(46fOxI(uz_lfJqta8X?2yRn!O?14=|W(lQm&;< z@L`NJFPHCI4R&@+xJp~`lv9d$?`3gTh5mFQbxOp-(-K;AXl0|CecVlnjF-AfGFYzm zqb^dsZ2Rh=PgxhDL#n^$a?}XwuQa*oTh8eU=4OdO8TcuQVOQW$zoO7!eEjS7k{7BQ zSaq}XLiWZQ^sOERRWSKmT9T~5?LM_rzZFQ5m^#y z~+^+=m030Gl^4}i1>yx`!esh@bWb5A%m0aNYc4ECZ z9jSQ(g4QqBkC4+*%!p|~>EAh~!Gd>}t9Vf`0cLKrv69wL7Cw*SmMM3~rQqdykl8Y@ z-co2X>X*-nZp$1)t0OdF60cppj0c#FQv9+jO=SJp6#+m{Bj=Y?V z;l;lz@}Z`l&@=s&YONd2Vbg|~t3?STT znE@YuvZ-IrLPANZ7n2ass;~r-5c2Lx(pIS)$Rx9H^)Q1PIHY*^XAm%;}+7EP=bL0Rll#$4Z@y)E$-WYSDail3M&fhB5;ojBC?uCcggmX5Ek0!JValPDEbRW3o!^eS_6 zPmy(tN`?j62E-^lY``OFrAa^NMSu+Gc^eoAH6M>@uJ9Tw0X3z^bi89B(I0gqsT(%v zwNjLwKszrJ|7lWnDDT^T0SWEIpVZo{jWMP_nQiwC_RjUONEOQ%wN$odVFbbqU+J_2NK_;!&aa=>B@jo(@Zam3U)q$Trp=56 zbwpmimVXwG*2DEFP+WpIUKee?$U=U9-yuajT6;^NNvPQK2;|JJ_Ui~I-L7~={lB2) z`>nXO2hwM6E-Uv(T;Ap9y|4ivIenJ2h&lnwgx|0IMY!?!Md#0qZMo3sAL4mf-ljru z!oy41^GA!>LLLom#jCy_FZd=Z)n)tPHjXKG+7jtr2u``g!Pc3?oL?q`Q&18=CJVbR zd>IAA1f7ud)&EVa%hjw;M(iP;<|2z_(1LY_hv~-)q9Nd_X93vL+!B4^)`D%(*WOv_ zIxS<=-RMB_Id&R_!dn(kwUy!4en;rxZ|K(-=N~#&U7rvwdj6UEk@5d285d9fLQ4Y& zBmS%Qn{YNSHRbQJ#CXpIG3+SX0RBJTbAQ6_|FIu+(~CKB^migYtyDYqH@}2QMrG;q zROq26gZJnf9V^M0Y|Z~U;R-53SK*$mp+KK5-^R$V~FV%nZQ z0HgB6E{uQM85&wOIy@#r_`JBiByBiaD5zwra-Tc#$>@cEixe;IlP$S)b-f5ni0-Ji zc(9?xjiO~nwm*~su!Vn=>0Klj{^E0itJ}0V=n4=dND_}rDlS~Qxw@BX%8}>8fp)}` zB^XOWZk*D3Y{jc6Zt-|0IBEW*0UTN^xItk&M`GYKwojtooHJjSb-EbDIao_UpAiK> ziZi2InmkjrH%;Jp07I|1z!pM;5 zuPgLUv7|gFf;hBNt4d(1J^Ta>52M>De4Fl;`MepE!y?{C&2ryw!w`!D`Nq$mYyUc1 z@Qr}ZppBtd?N7`%wPKCxOEXPKD*z3blslxj*%$sK?oY`PUuY{ehA1j8&%ex39h*?PV ztAG|DekupdakRRV?HE~c&G0FHB43^C?+pP@BOsEoV3zDq5_e>Sk1mWSn&L6WT1djZ z3RQzWJjr3N()yme_45%}FDZ0wLjSs;0;n!NI&x=7zmDfQ_2(_#tHbakffMWz|BJ74 zk7qjW|NeKgv5lA+kwY^xr$my|l8udRVvbC_ckkq#;&gdAoLIpusvQV8jYB8N`S zXN6P}9YsgGzg@rU`d!!cc-;5>zyId*{=N^d*X!9_E~&ZjoJgjbnyA-G5>s=;8?!l@ zxCpwA8#gPdW%e`yl`_voWKaPV&gSa9Wuk7e!WWzGDXk82N-Q}Onu z4uNPcCtBT?NmcX0XdlM;Eyqt-lhHhqU-=WYumXUga?TnSS6ce8#h;BQ%L4$uWn zXMa9FsNvPWk9V3rqD}$s!;YT$`MAuOwb+VMJv4f7_!fU9T$A3U$t-j~@+mr-Xr7E+pMJOF+O3BZ=X1eJkfiI7@KYo}DpWs_o zcFhKKj_)yt<8ZO;$EV@yyG|8;93HKBt`gs`!1)q;e_|M=#!@Y#<5?lYC_f>Y+#+{z z?u;t76!;b* zUXFD%yiDX$te0#xKuiiX8AQ^GIfGjnvc|UZ9~C*anc_7jEd)phvC!DuiPWvgzEE}+ z!>BxmdDog#CdJGoWA866R&hE)Bwmm+hyyQbk)^c<&Xk0Xz9a$!zTN0$Xt+eLUW#a? ztwy`dqRLUhdjAXl(2&dC8d8H)v>J!|DzE7zhRCh0{*Z6yRv*&n-8g;gxb%J;1Cw+^ zLuSnl!?wc8RIhA_@A57Yjm#i$+5|$6#kY_K%5Fe3fJ_Wvw@QAYaK6a6jyE<%!K_{2 za^%)~H0h^U$#^2?w>k&{y~ckGC&h3-veBo7*0RgWW45t zd+oq3e=1&cX^;>LKvSppONJIqyDjQ(y;|rl=%^87!QU&+SfoRrIMgTtbj&${-5)%U zKCJfp&X9eLQoIS5~ zZyc;mKCmM-=g!-yoOAurl() zLEjT->L;mo1x;ByK2NIAeAKVhAI1H52lf&yR{yzC2T8W8^1sjj-Kaxjen@m^4(Ng; zTg(X0j#YYen^{Vvv}$i}mWoWPW%iPyS*+IXNAcee&4Fm{KKPW6*jv+VrSOH7ppTxU zGW}R6EoE)1eF@ZGJz*&$XrvBRVja4K^&g3`&XOu3bc~N*Hx*`jsFw!YT-FPP@Vdf? zL-m57^X7K0dsjlxM;~_$prhkv6qpC97mA;&3EMU1AnVk@ehj-wVQ+I<@y{z3*xuZO zlwRuL`jw}--60yCD%UHASFlp>Y5j;4^rYCyzijxR`G%m|7UX4w;_jQI9}z6hh{_=fNWwousPu z0pq&acxRiGdqNy+WwTid;lo|FnA+Opc)!V!$)R*(>YsQyt4knJT$3MCa}ibvV!jB; z*%HI-dR0|U;u;c^ep;Md+Q$0Eh@Icx8hIY3hT77M#OX=0#biz)xv~^wGhTv~xcb_G zE6j8m&}}pvVPX)OpYt70{fTfm&X~a4W-et4i0Fr0Yw0H27`=NHI;`yY#-wtlh8X(V zdF`!Z4DwSUgjI`%la?!hs0uti)$zOlM^%-q?Eg>%g-=xR*#)?m>o3P42h z@t`BEgJS^{$7e>;%}_@qhj8D(Y1!mMh}E2n1s&N}k=L`}kIVSKKDINg?%^*ic) zI{!54>4S9*M0d z{N8CJy5GN%%mHH=ee_1Zfssg7m|2hdu%fU6ME9Cl79w5+fGP-3d|aPlN zI_OZ&Ln2F0fj17FKzcn+eD|!2kc1TmGt9KTvztUX$xATRZR+XmkrTnK7hMfL{^GFc z@2iD}2;K8(0rI^c?&-&W9TqxM5^Q!ANfmsT`ta$AK9r*txgQyMJavrBqiYvK^u>P#Yi}Wg3QzpL8XF5rU zaS};oO0D@S3qPn;IozbkN_puGlld1T;2+cB-`ZsVUyam1cj^C6^~_LtJMXW0M&|R@ z#}}3RI*Sayl-xVW58Je--(twt*6 zXT%{|!p$AA}o8@ApekcCCo2f-XKrYr8-9*ikmq0nd}Cwywqjse1wLiPcw~G85qBN z2D@`TC!Q%Ryc9~fop_>I5&-V(dcOWNcvwme$)itF1;ZDLR$ak-n29pGLL~Phe~%{D zu^jBX0YuF26KhVUtCLI~*^B2?CKl&u*cU?97B;RNU4ZbBSX!IYa`)X^`w<48;H_WLeefZ+mh3~#@DPZ zDH~#7#GKcxS1vr5>jH1FP%%sXz%DbMpWhHWRlyC&PjP|p6_>9bZenb+XN5GfH3rKb zsRi(7vI5HspSDU=-)J3wRY{)2&lK@Q7vDMetD3IVP#Q1p0Nkvmr;Mi@;pFU{IhI`G zSYRQ&loZ;u8t%WWk`wloW;)h4=W2-AKTF#>kU2m7-45Xg}-v_LKmUj5$kb6sE1 z`k;QN>1Oa7#O^#Kpy+YX*F}0x>bE4j2zG1i*7bV9{J=(VI)KnIi@>+{jrl%Fwj{rw zMw#KONDhEb2Jp%38gtd4vk|wEYo_aL%~B2r#s>$=D@-T-1XXBQ7>&oibPNgx;9B8Q zTVIJLnoXX2QD%mJqyfZR7TQukB*jh~Cr}=tohF2_y6G++uNHDDF(IQtbVp;d(5tRo~knH*RcNyMwrO@*qL@@NZ>&Z-7Q{={V)yJ0^ z`}fhle|)JG6& zFd6GpvMvJC1zfw@7tDz>gPIibYiZHyyMtdkLapT^x=AN@zAoR`Cfxj19lUmlC35YbR7iM*|S_tzxb)4GtV*wp0|u*4wh^=vd{&Suz!+>xF66U9)l9C+KzI z9Bs1VmDJmC0hr2pN$jihFY9}%{10vlP%}lFnrR84lB3obp6c3&Z<3-*W$gO|hUbB| z5J1Y3+zKT_Q7y{0VAv9zP1$mINTGaH=F}x;3&_ADXAPD#(RK0|O|{0OiGR~GcG=Fz zHT?ak8d?oW81SQPEHP^|o8pXuQj?Oae4#%1Kkx@?k*73duu>WtG8LcwEj2v+RBB-x zw|-H@~`4!%D3!jM-4-Aq*egx?PYy#teU1cSKn+Hg0`I zMxklPteGe-87C|oP(RYYv%oW@+tUr3D4S=T0+g%XhJ9AA>3LKym7D**G34VR*s<5v zIPzt^T~63Bw|9}(wlV5svhTS{83L+b4uv9X&##(2{$sWSV4Us^J@yE$!AQ{0lKf_e zsgaX%Tb2ZO8LB;}9W}7#2Rw(!a>{Eb7@6vDsEc5SUra+4;>DD}B!B48WMmYnB-2Ik zr&I|3L+zYx;2$&8NIOgZyNO#ztsgjmyQ+A079fB}y+o0YA&*0E+yQ}VQ5cRK_O;3+ zLt&>HI#jL;4{*#DgWg;*6QPzibSsP!g>v_QoMx=Ay5l(w*Zj0QLSCgC=kC-+j${}n zN1NBPU+hKCDS??`ovH$#6RM`uz6G;R7w@Bjp$JCWPY)r%P78*4a>RU#>S8gn!G(rp zrQ=e?e4w!t-{W@OJNKm5Btrl+@9*Yr7{_Dl&MADyAVdJFx4}Wzu}q_KbP(WudQJdL zbffGBl7cCux{1n}1o3V{-09fT?b=Q^cP0LgJCSVqf_hqNO^lJM6|;jae`jVmCCc`Q zTm1yIW8Xzm+KdvK0>pDLVKt=sLmtqq8H<(1~-79&Cow+MC}T7(j~6B;#*pIqjuE&&?!9?)XnA z(g`r@g9aG=yC8XW;sp3I|KwW#l?&UIny0?*Dbm8XX0x?^xPa9(zp*MXAYTIldS*AY(*7Q0n& zLUwI+e{>cQN@9$Jx)#@0!oV96v+g4Os|IOI{zKqr(fURH{-hFh-soQe2>;pyW1|sMl+H?*OA7X23rC zF36voCk#<^^;)F@z*cB@R+paOsYMnkp!}`ZsTn&gE?H?-s3Yuhrdj`CSSZaqkyTz( zO_Nq`kURlx$pf-IJwVUF`dU8meD`F*80r^KQCmu0SapO=&zeN?WW zi4Wb+12A26E;=$^j3-mRJAp;@`0X-xZe=0RyoSjSU=~+Lka_8qo-8a(C;qQnuQ7on z-6AW84$U4JH(?Y93`>zmG`2Ss0`o4RT96d4y(dJlalgy?*&@ucaCQ}6YB+OwoED~HKpUv1^2Dts1zB{{%I)(sh*i;Bj zqdAAMqbp?YQ`lLT zbzbxAM!=!CWXTS_$>ZC>d>nUSEA5zjV$xKJ>l`HQ*Xp7@UpSvJxYJAOdSqTH`sdXE}Pf2jN9m|LJF^xRNRD6I2b zCs`q^4U1EwD;fpxI*85H_s^@A>k9n#T0DhE-w=T)LM*bOGOQ7^MAbmt2A2vuvh|@d z+)Ma(pHDn-q$}=fk}ib~!{k&V{CaoVxBED3MPjao&Q!=V5T+ZLOqd#>OllUi)oYYX zB4L-)CD;02Sl@VHtk)$~-#{a|)6j&?CtUGxYapc2gpQ|~<`5X*+FJ1k42}ZrqM+JR z1VRDy|9k$5`Qz4x{zrdg#0JYz_l2!$!Ck%L^TtVhSfJcwV})@vG)7$Rhs`|wqKG}1 zCCDN?E;I;WuGO#rW)b<|R9)@x+lRPh`ZhVk=GR0uMr(5&BRkLzvVnoCkAL!dUdTc) z10|c5M`Je(;Fj?^3lFOKdg3sg?T5)YkyQqY_^#M79y_fZHo;uXux?sc%7=4+1V9c(OXX&>cdtT7)D}w2gprgT>lttHZ@Xh!^?dKpXdj`W|LLp@Ko7rJ( zvQYSV|A`g&!~{8g&)QZH9JMrITpOyn#vcOq|ZqmA|p51HidXDpFdRga6i3(pcccTc`HcdNgcJd$1jr6SZQKZcsQ zmfo+&hD>jbeqCT?WM=w!PZ+81q~$>yd^*+7$73!C&+ZO5Ob$N3eCdSeUE2gKO@&7P z>e!EtY-4=7LMC5z8gko4vtZuW=V38wq;(^1g|H1Q^qFi%oj;UC=a8XS^WF|y%5H_Z z94^GRzLNU-C|TO9lF%dTQMlLtIRW;PuU=-e+af2@JG^k2MM79fT_Y@7f#L=fLKgat0!=Lqx2S0XtfHucw(E4V z*ZX=EFcGT)N@0@LN4^edwbq=Ph*|*YFKcAL)EGDMxY$YuWB~X@l24!d;j+$+E&oKZ zJ!rh%B_u#MT$2nqd)Qwgm!vidQQW&eYYM=oyPt#@JPpj<`%*a3Nhh#*Ahp}bHAoe(!-hMd6(Tq0a9 z%0l1_h9RcxM;5e}EsJ`$7;#ZM&efW?ECfADe&y1eR1;;Oa)_rx%MRN%lt;JkpMP7%Fvp(6&e*>a=z({}T833;9+ls9LQp=y%r z9(V+I>jJ`Y)9Cxh1I!!^S-}PiQE7UPzWtlM2D^QM66JG(@>gz@b|o`&bd2fh;y5=V z@|j3*mPY@<^^nmb*9LiNk=^jAW@VZwPqQ*lsw#*T>fi>NMXZKWu9`(}I(uZh4piJL zWUVP=4~#F&#I0lD{Yy51oLee)PKD%jlrF@welCm{eST35#4eY`=YJx~#9tC30$kh& zTUsaPmcZ1Yr-mBh8&uj_t~WQ=L`jTl%{}SDV)$=&uqyn%GLLMUr= zJ`9zXE1u}m0!zYY5u)U1=TA~o(pOu2yfesCJzH=T7@l@s9r|PX7;x7~iDL6-$@k2< z71(R=X1-S1pPL6suMey8s`jIlAshmPYgR)!cx^)N>?IIV=;3=C>s%I?s^2 zw>Ce-LCZeB-yYf`TImcmEd#rxOFnFAwXRP1bxKr|<+yc;EF0U#vQ82Q|Nmy z?yO1!;beAtrz9c_reuOOzL?(O_Sp4>NEGe%35?n=C=2@vib?sqqH-zkjO5Uj6Ay8d zcCF3XrW6U4z(XfuW<@i~h>7tReOi_J$|rtG2VIt*<`NbsKrz^d)I09Uqa{qQLXQZWALJ2GX9|Lfgu95kJ14!Y$C=2>@e!BJ zBp0nl%AGK6gDBQwpaCYZ=M~R~_ozV#arV6e6iu%u0~8Evzz%a;(kPKrMLlb&h~qSx z27`$?v+q4$_HwT;WcraRofX2-9j3o-X(L|?oYrfz^Z z`8q)J2Kcf-J*BY{5a&k>_2xl23|q2h`Ob3!?pxw+`gJ^H{mKTX~+txLTP=*VaPr zgYVThjYf|(L~MS~hrg$#Yy!Yp6<8cWJ&+PR@KlP|Ad0TEO+S!dX^ZG96P_N(5@`K& zUb1nknW%#@Ms{5=X^Y~5r|SQ%X~4PYZ;ALAf%&Y1bH?vq=jhXf^iMD(6X631S zLJ$o>Td8WRIQ-XZAu5y(*VwZV;Y|(B@=$>WT(JJv^IX?hGVJV`JKv8?4vKBx-E2V& zb89V-JkoR`VqPn{u%fyAHY09&ET-o{qI5x-EBJ$F5?hq}{HH@DPJCF=w$(no;f&%t z@8dd5YhD*B25)E=vfqbQi8V)SbMZgy;SEMw4UP6SWil;{V{v8r+!zrxJRqZ-Ic^=> zm~3H7iWp_vkQ{Qxn3VNE2uJGA7IqFpV~@EUz)0<$VYafBImchmD0LWL1v1Gb{+6jRX>#3!@dR^Qk%NEr5o1G3jtJsHUeZ0~{Hliii^d!Y^89@cx_qyv4x zLY0X+hVaVPU2hDPGP9>^IDKc|=rfaP)!qA3g|_LcoM~_VHfid#=Pi%E4sZ)V)d-mT zogAW5ZMvT~>YHuEly1ouRbT6=FXB8|u0H6a5L~P?F}-y>)L_rpwABrN*Jp>p^zTWjhce9x z2N3Fyhpdi#`IdEL-{7P1gN%4TVaG}Jkt^N>qHF$`_EhN_VAC`=N3*cw?JJ`3P!-p0 zU!Puq=9phz1;Zpc0DElg4-Iujz{3e!qnvhUm*wlYyF&%=7Blkmh$Ua ztuKkE>oDEW<*GN~sni1thhA+9Jiz7a-rf>-{iL!-UlFR(Cn&e7HJOP_(}-`nZv7H%|VuVO{17FknDDazWICIhPwy?e6<(X`0w(=QRl`4gRjo^>73G; zjF?a82Tv*5JnpM>(oR_w_=wSJ!Pc(O+O>)UH$i9tjzUKDzRTEGfWR!J6#~_H$N!Af zeH2}H(l}F7eFq>H6?c88{hTHi4d7h=sgH_ly8#VHZN)ozJ# z);6;%d%xEaETY*2#>7bf3yWBN;hpZ2VP%igSSZ09T$Q6nG49OmkdtdTG+GwNKXKVx0*-!_Sn&J9dk;s`wJR>|8PEbh z3$)lGr$Sz^ZJaGA-_gvCFlcHlFJ$d{uCvm-I!h{?n=^m2}AYqg42Q>Zt2pFx-907VqH(e6aruTmB|NK zc^8pA@=!ikPo^2^5X@RDPeQ_8`v9`l2I7W15m+uZwD}=AGRW1)&f2gA!hxOsY!MuW zAG!UeM@f6a!J0S5!OJq6-aaX%n@d|zX);fWA>E8)NaKzS;{ z_du#pLw6E1`Mo4M`|GSSbveDSXL+#bsrf%)p*+40dwO zB7yqUPS>wuTM9pz=iF<~cRnik_1mxRJFn#W7HbN#ousdiNjo4A+eN^%-$eWrc-tve zL$zujr2lTp8KPAk^;}53=-HE>j|fs0nXwAd5kmCai6T!|xMS#@s0Y*~mG%>;x3|BL zHz~9PjOsM}WSq&ptD$-bfGjEwz|;n)xIMe)t(kO|)}zKFdMw3-{CMYJprwsb^vg!=l#d(#&8n_vNvH#MvkTKHylGpm3y%}hMOIPHjPOJ zuRStW6U|>+Mum?)GI23_5qQYn;au)x^?Nrb36zViJO}wJ2Ohi_s1w?%=b^oaL+}yi z4HW|9xVnJup|iCvW%YG#QAXDSv#>I1ZVm#ys}ZjsI9;hiIQ0%SYpUJ6DZzjKyRnKq zZFc_9j)U6CP8X7)*-A^#Uv*?E>d!iPvT!{aL}j)t7}LW`B0xqq9H>Gq!-XdfHXh%m zc3*jPfS3XU5Za8ruf@#VKqCmX`_h=KjMOaXfA6P%u{p!zE?5JV;I$iyX!DzQU6-#s zi0KMl^9GU$N?S}9<2Qy)Nhd33$XAYy4sZq3zKa<`z=x5^2^qFdVy_suGcZ!r#H6i$ z4tTX;#G*Bb&M5EIoe6vO%$U!8_Irb!f}3YPmI@ZoC-Mv>%h)+$63aan#J(T6tlss=HJl-{B4U0|6axDS7MFv$#rW zL=t|8(J)G^*S4@N9lqp%r}QY74#zysQCh~5VU1Oe;2N%z$Zqx#ZW_t#Rm)l58+hr| zhY--}%HFFo>vB&SS7nBAIgif%a%CjbLzgH)*S1Mmw2^%l8b@|ykPZCe6l64PY5e%W z;BZ-G(1i+43$Lpn%^1ATK~08dzN}qa--U!-ppm4cRcQ;T(j9vCJj83~boX+uqu#P#zV{BD}@{C=#sWe#8Bo36oY_**8xIhMfYMgA0?y zu(OQOS6yRO1_E5Rk4$^Y-U{GO+*17H>geXhS4ZQ>?veo1T43La8J3)go|T;Ulq2c% zRJMogYD2JCCxqLyl*sw(%&2UTARnmbmX%;bVceg`e&1&6dggtZm4CQMfIfNKH*>g5 z)70)M_mtq%H;Z7XK_+0$m(+W@+WGsvp~vR$2h1Z%Ix=5+uTMu*J6TVDd1+ECko82b ze@2u|tF&$RwaFO8mb-}4=W|zCk&d8pTVynac-sD*JGIdIAO$omY5DPre7lU$aYv z+@P6Vb=VJPOAB)an;u|2;RZXdrZ`)U2~k$gT=$8{^4z28G2Q~4U8j3v zY?_6~ zAQu0LNCw*%1bp*HOO1psuBtt&IiTrv7oZkX z`+MU8Hh;exy#?iU!LK`(;9*o$dsLVci-dwuARGg##?osE{#JKsAPJS6*c=>IJAU2s zjHj`x-66V;KnBWcE=SY3#aGDH;j(Qt^A1b&{u$YeWs}^KS(uq$lJtX3F%Tg-i`#Gj zDSeK(qfnYn>OBP43H=pi2{fLeOlc+!_?AfFBNuh6?(m5d>PXK1hYVk> zUU|TE>AhIN#V=n)@j3xY z*XD)Ur#p_FS@erSN(*8wHvG=}03TF$+2UhC;}hiRY(ww#XEQ?Ht| z*WW*C4uJ`$0ebx~w(rM8BRaw@k$tI)>gNl<>a|_jH^w_Ky>@=)zkN`BC zK6JI@IsEdsJ@@<#$~S8XnkAy$&*cjYlYKN3UOY6TSq#6#v^*?eLadauaUH2Co`8fz zWC70r8UoNNYTDz22zlx|iL>lG4DSSj|gU0nqr;uNfHqiM>6Zd#_U>z~+*(ykWB zF*zvE@O<;YN{za)ZOk9u*5Ik5?4T-{aA8Eh{rG02s#d>$GJ(efuSQ8s^qKTFoyMHndug4YlKh3ao>u1tk8}Z`z z{q_K^Imqq!%!Ev+ipEsx0qOF&cKL!XgGWI$W3Rxj#H82B`%jly{x3EWEEYq63dH2U zi$&bOnvqyOp80!2!yC9DwmVqYpwZVNnoss21Zt7{(qxUV5VF`fE{xI2#hWqxHKJQ> zs~u!?d^B+20@~^yJar&)--`1tpW*#NvC=syy0t@zd!whaFytk21@%JWo>P*C#$sAs zrLOk3t~|K0PdQQ<;k7c@NSxi=X3$v6baRKh`dx^;;1(Z1gRUE8Ydf>f|FEXYW%{v@ znnEN&oN~Zox}XhDZOYJ_6kA!!?A%dy?a;H6kFDRhh3NvUXba|Vzl@ujMe89)rZn6Z z9t0gbo&lYo$`HLE?%8nWXFjE>jr5AT#;nw+*jAq|RbG37rOB za=|)52jo!>7&Nn}df_O4RG*9O3&OHUmGrD6at)lEo(54Ze?pi^Vh3QW+zoO7aVwl9lrNA4V@-@aJEG*;ZOc$)NqdDq5^Rq$VGhf1E)`m#T3P26DOp7WP*Rd)7Q;&jfU+SFYF#~E9I%B#D4GvZ zWd^&)Pv2V{zWg%Wei1_452wOUDdA&0yz@y6_83lU$0;4o;Yh3n= zb$LDMSkH35aJ+Z{vd=7uQGafb$6Nn!Nh+$=-)|<$<#TftJP$ z@~d;S$%gX(pp3q4w>}3n1rvHOAz zRmz=9@WK+&7c$;=-i(SJg&KQeJ7v6I-nNkIAI5XtK z!CV?BjF(E7Rvk;nkh67s((x@f7>3ZDRKa-U3*T|_3hLzhUAp1@@SjcM{R2v)A_hQPD0SFxph1rdpEW&t6I;DaFPcBzB+h?5-XlZh* z5c%;nqfSMJKWR zGNM%T(Bz&vU=aaay-Wst)zJ53TG?h=XCoJ^&Y`&ACmumk*ZwF7i6>M}n1Y<;5XEjO z`us62%r?#3*))6}Ug+Q|PL;-W;67CV@#573oe;U-WxmkQv=wsq6zoeN?Vgbov|JGa z!*qBh1L#xfuXpu82d%jN?W$c&jlCwvv&euY_qxMsgDFa*@UAeTOH%+3w_ce!S#%#m zpd_+YuVfR?L1A=v%>B0AS#{H@nkz$#fRMWeYwtZp%GdfgmkB@!R7(Ggshn1#)EGbQ zip|b9OIgX7E}^WtYea!??V+UQ+Eb`A@)a~K)QI;nvPVAs^r}@YHEvxuAfJj~P&J@b zVrk|U{5F|h-Sbn9Q54HWA}tO+ivp~w%6eTNEij)Qtq>crHS$(z$6noS<` z?EjWq-b*8sYcGU6g96!*PYE7|-f*QPnYByk1b)L)skrK`u!&EJ15FwGu~UOL>V7}f z(EnQ{da1aSo_|Mbf#;S_V4*PluR_83S4adUUi9A~y6W*KY%6-=<@C>XC26xwqm`64 z-TGKKi!3$ArXt3$r-s|=W*N3E!s~f4Az-uo7B4j$CIC@|b8+BbF*DB+n9Vs3ah5lN zFEJf2W6!xhR3CM2sM&%Z$8SPw={7I{I_8!Xs4(@!_7Lylnv#MeB(+mnh&3aAd4ExZX!4Y!C-^} za|qVh=K}kzUjze|dhn){Kp7DnlmHRe|65h?F^7FCtyRS*w_EfB6-iOV)wK)uHzXIq zWk$9VpwBMIPXbc@o?x=LU!NPhoGk#4F?2;4?c>&FDWR>u`OTBZ)ukpXEZ1!d;*Ts& zG-31^1YTE72h7x()CUs~!Eu1W9S#G;Qdp7i(VnF!|Dj_UBwmQ=Gj0WRJwu0seY~Tt zSdfQ6GaBk7>vu@OMiUwJRU@`g92Zo60yyrCXDC1t0~Nkn(GD*W^vpP*2y{{Y;Gg8? zAa3n(y8l$~mlkH=uv1u&z#iIE+^0z=rpD@yz^u^9-??OK{*1q@?9~Q4OA;^pamXz) zy@Jc3w}{U(Q;&|PoV=y8A))pr_m`TX|KTsg$Y zcy-!->bp&X)-ZNY>Q%uTTW$}bFS1F2Hk0@`_qY7zAf2hnilh=jH9>M^_bpYI^ixNO z$+{bnNnG7Ro+c;ygm|TVMnot={LQCMhvz1nbHXpktp-~IER=|w1@Va$DxAb^*9f;> zPk_d8K!+8dr};*?Q*f0}p)Qc`bD;roTaR@IhCoBa;YZx)jorjsEf4yo3p1W$X~_>F$_Jxj6jLYcNh{gorOf$6Kx zP3`CF{j|O-rn>H6?R|Sj`D|+b%ivFO?Z5w2882TbW#QVguN(C3k#b0bUBpA~b}z>7 zVS0Q!p#+%&gj|_+EGz9e`RFcGB1xniEwX#4Q}NLu#n%z^|JA92^TrQA73?Jb^R_~X z{ntJA9A9+mkiq9NP^T*4GlTeC(gTRY6XSau*_{U!>`zhO4NBE&@>+XmsEH05tUYcm zH(G|-W;tX><}O6(<-rOh@4LHnvs&#ri;8XaZINDG)s&lZRsct1y!;@nLHEPhO}) zYdskyh{6PFAU*t;E^@dXvo#Rtk;T&u@=LIM`8sgS&u5VgVuf6Kyx{ zEz}BxEHEEw_Pl_52yj`A1_6teDUTjGuPeE5-Ky*O&o1me`JM18rn=en?@)3TAH1@3 z$;;HO^T#z$lcVe~HPtPP8K&xLBg_M<&LbWt1;USwpGNa~6e#nnQR0zM1p_%+L4Cjg zwUTh`V%%?;wdc{5GZ7i*2Sa%-u|j{oc*cq5>?tMdi?YR_fZX_`BYZ!vi||PCfZd5{ z$;b@zPC|LA&QM52KKVnNk}ZjBWjC9$VGGaK=^!jTGueb0_yOBAEnHKfaBvF%g)g}4 zK-IwKNNyXo)>zCovnH*|S)jBJ=L+ylL(|?sSpk090Uqc$Y5re_s zu5-@sI@kIvs-{9Sab|jsdBaB#s*K*M+LwB&+t@;n27+%UR(va-10!j?a*+Fw0v%&> z`K?aM8sQK+O=EdT$3^#4kW!Pu@8ae&0I2hR^c4GpGbM+mGveK>;)v`!2_;uC?SXc^ ztiHmV6g+TSy%_$x#{3nK2Ks_-Y=gJ2oa0P@M!xrMlHL&%rOodnO0I9w;A%<+kT{a^ z5rz-qq#r`W@jp&D#1{2Mml;xEZpA-P9g$wa75Ed>o(3$~3i$Q7O&j#UU4iBf>iqW< zbk=E!{icD&L5SWz3xUukwMF~*no>^>+u{ZPQxf)|eTO z14PE^HOfR{cI|A>(b(5%$6~tg<4&C&?A-*rP|VP*Dg8KkLq9N zRa6I9Y6%RGd<*=Z>hMOQlWv^>8Ndj@)Smj1FP;ND3c5eO*73cSly4*E*3$!hdmk_A zWNJ>;9RdAxPo#&wL*ANYIIvdt%+*{;^mS%DF-)k56jsG#9sH_p=4s54)++twLbc?7 zy*I!qaSEyuTK}y|gu|JI8cY8+cF}{Zsq-scQS9O#3&AojJ+V;X)2rZ=021LiHFNi| z)voj|hk=Nbu@8Mol-slQxG_tBC}}^$^Rs3$4GpdlhWRYOcnLOK46Qfufi2vy!Q+}} z6Ype!8Vn@g@e-yQT$CX6?mLcyHDs(H>m$Vq=sl5kh6r0TpV{KTEZxcZwC~bwFiNEt z`mHicmaYgfOEE!UI?j{2^UU*;?Wb+mL*-ekKwN8w;K@KEtA*y(*En9=DHRsy3N&z) z+%Q?L#MxHd?1k#o85mt~g-;7%_Y?t9Pw6RLcm23AOFC(R!H(NcG5O3nT4eGUj;3zI zHojXm8-JXBEU+05Xt#d4Gc&Po%!N*!U%&h1gtM0m$jg|>#ju~BpfRiG3>e0o@>rXQ z8}YrFy3O$-1<5)5pm^3{?@o%<11s;wYyuALv|`Se$=)4?Sh#F@<8#w^UKCA}oS`@c z+kr#qna~)gM^p;b-E0(hKMs45z#Tz77*UME@nklWRIN{MF&b#i-D1=ND~u9uE0csx zWWXzemF~i8$e@7QkCmkto^KpWko+-I zj}8IQ(@2~N)pCLg$pbqiKVF%M<;S%C6wb`1g2aGwDCm0a4)CmM(g678%#2JGkw_js zWX2VWXq36P=s7=o?Bs4-^ zkp_D63c>`76nB8}ioQMfYt<6)hGGW53(R;Ni`X3aq9|_E)Z?z76+j^ChBBYZOK3z{ zL&EtQT^*QKn_PpeY0L#pFB?NW`Q3eJu@%Un>x|KY9!it8Kb<#rAG_K3oN!W>wdTi^49DWm90uv4lh1-kFb)Ru#9t#`Uc zC|DSduwf_%gH|AmADDJu?^A1sm(@urg|#r2=NZsVhK*x7C#b<9W2)Dj7GAumP(Qp| zosPc?Q8S7S#i7LGgM-gM@o3LTv+ObCGqLh|99Ww9dnBF)tI2V5V@b|tY~(rXg4z#C?$y%$v=7>8QE zf>>u-TrF4NO?Uf7>D zdrO{RsHBbXP|19B6D9N`Rcf_6LvHnV%>MM#B77}PimbeQ7`kR#=z^Y*d~d=9M!kZn zsa*XfdM(Q>1g7a@y&!EA-6`YV#GmpjcdDA z=`)fG1)7)=&>=g|Qx2Ll?kOGLqy-Q@Cq>8y+wY%d-W`W6F9cD{$l5wW1kG3&4q(#>}6geqGHk_5Vx2v6EpF_NDrSv7i~coCWAzD68x92yMI=owH(@KX?9 z(JQ50ol8*ph6Y!XP!TPL3)_t@#yW?`{L7f{-lJ&!>ojETAw^12u;Vd^#Baz;fFFDm z0?8qL;9R&`nM@&qmyqe-LTIB1=v}XC0EflIy_yv(Gc5o*vW>wgA8xl$=1^$^>vt89 zygdK`3W4O%LXiXx*f$#tbo8q&Z<06?vUqrJ#`!c*+`23R7o5I7YAiFK)kAPOxKD3a(Zu{S8;azP0|Q$-+Ka(WFQVH|H39t z;WU}RGTSsBHyWxDOo|yU>(9=F{P=C>Ob$KZCv5{S#cN^#O@;{sjcXza5P9MJnEJ)^ zfEk4sWnXT02R&SgT>0Eye3l>1Ja_hlT>9GVNCYA#Gv6)wc$|86?Hp&#W}k~jl~eF+ zDlZJBoz5njMHdcflbw&fOK#)3&!UKqMN{U8J?7_Y!x2L)sh00<+-LqM>(+C{wSFeB z^uSb9H?&&mQ>)=0v(#9sT8~6xL0sv~_w#C(LP9RaT*Ap*FdX0d_Geo8whAfz9^h{| zYpUZhSGIY}qb*EwqrsT*in~-(sP@aM88dyAU-PnuI#*uWHu);O*xf2&rQSz$bXc$w zEM9}QO$UlHc6Mq`==obeKS1@MA5-~p>PiG3}UctkL{~V zX6%SgV)*$Kz2^-3?A#xaQSPzv(5F-o>2{OXBD!?L`wuw;(+3%4vjBFBXOTIg4vDc; z+K*H(ePpE*gFT{MS-||hL0iOEMK39!CGHQ^T`JHH_r4z!;e>j7ac(yuco2-g^u1O4 zxtmC!E9Rxf^=WeL5n~LB`PuvXbpL5e7smDL+3b;?4E}}k?Kir+mz+;mB61lwfY01Z zd1g=|X4OAn`Ft<6HoipSMy#Il*jU6>^uJ$3pk%^JAq+|;7yceye`~A%;%fdqx@5Iu zOh9dwN}OgSrmjdc;jEU_1l+%{FP@Aqw>$aHUS=un@-hNi7FK-m?Ssp9F>Di<_A9Fy30Z_X$n`Y?gGK-J|`k#|qvmwoM zVfM6*UVSa1EpWQ_bSa>nTYB}+WnIj8TYxR1QJAAfRTOh-2?Nj?AM4U-U0g2^i&y{z zmbLLHQQn2(aO;oW3tZXfaYieeU=Lr~jUW+=Aw?|Bv+FVS%yR;_?iGKFD7K?i&#h&3 zd;O-!gLOnDwrb|N{@p*1?#gSV9CQwj4uj7SmEvJJSRO_PIZ} zIB*j_#QuIEOt?iu{QTGHgLxUV4LB`czG#{@^!sx%DiPGBOnf zz;{YE)mwEAlRY35fV#dev&`iYul~>57lUM$M}u(7TdtYjYwPl}aLif4uLMIPAhMUf4$b z8_{%@5YHE2WN2LCsCRz!?ea&wdd83l1A}~l!lapeSU95 zGd1&AgFa{|)f+gY&Qd9v$n>B^4c{k-L0uuOqou5N1ONZzSSR=o{H=@MwO#MQ9I$iNC4)Nq(udBDKh)iO4W}0rK z00lxx=Wa+#eO3na2G3ly@{1Ith^5paMr@nfu@YFSX?@JiQ*A%71H>brF{k~qOfi$! zg?bZXwsq*mw`2^1WrLMMQ|9G_FOk62fSibF>8bRKzwMcFe`M{=sxO)LjB{T*bht`i zvt}PGIGyf@$B;W+ATzye(AG#vtR@XSB@9};la-A{>oUmWbbHf?KeczlI0o~n1XsKM z>wJO+8|g*C`_{j!P(Vk<|D#&${3*?UH_{7|d+bDRJ$;|0d~0)|zoB$E5B$W>=r#T& zdU*2x&uTGRz5aow3b0x%NsL~7V1lU-dHo>ITiW%uSWWhBm>1SACs?a z2eYS`lUQ6+t*@7TO0x_4yOCb>v!`mpNnVOXs{8e1tLi%+uX{fiEyZ{YWw>MqeJ(3a zx8(>B1R#xJ$lNn&I5!gwp}Tqcv=rx&`30j;#|YR3E1?oy=ZidRB)65{vpkxi8~QK{zn=-5YY-QVrF_)8Qs3~9p~sUT9bxP>V##0l@z zYj|QX2GN(0?eHcEflM`7$<1KNOvlxG!z4v_|RP}+$EbdJ4Qkh$#Dl#VP{rq!`&7%iFQ@zo@e+@#M zBrz8jX5`Xj-D!L4woKR?4fp8lq{^PD34fcjdBbmHD5D zZ+nAERYILi_}@~#qt=qu{LZI+V-AUxg(B&~=qhhgGTBm!7p9C_z@@8V%)Ytev;7UU zcyVrTZOAFn#9x6!gg*B;CgFO{k&#Gwjz;#E9)&R(l{)UJra5*mOH!Ct-CZc}a2+T& zKA-IwieN=JYfOlwFs0R^gZ*7fk$alqeZ=sEcMdO+nmw|I*P<-_5+FH6&}Amq%Uidw z6pN)qvcewUBd-{Nud+$lv#3}olljN$>neKNj3Ke|*q<_Y3g35_nkS2(|3ICz82cl% zcHgau%4sTuW`B!kB;{i~Qga3U-5&10D~gm?Ks~;IHcwtS*G`wl+tEjZ_vMQDzBAM6 z1OeIUqgRh;3JrZS{j#86t}A=%8u_mJXMfffxcDN&$TBTC2ewGaVv4W5gpvH1Ezju+2#r87(u7|io& z2i-*Msa{1KB&QJW$3l{om2k0!*H8K0s-m6?Ml`vnF`h(^$-L#&{Zn%W_RT@6}R9n6&sA^3r!nfZ_sHEB#*Pjmsl< z&yg%Va*bJmx5a#ejY15MW(N(#L$7K*Cz{?3QYGFCGuMxq_;_v&3q^jT5Vu~DucdE* zN6SRz8FRVH9nR_LH5@1}NL(w~;2f~dFS`t4_MZ*BT6S4C?|iXG%@LaKX-{dZO+|ia z4zQTVdpe_pOIJs8($DlMqWoSckFizqa;D#gMieC971fl?rh24Ed#1$81?8tIrMpu< z?|9*9yF^LBQdpTi*JH~Z+E7;e{$H>6@Y)`SDZ|X+?@YqbTF;)#F$K1LOgL7HsETgb zNO=eWTGH4!ws(dt7HyM~QX2V}7wH}7-#I16Qz|g&BBBY`29_X4d90tYGAwmVi!)(b znPPr1A@2%UZCsNl{1VVK?W;Sd;^#RJ;f!~#wT8^Na1(s}9$&tdw?J?F`qSjR5;tkB zl{cd^pV`f4OJRjCQA8sDN2QTXh8m^qtWHZxUw7{BPhrH{vW8It=KGePGqPvNdJ{y^z|@cNb;H7Z`r%8ED22>t{5rx5BSl_}LLRAg4D3*BXr z5&RG@NzzJZtuGu(wlqjH)cl4?oa-TUao9bJ2U)ZwTUX%5*<^x=4MUJ&mM8Qc?m>%SJb6M z_tVJTJa>KKydT1ylHT)HDfWhZP>W&t9CwYvd^jX_yYYu@hVET??-F&$u2Tts5BJJzL=-h{6|<0>t@$VUJ) zGm{dMrrocul$Rlf9_T8U&-bd^uhXAA`Sv4ws}0T9h4gXV-m2fns;C6r3uo}T(N>`? zWKEqQ-`wNZZfmL-pdM5E=i%*E=3LAd3aTZ>B~(ziV2b97^2n#tFL6ESZQhLg2M%w8 zr+5}a=}j{}tAwznhRzF>-NG(nYe+gFbmB#C`wYz9|Ll^Rlt($jhddHdxnE1Z7nZ1g zzaWdM+@_I;%|*m;uAX!8ym@@i{cU;17JFQ3J0A&%pmHJm4z~CH+AiK9rzsUY_$ILU zJH)jw@=n5O!no~)Q`7su3PQL`#>jgF_R~JJGC5j{@x0k(rlC+M0U3OBnWxcIh)+xY z&$^Gz{vC!RiF0)VCfdUE8@Kmgqn4+ce!UKwKMbJmW4d#j3yx}-3rtT1y0c3;&2mUY}DIXkFDSX*WgeN>8@^nPO z?=Xr}*quUwz-d!9IOrMEqqT^qP zz4H%re;Ab}Me?WKOl|PH^dyutp@tdp6{`#7Npf!$WGXxg_u9DJ#m9WMRZmkeM)WwA z?);w8Qh78>F)CoiacZ5dhZcjwq%k$^2wbHw`kA00HKmc zxqNqm*btpUk$PrLd3a6!WuICiYh8IFX11K_=}d?Bh@FP_8`g z{t<--!YE{!+NT*}kl}<42kHzCU?egy)x5Jd=CYuZQxdTm72hLB|A}y0l*0;|{^%r_ z`RzJO3+l0^h|lBQB*sw(gCj<5Ek(ZLkipy0);)aPN|(T(bO+fjw0qy_#=1A%og3jC zcrn2wPUmtO%aY>*yAw@hNwWfexh#Mz_=qRN;A=Z7wQB5lzRk_F-&gfD3znG`5_ zf>somOmz;llAQdVakI(K{Tv|2=2S5O0j3Nh8S%y&N-3iur+$Lh+;7Cb6iJQou9A}u z?s=%+qzg*|=9IaoqTD)O^2aVat{?k`=EL3v-#c1PUq#IAwZC!iH-GllhYeY zQgiC#MyF@MG#(Oo>4(BY8PCIt<#|G`Car%oDpd&A;PeohP4p5<=o00rP>O>xL7k($ z-w6ZFS8Shi<_wP7AMG$^ucuZY-rOhM-_k%5_8613*=NWb-u2hctp%t2vDUiVW;DV^ z-#VcJuM<~j<1wccDRfH+2vaZ4U9y^`X*a!&7U^ortn zBv%2_gR$8+CVGZJ_&Vd{(}D+WSx*XlFThkPW^=9{V<8H;*?a|J7te14J}>qPWqua^ z>F1RDnFiZ+J3E&s6|2fAe?y$BK=Pt^;$C4qXVDA)^qYJNk+1z;2tFL+yRq)fIGav~ zxX$UxS1|RoF!)-rolVjG-PkY|yvGI3$5-TgA__V8i^zFGKiS*{c&~F52Ju;l zUrza4_>|d&u}z`a`)A=5S7hHY@8OO?Xj*b?nGRRR)4OCYWvbm$nR1S@6Qk6q+^+>J z`0iM)z_WFcnRvw*mpB6R5CFp;k&3&!d)3%3B1}VWUcV$jGRkii=GK;}FqO8t8*L&c4mF z%ul^3e?G1#RvM4iJKw4o-j5WJFI3|z;5ooljfmrF-6gIRu+GsO>(Nx@*JKf8U+}|T z53tv0lYWe{slijYZX};e4X4d&xw{2C$471x+5&aSf#Sg5f?>z|rP9pZ_x`wEY2GOZ`8J@qBIDk{=p zM4Viu>Q~k_RQo|)mD&@r_d;BsOr$iws?CpRb}!40%h2CGxS6J>Rdx@X^i{0d7D-xW zSl19wfV0X+>kOA!9dn47QCcxNKhZzD|BcKd9PmTl-J1EhSNYS`TTCnU^GzCU16s5EG%MS%nqy!Mmo zX)S$iD%~e{m^XA6V?1eXEvTriZN<$3XVAk_YGfKG!|!vz9tKy>j|6J3S<35} z{hEIs(x+jIX&C(4D#IcB3P#t1$voxdill+MxHJ2}!`V#h{VBR1oR>nXm?%i3(9xB@ zEWM=yc&dUr39*o{0ati3id9HRlF)VC+YlsMvSjXG62O9p~c+{(6(=kZk_@%)I zoD9r+BpE&mWh$jF7^5MdAE7)?h3GkdoblEww9W4l$DF^U*ISSVhWrJQXj&~?#4|6f zN^;NxH=!b@CZh)^fIFf}@bOJz{pbM?T*{>zVlpvqFs@7ob*gKEe>8CTW|)p4_s412E(*>TSciYXHk(K9QUdsGt~ zSu>}vE^Ed>k_1|a^0MQz-PdThYsI{G+#m1L9(Fg{VrX1}VV*gfEeusEOT zvzMMR9P%@pAs@UMf~(9)%6`j!vf2K+$dh23UpFsNAW?B^kC|@mQbsGZOZd>}DrI$T zjNi%P(CS>51Fku$_?4ZwKwYK*H4XntM)!^Jj!@Z3^}Dv?PH%E0mc)|Z)QD3=>?M<9 z(;-#xUTO8@*MBjNqL+PWaXa=>SB&F*jPV-&b|}j|*vp#%7SFg4TEocQMWMRgWlV(bG5q z{|4T`xw+@vsbh74*JyDB;EH(n%F6g^D!=OoHV;Z*w^HhAM^P8}7u0wsbGjlc1srEJ z+g;jtKxP1NPM<9BuLx&Zbsye#eTeB)t+D=CE%0$3kuUEU__0}MIkcKB*@(Tka-+n9 zM=TC`ObeYpv+4S>!oao-pAXxJA8J+jYA{q%^=)&$r{nR(k<#)F?M}f&hI1W1Y0Y0r z>STV^{khsiA6%_2@BBogtW4%56kbB~8z=zZA=AMehhvlz21$`f$ zv*Ick>nx?_-jX)>w*28))yPDt$G~f&?~~Kd*ag1giBNvE9Y`M3c7*1u8v2)m>vw4N z?@m#^y8`}F1cR{xTJjDD`PyPm5$DqGS@JILxxJhGdxdG+;ktVwd3$1AdlE}~Qsg~R zN404(!~WUxy9V0(xqPY0U0fH*3o40Ra^!tYM!~SvEv>{CHAmx@^Ee~85A+@D1mjYS z)qj{f{;&-BVV(EGrVDM<^@HWza`ERMSJe+)9S^UE9J=KldPt)cYf?PPhrZ{I{MC;F z9FKxRjw(kFnMQvEFC8gv9udwRhvx2tg|NmM9glqev{81PKXjzCavUhV?r(p5*Kaqa zizzMSB=Km=$UaHRa3sHLEKmAp*>e@QlH5#24%P1~9G8PalTPeL4Szn?Z%EW_T1spQ z`SoG^i`OHE&ZS@7!@nLhANMXDzpnW-^yk;hyx%>;zc~evVhyZCx~5qDKM?A}G^;+ zN#1|*&FRhKGl?AoySuI_FxuuKiG1JdLpf*WxmqJDZiHr?)8{bcf`4gByFdxHbxV5A zF?ku@2$+}sW<64Tlkv2o^>A(J)#G!QeFBb_B`K|hZ`<+Q{qQCHUUJkT=f3aCX8t&{}ak|1CiOgP#3=6`--nV*gWsZtz(A zhXDO5?#w>~=<#yS+5f0orqE=wAY~ac9TL{>FHP<8bGH3ed;aZPjooZ~p49^Ow(AzHda=vje8w*K>kD zm#ydCKm4+uN1zhh$d6#NnNW`sD&HuKSKQnvBI=5LDdyzY`(l{pQ2yml5-E zQyoyGWoj5=JMauAn|p#$eHxi<4d|JV-jy>^wvwC}B(%G2;CPV-OzMfoJ^lI7 zb|{hG4uyrf=&rcr1|`Bia~R(y7Qq$;^qUr)Ta z*8e~VE8zW3XkBmDyX=fOO909n6vI0qGgpVD4}&E!D&qRchG(;^QzTM!~wMPyWyO~g#?!Efa;M?Z$Hnr0@}r`K{e~kFfy=$cx`N$oU15Ig{W{P!|^RlMfo-gb9)W5F}J~c6|t16*9AS zmcx~;5sIhb6`=@UsgG`%ONwyK$bFYO+rUa!A}4|z-scMnBaoG zt7i}0BKgTABov3%q#@P5J?QhR)CLL(Fghw;$gVa9dzIF82Fi);(Gjd2MAKwNV8Wsc zlj#MoLMg(ySV{1Q&hemUn`&SX9s%Uj!7rM-KzI&CAD7UUj>C!;_OZ;6<#~afVeQ* z>i2b`Mi^{K#`hS|I!&_a-B+J7a`ZomLWC#5T|U$}`5a7aO6bHvXMCJO;Zf*K3UUkf zBQX?gyIi@LsuT`iey}QUw@{fH?=7)&?#E0NI=-yAT5u&Wf6rQuk_Kq7Ft?>VpZ#6- zTG_~=(Zh7jT-C5<7|G*(`YZ0UqDWqlid(~5Y(1^{vZN(-k^W}=E#4QhB{G0VwO`fD z86fyZdHI6_b_N3or{=(=NCv3Sp>@UtUZKu0$BS0~-BmVNEduQ5f#8UmHqy^0d=BHC zy9mqgWe>+&;vQuy+_QcIjA-HwX>HH8PhnuBhWOM(3%Os^oadXTgA51HhUXMH+osMe z&wABdUpQC(hFvPruqlZY`Glo5dWMw5)X*G0ImqjIUi0~(-Mt8J)B=@M`8^*7zi5jm zKCvZ(_M(j~qyB07H@O#9xsF=<46FUq-z|K;c+@uXxH_Oze{s|1==se1>Y$c)i{I`Z zwJ+1x1i#h)u$Ot%v0+$qclzCj!{mj+yX23qa>D^zZY(%WI}v?Z^ObkaDs2s(=63 zU#gLWh0^6@%9Twf8(x`9=1(afC0e~Q8hk!BH5%sNx5@HuN_aNpFhGd+$>HbO=3r{s z2Vd(w7n|;Z)AqSW#p=3b|uD>?nFpFm(D#I~)oYUG?x^sFroWAyOi?zfHi5I2L-4-XC?6I9T9 zKOUzhX@ZUAP&1aC8^oJ-tRhL_XJ3PHR3ljQ5@s8_%Af_mBaD%(ek@#oIsJ2aOnvi< zb^+#FC{>^0sY3Ks&q6`gB0wb#nxqGJf0EDEbsRqGfLNp)BvA{2`81}&fZ1zYd)JZJ z&wj-PH;Xw=mJ+^sgC>U_uf0Td{-}w{J(K3xLl8YFs}Cu{s(b@7 zb5v#QVPmS%&&^C#I0gA*(ODw0h&T!#J{$_;TaOTpf7#S8G!F;Bp7(gpK~hNqO$<7_ zQ8TV$c$-|hhRK4Imq2Gu7P?roLJT1-Cb#H;)7mPZq8eOu{4{*}HDKPnaBqq!e@^!j(=yVXCg*JMhCT>NEXcdUu(e0dv| zseJFF3&tp6;N|9YCb{pK8wgxR0TV8Peq@ECkEU1HJ~oEv&NUdKDYuVZQ|c_poY~os z8Cm9#xsnLiR5;+vJ*C~EI(BO{kVP(DEEG3#tG~)VcWsFkHu*WbbUpKBCVTOw>fTfj@)ba`^XJ6O{uLok z^bgce)%om?h0NGb{tO3Q_K3SOqM3o_*de^*%Y6g4PUo5Z9?}aM#}_6svUWR!LuIrok&>u7_~F@71!KOl=5H!!|lFTXMgTQW5Ae*MKrdTpKJFY zsnfn*p^Lk*Ch>(VrP$YEHoI}wgN1A@eXphN?mlv&EBgOvi&@A1+phKOLiBF|-v8Kq zjloG{^H12$Ka;DDR4`taW9fhP#yqLz)1qL5&AdAHEy5(SXvGyD*MO5oFeHgYj3^n+`g8AWh?OIGH_D`X-SA~Yj#+P>r^?8o#dIAO{(G zlIV~xT$zbrjg%W0Jn8F8(bOGa8_rjMbl8E5GiXlro|4QMDRqsYP0kG1V8(ptEE6m& z_EtXc^Sn~dr*V4I{X*U;zSBm)#s{9DX5c&y+$uub~vkh^nXv*r@)16jP4jllA8 zZdB|+D*}VE9Ygq3o?ZH2^74zgzp#2ED{hJ*Y1QE&)o42LI%<&GNsFyXAW~&g@ZjC8 z(~|Xc+$kM&Om|q2jZXuN8277k2$_Gl%@E46q{aC;CE1?sSiBV8u@QvY1=-V3O`_6Gd~*ab+sG5o}ZtC2~m znNR1b>NXk-hjojL4P}1|5G5ENv(BdHA`JNnXoR=_yf=4}7R?1bzy}j`IUQ#Zoj(R+ zXm~0)!GGjUNW`(Y()_u-Y->QRH`Y`G2~7v_mI6pS1ReR{iI#8m&vJlJ%+*_2E>vGu z>8Dy!ZqNeM_Yb-Dj?Huuy$Q07Lz?fLeNF;MN^$L z!V*QA#B{(hvgU(wyn2D?o;8?yF1+OVu>i2+XO55R2RSCdwio3_`W`(@W0N4c^!9|xb_Mh=}?Wb+Jra(ARHYTaiw^XvK13~8$OHFU?#vRKcm z*n}2{5NzeYbgHb&6rwGiyVoyu_`9D`-?EJE>AbHIpZf8VNjD{N`QWjfkY#g?khJQN z7Qe-PhmPwZnIGD%92fR|1c^!~6LM2;>Nh>RF8rai-R{yU*UwSKPt)ArmF73%o~2;# z>!$klK9msw|MyeYghHIc7?Az<>hKrchMD1?(Gb2mGEJke2DT4X^+#2`fQzubzIhPL|*T&N_!pf;w7D3-T*`9Vo?>PMb7P}*yCGO6v0-~VC)^@LiM}QB_Yscb zh;ELYIeTl17A%&nGQ_-pY9dzBqSMTqDx^yF?ly3qLQD|{CG&va6K>ZtMH586@d zn@IRM&0>kmmY%0u&G`T;jk$9KZex1Rd<h4@iR5@&1Gm;GjD6z8J&tip=$O~!O_dheq$7L+ zO8xeG+(g#}|8u}~5`#RRNk=fy!^B1B8PGzV^Ae6N<<%F(l6tu>%zRD>gB z7L7zcq$o_oz>i_tpm&p%UG@g${@eOTU!|yzcImXE$M&8_21RS# zJ*^k$HGiC3X7%6mzO(nL@(0gTRg&)jed&NqET1lpEr$JFx8ziU(HZy5cu8{_rbgsC0& zL;bKXqU0u(x53z3{oyK}!boG~AdPSpL+*(lZ>zRX>9*#1(Cup{t;0qn&LF>~eyr&t zz`H3h(M6PtsW(wQs|Rc`A@TbeJeJ6PXq7E>JGoOZdHdic3v(&#sJm2vtnpgWOlYRR{B zx~ZxBTVYsYy*$qvn%ud`BBb1eH-Na_!1QgwoVIIqsFd6uSq6-RuujAbo4if>mu>~- zz;1vayWW4NMgOAHG~Ol_yaZd{xPB|h6ky^Yl2juxenq{BysRD*BK5qllDoEMJz48Z zdjIB5oK#G*ft&{+itdI|V?ZiAE*qDUqLGVu$PW{1bk{BHa-B==4&XKB)w_2wfGb7B zH0^T3&#k_ulIaZHS8<=NSZ-X&aH176+-&f+%Dgd-8jNeY0f|O$tKH`ww?wsFO%}pl z)tAA(lvgUVrv zh90CiUVnMAKVl99DDi2K(C1?boUqzujP2tCYjYMq7C@&N2RPkhYuYddvs`?9HyCFj z1Ss`IjwAv?P*Gnf8?^+Zf9&);xD7oDTsm4^9 z1U}0vX)=4H4u06!%mWC&q2!^-M2=}OvCd4qjA`PHeW>1gQj{%F8*8OcH8POgjp2gx ze)4L{RmI)Ge!#3FPWT_Rr$V5_8?f5<9s7{|kMgTVAAM0F2*qq7XWq3$e&kKcI$16c zH)LRb|8Hjv+N$&}ed;mt$i5rp-pOMvdEgNkdH?e|LuY5LMS zKkilOuwMe)LRwvF$G(#+t5 z(mVg;yuW512LHnYLN{${!{}Y@Kw0l!s`O3p>;B)I-TzIMfsyI|`noaEa8Lzs+nL5h zLL|9*v2{gn6KKvydEKZuBPxml&?bodPjAx^YjOi+heRqvMKFM*7@%}ZL+pk{yYjS8>8 zj<@qS$Y`jV7f{ID+YJXb46^&DUrvq*RDSwT==R%sEXDgBFU6m6RuKhWLjF7kQ4kA( zCsw96N9ZTwf+uy3CT>$zr2%)g?4untjwe5{gj4wm!=mVMq`8QaGp!#Y_WOV2sMF%2 zxH)BYl!<5@_=ta0Rg8AjjJ7{8HiyHgF)FgVF?Jf=0CSA0X4>^6RT9ws7&y{C8TAuk z1ET|CZNe;Zr`Fnk|GX!t%cVWzN8%0SMpS8Z5BPKsdlA>Jx(x&jn^-*`PXJ*Ke?6$Z z1UBU3M9iMCkVKeb00J5{SV);d;Nr3=o3xC?vsTeC(QGi3Ae0sH#*&u+1wVTy zE(FN1L6gD6XegATw+dHW{@Iig#!S$_YS@fi#X$GO@mW`zo@ih?Xa=uh`LYO>Zc?@; z{5Zb$4B#Scce>W{%Rz-N9Ar<(lYU=gg;;VTB8*&^(x4CXGDLto?-5S=9>_X=0Ib?A zvW7rt2WhxJI$ze~C;ZMRPnw6D7)wH$P&?OvT8n`fyt{8qQ%7gzwmXBb(_Amog~&Yx zco`!c#nE^c*TK#e;UaU1B{@SG=Vq?H>eD~`I>3ohKc9vx-O*=1n)9<_O2YcDK7?Mh z4-R;Jp~oOU5FBxEZxHR*J54o9$!o&z$1$e4#%%jRTrPr_~BeFEjs=o=6I4Ov|2ua zn7olFSzLK+Vi$ZWgiI^F^Hd-90gx<)Dh}Th{?#4{0X32I}dca5<7o>y?1H) zao>j~^U3|S_jmHg_+M(%J_LLn4~vf&v$tGjE`4!0Jt$3c%+>}_7=)W%Q|xpjMF_LJ z5w=jP0ZFBU@z#XX81{iG05VAW(tib?{3%2!O#b_6{#PnO!tI}#&1|gSYF8*b>^e&= zQ-SKeDlZEj9BElPj2GvPBLQ$iI!15cQgGept}LbbGP?{+_q#ld;}FjPQ>kh8HkyNO z-~eq(x?D6jkFOOThpIC--n+PGH4)-)^OVHT`xFDHWk43kh~lqnl(zpgls2xQf9&1%TmSSHLR^*S3y#Rzy5ZI_ix!K@HFcFgi|6g6*p)U}RP+^-Rj*!(Km_!yU-^nYeolq9A*=hJIru5Dq(f z0yv-fn1H5dbu%G+ByODLz4_v3N!NQZsK5?|lEG>%yiy$V7coOOA_Yd8HbS z8-KEa){v#b)asbOe;Nz65?b)d?8??tT5Z%N8kX^n9V&{L=X+q|N+-+@Kc=6U220V0 zpq)K?DF0|DsN_Mw(hE480Px15H50Bt1#2UNnYhiP41Ub)C1SlLF4Ks2OcpH(y@1Wz z+L0=0`UcB=Zk-Wz^|FY=G>;q=-W5m15`$ck{lZDxfSzCT$AyS>Ox@zt2eT{n#}&Y~ zlc2vj#7jU<#)(?)vDL;EPJX~a)6GSL&L=EceMl4{A~Qc&6`y0w%wh+zQYSYl>dpx| zHJXN^Nq;>9nENYEKDqM+3UM89aT@IPSN?NRxb$Zk(}FXRnmkUG9J%X$lk)`gj68K@ zupTPX?TL%I4{Dr_?A*iNX3?XYl(Tzt!;`Urg*(4q7%eYZ%02;ZcfE~nV6pxKee%8W zN)&R>xOpvAvT93+B0Q`t=8vDU_gFHNW39yUNA^`?j16?%yc~ zPMcjhTZzsNi1EQtD(jB9V`+ODFC^u9bf=}AbZBPTB2+Y(=Q+kCw2EW#Bp#0`lK3id zhawDW-K-Hl@}2$O1w&MGcRex2H~ipLtmIa~rG_TohqSXfm+A8lwZacB2i2?aBOfr)^qhZV=XAo!RHx7Tzy%?i);7ugM_n=ayGMUo-vT4( zrz4C8vPFSHu-3g9joU$e*3ZPSK4l^LEq4`>t-rC%G<+E@)F?t}>#@4GhZ{NWp|6;g zPn0{gIKBUgkF%Jf6jSSuV>d45>8SEg*a89)Y6!iEl+Xl}4t795Kvb&IRHO+i z7DU9F_qzA9_p|pNXS`#abG|}GvhrVZ&H0;}9FKx~)2Oc8>Fk}Z{X%YS1hi)_yZKPg zDv_r3*VUDp?~r%^u>slAoQ7y6Bgjb;muSuNoap|mnQ%I144zx3CD;ChOSfo zp9jeVJrPbod3n1fG70%2=hee3+dXLywSMEf@C{^?f`fF2TG1u&lRAL9oLh)TlEs~8 ze0J}CBP9n;j9t}iXmva}362a5c`CJyC2NZRaI#UaCxHk(rjVcza;#BTuTMl#*`h%r z>*4F-eo_DVHt`v57Tc7Q?Gf@|=n0?pb;W0PuV3W-UPQ-F*1losuSp6bSUV2q`>1AK~)W{Z`|8Rnz>ecarv@n(a)M`3vvTSU7F~cMiyP-{N4+XpCZah7; z&)YD-*;8HH^){vAPwUSN{i04|s`_6IZs#`4PhQ;{wJpDtp*^a+*VnS0wee~TA*}N5 z#Hd}h+h+UB9s!2~v+ZX-3n@6;oTjKePV^uOT)_eecSp&e@to>AXH@h!H5M?%MRtc_ zg7Ua~DT75*ytS)RUhAE$6LJ*=zeTyUeoTb6bjcLB(+44$QzEJPW)eMu+6k(P^+EXu zCJC3(MoUci%NmmTw+I~_jcy;2wucXlYCr7`PqslWPm&h*R!f*wxI1{XWMRn+ahdvs zL`fbzz`w*mk-;F#F-{0mSFyI%dRHxo*6ZcNG@bPm-g^n@d9p7f#+l3`h^i$VfuC95 zldLF~b>&}GWB;F0-IPZjGaI>`!yv60s$RHbv7GVCk6C+p`s`up57!vXuh z6qGGJ5hIAM!72(Eb?7UPtUELaKt&yiOOU}1Dv!vACB{dc9A&_&^2mzyej zE`B@kA5NX`BMSfQxz8%Q>$+DdeDEJp(LF{2;%W?)TF9*k+DX$0j7n;S^_5#tD|H?ZGT5aO_TSo(n`fu58uRCsFj7y{O#0nIriz5sVAo$D=OU)@%%0n z6|J(KxZ!udor6UJ-e}s*!`j+^J9TUy-Y5Kgp%3lv502bSe6f17?cH#k5M6ZaRk*=s=tr7JIXAbN zX>07s?z9fF%6?DyHn;fb(D%8IcAqI(?B<-qfGYow$I9~z{mHcN%uMm<9p5j#PS(K3Px`(5Emo*W0a#wqEy5>R z@h3$m7cvMK=c}I3=l_bDA-_b62SRpJHK zm-&gHD17E#W`^Z}r|`<(pk5_@hn#}iKp~clzx}r;&e8FQ(gkz+OK-$qQ3r zEV}Lh^;FkeeV?+|rz)UB(eTWZHwCvT&L$|VPc1OOfBlE;=)$klIy|_nVg084$G#iFA)HuM~6&N7&LHe6@=A9MsMv5{bEIsF~s8jV? z>1e92AOg8tZpXA`Ym=p=m7?^A;%^63`9Gc=7)zE6nUL6v+F(l*i0?9L=I4ZVA1s>c zU+(eWX&mgc|JGZFJe|QIml93i!XFlxFp^$utDhkIyS2}Ra$X{$At$~SRrdo|h6(c# zdkrf+zVSf9d%qaQNKY=zGHG`}zeOIg1R0QKyF+6UiG-q3VZUXc& zgUKpMGyAoV?YBF`{-pRwwAw_>Zq;~wT)-Mn5a4(pB_B%e%ly+2OL(kf8eQk(HtMhte{ruL<*XySr*B$vb^!(nBuQwRN z_1-&drg~(z8k6kmeWe~v_3z(mVx`s7m2IYnJhqziAJ+%$do=wdW~-&NLCscBZ)T+b zO?8!BL&%{=GtX{4Yd&zkAvDltc1CVy3&J=xgpY1Kdhx^H^4;GJ5tnV|X82AWgu(u; zp|N0SnBzaeNB`2$pe0)W-%B(^X1;V^D`c)_h1cjY^;+36`4<%)m0aqN&M zZ=Hv5EpO$sq$A_eIdKsh18~~R@PXUZFpsmL{P#$2pZUjCfN#c@)jqw_zMc4mCSe$z zGGWK>wW4p_spEUY?W^9s?^5-QL z-FNa(j}UKbvc~d};73Pxo-&yeK=`$HPHyay{vH%In{<5fNCAD`Yfa!X4;Q`YFfV;8 zDJKhL^?vE9p67k`vNuxaT<=w-H|MxAr#_hp0IwelwP~sU2q>LhNQ#|fIKP%Jy zTXqFmhtPTA3e*{bQi`KseZoj}wNu=NE}3GCJ{vzKsj@wm&Ear!EUJpOR2{#M{YTMRU6jad1IOhO4Nt2+zd^&jp{Lw^?VMxPRc7<~Fvv%l8#hmyem$|$4nWIJ1%f)m6 z!ozo!gMb(!9Sj{yH$@w(m$rbJJhnQ6tP?v2T_l&hY?t0kAu43lA(nb~M1>HNZTQpq z9@y%)lidQnwlVAHyc|ZJ(Y}>XzDN7-n$T2_Ki+?!Xl2q0AiYV6D^iJx(19@DBpa}e zG^8C9{anDBDWnfw%aQsmq*>bskDI(=xXT%mK#=HRXKpK0K$@fsvz;dBYXM00;}Tfl zVo3r(OZCagawBKb3~31LS3_i4?voP0MDU>!QBD#&_K4r*$jCAxe#(9|e@}a#Y01ra zf=$xCmo<3dX-q;8P1+nBWrV|Ps_pB<&cLW?=OnCnCWyX7+WrW*^XpQi<>_$9wkNF zr5*OFP$2-@S;DFjMoV8~skP-XfHnu^K-yi)4Lm?X#|2AGXxC-zCUN z7wdT>-J~8Bv+L+a2mf*($@;Qv=3(ExW}G|q37%6gk0;hhs@3vppOsNM+dg1%nW`Ii z2y)tOPd&W+%Td!Z6O>U??t}Qe$(MfGD+-@sZ(@(LWsQXKMy-{0JxfP;HaPz`@X`PM ziTovhz_v;+Z}1;ach96iEP4yrmNXk|Tq}Q=!8ZtyAwb$dmME9MwT+2|WJ8a#;kgatTUpAQK zeY;ru(!J25UR-`eL#kh3qM5UaSrIXkfYj1jceL=mIlb936Mm&x)jRvv7uUOE zceIDQY}LArNml~o1qViRR)=QZ3t#H?TAcImAKaEac#`DB4~@IE)t$UU;yT3kOEs?H zWQN{xGhuAQ`tI&|VR)WiHvmf_3|5Lii=hAnYjd^3lBEC>fkYrDrrS%Sqxc&$kBJ5c zvh-u&S-{0#1uIwM9m8P2DOH#XL!60)3L@C88)874mv~MpeD9RpIc^RPFe1)NkOPG% z`;w2#n{`wi<#kccBTPcg)|aI1*(HE$I#d%{*|%M6)}BiDH&aLTLWCs*(0kso!Tl)c z>>=(?Y_PpNN|?%CnB3vAcRkHBmGAdbS0e4Bu z6+0~6?pEc0uOCz@or$tVKeOZd?X33y?OW*>{umLgD7F)0VD#S^i-)1vS9j9RXY9 zSm?sE>7OV>n3)_U6V2%!s-$UR(?T8@PI>`yUGV! z*Lp*L9dNX|f!sJAwe;&tX)MGc_&(z$bCqx#AxC<5;=`1gfQ&WylXL`@9}rXhv)w{L zF}h@gbmsPaeMyHMn7Bwhn(TRGAVT5_8ok$}F~QW0t@`t^#znI;PuohLUFGtZUZmd6 zAc#EZ&P?r*92K+%JDsHe2xUZU`^h5Xy2OQJ;>8iJ(4rL>_PPBpeRQrpP_|35ezh7284H? z8B^VF(CivD>P;OW<#yVx>c!o$Q!hs++!GpNQ~4{OtZb91*6@Rj;tEyGato^&5n`SG z_$goJRrV;&0&^P|ortqO{GX!0|BHz?FH~*#kn$w5@JsQkZT0@=gHNJweYx@}wfevt z%F~#cFD2W<)%%!ao~-}%NL3KB81K|t=4tI4J>a$nZ%f;E97J3jtsaf#qW<`* zhzHh1w(|luv?Xrgj$nojF)@k+CUj4K0GtVA@spTiyI=LF-rR z!}z&%5gmn2v^2f=((BnZ#&t?&71mJC(dc56zbSqk`eVCNb6&Ldc{n{gpFd&ttk-cg zShU|_cc2E<&lpCq#B&XW_XG#MzCR$)yDg z2~-lz?>mvN>%3k;UXjTd93-QPRFoMOLb-YKQBvo>QKKSoCwD?*xAK8g7XEmdIFYwI z0OXa)iD|2eHnt@4w{Z4LJ6!j}(c>iva5;y)!L4ItVm1aD0f+woePlty5j?QEL=6NZ zloSCrGQJW(%^Ma{K8p6DRBaE^pXw74Bmpm;%34Pc^O8*&GiQ%ATnLy`kqX3;iBF>R zB;(yczdtHCVnJB<;bO@`l`ezzf%Z8<)COe*IX%fNC_>3Kjx&ac7+C zYl5BaQCL2|Ye1Joj<(k^wQ^>50~uf7#b=U?tfyHXN(V0Hsw9})Bfopc{?QH%rP$6d z8K(D^_DTWQqe<(njrLCEK$nVnX-OBQZfxWa>u*K(v|)d;=Ur@OjlRjVXZqcrib?2( z?JOC{nl!9?V!5*-5_;vvB2E*44U9dRoL$w*WwkJCt(5nqWvZRouMjdpuXH~aciPEjX3vd zNGDSG=#vq@iJ5Vu)z^x}(P$12qsxLR3pdii;)zcJ^+Se~Wt3n|l3w)?do*tzhBBIt zf)PAP-DD+`;(ZTpLOvYj&p+)}JDgmQal17;KiXAH`h5Z+Y2=2y7*@`PGpgL#^UP01 z$0IWLZW#PXL51Ww_QH*epKeefd?EbCL%r?8bj|Ra|lL+b`_rQLL;=x61ZkE1*o4h4lM0KAbaJ08-#AeMA50XYpnc_5rLx-5pWO7tpGa2n zkQjHbSv0FEZM+Ra!rwkkB`o-ndcXl={xNj08atewQ)(fy&bnax*l(z_+Wf+*d15LD zceIUSd~zd8WRwHl+W)h=da^;D&CS1Y-WQ=(5a+3(+`AB+S76&hjfnD; z+nanR34+)H0MxBFF!K6FERy%nOkDHI!%Nz`6MIj8F3&Cm>_Jv@^J+Lmfwar`ncIUHb!EX4dUITZgg?{FSYLpx*=bHRjF)UTsc{~5Rc@x-SR|MQUR2QZh{dj zJHCv8wX;8`UFLNiWMuOp-9hI#-Pbd-aFv1fr#ml+!9Pj+hrsUhKKr0rT8u&y+lPNY zG}+fPd<+-P1$|FOh9z*{AHPhFL7#~AoN3sp@aqnP@;sJYb`y8&&G&b~hYAVwUS9Mm zBgl~#2tsZxpaRC2CGLQVDHyBrDg+yDD~^CJV$s>w2$!HT_@me@8?UW9n>&q;;D{n_ z-~=z@VuVZ05p_}}$0PAYn*C1>`~3ski1P%yi}e>)B69zYc58qJtL z$yl1pA-J=)ZrvbOU`y9bAu@PGX19^2cFQbQ5t2<;+Z%)VbltBLPU4#EjK@~Dj+b_S z#}qd)LoYD^1j}XouVU21m^5KEmyB78n03BW_kE9m&LB`e`xrq=WH-JPkj*mr77CTD z-m(h_Da~n9iq`Arli!PGd~$Uv2ERY3jXVx6MiqaQ#Zpl3%Y|*x1S}T@M+NP$b9q2H zs4;SXx35}2x?Ue#)Tj*PAz_F-;P7%#MfM4BvHkH|7I>x)scQ7?P{*BPnetI1XL-bI zS6oH^ESn_2lmH#9!i*>&%Id*-h4a+OA!FTM?*FUk(UBV_EYPoM^6QX|lQq3qU^MGA zOqBQb^^Y(17467uIi&+)o3rCqFZU|}z8w_7pH+0B<`R;o@$RtowGr)wUMam+B{~5hg`dtM8skWI;fv{C;cXhA4~q4s1RMD1jkfOa*tcnWBN~`$!PZ)tIDbaSD0G&j zBj5;|`a_m#aH)G!0=S}xacvJ`q8)YJbw3RGCz_tZquUht^?34G*9mieS^Kmdj<3%> zsZlh}ti)e#5n=$~nUA?s-Fj`Z&MgxqKlL^k1W+@ozXGWt&su`UuL)1T zeRt>vN0KH#5Zv&05*m~Jsr9d;XWM5or&}$Ca_#87F+!XU2*v5rvCaEQ^6km(;HQnM z#4QgBh+IB4@#F)qink*@bJF$v{9PO`18N3)0u_9YNCI>r=)Phx%`-uC!1)NCP{l zDx7pE3H{0d2G3GB*RFqPDAOzYjA%AQ5ND*pND|8hRKAgP6hmbX@|;Te>T+?ER@6!? zf)5>Qa;5Bhh6%K=5{&OJsUTgppb}-xlLl{V2p8CT0cjwvOFWhJ=fqPCm^}*^F;RGU}kOStv7G3a$9-Cf#W^`*9d=7`50JZlyeb> zwDMLX@wVA?&gGu|8U&L0i>;QVIlVDqo_$dLgWo5MI=@3}5=&2ucwi_J@NHYH(u${y ztVn#9R;L{_Q$Bse1kis}(L4muRtm11EP{hPy0<<)xLNQsqr*>u^z7Cc92n3ath%X1 zq@@lvGLd))KB4zHjm1E#cP#?w$9d8WDhI z;i@|V*k_UmYP6s8{n4LaCJE*<9~)sTn8foJZIHLdb2VtSD4?Uo&M4>mB=%Xvo16e* zJ$Al~IE(ewak9L@RsVu#U_s!4gN6J__3!-+owO5TOM+<}MyDN`Ve7b;BWzYMJOz-p z#hIKJ9owt!d+m|xtGa!{%gp(@aA0FaSP0!KV~wo71yL5H|%+_%c68z@J@bh+G6tJpD4w+}5-?w{vRPt5cUpi07q@DX~pLbk!+TzI) z>-`1`9UFbPtVXfNbZuUZ@231z&|z=w{U*aYHOL;isV|98>;4d%uS7QHjGCf&0oY2# zi#U-1Vqw&q-7{v0eQ}};64YN+$n++j^VxZEN{P{u@_L=o)m(D&QzAC@sMU<({=JlP zBO1b$$PHNDsR<~ak6oR3PdIh;sI>59sxvda-Au$nI#f>n`wrumak71!TB<05koIF= zds8Mt#UQm@mdM7Row{Vrppu3V3wv)65_B9{W+$|y8Q9Igq8SJ{vT(b1uWTfit7fIg z&X1SuuV%$qo6X*nxcQ64ohX-e;1ka8+%HK9t0xxPH-$>3At? zs@@>x=_!{bC75xZ70h}p7t#<>AVB z4UC|B5|P3)f;z{2q2}s6c*Q-Re0nc4b_K*6W{LvVHwLu;yi;fyPKMO+hp0Scr3hcLytEe8}~-0fz&K zBD}@S8ayRp(gaSVSf>~W^BJr1hI^fbVu0BKbeo=peK3ALWTnK*2Cze;^6Z9gUmW*6 z4D3+_;<+}p@sz``R-5!+`aqnum>YM?q|v{0`OgJ+eO3Qo7U_Zx>>pP5 z51!9hH#qS#r=*6EpDr9FN9vW)&pMA7dswJXz>baJO%5lHYIAfp53BS4`I2&e9V$hX zoa?TNk5-!I*&WWOn(gt|*J&k+PWQIeh)E_a0z>*1*37aMR_#3sP~c6%=P|tAC_5f& zx>G>Iup|M5%YU0SV*{+D^RN*WB`91F;dow-{hAIOGm^oaCbTZ>jN{APBbE)H%q=x( z!1m=@3pVAxH0`f-J9_SwML>$b%*#NG^$v?(VIA=o@%|wVfTM&bFuxX9wmHc&o(+DL zWSDNj7t4wZgy|V3RAH=3v8-gsQ&Vah_mC%Aae85uEr)8OU=+{bb4+&ngj}VcHpqtS z%td^AT3A1s1xJfq*qWx)&*L=CzbA5pbkL|Zx!gJD9YP?x1Wp1anhReCsn{*49+On{ zD=4{&l7SKjD)@D8R5>3$7o-3TACDZd#mG^9=M0ne))rx;A`JGqHy9ryT?Ef;pY7l- z**vLs>Z#*JKHX5$MHLZk^wKY)HdBtf^NS0i$2hrjP*op_t$6PC8^^xRbr>t3*nD0#-lLXp$ zu6V2PG@Q^8iJ2KmJgBu)CeG~2?!wa#tfVlj8+hZfq8Y;Li}`KuYey9LMv^77Ywv}C z31NJa0K>K?E%$tf$H>F3(B^h0lz!lKH*g1Q)dg23}QNFQv|Io0Of!^sn_yH$v)m-mY+MG84*9b2wUj=ZB3PPWiLu<}{yGIM(O-z^S* zj>oY+`(cDt$^X;hfHfCarR2G6u=DBIVm)`VwTRyTJ{cilZ65X&+FeQiwY`EL760{Q zG-%z&Dkr9ZI@WWmpN^6|KZH8Mu_H=WOpG9{muxM-$m0jF09=Klnx-rd!dRRfLh4rg z`#IG;6c9}SU;w6U@$oEwej z?G*-97}$1z)vBAK6E;hocW_R ze9@G9aSYxvZMI1n9f~O?Ztjfw8n!ik5xJoZt*dl#ImhRv`8K776h>8l0l# zd+qSyh0AQY;oQs{gj5)*%~zxkorO9LQ}wuIc-9&1HnSmfE+gP7fWQD7FMe%diI$cD5x6x+s)@399A)0P-`tsK{ecq4+d8&mCH5POL^6k!5lF% zdU+t{t;711xjhYR6F|_!D=8uIijtPe7vODHju<8oxig)I0tFn`;u2I3lPPgQ^+5`= z&+hUq^OF-^#$+q&zrue;OGtEwA$F5;p5p?8%J zP%}`z)AE8k0RxgAu}q6X)%T$JczBN0Vju3+Lekqhgpp(76AJzJ7zq;(y8&Oh>o}s@ za#jknt%$O&0wPW$U_We3bQKvSS~pfcwWHtCFkdswVszGYtM`turFq`+&LGGn-PP{% zPF6I2ScD6uhx$h>=m zFV`3(pHc7nJHjbstVS>vrGBlr+}virw5Z0;Q)XBV~uNiOnrt<+7_$9 zlp8UE*GlT{(bo}8BKOvKDH8>MKT!7dDY`a1R$ZM*Cp(;=dHu@DJx6(}o3k*!daK_2 z8b%VY`JzbCs>ew>ZM0s=u42H31TVVOsKnouZ`oOBju%tozla)pMIkp=!w)tDI}2cP zF64`)wq81*k@f6i*Y?#c94omjc0Ll4Vno+7^`yl8%%}R~6KqpWC1G~wv4-YEt)?Uq z7%*-2h1K@;v9;ATUQyM-JPX=b<_;g(ABL16m%Y{5m*SVq5avT?-BPu$@>G&y%-Qbc zkPA^?Q1JxhLVQWfzV|N|VoP$d(0>G|7htadQ^4cD#u*>?pW{qm_rJTmp*umv!;HT- z;9y-0B}4RGli#Va3R4)~GyE5Bq{KE2KihV@;PZ2n!rAQ1nZc}bO(>ZKQJWBCHng5f z_y<9?w{-xD*BXSJhj5z5bZGF2dIr=^j|I>^PIa#LA)^^c7puiuKd?`jR#OG;>hHjp z*ELGiw(%Pj{5oWSw>Y~skr;N;wacfC6Uu*QAFBvc9pIVy{g%av<${Jr{B~hs!*tv_ zmX}43nP2T~4{f(@)YWvYJl1h1kwQfwX#o%0t=Zdoi^-y&|G298%ztTN0<7B?ih_EQ zld6@us;g7-ht6vA=e__5h96@e;MCTC+>S9P01G>=cNC^}eFnEtugnB2s-8s^xm~8B z2?*8^qCqBD40t<6k4AmT6n$m7>yMJK&LVF#QuXj&^3?%jculV1^VgYNEI2IrE$TGuDEu&>y$*%8w_sHjT#PT3^~BXqh&R#K{Jk46nye>N2LQjsp{xBr?d zHHYUO2lBNz2cQCVZ$aKYCP#3%Us}rfM!s*Pn?yUX{pJ{P#j+cD*(>%(a4Q3CH8KcS z{0@aTr&R5l-k5qhB@MID%oL(rt*%) zG<{j@VVV2i!zb(oN-M;T|GsiF;fv{JYkl;cOs~E9$554I_?e~S_^jD+<>>L= z*OFugjtV-GS@CXSR}`Go_qV%b>BUAkX%ZV6^8i&RJhCFU*C#AE)6u-M?~voL8bR;D zZ{Mc_`M)b%QBP#fARiacocrZ|O4EN+f2s9>wPro`enM2w?{V4uE4dT*iCbO84M6vv z62*D7u-b9c(>#pmcuLGG{({D5%2INQ{^w{BHq(ai;*0wHC#8;$kH85{{$;E5T^l6> z90GP9t|{Bm-MyeC;i*h<>uu5QF7Q@nr)tHLo3mc;XZn4TP_EXjy7*~kvPx*fEH$cDvTI<9z#^j!>~MKQ^M|y# z;x}@KSC5j6h0ScgRNo~vV%qK?o*BLw4vAa}dj>g1cA8m*MYrJY>>>+a{azmOM@dF> z&tZdy-}A$6eJS`@Oy0k^rVGSr6n_krM6FIMAiYy7(8ZY;(>)uHV`Vo>-;!#~q=rTk zLABF$Na>9F&H)x+GlLLi2rn6K;A~HJ9E$7At@$&h~9zsJ_ZY(EEr70}V4$<9AoU%4! z!-JYG)C)d;_OxmT>~X>_lokm5Rht}I4Ry?UQUD+wDkEogB&(X*G2jFS-1E}@*2^7u zMngN&BM1AV^nR=(O~9535IUwOy-@Qcx20Oe4VB1u@q0@;VQu}*&IYTc1{c}Bjb)I`NV z8i@b1gqX&cy~vG+6z5U+`vU&o$k)ggjDV>@*;EJ z6R8ElI2;upPq8FJ8WNmmxY)B_M%n2Qj!3mT+Du`&%mH8-TXaT=S<0AO@kMuGNA0cN z^Ku}^O=bdAD@hxXY9=38Nk=7a{Eh7EDGVha3R&3DJIXR7n|vtCGR+NfqOWDnfyb^mBy@wY33 zGsRwTx%%W=ib;DY)F7tK)IjQ38wA=!PzX02<9{|6`NfC9kj~ZIDZLvm_lcnntoFtp zTA5|wfv;KmKF^MHSazU1P;G8)sASaPszs7K$H zCgj`7+2Ub_I6L&5_pwJRYGDgD@kz=GjPB@m_zM z4W$l!J1^$E=i?3EeDvjR&W$9Ki@gWUw(?2!-A{;i##-GNcuTx#z_O!R z5pMmnZs_*VYt_uOAY;00<~D)WwI_#1gRJL~5z)#<;>d1hpXW^5p(f>oN1;K%315X) z?|u9I083#y7a4YF{_4Yq?1`t{Vy$GXjD&km8HxQqho9<^<3-yW_BdwrbjUZo$6e&2 zFXzsQ?(akF@ORkds@K(1t7ZR}q5G!GSP$7U!;Lq^-?l4Sbe|BAw4I-tF+ZA4L|Q-o)v2E3oSLaYUm}8;=vU+owwVzJw=RwR z&w=y=8c1gUJCIoOrm;%`|GZ-C{HS>V(d64lf(`Mq+?sMsQqaPv;uVplhb$FAK1^Rz zd3HAXxA0Pb!{P2M!F3p8jpYkmy$5cGDB~!O{IvGaje(Y0f@c^T3lMVNI@eLiucJIh zB~`Bx0A83`)s=?m1~LT(0!eV1m*Pwd&i|TtFr?hYz8fzwp+VvNDPQ$)b7<;d6~($r z%1MkPe`aS+3%aN}ilGZ``M=Z7Z$M$mzVEQrKrCCo^|_j^ORNj7H8NSctE%Vz!CMcc zIrIk}p>^$*YKmQN7V(w$u-loQX!QEIAr0w#HL!c?QqLTxv$5+b7{!&qD*(8z0>E4=DNT&6C|o9{1^a&-g9X2{b*m2G_& zfZ;qRz?u1NoNy49$w=Zt94I6Wf=DI)2#d^#cw~q01z4FIPty!9Oyy%@U?>0?3y8TI zU(m&Rxj5liuN(~dPy|%g>--9=H2}&WVQ9b>&G`F)vaRX-A~Q@=g_XU}ezC%Y_9xB{ zdQZq;!9V9^Y|-kP)Anq7&)3nkZ}S6qqhmj?%O>Ac#D;U-J#OOAB)v^RH@e8_71MA9 zvXaq`@7Zf~Hh`hKbte_Vi-hlz@mZk?*zqXDNv_98+ExV0R)-tLpL#?=i>^>0Z+&yb zfI&7_Ot6h?Q9%#u2?_y)hOJkxxwNsBh&Ot25cPp^o%}kLdXI2ufZW}XI^l}zOA~HW zdP{sr+jPJXyn7{4e;TTeOZC)B)xYq8>#dk^FZ}fF$ zY0g1zpgK#X^o@e3?gKN+yYM@jke2Y9KtrUJ2GVX<2JpedW>Cl zFLT`#(RvRpO@BmS&WC0wPV%9IwIb2$5h#BDZE~eBTx)#9=e^o@dHa6<{p@#4WjWtk zM=d5Ar8uSHgGo~^?@ceBpc7|ckF1k5vFQi=RD@;zHM}4_Z3NZ>I06^`YXRNy`(JvR z=*xc?cvJq4EFc^ep#@ZUMhvL|A^DUj0-Mr$%Y#W=zIHKWkS8Rslf$O5#34x8h^}92n0>m5wI+? zYZ8R#%~Dq3P&Paa%!98_FEGE>F>V2&uM?7-yYO`|103k=jGiu9=XA+W?OU(v)8P%h zx!;l@UP$3n+qE{PAkzSf0g#l}eRxE;77A=x&bJd7?BN47ttGB#h@%6x-`@8j5rTX; zYIrZ`TL5JKP|dF8AOHck;QsV}vrO1#qp(Vj&<8`|Q zSS>1^b%Y7LPPfr*zyn6ffS3@P2*fhd_w$J*ML$*acR8dQu$h7f$QzGLsRw12Q?fLb z6?C?6jv3lK!2=WVD4_ES@Mj{<%b2^p2bUdsD{J69h(_kH2tp50LHAh;yNP*C1vB`q z#_t)~p)=4;p$l7$jyS8;UkEg~<&+TP%v6!c+%dOR{C><1ILdJ{TG@%Dh`++-5iJ}w zg)D1!whoe9cqMlGy9%H)?BAIm(59H%6?oWn<_Z>6Sy(1mcd3qK;1tnSlnVdlV~vgi zK&9q-s2ZsN+@jMnm@-)0^b(%QTVuRxLB*4YR#jVIz7tgTYbw39?PfQb-xBk zM^ZKuCsp1r45t$)BURtqbB|wdnXJuSE<9A!IcvS*NqOyrT86Q6#oGau`jt9u*OSKL zg0qPM!HRrI!9NtQeA97h?dzJ4tLJO1;Hcr2fZjk_Yt@&jPl@8{hL~o}l)F=w_=hOs&8bR>6Uaxs ztL~5&@Rl?5RFF)qN+8+H`im`_z9c4t%lA5yW>B)JvYZSZk z2*m-WzqwZRf2Vr?{}_1f{TEn;N=;AqR>B@Hi&%wFkO!VR5I zA1g)J)tCm~9A^9nBxxSj0bN9)6%N4#{u%I!-4gkqr(R+^8)2*S>G=cbCJOark6Z;Z zWX+Q`f-=1aGiAi|Y-`w1lV$_FCYy=$e{gh<`dj@VK>*@t8ps?7{(>gQx05rcNdbZd zuI=#Nxdkx-SZ9`UL?ie{PWCmzwI6U)YX}?gd9X5ZYXrh6AG%@98jD&x)O3iq+zuoN zcxHh~0_YqASoK-(kIbEieQH)P1cNLBw@tS0^U(BYt=6E%!YzJ%9KmaN=j!}@*$3D2cOJg@J_c-&}*^5)$FlVLmcumC9w-1moVW3?pdzRH(CDW z{M7Vdh|F;8^k+$T6nP?&ULj4%CtV=P2WN;wDE8O>`t}&6=D8nu0%J?%4E2Ig4tM2w z-F+4%oiryMGh4Q`eIh%mG?vMZ4=c&0v-5Enf=+|TNzVrHvdan;*M0S~#65tKfDEQ% z%2kstN?bu|$IZR(>Z1ebnW4V5h$40@Xk~x;h5&U&vj4ZA&8=9?-pRu*hy5Sjq zL63LsXIUvwK3B6FvQGt?HzfJ%-kOvZPX*jjtxKk3?mse)lIIGVh=<(YyMan2zeWk; zp?5eBnZh$~!w3*um3pV(ybP{Y`P9q z3ex&p#VhDXOM%l78zB(nU1|*D(2npF2`ucCM|S zZgzg{z#conGB=mI{(|rivpk>o*4dI>c~>a6`epK3;V_-@MZxlx@Vhjza|Vmez`pg#YhEwZL@SoN5fIemhx zb4U~;>1YEQ9U9hZK%FNW1l_ZP{O(dejDwSu-HxI#r~*HW}bA zwHcXCs;9>8EAGsKrSJb9dD1oeMNc+DgXiM!^uiDr`6j(<~1$<8AF+WYkG?M0rclfVfuj4(Wlz_MXZw470cgom=~967W=0RW^K0BHCu`sTKp zl5UBDMg1$5FJKgVt1IVTE>lD1M)qd(}-aOQ@J4%X8`X>YKul@B|75Y~gPv+21&P z&zY(bUNar};!&LMC6fpxBTbPmn4$D0JvW~K^7q4i8ef?*gz!IzN(3#8Yk^#MmGXXX zzS|`Kj-xOvKhTQ1Z;|HA*{(SivDx^Fd+YFIZr9DVw^kJHuB+eIenT)ke-vNo6t!zx zM89_&_tn{@In_s_n%~0#HhM51ZtJpvrrT0DZ3y@2@|ps$`SU&JnCi_#I@ky3pD+Ub zkpU$S>k*C709xedM=2|xKc<;CAxqCEM%zag1viJcJpuC(5KHBfxp30DIsZ*2Z3wx_ zH|m^T%Xm7Yvlb7(!wbpxVuKbLnm)Mp^emD zSMwNDhZu5nLq+t2v-Viog!QLv4Zj>Pe(*&Sd?YIYSkw2|F*Qh0<{E^k3)!uoK?}u5 zR;oX6tjK!&=}d+|_$Fy-*Z}!+X2IitkYhtD`T%yNBGo-t8e8_bWdGIA5AfH$mkYfW z7z=v9F%u=eapLP4F01~+t@4tVH^UhbXmm9mu!#*e{4F$eO~J3?A1^b!T85*ZGwR(E zf~Zo&2q{@vmg;V`wAdBu)Iwww%HV@H#MbX8LXZ5`Y7t%P&T~sOV+1*GDFi0!;_cwp zPi@;d#c#FLZJm#0c=b+%Mpi;t6t0V&z z9iv8f8fcbA36*aUOS`rwHuk2!db1)N1C1RRGnwy4zLeSSecpZTS0VPZrrBrhWO)sG zo4-MEjxw@-EF8`456gL;91;p@mU8ap6$>kEXE%-Kfb5e2y{)4NY^w$Caq@Ie5NA85 zmOE|d`F=s$T=k4g_b#KMF57h+|00;y3k3Q4=Nd%Q8BJ0 zk1?=ds_|c?6>?I?kqhxJWJdl6eIk{LHDI{j1dpJeE=*hVaDt0dg+LdzDoAFtdCF+J zPXT{NZezI$CV|7!yIVxsU&eml5lBi4lqhPF{5H?+=BtBdj?uM~e%&dn4T^y5iMzzg z!wGkyCZ9>y+S{kUP2=t`z}FosdIu}gF<%$BG{m}prYUJ%R5VNHlh8D{!X%RwjZc2I z1cFJtfKr-Ne{E++68XAVP3xtmo~2D9LX_3EY(R=A!Z;tAmlUeV$PV7381a1eB|C#n zo?1Bfeae*XVY!v3EH%of(HtM=_vbx~U?+BEE$SMPXL zERPno-dh}m1;~?$A-Z*kXKIEIC<8O3|Lw#AqE@v z!?+Iw&0fJTV&q*cOci@QPeu>Bm1o2VyqYIZiu|H~s8*$p6OodlZIJ@DM1L6|JwNy0 zs-U@cJ}pyiqVrmjVb6)x+vKQ1RLMBjuCjtXB%?BNIZov3vKE{Hb0NniZH<_3_pw%+*&soOBVwGrFO z>rCf`)%Qu8pf+a2W!`8hImGUUt;Y-k(83_|$Bt#85bj4UKdi83PN*&)TV8-6`7f?x+%a=dl9F-Q!}1t|KEc=)rxOkFGCIiWz5Z_iuV=U`sGM3@30$cSjuU z&?yUDXSM84Nvu3{Up)eDM{DVwD}T8ygrynfK2|W{{T$z_)3hB{>@Xx{sdcv@plPop`P!|2mr;%$p`V_ zz6a2v8r_{tpo?u*3ks|Cx9^6sIRz7U=2r*Q9n#3Lb-(gsB9jN4HDsncdijXk{fIvk z0_Xe8hl?r(DN^dk>%|I{tPUE~o#gW2rTrwKgBdV=d{z{&UioDQ)3J3eTsM3FvD{xL zV2S&l!Ny6>(Z8+QDYY+7(7s}lC3Lgs$&QSa8HHGOdi7`NrGA?d_07<}cQ5WVWGD%1m7)Ru-r|3%iLb0EZ}K5_HD z`w}FDhQk05S&#jc@{Dza*p-U47|}kU3_d`humHQZbE;dyR)k|-U{SpU5Drs-+nqJO z=wL}Af5rmvYw~y)9Qu@L?q%M<`!)6rl?Zs97Dz<8i93+ui00lF?PJ4;5#p>#4Hl*b zjv=TiL+1W_AW6&_?e(~A90hAd((t`cs`6+0A2;RHFnl4oL8L2lw}Q>GU`lZE%ydtY z09CtK)es7+&pI$}(|5jkOnM+~166J^iQt_0is!o*+s3W)ZOjg$7B}zJnx(A3Aq%~} zE*m)aJC%QqK4Y=FKC(P`-=e_06KU}1%G?tfmb+@BEw!z|g?cSwb02tL$Kf*lQUcP6 zCQrz53WA3dFI)G^kYaj5XpIE?w1%MS&xTIH6LQoP*40<#^Mh!-dTy&wZA0r-`V8B^ z)hY|2fx@D)+i*bTLi+?iP8GLT7cN^RCt$TMh@!J_TL-MAEbMxKGYH{F{!k_ROAc%> z$6;UqgLCoId*nuL^lLIeMd|kX=0QbdB{s;CY!*g9&Jwz?MG$)%(bMR`;Gn?v0$<%e z!^0UCZfb6yLiChI505UEX(vB)}$?+_@D7A zQ#i=X^H76&fesT1ayk~N&(ojFAMwps%#r$Jt-NQoL%Md$RWNo}ZDKVFrp3aHb=g(M zAkhsec~8+$5CbK%$YUstxn|HZ(7Gwfp+6*rwZAXJ<(hy70oM5W$Cj7Yv#dg2U5VL= z%u|Zu#knh*rJwfg*uR37oJ_Xufoe>_=5z zWNI{2$2Y$BF>j~rv4liqP#?#R&ZnDvc+InUZX>;nV656Mp;uX2bsyZJHL}%Dz1$+m zxhlvX1EEexefZw73Z8ue(U&_)RbH{%bsYYmd_7<+#@~psv=BC!hk-mHX_wYNSS*(A zLDyFyDVGv5j|fqul^0A1!jC zs13a1%?YRd;yl^4^98n+8)xC9 zeGgk4fd@-P^a|8@(3lD9%lO)=VV88oKe*&l8l08NM%Zea%}PP_FK#)}vbuM&%mau< zf2sweVU|E8Dus%z{DSW+Sysnt{n9rh72UdnLO9Yto?9l*%W9g0x^@~}c#A%z!tb(E zD)D*rxB4mJm!~$OveJP2KSD&BdrV{bY&)~o>9s5v#>1>QU~kEycIjorj&*|JyGljt z=6-UD4VUyFDFdl1Ij@;#E@~7O9V4O26GA cKd;KpE{|J(UzH*MFKme9LSguyfDo(y0)=kqz5oCK literal 0 HcmV?d00001 diff --git a/scripts/simple_run.py b/scripts/simple_run.py index f1d70fd..4181f8f 100644 --- a/scripts/simple_run.py +++ b/scripts/simple_run.py @@ -9,6 +9,7 @@ from PythonLinearNonlinearControl.envs.make_envs import make_env from PythonLinearNonlinearControl.runners.make_runners import make_runner from PythonLinearNonlinearControl.plotters.plot_func import plot_results, \ save_plot_data +from PythonLinearNonlinearControl.plotters.animator import Animator def run(args): # logger @@ -39,12 +40,16 @@ def run(args): plot_results(args, history_x, history_u, history_g=history_g) save_plot_data(args, history_x, history_u, history_g=history_g) + if args.save_anim: + animator = Animator(args, env) + animator.draw(history_x, history_g) + def main(): parser = argparse.ArgumentParser() - parser.add_argument("--controller_type", type=str, default="DDP") - parser.add_argument("--planner_type", type=str, default="const") - parser.add_argument("--env", type=str, default="CartPole") + parser.add_argument("--controller_type", type=str, default="CEM") + parser.add_argument("--env", type=str, default="TwoWheeledTrack") + parser.add_argument("--save_anim", type=bool_flag, default=1) parser.add_argument("--result_dir", type=str, default="./result") args = parser.parse_args()