From 4e01264bd951635a218d054e7191acb7523e8d1f Mon Sep 17 00:00:00 2001 From: Shunichi09 Date: Mon, 6 Apr 2020 17:20:17 +0900 Subject: [PATCH] Add: Environments.md and MPPIWilliamns --- Environments.md | 34 +++++ PythonLinearNonlinearControl/common/utils.py | 1 - .../configs/first_order_lag.py | 116 +++++++++++++- .../configs/two_wheeled.py | 5 + .../controllers/ddp.py | 9 +- .../controllers/ilqr.py | 4 - .../controllers/make_controllers.py | 3 + .../controllers/mppi_williams.py | 143 ++++++++++++++++++ PythonLinearNonlinearControl/envs/cartpole.py | 87 +++++++++++ PythonLinearNonlinearControl/envs/cost.py | 20 ++- .../envs/make_envs.py | 3 + PythonLinearNonlinearControl/models/model.py | 91 +++++++++++ .../plotters/plot_func.py | 102 ++++++++++++- README.md | 13 +- assets/cartpole.png | Bin 0 -> 60984 bytes assets/firstorderlag.png | Bin 0 -> 38160 bytes assets/twowheeled.png | Bin 0 -> 27226 bytes scripts/show_result.py | 55 +++++++ scripts/simple_run.py | 8 +- setup.cfg | 5 + 20 files changed, 669 insertions(+), 30 deletions(-) create mode 100644 Environments.md create mode 100644 PythonLinearNonlinearControl/controllers/mppi_williams.py create mode 100644 PythonLinearNonlinearControl/envs/cartpole.py create mode 100644 assets/cartpole.png create mode 100644 assets/firstorderlag.png create mode 100644 assets/twowheeled.png create mode 100644 scripts/show_result.py create mode 100644 setup.cfg diff --git a/Environments.md b/Environments.md new file mode 100644 index 0000000..7799db1 --- /dev/null +++ b/Environments.md @@ -0,0 +1,34 @@ +# Enviroments + +| 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 | +| Cartpole (Swing up) | x | ✓ | 4 | 1 | + +## FistOrderLagEnv + +System equations. + + + +You can set arbinatry time constant, tau. The default is 0.63 s + +## TwoWheeledEnv + +System equations. + + + +## CatpoleEnv (Swing up) + +System equations. + + + +You can set arbinatry parameters, mc, mp, l and g. + +Default settings are as follows: + +mc = 1, mp = 0.2, l = 0.5, g = 9.8 \ No newline at end of file diff --git a/PythonLinearNonlinearControl/common/utils.py b/PythonLinearNonlinearControl/common/utils.py index 07ff604..a22b22b 100644 --- a/PythonLinearNonlinearControl/common/utils.py +++ b/PythonLinearNonlinearControl/common/utils.py @@ -1,2 +1 @@ import numpy as np - diff --git a/PythonLinearNonlinearControl/configs/first_order_lag.py b/PythonLinearNonlinearControl/configs/first_order_lag.py index 7726a77..1ad59f6 100644 --- a/PythonLinearNonlinearControl/configs/first_order_lag.py +++ b/PythonLinearNonlinearControl/configs/first_order_lag.py @@ -5,7 +5,7 @@ class FirstOrderLagConfigModule(): ENV_NAME = "FirstOrderLag-v0" TYPE = "Linear" TASK_HORIZON = 1000 - PRED_LEN = 10 + PRED_LEN = 50 STATE_SIZE = 4 INPUT_SIZE = 2 DT = 0.05 @@ -43,8 +43,33 @@ class FirstOrderLagConfigModule(): "kappa": 0.9, "noise_sigma": 0.5, }, + "MPPIWilliams":{ + "popsize": 5000, + "lambda": 1., + "noise_sigma": 0.9, + }, "MPC":{ - } + }, + "iLQR":{ + "max_iter": 500, + "init_mu": 1., + "mu_min": 1e-6, + "mu_max": 1e10, + "init_delta": 2., + "threshold": 1e-6, + }, + "DDP":{ + "max_iter": 500, + "init_mu": 1., + "mu_min": 1e-6, + "mu_max": 1e10, + "init_delta": 2., + "threshold": 1e-6, + }, + "NMPC-CGMRES":{ + }, + "NMPC-Newton":{ + }, } @staticmethod @@ -86,4 +111,89 @@ class FirstOrderLagConfigModule(): shape(pop_size, pred_len) """ return ((terminal_x - terminal_g_x)**2) \ - * np.diag(FirstOrderLagConfigModule.Sf) \ No newline at end of file + * np.diag(FirstOrderLagConfigModule.Sf) + + @staticmethod + def gradient_cost_fn_with_state(x, g_x, terminal=False): + """ gradient of costs with respect to the state + + Args: + x (numpy.ndarray): state, shape(pred_len, state_size) + g_x (numpy.ndarray): goal state, shape(pred_len, state_size) + + Returns: + 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(FirstOrderLagConfigModule.Q) + + return (2. * (x - g_x) \ + * np.diag(FirstOrderLagConfigModule.Sf))[np.newaxis, :] + + @staticmethod + def gradient_cost_fn_with_input(x, u): + """ gradient of costs with respect to the input + + 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) + """ + return 2. * u * np.diag(FirstOrderLagConfigModule.R) + + @staticmethod + def hessian_cost_fn_with_state(x, g_x, terminal=False): + """ hessian costs with respect to the state + + 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 + shape(1, state_size, state_size) or + """ + if not terminal: + (pred_len, _) = x.shape + return -g_x[:, :, np.newaxis] \ + * np.tile(2.*FirstOrderLagConfigModule.Q, (pred_len, 1, 1)) + + return -g_x[:, np.newaxis] \ + * np.tile(2.*FirstOrderLagConfigModule.Sf, (1, 1, 1)) + + @staticmethod + def hessian_cost_fn_with_input(x, u): + """ hessian costs with respect to the input + + 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) + """ + (pred_len, _) = u.shape + + return np.tile(2.*FirstOrderLagConfigModule.R, (pred_len, 1, 1)) + + @staticmethod + def hessian_cost_fn_with_input_state(x, u): + """ hessian costs with respect to the state and input + + 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) + """ + (_, state_size) = x.shape + (pred_len, input_size) = u.shape + + return np.zeros((pred_len, input_size, state_size)) diff --git a/PythonLinearNonlinearControl/configs/two_wheeled.py b/PythonLinearNonlinearControl/configs/two_wheeled.py index 9167ca6..27e9834 100644 --- a/PythonLinearNonlinearControl/configs/two_wheeled.py +++ b/PythonLinearNonlinearControl/configs/two_wheeled.py @@ -39,6 +39,11 @@ class TwoWheeledConfigModule(): "kappa": 0.9, "noise_sigma": 0.5, }, + "MPPIWilliams":{ + "popsize": 5000, + "lambda": 1, + "noise_sigma": 1., + }, "iLQR":{ "max_iter": 500, "init_mu": 1., diff --git a/PythonLinearNonlinearControl/controllers/ddp.py b/PythonLinearNonlinearControl/controllers/ddp.py index ac04b7c..4abb229 100644 --- a/PythonLinearNonlinearControl/controllers/ddp.py +++ b/PythonLinearNonlinearControl/controllers/ddp.py @@ -23,10 +23,6 @@ class DDP(Controller): """ super(DDP, self).__init__(config, model) - if config.TYPE != "Nonlinear": - raise ValueError("{} could be not applied to \ - this controller".format(model)) - # model self.model = model @@ -296,6 +292,7 @@ class DDP(Controller): def backward(self, f_x, f_u, f_xx, f_ux, f_uu, l_x, l_xx, l_u, l_uu, l_ux): """ backward step of iLQR + Args: f_x (numpy.ndarray): gradient of model with respecto to state, shape(pred_len+1, state_size, state_size) @@ -317,7 +314,6 @@ class DDP(Controller): shape(pred_len, input_size, input_size) l_ux (numpy.ndarray): hessian of cost with respect to state and input, shape(pred_len, input_size, state_size) - Returns: k (numpy.ndarray): gain, shape(pred_len, input_size) K (numpy.ndarray): gain, shape(pred_len, input_size, state_size) @@ -353,7 +349,8 @@ class DDP(Controller): def _Q(self, f_x, f_u, f_xx, f_ux, f_uu, l_x, l_u, l_xx, l_ux, l_uu, V_x, V_xx): - """Computes second order expansion. + """ compute Q function valued + Args: f_x (numpy.ndarray): gradient of model with respecto to state, shape(state_size, state_size) diff --git a/PythonLinearNonlinearControl/controllers/ilqr.py b/PythonLinearNonlinearControl/controllers/ilqr.py index 40be9e9..a676ade 100644 --- a/PythonLinearNonlinearControl/controllers/ilqr.py +++ b/PythonLinearNonlinearControl/controllers/ilqr.py @@ -21,10 +21,6 @@ class iLQR(Controller): """ super(iLQR, self).__init__(config, model) - if config.TYPE != "Nonlinear": - raise ValueError("{} could be not applied to \ - this controller".format(model)) - # model self.model = model diff --git a/PythonLinearNonlinearControl/controllers/make_controllers.py b/PythonLinearNonlinearControl/controllers/make_controllers.py index 99653d9..74d048c 100644 --- a/PythonLinearNonlinearControl/controllers/make_controllers.py +++ b/PythonLinearNonlinearControl/controllers/make_controllers.py @@ -2,6 +2,7 @@ from .mpc import LinearMPC from .cem import CEM from .random import RandomShooting from .mppi import MPPI +from .mppi_williams import MPPIWilliams from .ilqr import iLQR from .ddp import DDP @@ -15,6 +16,8 @@ def make_controller(args, config, model): return RandomShooting(config, model) elif args.controller_type == "MPPI": return MPPI(config, model) + elif args.controller_type == "MPPIWilliams": + return MPPIWilliams(config, model) elif args.controller_type == "iLQR": return iLQR(config, model) elif args.controller_type == "DDP": diff --git a/PythonLinearNonlinearControl/controllers/mppi_williams.py b/PythonLinearNonlinearControl/controllers/mppi_williams.py new file mode 100644 index 0000000..1fd0102 --- /dev/null +++ b/PythonLinearNonlinearControl/controllers/mppi_williams.py @@ -0,0 +1,143 @@ +from logging import getLogger + +import numpy as np +import scipy.stats as stats + +from .controller import Controller +from ..envs.cost import calc_cost + +logger = getLogger(__name__) + +class MPPIWilliams(Controller): + """ Model Predictive Path Integral for linear and nonlinear method + + Attributes: + history_u (list[numpy.ndarray]): time history of optimal input + Ref: + G. Williams et al., "Information theoretic MPC + for model-based reinforcement learning," + 2017 IEEE International Conference on Robotics and Automation (ICRA), + Singapore, 2017, pp. 1714-1721. + """ + def __init__(self, config, model): + super(MPPIWilliams, self).__init__(config, model) + + # model + self.model = model + + # general parameters + self.pred_len = config.PRED_LEN + self.input_size = config.INPUT_SIZE + + # mppi parameters + self.pop_size = config.opt_config["MPPIWilliams"]["popsize"] + self.lam = config.opt_config["MPPIWilliams"]["lambda"] + self.noise_sigma = config.opt_config["MPPIWilliams"]["noise_sigma"] + self.opt_dim = self.input_size * self.pred_len + + # get bound + self.input_upper_bounds = np.tile(config.INPUT_UPPER_BOUND, + (self.pred_len, 1)) + self.input_lower_bounds = np.tile(config.INPUT_LOWER_BOUND, + (self.pred_len, 1)) + + # get cost func + self.state_cost_fn = config.state_cost_fn + self.terminal_state_cost_fn = config.terminal_state_cost_fn + self.input_cost_fn = config.input_cost_fn + + # init mean + self.prev_sol = np.tile((config.INPUT_UPPER_BOUND \ + + config.INPUT_LOWER_BOUND) / 2., + self.pred_len) + self.prev_sol = self.prev_sol.reshape(self.pred_len, self.input_size) + + # save + self.history_u = [np.zeros(self.input_size)] + + def clear_sol(self): + """ clear prev sol + """ + logger.debug("Clear Solution") + self.prev_sol = \ + (self.input_upper_bounds + self.input_lower_bounds) / 2. + self.prev_sol = self.prev_sol.reshape(self.pred_len, self.input_size) + + def calc_cost(self, curr_x, samples, g_xs): + """ calculate the cost of input samples by using MPPI's eq + + Args: + curr_x (numpy.ndarray): shape(state_size), + current robot position + samples (numpy.ndarray): shape(pop_size, opt_dim), + input samples + g_xs (numpy.ndarray): shape(pred_len, state_size), + goal states + Returns: + costs (numpy.ndarray): shape(pop_size, ) + """ + # get size + pop_size = samples.shape[0] + g_xs = np.tile(g_xs, (pop_size, 1, 1)) + + # calc cost, pred_xs.shape = (pop_size, pred_len+1, state_size) + pred_xs = self.model.predict_traj(curr_x, samples) + + # get particle cost + costs = calc_cost(pred_xs, samples, g_xs, + self.state_cost_fn, None, \ + self.terminal_state_cost_fn) + + return costs + + def obtain_sol(self, curr_x, g_xs): + """ calculate the optimal inputs + + Args: + curr_x (numpy.ndarray): current state, shape(state_size, ) + g_xs (numpy.ndarrya): goal trajectory, shape(plan_len, state_size) + Returns: + opt_input (numpy.ndarray): optimal input, shape(input_size, ) + """ + # get noised inputs + noise = np.random.normal( + loc=0, scale=1.0, size=(self.pop_size, self.pred_len, + self.input_size)) * self.noise_sigma + + noised_inputs = self.prev_sol + noise + + # clip actions + noised_inputs = np.clip( + noised_inputs, self.input_lower_bounds, self.input_upper_bounds) + + # calc cost + costs = self.calc_cost(curr_x, noised_inputs, g_xs) + + costs += np.sum(np.sum( + self.lam * self.prev_sol * noise / self.noise_sigma, + axis=-1), axis=-1) + + # mppi update + beta = np.min(costs) + eta = np.sum(np.exp(- 1. / self.lam * (costs - beta)), axis=0) \ + + 1e-10 + + # weight + # eta.shape = (pred_len, input_size) + weights = np.exp(- 1. / self.lam * (costs - beta)) / eta + + # update inputs + sol = self.prev_sol \ + + np.sum(weights[:, np.newaxis, np.newaxis] * noise, axis=0) + + # update + self.prev_sol[:-1] = sol[1:] + self.prev_sol[-1] = sol[-1] # last use the terminal input + + # log + self.history_u.append(sol[0]) + + return sol[0] + + def __str__(self): + return "MPPIWilliams" \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/cartpole.py b/PythonLinearNonlinearControl/envs/cartpole.py new file mode 100644 index 0000000..cd84313 --- /dev/null +++ b/PythonLinearNonlinearControl/envs/cartpole.py @@ -0,0 +1,87 @@ +import numpy as np + +from .env import Env + +class CartPoleEnv(Env): + """ Cartpole Environment + + Ref : + https://ocw.mit.edu/courses/ + electrical-engineering-and-computer-science/ + 6-832-underactuated-robotics-spring-2009/readings/ + MIT6_832s09_read_ch03.pdf + """ + def __init__(self): + """ + """ + self.config = {"state_size" : 4,\ + "input_size" : 1,\ + "dt" : 0.02,\ + "max_step" : 1000,\ + "input_lower_bound": None,\ + "input_upper_bound": None, + } + + super(CartPoleEnv, self).__init__(self.config) + + 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_x = np.array([0., 0., np.pi, 0.]) + + # clear memory + self.history_x = [] + self.history_g_x = [] + + return self.curr_x, {"goal_state": self.g_x} + + 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 + if self.config["input_lower_bound"] is not None: + u = np.clip(u, + self.config["input_lower_bound"], + self.config["input_upper_bound"]) + + # step + next_x = np.zeros(self.config["state_size"]) + + # TODO: costs + costs = 0. + costs += 0.1 * np.sum(u**2) + costs += np.sum((self.curr_x - self.g_x)**2) + + + # save history + self.history_x.append(next_x.flatten()) + self.history_g_x.append(self.g_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_x} \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/cost.py b/PythonLinearNonlinearControl/envs/cost.py index 5d10697..117d5f2 100644 --- a/PythonLinearNonlinearControl/envs/cost.py +++ b/PythonLinearNonlinearControl/envs/cost.py @@ -22,16 +22,22 @@ def calc_cost(pred_xs, input_sample, g_xs, cost (numpy.ndarray): cost of the input sample, shape(pop_size, ) """ # state cost - state_pred_par_cost = state_cost_fn(pred_xs[:, 1:-1, :], g_xs[:, 1:-1, :]) - state_cost = np.sum(np.sum(state_pred_par_cost, axis=-1), axis=-1) + state_cost = 0. + if state_cost_fn is not None: + state_pred_par_cost = state_cost_fn(pred_xs[:, 1:-1, :], g_xs[:, 1:-1, :]) + state_cost = np.sum(np.sum(state_pred_par_cost, axis=-1), axis=-1) # terminal cost - terminal_state_par_cost = terminal_state_cost_fn(pred_xs[:, -1, :], - g_xs[:, -1, :]) - terminal_state_cost = np.sum(terminal_state_par_cost, axis=-1) + terminal_state_cost = 0. + if terminal_state_cost_fn is not None: + terminal_state_par_cost = terminal_state_cost_fn(pred_xs[:, -1, :], + g_xs[:, -1, :]) + terminal_state_cost = np.sum(terminal_state_par_cost, axis=-1) # act cost - act_pred_par_cost = input_cost_fn(input_sample) - act_cost = np.sum(np.sum(act_pred_par_cost, axis=-1), axis=-1) + act_cost = 0. + if input_cost_fn is not None: + act_pred_par_cost = input_cost_fn(input_sample) + act_cost = np.sum(np.sum(act_pred_par_cost, axis=-1), axis=-1) return state_cost + terminal_state_cost + act_cost \ No newline at end of file diff --git a/PythonLinearNonlinearControl/envs/make_envs.py b/PythonLinearNonlinearControl/envs/make_envs.py index debbf29..fd3ea09 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 .cartpole import CartpoleEnv def make_env(args): @@ -7,5 +8,7 @@ def make_env(args): return FirstOrderLagEnv() elif args.env == "TwoWheeledConst": return TwoWheeledConstEnv() + elif args.env == "CartPole": + return CartpoleEnv() raise NotImplementedError("There is not {} Env".format(args.env)) \ No newline at end of file diff --git a/PythonLinearNonlinearControl/models/model.py b/PythonLinearNonlinearControl/models/model.py index 58fe32e..5eb2cb7 100644 --- a/PythonLinearNonlinearControl/models/model.py +++ b/PythonLinearNonlinearControl/models/model.py @@ -211,3 +211,94 @@ class LinearModel(Model): next_x = np.matmul(curr_x, self.A.T) + np.matmul(u, self.B.T) return next_x + + def calc_f_x(self, xs, us, dt): + """ gradient of model with respect to the state in batch form + + Args: + xs (numpy.ndarray): state, shape(pred_len+1, state_size) + us (numpy.ndarray): input, shape(pred_len, input_size,) + Return: + f_x (numpy.ndarray): gradient of model with respect to x, + shape(pred_len, state_size, state_size) + Notes: + This should be discrete form !! + """ + # get size + (pred_len, _) = us.shape + + return np.tile(self.A, (pred_len, 1, 1)) + + def calc_f_u(self, xs, us, dt): + """ gradient of model with respect to the input in batch form + + Args: + xs (numpy.ndarray): state, shape(pred_len+1, state_size) + us (numpy.ndarray): input, shape(pred_len, input_size,) + Return: + f_u (numpy.ndarray): gradient of model with respect to x, + shape(pred_len, state_size, input_size) + Notes: + This should be discrete form !! + """ + # get size + (pred_len, input_size) = us.shape + + return np.tile(self.B, (pred_len, 1, 1)) + + @staticmethod + def calc_f_xx(xs, us, dt): + """ hessian of model with respect to the state in batch form + + Args: + xs (numpy.ndarray): state, shape(pred_len+1, state_size) + us (numpy.ndarray): input, shape(pred_len, input_size,) + Return: + f_xx (numpy.ndarray): gradient of model with respect to x, + shape(pred_len, state_size, state_size, state_size) + """ + # get size + (_, state_size) = xs.shape + (pred_len, _) = us.shape + + f_xx = np.zeros((pred_len, state_size, state_size, state_size)) + + return f_xx + + @staticmethod + def calc_f_ux(xs, us, dt): + """ hessian of model with respect to state and input in batch form + + Args: + xs (numpy.ndarray): state, shape(pred_len+1, state_size) + us (numpy.ndarray): input, shape(pred_len, input_size,) + Return: + f_ux (numpy.ndarray): gradient of model with respect to x, + shape(pred_len, state_size, input_size, state_size) + """ + # get size + (_, state_size) = xs.shape + (pred_len, input_size) = us.shape + + f_ux = np.zeros((pred_len, state_size, input_size, state_size)) + + return f_ux + + @staticmethod + def calc_f_uu(xs, us, dt): + """ hessian of model with respect to input in batch form + + Args: + xs (numpy.ndarray): state, shape(pred_len+1, state_size) + us (numpy.ndarray): input, shape(pred_len, input_size,) + Return: + f_uu (numpy.ndarray): gradient of model with respect to x, + shape(pred_len, state_size, input_size, input_size) + """ + # get size + (_, state_size) = xs.shape + (pred_len, input_size) = us.shape + + f_uu = np.zeros((pred_len, state_size, input_size, input_size)) + + return f_uu diff --git a/PythonLinearNonlinearControl/plotters/plot_func.py b/PythonLinearNonlinearControl/plotters/plot_func.py index 216788e..16866ea 100644 --- a/PythonLinearNonlinearControl/plotters/plot_func.py +++ b/PythonLinearNonlinearControl/plotters/plot_func.py @@ -3,6 +3,8 @@ import os import numpy as np import matplotlib.pyplot as plt +from ..helper import save_pickle, load_pickle + def plot_result(history, history_g=None, ylabel="x", save_dir="./result", name="state_history"): """ @@ -47,14 +49,108 @@ def plot_result(history, history_g=None, ylabel="x", def plot_results(args, history_x, history_u, history_g=None): """ + Args: history_x (numpy.ndarray): history of state, shape(iters, state_size) history_u (numpy.ndarray): history of state, shape(iters, input_size) Returns: + None """ plot_result(history_x, history_g=history_g, ylabel="x", - name="state_history", + name= args.env + "-state_history", save_dir="./result/" + args.controller_type) plot_result(history_u, history_g=np.zeros_like(history_u), ylabel="u", - name="input_history", - save_dir="./result/" + args.controller_type) \ No newline at end of file + name= args.env + "-input_history", + save_dir="./result/" + args.controller_type) + +def save_plot_data(args, history_x, history_u, history_g=None): + """ save plot data + + Args: + history_x (numpy.ndarray): history of state, shape(iters, state_size) + history_u (numpy.ndarray): history of state, shape(iters, input_size) + Returns: + None + """ + path = os.path.join("./result/" + args.controller_type, + args.env + "-history_x.pkl") + save_pickle(path, history_x) + + path = os.path.join("./result/" + args.controller_type, + args.env + "-history_u.pkl") + save_pickle(path, history_u) + + path = os.path.join("./result/" + args.controller_type, + args.env + "-history_g.pkl") + save_pickle(path, history_g) + +def load_plot_data(env, controller_type, result_dir="./result"): + """ + Args: + env (str): environments name + controller_type (str): controller type + result_dir (str): result directory + Returns: + history_x (numpy.ndarray): history of state, shape(iters, state_size) + history_u (numpy.ndarray): history of state, shape(iters, input_size) + history_g (numpy.ndarray): history of state, shape(iters, input_size) + """ + path = os.path.join("./result/" + controller_type, + env + "-history_x.pkl") + history_x = load_pickle(path) + + path = os.path.join("./result/" + controller_type, + env + "-history_u.pkl") + history_u = load_pickle(path) + + path = os.path.join("./result/" + controller_type, + env + "-history_g.pkl") + history_g = load_pickle(path) + + return history_x, history_u, history_g + +def plot_multi_result(histories, histories_g=None, labels=None, ylabel="x", + save_dir="./result", name="state_history"): + """ + Args: + history (numpy.ndarray): history, shape(iters, size) + """ + (_, iters, size) = histories.shape + + for i in range(0, size, 2): + + figure = plt.figure() + axis1 = figure.add_subplot(211) + axis2 = figure.add_subplot(212) + + axis1.set_ylabel(ylabel + "_{}".format(i)) + axis2.set_ylabel(ylabel + "_{}".format(i+1)) + axis2.set_xlabel("time steps") + + # gt + def plot(axis, history, history_g=None, label=""): + axis.plot(range(iters), history, + linewidth=3, label=label, alpha=0.7, linestyle="dashed") + if history_g is not None: + axis.plot(range(iters), history_g,\ + c="b", linewidth=3) + + if i < size: + for j, (history, history_g) \ + in enumerate(zip(histories, histories_g)): + plot(axis1, history[:, i], + history_g=history_g[:, i], label=labels[j]) + if i+1 < size: + for j, (history, history_g) in \ + enumerate(zip(histories, histories_g)): + plot(axis2, history[:, i+1], + history_g=history_g[:, i+1], label=labels[j]) + + # save + if save_dir is not None: + path = os.path.join(save_dir, name + "-{}".format(i)) + else: + path = name + + axis1.legend(ncol=3, bbox_to_anchor=(0., 1.02, 1., 0.102), loc=3) + figure.savefig(path, bbox_inches="tight", pad_inches=0.05) diff --git a/README.md b/README.md index 81bbae1..7c1e73d 100644 --- a/README.md +++ b/README.md @@ -14,7 +14,8 @@ PythonLinearNonLinearControl is a library implementing the linear and nonlinear |:----------|:---------------: |:----------------:|:----------------:|:----------------:|:----------------:| | Linear Model Predictive Control (MPC) | ✓ | x | x | x | x | | Cross Entropy Method (CEM) | ✓ | ✓ | x | x | x | -| Model Preidictive Path Integral Control (MPPI) | ✓ | ✓ | x | x | x | +| Model Preidictive Path Integral Control of Nagabandi, A. (MPPI) | ✓ | ✓ | x | x | x | +| Model Preidictive Path Integral Control of Williams (MPPIWilliams) | ✓ | ✓ | x | x | x | | Random Shooting Method (Random) | ✓ | ✓ | x | x | x | | Iterative LQR (iLQR) | x | ✓ | x | ✓ | x | | Differential Dynamic Programming (DDP) | x | ✓ | x | ✓ | ✓ | @@ -33,9 +34,12 @@ Following algorithms are implemented in PythonLinearNonlinearControl - [Cross Entropy Method (CEM)](https://arxiv.org/abs/1805.12114) - Ref: Chua, K., Calandra, R., McAllister, R., & Levine, S. (2018). Deep reinforcement learning in a handful of trials using probabilistic dynamics models. In Advances in Neural Information Processing Systems (pp. 4754-4765) - [script](PythonLinearNonlinearControl/controllers/cem.py) -- [Model Preidictive Path Integral Control (MPPI)](https://arxiv.org/abs/1909.11652) +- [Model Preidictive Path Integral Control Nagabandi, A. (MPPI)](https://arxiv.org/abs/1909.11652) - Ref: Nagabandi, A., Konoglie, K., Levine, S., & Kumar, V. (2019). Deep Dynamics Models for Learning Dexterous Manipulation. arXiv preprint arXiv:1909.11652. - [script](PythonLinearNonlinearControl/controllers/mppi.py) +- [Model Preidictive Path Integral Control of Williams, G. (MPPIWilliams)](https://ieeexplore.ieee.org/abstract/document/7989202) + - Ref: Williams, G., Wagener, N., Goldfain, B., Drews, P., Rehg, J. M., Boots, B., & Theodorou, E. A. (2017, May). Information theoretic MPC for model-based reinforcement learning. In 2017 IEEE International Conference on Robotics and Automation (ICRA) (pp. 1714-1721). IEEE. + - [script](PythonLinearNonlinearControl/controllers/mppi_williams.py) - [Random Shooting Method (Random)](https://arxiv.org/abs/1805.12114) - Ref: Chua, K., Calandra, R., McAllister, R., & Levine, S. (2018). Deep reinforcement learning in a handful of trials using probabilistic dynamics models. In Advances in Neural Information Processing Systems (pp. 4754-4765) - [script](PythonLinearNonlinearControl/controllers/random.py) @@ -62,10 +66,13 @@ Following algorithms are implemented in PythonLinearNonlinearControl | 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 | +| Cartpole (Swing up) | x | ✓ | 4 | 1 | -All environments are continuous. +All states and inputs of environments are continuous. **It should be noted that the algorithms for linear model could be applied to nonlinear enviroments if you have linealized the model of nonlinear environments.** +You could know abount out environmets more in [Environments.md](Environments.md) + # Usage ## To install this package diff --git a/assets/cartpole.png b/assets/cartpole.png new file mode 100644 index 0000000000000000000000000000000000000000..53abb68353dfe126f758302587cde5436835e5d3 GIT binary patch literal 60984 zcmeEtRa9J0@Fs*H2_D>oySoPq4#C~s-5r7x+%>@o?(Xiv-7Ve)fOavk&{W z=WIXBoSC_OZ&h{GS6^4xM1E0_M1GI|9tsKySz1b5843zE9SRCs1OX26&Ewn{3*_ys zi>S0J0%Z6im_|T8P{LpKVxpVw$ZDUA>-BL5s?g-o^&r>c9C)_feuqs@`NUnCzg|7{+G_=Pc?ycGSm@ z2vVq>GS#!9$Zw^l%{?xF{hy0W#S)K5Ngctl{it>I?MoExSvf9Mt@h)%CTQsYjZrd5 zdz_DC{|&FCH|GESh(3x9JMrI7WQmOL(KRu}`**dUt8sTTUJna=yO?NYf%P=v?W87n^JK4PKN(IT&ZMg(AYPe0UMQ`kg_M4i zP`!t18IUpd;UBL`c>Q5|&y>?&xD{)0te=V{=Lm>nR*_#RK*#$ZPfKJxF~n{a)lx^> z$a{@~&w?{GwxKRM!Rk2UjQmH6k$~xZ1n#Z}WOg_&wpus3av{Qj@__7?GdHvFH|7cS zDeu1fzD&6Ss&lilDe7EkvaULB z|J=aDrJdoAzPu1o{?faZY$cL4Tjtqghd}JjmBm8epRjVK{5QNbD7uY1aUZ2j-t$8d zCRg6E0Po*Vo!9*le4o(2RWI-_rKP+Xf`8v0`hw3IWWkag%<|>H*v_`O2HPOra_v9DY8RvYt?;PZD10&dS=eern}a~R z9;qtLsp)Bp$X5;Iqewt=5)!UUa4WM1dB?Dit=zjJ=ai2M)!=v?o2A_*RId2!HU2-# z;*6{e|2M?!{~S2ao2wqr!u0%2ul~(awydEbIUImO{axB%XwwC8DqaF<*`Ha=oMX2< zr5X+WWWdjsOHuw=SYd#8x7mo99dvKdLM|uB@y7(b(pz1B3?ojlv|Jl-nI}}e>$xr2 z<#o8_h}Xkh2qUi0y3{zKto25dq2%}%0NA+A(yoQuFvlFid! zGFJX4<9o3;(fa;TMN6GS*%q0~m-&ngZ{9rDuuxoV25$w9uItc$Jnv%4R~#~e+5T=j zm+M+q(N6&Jj)d%D2gASCCXrsbfa-FH8@%4y!b~~W+B6$4HNV5Y9N14MBHoRHsn9-| zkI=b^JKhy%n_9LQYHOm?f<&n3cysgy z1m*BL$fYAGpZ^Jq{irusndrH_=N9A|wS#6bVAYt2?+vLmI1p`GcYo7o{^hQ^L5W(e zt}yS0_ybz~*D_CH|3pITn`3_MSeO4j!r&}NMtkn{DlY#X(>4RcYP0REQ8THi{jrTR zW1XOmX4^9^*O#wU95(tNn`QqXN`fnm;gl0`zWS8eY+)$_+yrQ3$qA{UTh0uc%1l_c zSiwjkpIR1(So^%QHm;idM=sr@^>8w+CVuEigFl(Bwa!XB>~DFEY>lxcu1m&Y9+ZBh z06^pJXWqqfy5lQ^m5P7d1ze1BsB5Yv;u-*^C$`0pkF3l|{;6?Ux41_$AEZGgzsLGC zySAF^=Igj*i9OWDY$N}d;ODFq=&g=0(r|?8xOdu1mrmQeMq3X!p7$jL@46dVB^HFp zA=f4DVX_=iVSEBT<{WRnT*D1#n1Rv?td^WJRu}i~FO#~vdjDi;se9aMbnwHanvj-j zBAs6Nb>DaMKW?EAyAPDu1dWHv>76{KciXP5;k|B9;cwi$qr6*C{p0Hz|0MPV!b9^L zc;GLa0fAj)%-n=e=R$L>{PS5KhNm(HCQ8Mj-oH&L(A~K`WL_hDyyEm1a3R>cU@Bh; z_@hj#_*VZPQ;1VY;>EH!EW+&~2TBChyjP|9jht}4@74iawUueG6_1C}wJ?rw(tE~b zr8hXbe?2RFEt&q+5r_?i2{HNTzXXILJXE~fhuO0X%i|KHLw32@a1D#|Fc?kU6L!)~4w?XN#4+hz)E#ANpQEeKpP zC%a!J8YuaBPmzAegv8#ql;IU2YPM>${N?t4UiP(445w~%&oaPBL_fJrE`e)~;p*R$ zU+skgSh7EVBQf4>5{Fu+#<>n3ISzlZ(yWBfvy+-Q@cWOACUi&< zO?YXuWeK$>F@qyxl)_OfxK~bNvW4( zd)>co&!uvCm~|CQV9~Y#P)Q@X!qaS)*CDDv#jM6NzR}TTRe-s=(#hRvZb-_1w-{Lv zg?7o^H+uB|u#5wQicx8Dz#q>C$O(lG-h3={v}p5SdYqP@3g*6fY_3M*awDPagJ*l# zY~xjF`p@XPY7mV?!U`tRI}#p&e&TMz^c!}%1h1wxb?`L^b_=nW!AJIKaX&Zm4ly{H z{^!vFBG4|xrb;nc2B3tj6LqO>A3W6XMce(FwZN3P)3v62DU>CeKhgTv&=7{5@KW}t z3vIsjD&JukPX+WKKV+S7*y{{QqA~t^6GoppVL$frevb#7N_S$f&p8Z$0K09l@(n-=l`*qB*Aol-@mK| z-HpHgYA6jM4~RJ$-lz(=ut~gUIS=(;2fDq}&wPB(h-h>5hw(tNZd2>t6dGXaoDO38 zYbJ<`#?*hp(FdP7^~u7<6L#l}k_b+lcx*}~aZRId0ergr+R#bw!dR_#rSQWUjWkaQ zaCy$Oa=j~rE3F%iZo|}lYtQ)MRFOx{_5Ohi&Zf?2Cl~@H28ypAetg5d-qROo)q@ZK zDdIxt4zJjd_Zyq0$GN=~*@AIy?Qu!U?jM`uP82)`gRRzhXxEM<4goFUX7xvP)=RX{ zQFn&(-&q^Vh@#jvPXC6aQ9mb0O1=avx-7yOFR_Dzl-3>RxLuhG=>;KVtPX+>#AXNd zvYv54Uo9Hs4PmwK`~%f_)l>dj7AbwhBs7;y@f$#QAyqczMW2N29}i6AAQOYUSILx7 zlYwrFYQ;aF23tUE6(5r52ghD2!b%uuhV^47DQ<>Sb7LH`GFnA{vF+BMEz=jKy#vgi zCiA#tsA~IV1aPx-6`$;np3!iM~%}y}GpaJ>F2cgOGwa z-s`w#;~ysZckN)`2|IL*dppd20fEtl$SsSbxUVa%Z0nHmex+3}3qsWxjZ@?DZ2(ug z+_nO1dA1V2h09CUvUOi!g}ibcPt-Ip(iKJGw`RX)~K9 znfd(0EdAtMjSnFmd?r&hS4URa_FmNIS_oxUQ_=a5UoRn7v|3}M8AQD_HW))Pl(Nb z74AAJ$tfdDf2ExBpe$*Z58^{*Yw^({#6_uk3UTYchR#8{jJ9rLL5xFono>kuY=7VTYYn~1UJ(A;|=d8ZHKF~9+HN6{Mmwf*cNEi zcusTrAPN6qj*5-lnZJZaWb%;P$>-JltKR&lb5iRkVud2&on>YK+s`iqZT@R1h-o+V zG%}tKcRT@npXiiqwVV+6)Tf>G$Z%x%Iugr-Ck;XO7(BA-B@6N%v*lXvsyg%o&|B5@ zGD^b#t`t>?(po4cZI7PQ)eZYuQ<7{h1V85J8%oRJ-u0I|norfcR;)xer{zvw@8KD1 zU0-h?<>?2P6n`tSfZZZ(v;!MI?`>GklwzxmVHY@l5{mkove$<1)&hJX((*OW+AAM& z_DOoY^#!Bu_MOZXT9eJ?wFafyeXeJ_@1r!%!K~H~Wf6wQ2GM%y@#f`d!@jw>@tDua zM#~#)6Q8n}kR}^m7fV{z^R&}Pq9oubFy7V8wbjWZW|sJnwgwv&QKNf@tSvhu>+^ z{Q4u-MwD4o(sF;0v{=jOon3=Jd*UzwR@=b6eMK;3nQ|voZxB;{Ty7tf!k993hiEad zKfWh34zRn3&Q7!J%)w5DT%Z-vjN0JAiG$qM-B%DdZ@&3J{59L9J3dR;aAqCF_LgIR z=pJXv5ZpY}>4Rbf15wyT4-lR`IC1W$Pf15!ewTM?9rIg8 zYJ2xf-TO}@RIGkG)VK5m2%pd;RWdo5<3}yzjh?uHb3V%)%Cf=(>3OfnY0yzk?Fn3i z*|sk`Ze6SUe1Kf+AXU4iI3aG;qMEn@%eDGQy!!iXxG2ouQcGFE>{@9fptE^BUoVe< z+)Ss4FjU`39IG8RPs!Sb)6K;E!;kFxkI8mk`z{cWwEwq=$wV*qoWY}exb^ChCn#Hy zlf`Kk`!pa2x5f6=DqMiW=S)SvjrA-zWCY53z9M3dqTX%Sw8?_(jO`F@3)v?}qU5L3 znhvVc2D8mg(zyx$iW?bh4TAkl6gDioOF&jXd-%*vLL?z@ejDtdU*uPNV`4|Y?QN}# zBNesM0}!^Ibkzg{_edVE^tx8?qs_32?xLAzN(z~9Q!CgHal3^!(}qjVes~u3cDyK1 zi!w>szp>Vzb^~Keax0ph9L}%PszORU|LAg!W&${BekJJ7?yQn^V9-FIUa${{5K2Kb zfkv@l?F-*jyz$jCNN1wPbIGP94`a9YVIVbXzL^+7c(31(lC&L9#uGTlpIWnjSp+XP zJQWbWR7{dT`%TP~Mu279ZIDT4Dvy@9Cr$<({j1q-=^~Nfw^xCC&UQ$(4aqa*hh3Cz z!#6WnblrIp$9j(|vRLz-x1Uaakle#P@ywQ*r4K;AOu2W%F6! zW)Fb^2ueF1_BdT+2{^$tuU?rbe4Qu%*c?3;KUsTBj(62>Z~K16__vBHio7ryD#GQ3 zG+X;}E9)KxNz=;UQ8jpgR8hj7cr|ZUONdO~d?EjCfWYxf7~J_!eYO$K!?$y}-m!V8 zR7yQ7Q92m}p>D~;y^cP4l;^A=HkhYKAZm6$YQ8#bPK zFU&p*fEk3J%P_upB|PmTFUuq~g#-p-$e| z_yb%`C2p+bAWT<#Vv>emf7*EdJ9-bC=B6ocV4aB>e7}iw@691x>C35Y9U#GUO*P0t4|+N)ncm@QTO>sBERLNOC?@y(lebnDx}hq zB{I1|>bX|g;J0va$}B9xC{<_URDUwUzV*J*a2nuhuj_5hfnuc(+zjjT5>PqoH-^Qf zxgOV*#nhv(s+fRFS9)Krs&ExxD=%yX7kyW#Bm01V599-O_S}(u+hdMn&?OWZQpN?I zFC5;U!n{+<ZW!uxlQwIX4hae z*V1T#P%h37eG;VjA1O-gU~t!KyS7}&oZV`(p&=4~z}4K2LUgTe@D?9Pk})s?sK_ZC&#qYz)ZW5VDyNiJXAWUxJbOjS#`wCAjM zel7W=Nx2q5+~peK+0o?9x_zQS9h?t+xKCKydvB+RCQi`H6zq*pRO`g zo!<2I?%>~Idi{39mnKxwzjpZ0cKqA~Hl+f}RJnzD9(KRN((eiyf>g=_0!~0r{>a`a zgcNj~=lIxn6p^~@F~brNks~9eHP+Q^{{=gWZ{dDh{v(P3ly9&pPk{Lr@>@zZcCj^n z7ILdWRT5xP9A=n@=7GU_(4OaeiJNeYO_~5MYgzM!#5;;-!GKn~p_{aCygkhTx!u6E zzyrk`f4{PeG!aV=PwIB#j{4}FeQK7R!3C&wi&WO1k^xjtsAeaLthX%}&wi{FwU?bg zd~wQB?kQZ9QRTNc-tk{Sf#k{UJ37PS5;&lU^P2!WuG($;NVhM!80e$4nY|FwM5aMv zVgdt4;8K*cnMNO5t5|3MXnI(+8BX88$Jo9uGn^^G<}^*AkazusqTvgiNYBCmm3Kep zki7mNZTIZ_`LC?aO8R&}aHYW2lNPH7Q$hfE@QNpTTN%sBQOu!@izfAAns#T~*?dBG z;;=h5$@0BYowFa``g+dLK^?{?eW4+Y$u@(4{WRVL+hw=(B#T`~-l#9d*5rJ*9pOGt zsz=)`q#ZR~1Q=id_WKu?Zg#@uuJHbu8Sy-x(a|JoUau3(t5EHmhj;}Xx9uU~m8ne_ zY94f=$x#(*Ubkz^5{35C1px2k;*I+j{u77J(X{EsbtNHRN<_UOZi;o7i&%4$Dk=zo za%Jm7u;ouA-2r`BV4YT_I`uJ`v#Qc|H32Hn4EBTa>=INI=Hi4wuk>2J@eMWyefnLK z>{@3E<@j_)_d3HKXuQe}1Go8-2kw%)F|wsqCJdmqbjWxnb^3l%64yus$KhP4GdazB zeLV4}1N&Z5m#UmacD+-z1;|^N4r#sz2}<#d342nzr;X@|Cj(!ulB=_|QAG`$rO9zO zuMSRck2&{2MRQ{d?J>qG!a6ZD6#=ncW=L8P6FI3g*NF{9vJ5i2Xh;Us<;Ak{z8@xi?f#vDj{FQ;Sb@d}i~& z2F1kn+RAxh}@^cRfo;mg_O<=k2rguX+NP%U^Q6uGG4o+>tHL z5Ql$IvieC$;x}53e`~(oiS;2ljC>WCF69<7y1G#9In>;Ly0!b24z5-(^AR-~)1Zy? znO6ObawfhJb?0R`;r#&|?I*9rogf{MI|${kTCgC$WU-vGzu5#Sb``t5WX>kj<$)KQ zct^(6lsp}kJJjX#T;kbxh3c{o+A*M_w=ZQU4cu$p`&7BwJGx_PWQdM6=Z1IvHzh4j zGbaa%UM{XR7!+3!-3N*4(-XMw%+7*NOI2)P@;Wb(rUhK40u+S@BYuQ<)d2RMI|>+< z%pQC-gp+E%T`6ve=E%7He(kG1lSaum{UU&>pJ#@v0e~6nO3(lk414 zba=|Jc;qTk1`Q#3`*5u(9u?@OuwhC)Bvq3{f7h=celYX6rX(32uruqsd9l>4{lEzD z4EOS}i_)kPudzTCj`=M&IkqG4JTn&1_LUjrS*A4M_k?nyVcXLQm^!K6Ly7W(eR5>1EQk^yw2(xprI3Mb+#&<;1{$YCPEfWt7fBU6XyZHr>x1E_%UyX{MP%hDTCMkF93z7>84wawz zj)tMlFp*57HJi+!wEh(fk+oMuLVhP0R?ffM`7jdiU8`P|F5Kv;K1bs-qsrl9f_Xi? z%N9@|vV3CXlCJoa9dYtq9B@m)-=}=k!YB%>b7>;#=7qUi=_)JUhc!Q#^NFW$+So5VAbn`mP#wy0b+?3O^_!UPbTp8 z%gtqWPDske;RC&^?r2(TTOUZtN&v5x2289!ex;;P%mYsDweJdK*% z$DNyB7oDr1+p}UA&u(qzaICE3?>c<^g@o%vrn4ZS_}k&V4(=s4QSPQ88{foL%ThXe zW3;D+NWT^S7XK23MNOw22^)z!5<50-ja(zaaE6P4Ul}z{I{FS}4Eec*OBrN?C1{Lo z_E6tWs4TZX_f5{g7U(HAmw&SYBv2&T9AX=GHtps&w?cLNW zPi}7MbL7xrv7tzoS^-BC%{87uYsIGjI_hBby3Jc>dw{gJDiZh zlZN-*@e)f~G@qs%sd$OaR_W~!T%eW*hAEAZvLp3Ie@-&BeKp{L>hsxhyU{>9hmH=O zN2m@5nDtk|5xWOG;br|4obn-x-hn#v9YjF99~K|3+b@a36LesbrSF`qKy6pL4z{5n z0^$E^6oVC7Z3`8|=rSLR-;*O@iNyy@?JQgrF}D@g8J;RMynBjqk_57yCTVqe?m@jj zny=EQhy*!w_n!4*;a<%_(Saab9@=a;_xxTv;Rm6*2wj@V-E2LWdtou2MlUq7LIPiA7Adsm}d+1 zI5_wY*ATz{aK?_ixAlRqKRQ!59ce~rVT!1aKD=z7_9?8pZ~kVLllGA>dE*@$PF6mNdGWt^u)!BTini0A&8vlz zng*Ik4o;T%Exv|?Zy3ZKhF}e|x0WVK^ja^eFmA8%+;{vsZUoF66D+*27s4P0~t73Ln_@)loO_BUCmNMMK0nXW6ilem3%mQ8yukXkkTO4uY48G8R z_ID(i)9xOfeQl3B(ylU*+u9XkdQ~v$=SO8Xoh4oE>IeqfSNqSL&U(hyn@yr4EKfS@ zrC!;dDjdaNJJEtIy;=qTVK`H>D6A)!tSHH;2sI?ATqa~m z+MimCuB@`6!d_)<$uYavFX3o^NR14;6_$IO19Su*2Hfm;rBZaa;g z${-wu{FXOM*BD$kIWsuEav?*oCHlr?>tb@fnH{K$QjY1imQ7&DU&d-IRE4g^^pu%| ze+L5u`o_WzE7KYPwKfAvOxlLG{eS5F-spPU{p<)8LIP6@&Y3(*d)IvN1!4QMfOW;(@=f-(1U=J2}ydszDfk{B4E|8rnbXel8 zz)0;J-OSF`B15m8(%sf=)CQa~0v~z{%wKK6j_aN-)v!(xM81W++bL3X=pX*A*E1Pu zQqqa&kf|BP^&HO)C_B6HX?2oxAsgZ^o3A6}aj6yVOV^wl@`6-nSRMMjiL2ML5eq5< zKuVR~UWD{HU2(jGS}P>*3MDsre6hCGqvb%=>(+?a0|Y9Hkwiv!w#0v%1$iuo&4Oy$Vvs3sH=P2jj_AAO;KzGb#>-VYzQ#|4FLbYOpYh<)@5R;b1u%n>Vbo`5m4K|1L7u>Z&t(j0z3 zqgZqeGO{3~=9)ITFi=#fUmXm<_<-{=L_)3X_$9EX=T?7-IKLn^!Ln!Cizw$JhKG5+ zDQT(3`DLZy*Gir{Ie0s(w`=RDX{Aqx``+yA-m^zU^VFT=3dD|$KFX`%)?>TIuT}Sq zK>TsJnszcvPm5m3KnO+V9&h4%ZGvwLm|}=dw4e0P`A&c*q{<>5!#haQ?T~+e4sd)C z-bm#dE>Sp)!^PQ_TmU!E^bL#nDDSf^Qnf)-Q|dJTP-k*mIz-A!H=~cR|CQVHBS4ba z-kniPEcws5@S$SteyVa8D!r`_stxyN6By`ulOEX@@bOoLIG-o;rr~x-Zp148!j)6i zn{CWn{-sg*kghpzWdK}Zcj_@(kFTiVV~>F9WMJIj=ve0R`j z-ZX*Z$^b^dBC=^w{mf*nut$76_E=c5t#r6K7VVMC!1qamxu*K9tP`bynM{-%U&alK z2*IrQCPzb&_i*Mf9^UT9@41RRp#tb68j3yPgiTBU#&e7Hud(eBEkRURV<18^6P}U6 zNhK>pA3mCyS^~Rh{Yk*-c<Ih65oObT^?fk%%{z#bc$ogJ8M&mvo`r}9E2UtW+xL?mJ z?;~=T^;TQ$`Eh z8iYdi@y|kU;wD(jB(?ZGX!#YWc3Ur_>`B(cn?5+KE%P6-_^&hN<=7w9UoxY8K3~i! zO%uWOWrgqM78um{R{k>gVkO6skihQ*11_ejY_sT?3P0MHQ7`Fv$a z;K|#rjI0T*`pzM-e9MSPUE*bVxR_VT8rbp2!Yp*+D{h1Xj<{)T*a zT8EGO2315J$?Xg&Ukc^4m^fP>00l%L-$vJKwgYgLmpcXN&XxV(Nhh^`eGEaHN>^b> z@20f_*M-dLdC%0QSDzzCM$%fvWuv|_z+XyNXkG)K4`w+mv#y@a_E!62U)}|J?8}@- zgyBs|dkixe_woUr&Bov7du>g9HLdYekmha5^@?tGrW+MI6e700w-f$0EMq>t{w`)M zXB60WAo;_%F`}gwnzGJIBgJ_=)x__@U z{Mz%N2D5MfJtl#p@#IgMU=aJFH9LqI&A+<1}Idvuu- z8cV>~++ISHw2k4<`Ie1IPxRRzad$$?pI{*sU&S8M7Qpw54w4aekjn@&QR!>wasZ{7 z7juPYo1@?cNY_{8XAZkeC6(;SGElT;-Y#-i^rPE%o917#=aCUou`NGg4wpv`Y^4lgh8b7Pae{Q!?UCGB(E?lu{FTfM2jKZaU4i z__8^?3{lF30r5p8qZ&=L=w`1k0sK~2306kBQjw|R54e=q&4mZ_nvj0k2d2$@N=|l! zoR~=MtgxGZ_1w@;u=|*W-_XWeaFxt8oLXfl`4jrNZ1!;%G){ZkwG&M_+*!?BPEq;P zM9wd}vI1!$ylVySlk(6mRl+mA*L}>{=WYB}89vJwDlc@6B_}LL<7^V(otiZUgim4_ z8l0)DfABqJ5P~Q47g4p_3<=NmN$BNPm-7(1NeCH!@X>Wm@J6|$+jbdUFD55$NrppKKnYhHOs2AZN zn>4GriKBdNDEDmmz1siYL0PZrIPeM++Prv2zZl31oN$Qtls#iDD z6;rG|NaYkP;!5XCsSC=?i)DW8X>ebQke(8SziH6$^7CffknEb6#G9BFiaRJYw6xQ1 zp1!zyLt6p1LzkQzD*BpgCE1QtrOGl;ZyN~|Pn`StDWnNUA9lxhV}Av*dpkp>`;~id zSFfQn)@G2=HU5-wUK2I9o0^K}5BI|8*8jPw$WxK;K`AIoZLV8=P^*Ce0OrU{Z`U_k z+^j#!S+3o%SjOXxMc+88z29r~eR7;cWP68NqL2$ZDpZiFTs8ew_>HJJ@c5<^QSVVD zggC@u-V+JE)mXPNqa0G*I==q*z-fUD8PW>k<$5w7sgT2W00D?Z`LO==IeH z!btQdjhdm~f2nsHN0QWBK7<-qCmuk?{4ONFYQBEu=Y8*rJ=GQp!?v z%mf1P0t*WR+C*W>)k?JCTsqF{UD7#@Sh&6{uOtMC`7)}e-(08I4#>X{nC%cVrJfUx z>vU5ox6hrg&#_s=2HCl!bDpBSviI|~Nb}sWd%mn)+=*B5g(AP@&zgM>u0KZPxS{3@o$NN_>W+;kZ@(yTZ79w=KZ1OQr#5VsZF zX;Kuz`>Exj>%F#Oc{al8-Obi)EXfbh(ebIr69)HZN7W$#)pk3QtzpPCiIrpPXKOwW zdFbR4)edrd-(`>9GS zdDQ#iHy>0|+0UOQb$LctoV~Yrv0-WStG-SrWetg6jeiZzZtAsCJ4`LHFIZR0I*gFg zPc9Kol-q?)RRBc+KMVFpSbV-&N&dDe0UNknG`^C)3;kS5i0*V;zwVVS9ZBZAOWh&l z{I)-jc+f&+$wlBG*lxm#Yw|f+1AIf#pNluR97)fcm^`>+3puDuELnb6?$v06qpz}dB11e;$YD1H@t#k06 zFXYr2J-;pf0OMlxN97&uTjsoC#O7l%?w?m7A-tzrK5B*HCg^^M5>{xhtuSr~084A@ zIkURKOUQ&N4M3L-p!qR$!p_ZF_;A&lhI)XV(It~^4w>5v(r#`VDs>;$oG=+>NW+0% zFk+&ynC2csRg%x5h2@~~6SkD(bQ&sUvuW*E9teHR~)SS#bT@f&88?yTc zP+)XF1xZ-#aZeq6|FTky{lp`TTJe=L#OL}PDtxIqK%SE)0yJsucF#{^NSPLr-&_*hnaV4NXZ z+Hirl9BFBKLhC|cd@%QT`qvL{cDR6UWDiSN84%#`2EN~F{(+Rr{^nk%MUiPgRAC3n z(*pUzIHe4iaCjE=X|6^aRcI~VGx7-1>YdOrIvEBGyBY;!$9P^D@h!fmgo1|^rNfv3 zU=>ezMZ1fv_JuB0W9=2+T)c^6++O(L82dNn5<>F z#glU;cVfbziC4gk4NfpgmV)}+{2=>9*P3W3o~qx|!4cz` zm4Ya8?1cS*Z(J$$+U&*zI<*@R`XFFoado9}D$R*f744ZYgR09T%-I;02~UOb zSMy);c}!~xr`qmlAG9eLZynK8+vX`27wvbGz_N2q(x9j-YWrpjqXz zlNk@ek=gq+4Tk(V3<6fplPrfw2_z_m^7ULu zzILo7OeT`Wtkhbyw$zgMzJn@a{-is>Yd0F5AwK*med#6)FJ4BA{mqCF&p!AjByZ&f z6xVgLH+i_U_be8cTXJWvXA6P3TsPw(!ia`uh*GZet(j&Xp)FUh6YAv;;H_{{`B~)F zhxZ{eyF0gzQTs!pirLY7Zhq|Q!-%y&te(3{9sT(Q52iIj!>hz@M;H(@Yru+Q`f+y! z*-Rh_=Wk!hqyTeSf)AQ3SE!b0u|v#EeoB&dhnzWuqMpngUor zl^k|xsY)}ULXRI;?CmrnW&L9(ce*D{WH4xzZ9gfzG;#F%c(pUsl*k7 z{$t3t(0L`01WQNa3)wlc^#twVYi;OHJEmM1d#s-lIb%VAq_j+28?e{5OWK=0UTl)< z*lK-}*Cz#C7S*yt3>KUxOLQlKyg?YkB>)V?GI;;pEMCbDqT?xZoJoUwq0Kvvp9If} zEN3I4)<)D72MY?wUdGmM&^}Fuan7}^^tv0IaG)1nyyT)%zl6d^E33g>9ky>E2pzeb zE8B^{8}F>d`AzV5ED}!le)TT7N98u-g^~ z&g*=Njm_VD!voIQa78FX3eVd5(!CR7VRs`*>7l*_^Fbx;x7gcc)XputM6nzR< z<=>snzuu9C-fm<7B}Lh@pp>~Hfi6@0M}sft6Ap<+KyHtV_3=Upi!WI4nZDPI)oSqs zq@oeo)EcnqNz=~?uh=gjT7k^f&chm01rj(a*4$KEKCh!fkHuIp|CWC+S`AR_eHKKIk8{E5bM~2C>>v=OMquZrem! zT2kn@n-3MBi6SKEQ0NIunojI7Pl?~pGEG`Mw<97Tp_p_CuQ!XAjDc%7 z)lDzX6Wc=W1l}zs!@eBX723zn-Jn|UIx zprxO5Uwyd~9Yk}%>SGIjH|Ye=(>fd(MeCiiQRX67kGWd0GsID(W&vvwey(5dAF?QQQgOPChoqMG z2$vAi!*q9@yDVLv{8NHp=o=2NK~!p@LfWMk@6lUeCO*kj8Vpq}`A|>iZNzi^>vqMgcS*YdDpUr*j5X zMWUYoih?7_L3tRM4iw#fCYw6lUTgA__%WA z2Rb(ikS@mw<(hxa#KR5R&a}ur=S*1q{F%F7;t_D@7?q1}*KM>qGUoN@^BEz*=O7cR zp41$pV6}U+&P5uNPAI+F|F_ILjJyi$smkB$g^oifW5Kijs29#hl-9~0^I{$_s;iIK zXUD}~C%(27tw!rp$;`TWRX~ZzK+}3bV|UzWPgIe9NxgeTKjY+VsCYD zjf#z4g@@1QEs0&^kc{;7EraUB6UB;^ z+W#@YfeS47Te~+`Jl2s$05sD|eZEugpR|m(_bE%7{=sQ`E`@ZSwx|@Kg(>*io{;bM ztD?hi8r69$Sy{ar*f7DZ?thRjdks}+oH54LLg zW${cuav^R0G<~e=`|b@K#c-W8){f)js4%AEtZfgdby`{il zs_F%|mJYTs^e+2PWa#7SPIs(FvS(MJ9XnfLtwXQ1h6j#x7W1>suJ+R{30=$d_)8wo zqpMPL&0G!hD$hcN%z1A&zkk|klG|(x-f3hDpr?~@vQ}jlANAgQVBe)7=(d(qpQbOp z+VSPJ#>Tlr#sl53(51IT{%E%S1h`14rASFa_aOn<&Pq|7)sy;moWq&<37Kt@yyTUJ zHK2*6i&Y_XTCXCjcXDPLC=UFfkvQgYdjqYd8$ynmgT;pYW@y2acMcnZ&^}g? z6cqSUtpu;>G5l9NsZ1LgwTIMH9qd64T$9BP?_4TXRmsx)M$i0eF&Q@FSjo%5<(x^M z-;m~YjUI_8sh(f)0yz8{kb;f1lJj9JBfDy&w=tNRbe^;{Q%{Fmx>9N=QaZb*%(ujp zgylPXW2=2;?_`Nc>@wt=KQw(JYpyO4-gSuBnE3iGV2|~rQF4rXU!p7==*+@Y0Co-u zoA;A@Ip}W(VpIm_@0XbGJ!Y`|CMmAJ{2m!#-`U zRw0kH_X$h8MGNXP)7wxdA^HABM?}7dcGJxuY+2n7Xk>CFiz%U(Z)}5bCjX1Ew~VTz z2^K{m5G+V=hv4q+1Pku&?gV#tcXxLS?hxGF-QC^cZjvwOox9%q@z&zUuxF;MtE#K3 zt9nK%Z!F#+muU<=8WLQh>u_&2(-ll=Gr4^`<8eW`!ddRB9Uf)h9xT8z!(O6)h3y%z zP*d)7TTegi-uJ#VU9Y8usY9!cUgdkz?mt7eK8pzm-IWg&ceHDd?5Mo7>!X*};}D=s z%m_PFYIaWX>|MSFZYR~y5bNC#CA7cuv?o1ch9;J4_fIB~u#2brqguL8p|iLXE_*J! z@j#dd!R)7Ia6P(IGF6JJ_pMmtEGGP*8^stWzO|k+>G3-wW_&()YD1U#C1I3;TFs|$ z_SK$?>mc31fbHDF-p5eSbu*(Exx9QHg4luP$4L1trJ5%N0c)iV#}d^Anw`u9M49_IxS>cghTE#Im{?I4)MUDM0eM}>feSk?p zh37WArl@m)P3}OI8rP^nLVx7`S%Oi93BlfuN-mH&JK$Y^s`+)SV3wdrZew$tn8Gyt zHTjUMB+7K92lch!t4sI80doZ9=Bc6t`ol8%5VL!vKi)9Jl3Dn%ONEC1Hu}H37Nb% zAnppwH5GwC_wVC6p>zpn{cxTVg$A9T_Y)RZ(dTGfOh^isdGn1w%oILlq0^OMfbD)t zlq~o@nwCgbL|V~$^=h-XgWK!37;Ca`A9QC?qMhj!?5_5{r+DchzR2#)Y+!EOu|uiU z;?dPd<3jhK%XD_4-hJyLr_4FP<*5IY6XbM`>L(`Cji?UBjj{Nh4qJSwQqI);&ZFvN zyTsjWF>-G>j+XmiLO1`T?WjONdmChgCBaQIT&Bfh~#Oh2SvOlAg>onZ}HD-?~+n_50br2gI!YSD^ zrms+c~g2O#5hi`c4a{jndSKqlb1Qm$iYo*8-Rt$NP!VukIR3N=@tcG!d zC4?snnZlgrZFZ(@p%-2k&m|bbmXno@F;;yu?5G?S6DD_PZO%#?Evkwp2Y$0%DbK~M zIH$~pT#%#*EJ1X;W!jF>5f`UVz@6*3c`sN_()chflXu-f`OKbxgA1MK{Nm!aniI58 z8~=sb;=%CQ4(u7_Wq#kKU5LtLr`Zd+0Ush%xIk~aU#nE5`F7)ZT@vB?3F*zP1ANXE z%G&M}mXhOjD9pU#3qXE989er7&1tyZ%h8osp0=^-5=T=bH|L(dFpoLKx>U%TZ#Y+z zt*5T@Q`Bf5!BJ-3lF#<7eR|%Kzcd{*`{FP?x{XFa(US%I`9{+zwW#BTw$!Fg<-$?M zG{QZwSnsu{sg`Nfom_f?J~&lr%!U!)has5AWXYCR?EXGalWw}9%C6bwM(dZqZe8Ey z*iJBGd7IB3l{@Kn)Ie`{%L0y_zmMi=QsaY$kVC1cN35E&lO~8t?P#!6Uu&Rc^5u;A ziP&wm;I9T+D;DyY+)WNhE(^iepXa}R4yH0vM!!zupnT?F&=VwdZ+7p=>YJ>!RFA@R zt*_qxg`G}pxqS@J-MDj0gN7$ik+=;qQsNM^m`Ou46{UHVV_qmZ!&GJ5+V8~V7lnA~ zB@-*9hyJZ2Mr-L}Qoy&%vQJjw1E0gU8IZYT`i><;XalDX>%G-cc9R znj$TR;Z$C1neaoI3dKrK0Fe>QX@~Ma>(b`J<83y7XMg2j`HGf7=h{{-w@{1C{h&&j$c$Lk z>0cqSGga>2DbtSVH>R7QX)jfWs=o475(7g?au*!ayvHh3^|jvj;|NJDkJnqkr?p`T z#u&&PDct7nFR08^DjqeCcbui|shM&!hUTpZq@T(_FZvaZMW7Rox9xfL1IItzB2m zU@V2xEQ3lf2eKq*tgMC3{2n7PIwN6 z@iUxoP}r9zFfMM+@1d0rSBqv$Qw(*`kUfMd8^-T>It_NkfgUhXmBMAKrqg?~ON$XQSMj+bkv5FZBDO0sF46B}e}u`b{IRvTo0<-p>ELnSNUm#nNb$AT1-v*)v}ogQ(^@Ivv*gdj}R z91y%qoJ)HPX;4fYknJU5?mAljF0JGl)!Mp5!ZKzm0?9{}*ghFTK6zaNKR1sF#3^tr z6R0_hH@=&BuFW;~t%!4P55&(%8M^(wiY280EH?D?XdvUc$hh29XR=K3JibSgy@1kN zBY|7}v-^?JZihxDajtSM|JHUPMOO*q{b%L&J61iB-&YznSgqYc8>?Aj$-;b|zCHbO zDKAHd$Vo!PW?LFajDxtY8K|PTYk~tBuM`wXtB2DYFv^JABCXfK7LG4?eoiRGX{v9` z5~d0{Zpk4Jj>!Xk*Y~Dl#MVFirNRzYqMDh^WXt(X$Y)FkQ?-76yYjfs)*rKY&tTzj zmTPhoBu}IfTr3Gke>rra-ksPpmLhn3ff8aYmFT@PD3Yz@$gJcVZzB(Kq&eLPoYXLu zZXjkVRmc)wT&l&qK~|&YEV55=GQnIAI}m6a+AUUY;ygQ>HJQA(WzJ;LTJEe>Yk9QR zC&74P%%1j=aeJ6#T{~Ec1AEgzXV8HFMozhY-2}G}jJzWn2FyDce^N(38wG;vd!RxNLD0(tvS{MJbGCsmx>X;LMBs9F3}urH0aF{ znO%Kz1z1fZe4TIAXs~ATA9OS2o zQW?pn-RpJzdF`*hM=c2U&d9@#J*lqj&S9_=W)ybHIu_|Q+?GsRkZaCCNK}A;db{kH z1~5_s?lw0m^4nl74(lxs@>V75UQdghhB+9KU(sw}2&92%j^@X+Zxe4578Vzy$H&01 z$2 zIW$(hl=pJ39&e)6AXSFo&T``F<1@B|FyqnE%*_0^g)UzKzFoc@K5 zCbQO&CF|1z=1U~aTvSBsEy8}uQzOM=&^?I*fqNM>3C4y&F8OYc_LEoizVD@MZgzAQ zG0a!iiIQ$8NW+IbKPIbJ^($uGQg=I_*_?J*@fcoNnLIgPF*|-ttTIyn#F9F$&$MZJ zGFJ4%-QT&46`(Zko+ZMaqS2=05NBR=u7Z|1e$?VsQdEI8Fxgly(|QEI-lNt&TsnPe z(?x=9dDmSZWt@`59g#R!&v=4yFV=PsjWwc%wg zi4q04b9+@QCMvTS&?(8=j+4?x3XSUP{9qFK7wp-+ zU2hZHY)xMc^e}>hgL&!6$De%`gm=bP)0{VN6Pdz9LXmLg3V-o)Hw$%0o5{v#qvfIQwc}zZ}!!R=e>ViLSlxQ3-6Hg_AKK ze+%4~+$Y$U=+ax$U#!=RYk%JeX5iLHk#=zbB{3Q|7>+Bja|?0tU>iJ*pH|UhNvhKj z(=Aq(ZvDkn90TVAr`qavclA7=reZJV z$6HIjE5jPrd>G+7qYtJeF@3l=(v?i%u*)Sm694QDr}A)bi%xBvoU7Ksaf(f!3FmvOLh21xx%r&OF)v4a$>-Q z*EXV^l|;Q~BVjO|lJbN-d4rHWLZGokN^u}DuIu-@-?i&Kmff4Wj6Qm6@wr|{N9xD( z&?ugbI&Y6A*3dAS&}7z`_xEI(88=Qjp6Tq}Feqel1qYePsn~OU7PKbbc$Il*k0K-m zIGtg}t?hFSPBh^#!2VJrR(fX`hM2jV%P)ySq`VlTMROXrvy+wHPI&@t@0Jc+!82S9 zsQx!qfr0q6+hI?5Myix_j!4~!-+ZOKtAJGP`eK7m{AQ$Qo?QdHGXznc}u&wwh`F&Ru9B0-My4P_12h5&(1f9FCdeA~J5@H);<#~yAjQ4rgF9)Bu;t2e})_%{N@`hgB7O8b% zh?S0@PO`hYULE2%T9*@edZ^hIt-v<%wFML4LQxmW#eIsS-VK8#kO_pniZsPEUNSIj zdt>METV-VHcP*>EimSY2T>L47?|8n;ml7aJ_Ptbxz}bD`8`$f%Cx~XbA9Y_)K!lG6 z@J#fG%w<|W4m2JkIbaY7-yR&@+V_rLZCAgxWG1^eUu>>}sRA0e1v4Kn=`Hz#%g90~ zPPx&guK5a+cnrb%0qsn9HoktN3=hN)7$pgspSH*B<@^)mD=Z$pI_0{AJ44u4jcDzS z@8)j-A-%Yam0h)HBq~|L!uv4sDvfBwn6^+=Cv~n!ME;)S;n3nNf+Rkp6>c!b0TPQT zn0&jZRbQ=!8;cDF5sG79gYwuD2&bj#)z3HBP|3;;^K*YCrs)m_iI#yE>s$!anoy^wt_u2KRKpz_~aFJ|eOZT7z#MrMf?{7w;_DXv+eH(fYra|Uc_ z%a6y6<|4SCASpp(Jf4Ke5x#$c8be16if9%qNx1#oUb2cenWZBfvE6rjyqF*>ee-BV zZtU3+oKTRlYaRzqwOq)uF4~6Hxi&zEbT$3pdycM3aIIH;bUK~Z9v{NT{nG#b``y%t z+SMS8yEB+#@W86K+^M~gW6#J?WD%-Y8e;o-%zkmX7&ToDeB)FlF$H<$*QEDa4qhz3 zVlK@Kblcasn~tVXH3E!zx?9#NpE`>tJ~;_dLYe7}Y))N4vat)8dGxn)qbPsI2rTYU zc&mxWDO-IW_9RvwJ*CqPD<Zt_OQFmyW%fujBo`Ps0^ss}IihR46beA@83o$@f}1 z->`L7>@EA_Mq{0FWvZ||Hm}$96v|lECD(;`*J&QKga_gdXd~7aW#IGSnUY^^}ud7iocMuoTs_mc_YFA(WDRtYw6DS{seok zB?i4RGPYdo<>MQOic??U3t!xiT4gL{5imxD-)R7dCSlE6iGNueJiX61c2`6pqDhmk z=HYUc8jeBF3ga{GK$xWPp})7^FthDZdoRO9m5{|<+;%dAj^7w%V-TQewV-R^Mz~k! zNc_<1ZX3|+BXu#od5QhCzN`mwaC7@`bKZNe)sBcT6fKYJ>aN!eS7vTQ7gNg-1~LeC zH5pdnD-qe$!VtwJ0(Q0OT{u2`)}sA=6(0BUDP?Vh(?BlXG#9?| z#yK|I{pgYtXQ083O1KjX$$7Gt6u)vsLd$Wsg5QEeZr>206Vnks*C$ktgT3CGmQE#zVtM>Rni+aa`hqN+xqQq{tR2t%A09 zJbtxCg7^pjulSZjlfZ`Q6@kj!B(z&&mB-5?R&FJmAHhNRNig0{l+vV#R@MTqfi6e1U2rdGMOZ)fkjv!lt#l>!FXZ2U|d1Rs9Rf8A!P%TZlSTJ>6-KtUTp!ZHgh`h z4$+SBbFQwhZ!9J-zu|>PEKutZn}|d6SH2xM(`b#N)HjvpRs*%tWWwmmz(&9CE@xTLM>u*g(psdon?g?uSp zQt@#R)D@5#41i&nuK=6L>riRhL?Ex9Ihe{ohdrDTLt|v}9{zD(b^jaq?uTEsUbm1#dhp)CoFh72JN2^1 z#kk&jlgkbJ=ZQ_#9KYaerQN5@FUsz0ko_;KPPSoz`sKm<)VCYde7Ul}W=y5~*QtK2 z`oT*{%B&nRIKnjRtU8y@y0V@;eDYL+{IQ2qA9rIu{%!njFC*w9F+6m6OnW?Jc{TbB z%t|_Gp33g)?ueVGguV@XHGDjZ{$ga|u~-{W2|m}W>Rp@4(xfxvMcCDmGC;iS(Yi)% zS$i|l6jx9iip<^y!lddpFe4KF3k+eLTJOed5y`_9w$#%ZoCX|Qso`xbXS(=)y_6_j zXV&iwI&HhJCq8rIIc!n>V?L&{VIz&3Ho=e-Y`dhkJkqQfD$iQQl2EYzRsQ33DVaYK zqsm;p+CQ~~Pv*U%bt|JieMU~~(cBP?jQGCX#%$ef?P%jWQ^)+H;U#kyK|S66>zvaJ z_E?IigBJrxcf7_4yFF@~Y{(LDLFx-yt^=YCBhF`3)2De_^rW!WMxWdHn889b-sQ8y zPDcf^7^6OTRo@zenv$~G=IlpmoPP3zmCEVq3wXx$Bo2}h1v`37mAsz z_lC_Lp3CUGUz?|fVVW56Z@Dp%TeB}t`SegmlkQ@59{UPcu*WUp zog+vyqP`pgJT~f75DDP}V6uZXqQNyaFg;7u^mJC5_%6%nue-+WluU}P-S~>?S=JF& zz`D8IAtuD1M)>yj#=uPLTa{d&{5vBV#QFBLJPw;Z6PrR+PCgT-XpPpCpri81-@lZ2 z!ow*W)n-MCoZE>7Ts90z`egydb#=sA3PIm?#&pZN*=*Uk>*g!@hXl>6tbNfjU0d)5M*?Y`2XKhZnZ-yR-3oa*xb%IVF2_jN^;3Ujw zY(>@*!sAgWMd9zbV>S^XdoNlqM`(I5GsF$c4ZEKgcP@1KscaRZ&cFNA&Q!MEmN{F~ zMGG{@ocQ26M@gMnBGux+WIc3A#@K}8ISg@X|AX zJ+_R{Yz8@dP3FpGS~I|rN1t1i*Bf||R(-WZT;`KPG+GUcpH`I{WuxKJ&Ciuj9Ry8( z#LdR6|8;)@BO3yjHJ?}S)Uw_JF)!Ep_`{rIGBXM$6_Udq^UFM}xQiax+pK!tTl`nP zR$fz8P;Z?{;}GO{%%>F^y&Kxm#?0TVEHcPnh8~|c&2`0>&N?95V?%t~AuY5-ED;kO z+=+N9?F*KlT;2zc6q*|K(Xf9|_Sbduc|4ae37&mct_5VATSMiFnHk}%Tq^pXZek#p zn<7CavhyNoZYAb+Bq}?wa>U-~8D&|9&_ z1AU&VFi~t9Md1pNtA1PEa7GskiOvDG=B~jvJv@=~3L70YLJnD~O~w=p>d&tH`g5(V zhbi}PPC7Y=t0%sHpCn_QDd!LOTr-|vl&9jNEJd$bYcDA=_9`eYQVEkiZ_}R1D3jT? z)e%f*4ku;01yUN%zzZk8pGOU#7)E=3Go9(uc-U!pmm!N>*+FF!#3*#6G%}FJug^$7 z*v^ekiR;-cH)A_96l`N=vYHxXBLNsJ#3lW12+%cGf~11+YztI*HMW6-$oL)fg_}q$ zJz{S&>l!v#l*XWVZv_$zdxxZNA~OZR&Wi(m7Tu{J#mWKYCgSs;5**lFXJR4;byrS| zHZ0EDQe+1qp_+K@MI1z@ykhKQCpww74g2O`3eGn&R@)i|9fS1Ow%Sx@@s|ydiaBib9!gFzzNfC}W{o7srm7_MkKrF0@Y3Rfz zCnj_=cd8Wo3Vj>+9CR8)XC_E7jn64|;*^uD4dpST10Bcatg(5 zai*^murN)q?!;$Gxd!iI)4SLR=V763Ui8JfT^0k|;?@UoQ8O!pLMh0i%P_EXsXnQo z(b8D`y@8KntZrav1lM;i**DjR(a_~TIiu0KUWrGL&ibxpem1mNbT#m%-h}c0`d*}6ZvgXl%NUFvSH@6qcq%1$Ze5+ju1nh5sqV8 zJ>vVO>w+Ua@V-dK44FZRPPypG>~T*iyQormgc@uGS4qRq{;&<~uqpCwg+)7$^0jI* zxq3?@ZPU-KB};}?MA$@29;0V+{EIdFgd!0N7dNDWZ^!JQ0uPof(TN zG2njL^};jeBZa#>a86c{E=+7~cU;hD_{P*joi?|P_rAKax{!g5jwNrMzY5<@MI={G zYdldCz0nZ~A%`%SUfT;9aFoz?v#9GmAdcSkR#7emn0)U?t0D=Dy_6JB)AWsrsBT39 zXqeyEtqy?-pbtsx3s17iEV4X*%g;f|@`*f0G?$39O?F`%WiD0>l=H7{JVb^zDOQP) z-M+6fSD+t#e$Z|g9dS`7f82;UMZ=ERZL6UIwvY7JLq9TlA8s1A!uMNMiurY47TQnn z-97$5!dAtGGMK#5tt+XZz~`Z0U!_QN^qGfD)MMosbVG9=ay=uERMbP%l{ve%i3I%qq$VqvfvfT2YXAKJyE zSJ|;WHLU5@M&gR8J5ixyv(rY%g z8_S2665h}Wiz__tVSiaHB=Xj@w+iDBTJUBizt`&7v$n8maIRts{iu2PFl3q-pg#z~ zm04$vcGAACg@x`sTz*-R{KT=Z8&`f15qf(qJY1Kfo7ySw2CL?>DBq3qi9eTAd)6Pe zn6pR66!w}&*o6P?V4-tL;zs6 zew|z3P+fl)u}qH)^!Tf%fO!f_*h^)HeenA_z4k_=I#cV!feqM~RxnhOll?v#9jy-> zPKqUT!OJWawyS(}mnA;szL>B!>&hQ&#$mXIa)=0tYmi~aZVNl3Cr$v2pAZso%3*)O zqR|QT*~np$A8JOYxsFoQ5Kab-4apyP5f$kfe7wPADy^mx9GK2FSqh9 z?w{XkGpw=nm~-t2$tDty_@vA>|ZTRlv~k zD^EX!YN)?0aOd_+afrXT-Bg!k&S@Z*40O01;mYU4w@kzRGn(VEeHsb3<=-Pe@5=yB z$mI4z!M;s)jxZqpksG=^^$&BxEm?$;u@u>i@(a=o+bu!EVQmL%Yn`{3$GxRCk@|X? z+-)(a&h^&smA#4He9&sv5xDHTu8_~}?ecn{)6e!slc(}&@fmi~s41?Z&H`(!Jb(G8 zpz>aBK*Tjw&yU7JH0pzd{E$nlc=5@b2ihvCI%scjXDI&V!5@@gXqOikCkv%;ZBI4- z>VC8sX$a=(8qV+WPB~UIqu)#Q%#{%)W@jdUz(C{;W)Ao>QYF~JKeO6X0B?sli_b@5$Pw)8+3BT8s2cna|mZ?wTDMGWf zSH?{J7nE}o%MdBfuoXufdT!w5WeKR8>s?NM14toC+mD*T8fVL0(Y`0PB-fDl5Q%QO zkxZp@JsA-iW?%HrUoe$SneLsVIX=|z56J-kGamzFi-X+o4({TB^+P)cH`82s0747Z z&TFY0ACigV+CFhop6!XkLfuyD5WKelTEYb;JNSRR@gKfD(*UadbzE!eu<7Rf0ydQ< zQFq|w^S$pd5WB1A5-8H%UAds!{i_bNVS4e$3;$5F#6s_J_F36tzq=YBmEwm#L_7os zQ+;{cruIROFKx`7AG5YQw2APPPCrU$q6z&wKffgIw6){^f#U41PrHwo;^2#{w{Ez0 z$(r`%PWL6yL;tM2ynnC>h<#%$nDQa6_RUOW`T1B{-1B37XU_rzkl<-lPIcwm%d&AF4GeqTW+Z>SL}!RV zp)O#EEiWqr65c~1fy?u8U1Np$!m=2Tt<57mo1dIRU%uK1Ndz0F(0AtiSr1Zm^!kw8DW3QdK=DS5w? zQ0}KJ?O2{`8;!pjb?p@JpI!i9J9{nu1}wKKFc|^PHwDK+6h_1K) z>~>AMExQ6&pC#bqQ>DPl((MXnL;8sN^RkgP2LdkXrh--7O~1N_lm8QbB%ZtApW(I1 zRL9nyYZTJHK!^59R|J=OKdG@+*oOb)sPW_Tm5KeuMZGiGwOh389ksz?r!wPjA1Fp+ zC9>sak^sGDR>wA|8d?A@@1cYl{iqzxLIZtWZedY+!xG%8dC3a#K;{%|H&9OK?s`y+~= z#P9!9MY4(gcNzkUxN@5J^KBwkjh1R3c%Th!FNCsm*LWmC)6>Cs1*u;;(o><|9|wCMS=_K=&!;%Ssg@;V(3L1%Itp|HnVLicPFNrW?Z2tSm4XA+lZ=011x) zB)s_@&>GJhNKyA{#sz3W88d3d;k&qWz1?H1@beJqSJdL(Y`I0MI2U{D2i^V8C@1qO zgFZA|;4Iz@WF*DGKWn1~4M+{JjC@-x+$uSO^x?1613kIyDa}3=OWqHSLqZvQ%e#3o z5Iee98{37ZOux-!JY8U^HNB@QoC1t@^pZpy4q_bYADXv%WB=2NCZ!0?U=uLaVU&B(w!sH@pspJq_Q@KwLQG&G5JH0lEw5qgc1wUUudAi0^e? zmMF52_GT^Lw3GVVD8WCcQ}Ym&C;<|xk66Y_O!$?=hWf_GWT!HTCm|k1klyByP2pe% zqyoI_^^L7@$$y*!L^RVs3uxIb0;(}(9kqO2V$i=7!4kXC+w03bP#(IU|gaHXJ~(;qc$=i+zSG#!DvW^%tf`Klj!xis>NJO zDeE2viwHQ|uNM`1-EEF^CZtZD$a*C-KFlXHWhyhAtF`!y9TAa`N8?*gdSO{pY!A!2 zBLyd^#>T!GXMoV)4N~K2aEuKSvL(6=Cp7(S-B#J}7|W_!e7zW1a=e`jn6v+y|HJp; zqelH_?oxc6lY``3nt95)=V|Utfr(V$0+nG{nOyNa)P$d;C)&79j~DgXRJX~$cN)9vpsY(vGAU1fz=9Y4O!yXTp( z4?Vi~6jmmV)+>Ij-~iZZ!v7P!q!WObUu%gc~Wm2+MYhd!eoqi@rPO(6^vv7?qeXKQ7pbi zEIIqX?)_yxx#h3R^mB4BgrhCQQty9?y#zXl<8!LJ8!4(x>wQ@5^y|e0;`+%AQ}mGZ zH01~{4n%maz#86Hq<^1r&`Op<@(rM>yzcdYw9Fr;Tq{oL{&OQ}u& zMKeK0Mte-jL$^^@WBPX9V}-N5rQhGo`wDGnY12}{U<3!H!hy#7XS5{oDUEr8?~iD} zlN#Qxt_`=>eJhYpM0OwoyJB&jB_x)*jb4eX82Y@KV-+v9e?vJRE&Q1Y1aP#^{u{fk ze;1RN$6A7+uypuQ+^un6#q zw;yh38?M^Mnsm~%AkhXGTaevzxVmx~@phj##Sx<`2rvDzbTN#qp9@ekubChP@mnPW z`@iTb>Yt{(j$paS|EjCu8%z?Ngj!6r7GA>Ub8^GT>K|=e5Kw-Sc1*~~LVli`JE%-kdD`O+~Z&aiTB@ix>xjDIBp|%N;%_f8hjnq-3Oa#-N z>)Rf$2D464R2;EIZwkACu%!OJ*?}ShMIGwX9i|1o3gzDn@IoI4j#c$tjlsEuoP7x_YzgV!44zt zFJ4(-_jdH;2!{WahZTR!UDT20;KaZ|?K(Yh-l;3!{X2hPxyUPA(cd)V-5fkgU|~kY zFCKHaC;_mK2WY$c;Hs5&N=e}33g3~zb*;j_jr-=_MzC|hpUX9vg^rm0xi&eJ{H$dvf?X zYi@_uC^0j8GZWDA+`j3%ZgIfe{K!L(QD!pHhJ2R5E*rG9cYCv99NvPZNgqN@06Xcv zMsq_+!nE=yO!T8A`KPX~yFmzskH@W}C3OkV=#0UUY7g*hxoiehmNr(;iqz~523t!o zt*X(FXJd+ZXknaqBQ;2W+0)SS>g8snNq`7^2Y9}>o zJUb3>L`+(bT`({gVH4;NaROQkp#I@~-U$L?I3PV>NI?#Kw$@(;`vj*!s7N)sfy_m_?z;7{r~m< z8^}9yUrSF9<_OpSepvtqA9#;*{CAbVZ_(LNSg0)?2CVwX=U|5a{ZIx7B<;R+Uk{+w zde1SUCodc0>?^$yqgG`E!+q`lM(ph6-$e3Flah%pWjVO-na7OKibYX2$(G)%0m{h* z1^C3en*JV8(*HlCH>seOcoiDqeZ!?@qtqlsA8}6eHzVnTzW%KVo|Wq~o83A$IJh#6 zuqfPQ4LD980v|uZie&b`_~I{^y#yNu0?pd}Zw8^Quk?zhomMNzUNLy;Il z5kX;OqvZEHrvxoV9tvx7`jq_X78Kc1!jF3&e<2NJxjffPfo8#q5|+8rA(Gqs409a< zn@nXvgFx4ayxD|IYBza?GAsgsr^$&C*pO>|VSbFx?^LEQHbgBE{DUL^g09=W*lt1q z@1kRa=}#|@^`swP7!Ul12p2w+cva|hrgZLEn@rdR`3tHYlz%T0B5T#dXl)hdd*tn7 zXh|B~&*vt!RQ^&^xY74g`JgaE8bc<)wRnl~rs@yG9w2qG`X z?%&$1FcqK&1mFHW@gIkI;P?zlxUT5xYb^mC^I+EOqS@6yC|ufTziKHp9TWWz9Um7i ztn|K*bOn*C!}r~4(>ujvpgm0!c?uQ?%u+dGuZ2nINy;;$vHur>!J$FMxqkVnY+R@M zbI?yyOIL?|f?+@9U}3UgufENe@-Tph<-c7z-%wT}*~|Uk=&EHu(8YP|!D+hfxz`Ic zUOxHwH~0(#Vf5eK+*Asi-yj%{vjwyZtC9aDlj{HeEG>@OAQkh2c_t$W~P)WI) z6UHF+=bj2SI^ct@5b%Q`m*NLX6jYL9`IA7GBp?utrlcS#E&-=<)CNEk&YrJV2Af*5a^uSM1tU zR+^icec=TwWV2^2rNt!sPyRqfCe}R#tC9|1^I~F1<&ypisw^CumWOy|r`(P4Cmp;? zyv;7y)t=dzvF&7P+;6P#)4xej*W;@(2k(Rrt@#i^SkSx^Iy=P(H__XO0pbh{6!tc|h_cA_%ThesEHq#HW(+ zWW({}>2ya}+}Z6VRjxd)nC)a$zy&mWxgNppfm5c~Cq^>9cz-qF?i5p|v%(9L`mYRD z1;LVVK}?q<+fy+GQh+#G54cyBMAD}lj>e6q&aq{Z-2#%$N z=9*KH;8z-cOFW7LFkKeUCt_NEAR_Ul0hQ23dks7+qdBZ-sN8t9k(}se@(}eMDtMij~tMp*iNfmz^F&wGxGPRf&8H)o+caG4_8Y<%=|J#_&@V@ zu5G><01=6hM<8L9xK1|}a_pAOWLq<6tx&u1#olRIf2TUC|KLQn6Opj`IhMPXwgc;& z267*UCsB=P(=W*AeLUCs=ZUUI>O}a&2CmB8{cz**pdHj7?(=+z&1luw6u3HH)_sNH zf!L26&c9Qo9|qSBu#Zi~76Xxrilk8_kfj0C?yo(mmZFKJCh(7f;W)EqwOeJLTo-0Vp~`j1xQsU zS#;I_q2;dy%C|yJE!;grjhR){oF*!y4Ud%b#$ijWxy0h^TEOR7T?A@Djz#(B5guAc zdpM90EZuE2OtXs)2?xlZkj7PW^#cyOLT}qCYwaZCvevhoEHSWlx-}d##3UJ$++Chp zTb>)aBWJk_SX*i*w7q_#1JJqlqcuT~LYGu;G>UUVeof!z)SF4WYx9o#vWaLzmI40{Ko2t!9eJ2< z;!W-SFK4fMk%GbNwyZp@)!~x-V+hDdKD9}Z4$blDNf20t6;zZ<-G&CX{b$6| z_5&|D85ZG~v)s+9q+4n3%P z`=OXdGlo=V3;N4_EtEIcq_hY6hzw0e2huK@k5LqfnVs%G+kM_FH@TWY`n08PJXOLB znMyL5|0XvAElzo~ClVRvJuTKhQ63I=dn})ymP_RjK`mdoEwZ0s%UV9JRbb^2i79B^ z+1|Dy*bjG%CU-rwycz#i;Dxsf?e?Ebh z&KVs|JNpB*X8w*7KCP%xduM8`cJr(8CJ8<3aY#}MQI%E> zmi`LT4zE87uSoGag4_Bq@@yV#wSD{fi={*#Fk{3ipinb<;eco)!&ZC_&yCW!n8%5| zgGPPi%6|D_bFtYNSdc7S$yFRQJyzWKDM1&7tKIjn!mpj9h5-B8IO2@TgG z*3jbgV-Q2%8J74~v_}uVhiO`)%%|igJ>JT#xbpPWdvF~skgD?lDgpYdLkqG6Nso{4 z`#f8t5ty{}rj|3R6Uy}!%vUwFhmOP9TF&&^Us&pkQsulr$sh;ygO@$$Nr+?gKYzd7 z;%-;LWZSKl^${QQ`?0g~eR5+ZhiT2BVEWcS$e{l&mkp4PkUv|Cq^57v`tT2VZV31> z$lL4N;}?W!8UdG`KP;MfT8nxI7n2MyJn6l>N_%-02vj5`*7zqj1wc1;76X_ooCDpV z-WutwHY+d1Rox-OB{Vc2Ug6eE2~lf2l;^D4muGNBiaK!?$h>lL>(_+?8tQ0fn0GRV zZWVCppBi%YLyvA=T|Sj#pLH-#v$M&lmPVChk=Q-g;Ts!G!sq>Z4NW!=A{Pw2U+%MRdUA7za$+&jcgy|t0ilY;9x7eP8N1$!6N|ALFlyxYn4I*IUTM!&<6JQ8?y@T)3o$331l` zKUBSCP#jFtwhaUb5L|-?g1ftGaCdiy;JUcGySo$IA%x)W5@2z6TWpt)>#ln0t?&O< zZOzV1Z%_Bp=P6Fw93OSXv{Oy8p&M%|-*DUMWNjD27&z;CGursa-ZW`K=#}4y0ii;F z$jbZSx%$@6|F8OkuzvwZl+7MwzhiQof#t)auV=m;H_6I>KZbPrx+9$0p&Hq8U_iO8 zL3dzy*6i)B4{zudx4}KuX<6!VVOcirJJs}4W~!8Pk;fjLB`Ln_MpHhqb5@|(Q1+mA zV+KP4*?$*66;e5-_iVjkN`6mwFpjc6wX&fwDXcy}KaUYu{TBm2Dfvt@nRDKifhCou zS42g2VHHR{^D^;q{Qr_Zg$DtI_T0wuC)b zS8d89Ny~I-PWlvidKwGkI&9gwoihK$HW`ce4I|#fnM941%H%U+?U1{z?H&tWYYiQ;j{Vnz7z1*z8IZY zW6?m2)9ldLqMsNgAKk!HX_~T(%nydY9Ec5u0EZ>ix5`tMFf^Pr%1Mdo;!P$3BE|l<4mdc4X+~Ur zI@QkP6JLp!Gdt~`2RgcK)f3(=zX63yum1(FTSS*8xiNYjKo5wtxJ!3s84tHb;hzss)~nu9OO}tsW;)*-PY)c_??{Smlc%)xb}u(_ za>{jG8zBc{ik@+yd)*7D(85Ts=zcUob4VC#4s}2s#^%l(#_x466NZpJ%YP~?BXP2B zvm7rddLc8O|DJq)Ug$GhH=&;Igc=Y_>3ZB|QZ7m;UKtKHrR5+Bx`)}#*`&Hvh3mz2 zd9|NS6+#>;ZB61<&!2v_)xAWt>Y=$%?GiZKc%;^-^TuK8RNE=ILR_5EteZ19=Ml;uE4vef&h%f($9rGR(M_6bbZJoxFhko z6Jxmx##gF4MM9gp2w>5+&-&6sBuf41sgo-;8pUXJ+cO8RkxLro&J~b*ry~y|VT&J~ zqxp<_2z)O2qvmiGvYgkK8wDg=2d&)6&UQM3ve#hLdgW9RpF=kg)qd}XudRN1q& zh6b3j$#ibPP8h#)vuk@$=Bau>VxNI$i|Osy6k|RXW$2`Ma&C+6O!*rV**IhyvtQKf zF`7(?UlsNDebhM`oo`A{W4aoX)mcJ22G*kttOc!^q}7O>JNj~2d;Ly$>=84jNI+Sk z)2HD%HS~scmI8~>Cu=GLe(%+!m-%^LIX@KP*Dt<4Zdv&WJuCRMSIf&^GrVwCDFI~& zJ8U0M-sGp9o}&l0E8hFA?;!vk1i;N&3Yhowi?ZTzFLWLq5fB*UJ1%qEv-RWc@% z#9KrSB*35Rje;dsOy=U-(5Mj?rfZ%~vlPBKGu(EeP9xmfU10PK%sVZvZ+F{l5MEP; zn8HEge#3`JOWI?lP-lv{j`=oC^>WpR5nq_%{>E&Kx&o7FGEwi5yGh?}tf^i@%afCw znm8+Gn-TeN4m*iBiDgO%*yZb1Yp<8{A+#(P>F~ZzK$G37DyXFI{5jN#a&+rHTxAovk- z9aOCZ>>USvp*Xmsax=-lLR;{x+9el8vr}^ISG+&x58Y|#o9aLlvOLt1LyYNvm#c96 zs?=OwcYU=U5j4{~nRC@Mv#-=|z9wa+;0%yQH$t&dyz5(d2KB3tcP#x$V`q5Xx8UQh zmOLX9cIG%3nBiYSAKvXxFeUQ0uUxC+C$WrI(m*--y_1vWN-*B30oa~tqk55hMeNOu zPp@9INi8srA5UBQZu5GtMTB+G*#9e%o6l8=ZJ?r6c=H8$zcT~4p9iA8TZ?^fe3j=aboqX)2k-sLX8uC=M~%43u$%m)x#sD( ztioEq1hHWnt52puZ}2Ja*c} zxkQv|e6hTal}de2Or>&Tai#WvMn|eAuA;>R!iXwmXm5SCmz9C73bz*BF!CuhYmu{! zNl1GpZo1CmRAVNcs^o0Ng=B9!X;dMh&qpWbr4+7MS|)FnM&obgQWTX@&CKeD^t~-J zluFSq4Mw8#dxuTb{)#qCcC_=ucBv*665u?QGBohBR8=H!HP(+R-iRD|_g zQ&XR}ktl<2hzj`QDr}YV=N)r~o927VdbR0x1{pco3aIOwKcTW-DkCUX+iUn95{sBc zmz}m8joE_d%6w#{nMf-}#fim-9{7{?J$yCE@e;%y86*6N?Gf$#I)9H5vrBRgYJ;yP zpiLLhQhMrb)cK1asw~;`^x8=v79zFyP(aUgj3sf+4Up*Vnu*NHVT$YqDQ6>i0i}Ur4NrLyTpXMc_mSoQ=XIb7)W%Q3BN_uh^n|7Np z&pu&4U>Xw>F(URq?mFy#zj>v_rUe9%)j6?A0q6IGk_0|77*9tGyYy)sGyWBHJ~(KC zxu2u5NkqLev9_0#`CvL_iLHe?>TrKLKcW_xAt?@kM_A3boUGDxuVh=FRh>GGw-;s#-#QZm>I&%<1`4;K9R!3jPH%j#ThYVj&XmV6z2YX z3!SZ~#}wB;4=ql`_+(Xpqa*YBH$zY`479K?^!NpIUx)AecNIP!Mv^*Ps9%!;fovCb z8VB&f3yN1bVXa)A{J?DQ{cd}TU9_->bLBYcV9o?VegW)mzQh+N|MP0Rf6E~h9u5#HeR@?V*x=);$soqC{qY~2dble&) z_F1fE5eLh&ROfyRjlaASU+eEq;Dzbnxc6>JAITpsD~8HtuWX()z?HKFI=3QhRG!{S z^pJ2LHJ@fP`>-H39_wuZg|ow5cd<9v-_&Ei(BKlcY7{yN~Wi;#cL?W{An|Kt(|mS1SFgV*cFby zoC%z6Cv8?#MdSO{XvG`UcAPaW6}ZxlO*Q{ZI94g%Rc;^S4i zg^CrX|Crj!BAtj8M$@2P2nF>iO>B^6p#76HHmCXkr519B(UccdNIRpGl=_F7Ty4~A zd7}$7l}a_%UV+qm{cFfxFP}UlEme0v^xu3c1f7;Tn=>`wBl?M@uF$y1#~)1|t4Y5q zbAwE^;vd3q?xH2?+ldEnqk2^wJe$1a#qFx}g(7^1qln#cC(n|QCUOdP4A_%fW1en+ zT|GXv-xUd<^z`*73PmYRSAc%p0IYwSi-)fUMtAB5z6EEDK~4#e>d#cM6LS+fziv61 z9K6Cf)2yzqK!R02XPU#aF&&OCjiQWZ@(&hC`x{Trn2>4IydGrOL9orjyo9r=o$h+4 z*;9RfEhBMs(>JdX!cD@{f27^8iI+}&Ga0^H<;(u9p1b$IU}m!XH~SLzJXx@j{_0BG z%ySQJzR&uVWG%>$$5x=lA6s%roR^sG9;@@|h26rJB7ZZ$6f!fTN}r)9TSO5T4*m^9 zOmh3$8!uxJVT{)lzCy6|jNs4r&uZFuPlJ1ynOIf<%Sf?^!GStpATpq4G&Af)=WV8s@}E~+F@GcrSQ8P=aA zJiph+`giUKMattj45Nk|!RU=Krs8pz7z@y5YBe~&A8q^SQ*AuvS_#a8=mwLggcF5s~8)w=IQl?0`5J#A!Y3?3s- z;`cnS{J*ZS-`VVI*8nBDt$*$7-U}rugv|->BWsfV&8G4cb`g-MquMF?fUa9W0wBW{ zgneP)e>ih?w0hl-;YDQVG_@1`{G<;^TfE4M@!ZyiZ>a!<>226t&G%f3-c6>+;1 z2ra+m6NdD#WdaFrIQhA<+of9#${PM0(7qjJ#B2&hB*A#P++3RA^TaCISQD-Fui6Vb zFPo~_Y>+3IUE#pWu5x=V94TMq=yEY;O+1En;5cY8l~exhjmW9?Ehj_Zk_7Fe++x3I z=l0^ye74Jca}^8M^E&z3`JwSL`fNXt!YWN)KF4{qsq}gW+73I<>(sO_pL3ji$q-tHRxZ7!OV}fhoa{KPeWVtbes~YFNzt z?hFLzPvRD?sx42I{`k1HFh7o9cch!Q zZ#XWaSc+8WkVxDwFTFhM(xPPsuMZfY0W%6oRN0$ zVO{a@-it!b70>K>RRXR7eSO_KQY@l7+@vtL`kVYAeVbO=PqvIWdTp$Pku8os@yt4s zViE1fYC}AAxaR22l(?S?wP18uDuji@{nI9fnv#a+Fh0YzFr@_3&M$skUOA|fg1S0HhzOMHP|>Q{Qr?S3{);1VQdJYB+uBru)^~Sg^roy% z3HrZ>7;vaZAh89@ycyeUmEqqRo;f3}dv8wJPi9pV&A-?l!lJ<1!1~`3sCnuSD%ywX-8Es?n;S}Vqmsao4=y@87mNAvd<}|?9Hr|veC9KyX zjsrcJd+xv(AcJW7`UCsMmWsKKE@j0MXjtxe@b4K7sp}O&(C7a;e~3;_+-^1GKd58D z|F8<{W5No|DLO<&womlR;^&t{%0XXRo*pdna^~jm1{^cA@dWXh^#`F=yE;?{{#b{7 zlon2a71n~~q-idwR7uWhk;n2P=&e>vH9k{j;P#KNh-=|VWr~8Kh}rbpcopXJ>&mj} z{9ns4NwuscPTrD1B-KK9PBx)@<`m|Oha4FD--CGzd zNYlIk530{r0dgf7kR7;$4Ny{BEuMmHn(5{M>@F%idge7r>-bT_ZbR-2u7FO+TD48( z;yXViYb_@;t>Id|e+3`x6R_^%zH|1|sBhCb@j&g(Io*1P%{nV+I}n`}7Cv7B?Kt#vUtaa0FH9PUM$2A$O9Ic@5cZ@eI*)hQ68-$nSiPwxz@@oZ+_wT$h98 z4THqg#9)z`s-+2@T-%S?_vv1yC5IO44^MTCmp(9&EO)r1z4iD=_l)cFtwl<}v;%=} z&1GG2>QJ}qooVB5MN#D;UM_n+>5>Y*4I~jHu*oAyv@{d}-CV#U2)WvXkHtJPmSXtk zw}{*Su>jwoa5y{R_5yrRxv}u_U<5yG;VT1!gO`KPE2JeqDyQ&y{U4P_pdUfP0}1yD zEPy{I;CnL^@uj#?QI6|ne{*q_*yehf>kC$x>cg4pS-e3Wzy`Vi;uVNow0*h|vxRHk zYs-<3>{ZUn2dfo7vvVfQv{}zdm;6JXE3q!u_^g;^ezGqG)idGL+HKvBQC`dI^^AYQ_KIR=BYC;|OUh1MB4A^cm0h?vJ>d!I^jt-Ko6~ zPC6z!$ZxIm=@WJI}>XwH8&Jf?dv9FkfV??cO?%%9p9Zh^pL_$OpvYUSzq_tg4 zGU~EC*(sM z;Ka$4s#@g}0N*kL*sZfXr=(f*g5KL-%;qwDo-oFsXo6G(@MP4%5RA9mMkpbwv0I~P zLWsP}S8EuuP%%d>U?rH`*GgIbtbQj_kl?40f9SL_q=q{5X`AVC8JBa|QP=MAvbXc{a z6T81LB|A6AeXh_osWV;S>h|4X1ahUR4-nx2TUzmJi29>?g%lYRR|!=Zx*x}w7s--c zh!K;Hdb`e*v)PZWQRXj$b6=EG*}UAZrylfSlvBrhp7vl=ZJGA9r5Io0@MDhZVqO>? z!B6zih(03HVdV-{_H%iR#O^tq!y0&_8UUCeAb7YDqhQCPq|n+4m7ewdl?{g=uq`rPUNipP{crGxN2s@RezTcQ!VicuH`kxJUw#-|?V~n%X4L z5AO1T`h8EL$@xaAPBqWcAZI82%%6QcUV9<{ZytIN>r)?qPY8qZE9@9W*)cSn0qtk` zcQH@Zs4rXMEuPYE6Pp6754oralw!;xjU@-G3CC(<_l+ghR=huX*1xU}#}ui329AeL z#|gcC-Qm4p&?w>3h!OD8c@vb`v$*6)rL#DfZjvFVU4ycaZ>N1-H>FZs`%#P3#!)&$ z2ubDWbf^0K2{nm4HfVPEqPNk!T<_W}x(quPyuNp2eJRj1vUPdrFo3O!`HW_4oJx$wCxfL{%4ayW{E>W*ZtvhwWzg-R!u>r$_N@xagQ!Pd zHhsLrC`C_nF1@g8M$N6#=rKNEWqZ+E;LdNe3Sf6w>|!w_>p^`g+E}!eSoD;cNnsfV z*UZiIMfs=gTy**KB#at6=ojaDqlZR~ z+U6hW3v36@YOSV_2^(|g;LRGv+aM>i7V9crFP_c5^{MPp2BvdxPzE@_vL}a|QIC7D z-J5>>*|W4&i}D;=vP!A~uSVx>6D}(kF=5oZRxiXgX4xyJ%7{^dfxnG(s!FS($OYu@ zM*Gf!wS*Y3P6c;N@*cUSH zq1rU~ST4I!LEvs%p7EDBE2kwNH+R?Or$2IMnsKtaVKqK!#|t^DUm>i9aSpRIoL>cs zv6_P+RJw8IuL%v!cNvI_w~mq%hkY&9Yq;-<{v5UD=SB9_?%TW*N+7W?!eBo%=f!%5d9}DkBFaq73Z24np2ao5F|NV zt-&@7H-T)o5DR|opIK^SI;G_W#(TxjxxZMfE01MW8~ypaxau++aD`;{%4i=c&sDIM zC84>(fmRXJyx z>bXIMB9i;fgl&i3QJhI12&Yf1g}J$Mzd!iD2dWHOk>yl&u5dtKWe#*8-82iR%-^qt zx=%!Sq;73Rf8+hq;N4QImDizW3(}3Aq1|XtdIEE9Et{|tCogY%pNq0Ol9tO*?gQy$ zT(roCY>=T!TO7P8M5M$_d|LX7MV|CMf*I)3qN~+~Y{Af5Si)f8WYKlpN#v2qL9mCg zs_vbB6|gzeX?1jK6pcilvl{dI4BGXF7zp5Dqr}%g+yorr3@i9yy%VGhZ&Uwuuh*BG zKs>jtIyp1r>ZmV=|Ha9}b>yt2^%fyKH5e)xeVf@FYN{583u%A<;A1GZX|iBiWI6r# zj||%ms5s4p2R>t=i|C9TwpiOU9sQtml!l66LkUFTFKoHw zZz6OYOkb>j`d-@kuY1Pt2$Ou%2&`7xwm+7d4tLyd=q$9BRUK+31{?ZkfVNJ}srb+Q z!+L>8O;_V+4z$v@SiYFg@v{US9?$Ujyv+0$OV~~+N&{b;y*wQeDH*AMsq_My@4YHh zML$u$gWxx*F3DfXwkVk&Tg(ohFM15_$oQx@Qzmm?>U8xcnz63(zE_^SB8;Et<Gf*9G)%UCMtKkJf3gUM|nj4 zdK0}fVmoD+kU|j!%uwBLum0=fFk+t*$?52elS)p3;@HmeGPE;He`d=ht1EvD>1T3O zv7`?sQB)Q3@aI%N=sj`B8c0DJVP-yQ{TO44v{zN;cvQc;NI&ve(}Gxl`*>iH>f?Op zCccAc%~_X9bdKIW=1fY8U2P#j#i@UGpzV|qF~%M$C-wSsikEaCKMRT_E4uT# zlQ7)#tOa>ap*T7oUg8ac6tdX-;lFt1Q$0^3Qxzo>J(HgKlZ?b$(0e=WsFvSP0(OdD zE1m!T#TUmU7z$gDtI6z5RQ&&e3oCE!0bsAL=i znMLaL3VPW&D14Mn4rVkbFdXVd-Yel@TuEAzu%hj!%-mDW5Em6vZnS9;H}#FW>=CXu zi&3-9?u-xijDK93_v}Cy36H09CJ)xMgkVgReD*Cm+7@}MPQYDrqGAMCE^C4 zs{+H>533pYZ}=r(Yp()l;n>u4p!Su}VD+^Q>b2gFZncNwQzI*4I}G783W4e2nE&EF zaqXs~pY1TbQa=9D1=)m|brtC4eN~$~wq{HRE_oofxX8TB(hZQg%@#O}%Fn+?!euV# z#UpTLjPASF425#=ww^tu9?F0U7nW2SEJjPv>SWTyfEt+HlcGR2{5z#tj(`2A`CLBo7~S0L9KZdR1;Mr(7iZ8e#1)eI#7ISEl15xE2Vn zXFnyNkkJ~z{;!@uZr?hMpyk|ANROYACsQ1M*hOCBZC#b0lu{4LO@1r`W*W6^-8;&i z7WXKNLIzH}Vu2O#a{s^JmVkmXO+tKprLuUT9Hrfz1jdIq^N!u>Rj~A^#D7KLGw%82 z>0%RN6!NxcH&HaVfiXK<5};0NEY|8*L_>D#MWig=NyW_Od3GnyPx>cap&J1aW$$`t zkVw!!D%2htL3Qs_7O(MFMPKgQ_>AWm-n|ja#C(%CV?C9ab<3vTu+H|{Z7DoU+UzYC zzD~QZvoWeT8D`ULYgWN)SSGd9CyVO|nwAUXDEi2Jzsqt*KH|=6)>OS#N?Q{h_3^%H zAK@mLp+@nACNk7GIG##RJD`(?h#O6@q!YYm>+$$~;tBhirlt@nsI%?^a+xxGi@z8Y z-m$;dqamXsflJ3D5}>+lJ~OYdkmueDJvtpZU+@a#y)ZGZJeFI z&<%3cU=GAwbXpmnweWvs=T+fU~aJszGCn9@>p*Q@=SG zLnoauDk6Av^*dZ4T3oDn{e@?3_${ldT(Ewxj8_MLm{5S=oW|t#m7oLDXH{F6h^CIC zOo!bSU`X{D=Fbn!xHEVTN8n=d$FLqP1KSoDcl{dL&Q699M!MfpXvbo&`1v_MA_w94fC;uIAER-jd8b z0$khC(`oG65{!H0f(+Yy$~ zyIw;=%FZQSiH}z2YW|T7c_F}c>b31Dthpz0>f3${Rp8JlhH+X>SyY*rnK>8Z36^*~ z=gm@6YGP6VPg$*uIA~AAdzmQ@)_Dr+=8SFmEY5>qv9fd30yYynG(s78@gxBFC<31>3IpHT{3On_RG`j|FzN4Ssv^rL+>9V#uuM$$#F^-FY_ zM9ra*#s|fDe`^XgZ0D^0G^_gt^Qpo~%krN>iF&wTR-s*!h)G~%-t8wd=081kXA5#k z&I>(4GLQq+rj}dk9be$Hzs1MVf09uZ71vltu{GoRr^9w|L(Ht8CL_z0ZaupbC{C+3 zl9fM!*Kibzhg6pHva2@l_Nwu~5k#iN3RM=0Hudl5C|rFYo^~keVOp*><}L3(dVdt* zXl7-74&W!E!Y!G6OYwv3X~OFG;ZpRp_m+LYssW4GJ$^Glp|}_9Z`r#U##Kl43miVg zTbdxhyjF0s#~%285k-GL<4;ui5)v9Z{5_D3GJ9^roGT}&IjBf~nya2{tFRYX$3R7f zx%xgs7f*FWEHJ-(T`n_}Q&8jr{^L!u4+#v$+7jY)w5YcjkpNadWaAY{VR%au9~1N` zxc13W=}~zYZ;upF{VS#46HQ1mY9@30Qs7n@3!hf=UTLp_#?@!$M_Vt^yKDk69^eO z0R$>!M^TaT^_b3&11_0qO@c(38bsp|%|flQCP`Qv1sK)X_#z5qTA%9~=+2IBzKQ?K z@&*0;HstkbYH20`-qNw~q-3SpK8N+`NOi}?2Z%ALw$yC@W=E|xm3vHnflLSik8O_`toWv>8v`QK?8yxb;i-r@xF(@Au(E5blFksn>qoV z_Jdr{9}}YpX0pzvtsgZL@=ue=_po!+l0V5ALWv1A??A!8r{@(${a@EzG74KWcmSVU zhreImt|k8kJ5*8#!sv`xviq!4^7*l3t#on!Uc+tim|nEu47I6QW-pP0BS!@cc6e&u zRHmcJb#~+xRK)F-1%dG)%gDP_Z9q}mj(VXj4Cc3>&{j9KIF!b3TA{nqTB2! zPV|wCCc9I!C~mrQoGzev>Y33e&p<|^uqU>pDe@@ZqFG(n6>o~o0zkQs2yATgy!`-v zyt_yrJ6Y}{@D;E$sZNZFyTjxA6-#GvmFz?HBTb;GnOT!%%l|{$Y+nCE+YI(&NN~6` z0y2O1vQ~=Nl;JaG=LAr2pZ!25OB&weY4Az@AQg4G_TXWDR=psD*Ejv0#1EM)dj(Sr zRvfRCIA6aN2*2XLXlc4KypiTlZ~R&G@6Bv6#W&-3J6H%Ik=G{ru{wtZ3+4^11QwL3 z#emjuT;EZ+HT0=yo`P>~oOb|PU<>d=n%~Q^7-XXBm2=r|W3|mY+fgI7zrm1KTwA#` z4A2r3`J2+7&rv{$GaLT?@*s#+v+QWSaSzwZj4F@ELO&Bb3<~p zFVo7K_{j3=cB;~H_1lkrT$7Kud+ATV+E?Q>r?OecrVEG8=SJnPEh=!IKunwVo$k3>- z*Pfn!vKNuQ2okq;AMvfY$eenbX~WDqi`zr~lc7|q1}^Vmxr5FB?oYPezxU>OPa`en zU(xPQ#@rTAkcYc*?@xqXal^)VPH*_alHR^Ta&UY*@VBmDIFc#l$!f@p&pmgP7R1W% zg>N(o%lFwv1YQ`~Ms$W%FKPm`Z=j@Z-s8*|lFd1p`;Qvh?uvZ_UXDRO}#z?-CsReI&6?3tHM4i;+ho2?w`Mh(x<2 z0z}g#GBr%O988?Dox^-VeOI@tCEd-Q#c1ynd|%c}YgSUJ4$fy)qUS9bpD$54Z1qtX z3zg)lXjjxIL%_gE|c-}=MF6#J!c&5!O=$_CD#PJ8HR z1(F8}4f5q$N($a1&9TCPr!AFN7WWZZm}B{Ns`iAaRZdrJty6cQuj-!&3At_6+rH}w zPPd1Q{A>l1b4~k(XfDN?U{_Ez+>O;JbU5$&QU$a{_}*noh#`nd$AL3bqzTv6d%Ua4 zFuNV7GtOS;#&<5SY(El}<-YG%v9{teaOhb?290bpP&9$nz=@TH{*l{3Zn@*t-MdF? zpRRS7;Evv)^H$?p4D#?PLa{OILKV8}#nP4Q9{Lj1nVZ&{jzp^*H!m)`&=e`rBjdGQ z3CTtvQuP&`BM|{-VY;FyO;st?p+8Y6aqg6r+;lOW#qs@#XU{nV$_`#zkhoRAPE|Fi zrNcE>Y4l28WoB&iwX>Xi`Lu4O9;Iy3zAjqs9F;{V&AdPwY%!p*T)!cm4Mm*q2B=@F z(`^q{_h9%J?h2}~@lt|sLBBcAUH<%D#NK)Q!eob5Z$4j0mAU{^xv_f7Njfb&{xG4p z=FPCTl>lJC$+%HPAIWw~S9Mq%xp!_JYAYv9b3%t;o;m)wJ#a2H0t*>YPr zTQ|_)!X?ED>=L{iBi@)h# zv2vzZkrueHemd2+d`LLz7QOm)=(Ce?`b$$64=>l%)$u!a!fQY2+KJH-ah>av z%=z&y9ncq)!H_c+@lq6&@$}=%tf9^tnhT*G!!{QG#3%f3Uz00k8%fT8T`Vud@b}2& z;SKR%|3q-rN;{ec$G62Vx!t+Y);5pxe*XAJfSF*ekJ;avsC4^jMx%iNUq^wn2BQO? zawO}Yx3|Nahn9l3+HJMMBAbo|uHJqt*&k`x12Ff`DAhC#0@KwqsqlsT=pHBCiq_lT zm#2K>(+jsVBL_O<{S-9*z1pDFziE?3KUrrwC5EfQ-nyRY=m<8z!n4 ze(cP>kd5?LH^Ab??z}wuzJXnWR;&7|&|8?H&pw&|?PCBUE&~wI>jpQ|Yd1 zUt8ZS;|GOgid;eD76_%Cw`>Dn<0z{FEk_A6Wt~cmy8U@W~BB1 ztF=BPLLZV-M4CDVe8!e++)fajdDs1g?->3he4;69rQ++xHS>#tOW2@VT_3?YsQG9C z{kU?Wjq%|27*6#OFvbrI+vB#OnpyJ3Hx_-fZ!6Hi`~vc>xb$T2i!db>v&1aP9`WfOl7 zZ@bG1vPW`K+7oT81a@UL>*d#SA&LsCqkr5V-AF!Wj?5xF0aU0h@B5y8=PI8VeNf*X zsjxB(SiMsu%tP;9^+;W-Pq2qU9sCP}eOo_pAvb&^l-u{qQL!(lzs9zszeV*L#al`l zQ}A_%_dr&zdiJyAj2M~_Uk?D5VVPfiYxMP6qXQ*;{ftNzQv`5ryO*{e#qp0Xe-OMo zyS;BRYWzPIE5D%bKNgD-qCiR=%<%|I!oHlMPB&jFF4){3lHFRc{pp7HfkJQgkG!A^ z6lVpA(@FBy(?;X_UfcA3#2_&~XA`8(IF%)L&ps7x^W`gE+q@C7$;`8QOElp{_{)yl zdv{7^YAoHii*?>zSigvmw^n?HO4iV4fv`{nq>*QqKQ78A;=H)5Loa(N`pZN3e>2bB63`%z!l*0E`I(DUd$M9L7fTK>%Z;i&5-n72OV_Jx46iU5VU;Y%ka=NP3s~{H?RK8n9Rmr z*=5c; zGKz&xVzr~g5OE{`dH;P|4}K~(SW>)6{l4Tv=jznz`j#doVPT$GxTFD>xQM?R$$sSG zVR29;p#}T$e(v#=BF$CsM8!ze;5(d-HfoUpZCFBrKHsgg!+bDTYbHU331g?5sU{0P z0_X8v3G+LDLp()6;f$Zc4?=gF>8g#D+kEB>36Mv8xh)_03C)}J<4vp;q@wtr2~g#; zrxL+0hHNh6hi_ru67BZF+?2?Z57gHM>rtOu45XqCR&QK91QWiAu(q$A-`bJ|dyDKTL1SNW4t4D7PILGU=6HN0-_Gj2#t^WU%9VoppIbzaz` z9GytS9+4QUR|5FUusOuCa20@_9@K)w(xKP;5e{cWLJU8-fUI3G4Efw6d91yRwWX`5vF<$Pb3!SG@-rCIN?`2=pfwR$-RD9vNsURl5n1QVdWho{%-DCKaGmWE2R zVN@MUEuyZsm@w8o9k|*WZC;;%bMke>30QqGz<9yAw< znmG1@-=no><8s~ZM{9 zZd^{DTHs6J62GYziPEcaw9EBL*ZA zKzZz|h3sxw_nJDEWV&psC64my=>k=^ta?PldjS2>vub*ZjSV$F=C@?emAKN&X#Fw) zDYFe^MD)?RB^Mw4=nJsc>7l4ORWL(b#5}O9qarmG&qh+1bRGwV*7(|%@BN45`287n z#3KxmW$ud6)OZI?M~$= zc3SgqGyEwvj-sS!NknI8Wt}mab6s&cC)d1F(nIV8r*^#kW2sUTd~3;pbR6~yI`PT# zqvdg*a_{yegYo0^-+eBLG2W1xnB6U7+l012B?DKzEg*xwq`qrZ*5K(ptAHkl-~cy z#xRxZ^5L|Z%#N|>`|8_8a)AFb4-AGCEm)s^lb-UVh(HCX$6%w6b&puaosD-t5Vms6 zku`YK9BE>xvNdCWP`5I z%F%@LqzaUtGo>DV6W)lb69ILX9H0if1HO^oeDLEgAcM{c52b~jTu>Z~jkBG?PLIE- zy`7q0kG_eePD~2kM;)%t+GZfAps|P)|Li!asF5~HPdBA54*Va+bdHs z4FKQ5=nbjzkqBP3>A8Zqf3z3Dxv>Oo4t!D=LQ^B5l8FV6mBr;tAcJJ0Sf%XXyE;hu zQD?2iJMl{tR2Ke2IpY{*ztZJ{`(i^l?MV*zha)4^e4gZ{ti@rLg`-ATB3?Yb`R^4)x-F zHV0cd(W$_p%-@=P0*%(^!Hr;+EV75lVRXHoZ^>ynqfZ+{l2#R!`03-5aA;#vwe-HV z#}>J2Y@YGo2n__;IK118TEFYje_^XLm4NqI-(UA4JGkm(&|O$4Dm3C`?lY=;hRd5s zkxA>0>dL}T%r9ci$_B5D{QIXtnG^hQc6O>3Lt7!&f$MX~4nR3-_vHP}fZl5?MmxMJ zmm22|5SVoWGeRwYZ9X9Izo@R_kX%D=`sMzE@m}AZm`MSTY33z3xk--dw&!$p$l1|v-)?faN?Q1|O$BH(WbvXMw^K~|Ex85fQ;m>tQgmV%3ZQq^(*ScrmwDs>ARcW%IQOac{4m1#UoI=? z4~G1;Un`J1OVLy}@9^n{l-tjn4yj;;(f9vr@2lG4YMOQj_u#?Zf&>QF0D}|UJ;(q- zf{iKj%`PSh6-D-Sc(8+$+5u(-P!{x)BYEDB(M0T}!qn87%d-w%$uF9$k$<6K)D#H7gJoX+9!3Xlsm8?74_e z4Z_O5gRM^&w-3(pMMe~(INS;=6dDV?`hCPcTe;#=^X<4o_0_(Zj5kf+(Ec8 z@N;hibO-wFOKKer${T<1rWu(kmUzTM&uy_Ejk2=HcXz7f1Czo#e?be~-qRoLNrqj# z=;#b6TskO_y#c*f#r87uPqdXBCC~q>mLz3@B0BE)E_7fQ95RqQBnD!hUwu? z`xmDh@;qM)n3kb+?>iO=e4NRc2_J+zR_MX{GE5wtvs}Qd-Q4CW|KXVR31Y94v1$k&o4+jAKj!6lz><7~#+! zZLKL!sFp^?wO^|@`243{g2MsT<9AWP^>J2;khGA{<}2Ni9fo1$#nTMEG zTGB;+%AlS~QH6T0=CsP~*R!L0g%P|aOn|7*Sdq`~_D+0Gn71z~KiLiVfTp0$k2*>C z6z5^uX}iKLRdu#b7E>kNl5G0go)AaPz1pScTHkAZ?H>rWeVqLl)G%|1F-W~V2A2VocSN2p&?9jKEf}Q7zH+^3>m;p6;;|P;@8NZ z^XCSp{(^K|&hNJmrohtrUwR=RnsJFfIU@7T`bOCJ%CNApIdR;)H1>G{LvjcW7-(_3JrWqFan23UXJxL^&tuR(!R^UV4 z9xETdThjZJ@W!>>!-!pU*KuqOeA3N#AGPuDT57rK z0ZS+<7m?|K6>UfjQK>Aoay_%h^e^Ze>Cl;|hEp$B2ojoD5xMfNGg{3x4t&Am2bS%X ziX{KtHq(7%!>>Dgeq)0Huid#f`g+7|xpJ^dF7cXrPq^8_w6gm8=B<`Sy%a3ou~{p#oX#4FU$cYZA% zf3b;TD0otbg|&6mZfWAGKY0+6fgkbX z`L8zjdq#j3s}yCij-0eiwtwl*b3ex^2OlE7a?j*xmgi~zW)SAb6ZSstrQp}_`D8z8 z@S=C_s85dtM0Y_jzo>ht?fYJx{-};91o?7i<*jLDT07fvJc*JNVI1*-%PH>|c_l8U zXf$@btPm2%4eum>k&MdL#zBov?V6lec7P;&tjkmPt`^FR;D9s_VE&{vqS_nUuk%z} z2Vs56wOhvS5O0$%;xZNYD4%!Kqo>+=B#(JX^BBcn^EXG4BoKK1+4tJ&k-#V23OKQ( zIvNi$ROP@#{ktG6b4SWqrys1jJ(pjSRurD`0PD{LCtx+1Mgy;Y^dCN68^cCsdQ*1XFnFPY0<#{#m`SU?ShaQI?rXcvhsD@iUQdPt5 zEbrc7#aWHakxPJK_{x65f3}E#+OGE~d3cuDg<8(bguBEzG~01d&SLY|ik(jv zCZu)jaA@yakQ~kY)^s|@6ENA}q!b^xKXI)#hg~c?m>;$osDzZ1z50})aC0|NHj|D+ z$~{;-J`_}hmgMkp#W1#4hR5Ka_+9NxO4%s$;3=gnrf7a^qS-LS7Dr;5s5@W}N#{ip zo4#rP-2YO0a9KR^gM4DAJwcQGL}*a-Ytt991?`n>DM^5OJ__}_=>sYwuastWTt*#2 zG}5S>I2FV4zTp8X4mv`8J--l|`HEo2MhMq+>JJ{xRoO{m8wzqyt0MP}( z(#&9%PPqIGr@sEQ?&WmC z(KefW`N6LHbmQ1R`V>b=F=#4TRX!B(tVTnf1OGP(56KSuF{sg73+}vTJi#jtm)PHj z+4(qha(of{jHQ0h-!ka z%cD&qr~R8JB_$d10f1g(>G)Wzs?`1ayQ*DOQOf z@xjm?4XtOMAQBttYSJq4H&v|L1x~s>p;muCRvI>vH(l;Ps~oAZlmWSh!bUy*L~syl zy}%1}t?r?v_CBrKF>RK9`b$4n0Gfm`3=y6)Dqn&^$mhD%K1KivDOU$TDAObkO$okQ zfQwN+xsrXWVGm{OmnR2*J=YaZU^+EsmFqzYO#d3TgMf`o*a;#B;JWUd^Je?4LAcG2 z;be4z@_L<27EnDI+fYLrJo-1`|pVBb^^S8K6fq^Msp^FQ&~>5R5Kf9UG=$$|FKvZOtY(J z1>{6tx!o!WU_sbJ+oTGgXUlPH-B(mT*gZfdBDY5hM}dvS?3#3 zMXHpHLmM_DZk~&_jE(sXM|H`x;?h+W1M*-yMO=#V0)a*N_Ed0>ow=YW9o;*`Zwy}o zi)dDz;QlDDIQ_^pZJxE>L+a?-@OXG-1(bt6tjPTo~6i!odHMGC*XE+ z;$C{-=OtK}^$GyhP%!}{5GLfs8GWfk6%BkbWO^nlBYF3;7+2a>luV}Kl@P1)(f-W> z?MV6zrlR90^7(c<7CUywXZoR33zmE%6Pa7bwoF*v~+V#J0=^{l0UhwLB zE`$;0xXhyX&_oGkw3g$Ql$iGJH5epiBavqs_4L3oXoa$`ItvJk86~)oIHGHD?PIqe zJN^c#YM6?7QO?osS==8ip129IdpH{zk-~BZf?z6$z&g+Vac$I48-m}z#_aZI<*v#D z*9~{objGR?rD3d=GYhyP*9kpiOF?q)6<_St{Ro38AXc&Xw0jE)a@pW=>o5fe><5V` z_oS59pm17TTtN(koV@H$(YD9EUogf3S8k2Sx&l!@yff{kA!|hiCT>ME*+v-{;h%J0 zcPp@lt=ysMN;Q9KYSQ2BvwpHNrD`Q(=S7!b#`!x*Kfwl zG8N^8!$=u-6qqC~36;h{@dywQmEP_%yulL3C(XZVA^IUmqBG8|hYceL^!_gS*hX$e zC_|)>hEZ|}rAn*`R61vAl!XWFqn7yYjq)CTWihbIuepd0?h~E@I>~T~bQVEEp&eYG z_Nu?|Ud9sCyWJa7yDLf0(;wiMZ?Gkf5Pee>g|N(2IY1;Up)_GQ#DHyH|_gsiJefj0`?tDWg_3|gc~VrjJlj0 zs+&MfMM#)40xONMIn?|U#LKfzH?E8Zq67AuO+OWZ?2#^ zXfX%#fL1d%qu&li2;KD7#HeK|a*(mCBbu?uue})CcoyO`P*l>lwL*|6gBtP3+6Jti zI)T}(snI%?J4u{aJ^hmv7xdGV8nn%B8v6<{$B}CNhF4 z0H_nFtO|>XNnsyGus-B64P!+^N4xT?R$JVXmcIk&r}V;UG$5#G*_6VODOvB7MkQmN zg4tvuB?H>K%&q+rS(%I1Z(Ds#+f!alG*UX;`SuiK7=FnC1KKX|Us=X;^qHDN%s+}0 zx;^#m>Z+c!SaW2G6Kg=r@q)|Na z!a%IED!${Ko}n|N+L}3lv+d2Wwlg1hU;k$3hp?>9oLV8SyW&*(jNagrt9kxw6YJ%e zf$|i$XmOgj!9xE!o&&zgqsRCf|53RW94Y#;lG^7v{PDcu#x^l*su3bF>wy3vY6NyB8&Sn zMB0h&-_Bbt^uED1uZ!6(c+xGmwS&XevlgIY#j&pX= zL%7WQ+A>vK85IM&O)hqs^;M6MyC~Iw+jkctM8t6@l~Rf(zZ9-LJ&3lnUHU6Qo>c3E zb9s=L2Vt^nC3*t8O6P#}b+SANW@Vnmv^H@@D*q*T^GJ>WSF6iq4zkvc{g-On!p8ct zL1kk$2R2bY2Ai+9MSce8Mnl)=`Yt5jZncH1gl8!}(2=b$CW;4r3*vu+O}?T7GC)=lZgQJ0=oaI^i8- z0=E%lMtpQltJQ@XOVnLW^_M^DnLpX<$ zTmb-hAC=`my2|s-wiwNiZB#mKFo=A4^TteKt{mfrrx-msoUN#OvAZpsIR1p#9&oP3 z-@*`Ud-W;leoo>3OEwPim&@J70S2k-9I8n3lA5UgSY?g$)cO||m*-35&Hk_bvYdP4 ztHMrX$80f=Z}Eb}Tc{-w$N((a4zc{6>(1H}kx;tD%rplRU3}+_z6zZAH{bYgmq;Yz zqk%PNNS(PYcsRPMB8LGkryHGqx~Z;)i>%e?O*sE=mMy}ZJ5L#=|AQ)MFqjH zG>5ZyX7~`RA7VM0COnknzdLYc8-jYpOwJr1OJd`eU z!Tg3T%IX|Zm;`D$UbG|+#>9X+Lkg-08hU=x;zr2LP5P8I(#NJSLc4t1@M;e9sNQ4{ zgdN%MTNE0gKz#nY9i6G-2Zb=1LO;E4!fRnyYzzXGIBB$B!t^!bUJVYa28D3FF%USU zg-%AOn}1m@bM3P(%hT}E>T;Xt7E8{Xo(n=mWF3^JDDibKUZ(wl?varfJSF!Yq&B+;;q1{R(wK|XgX|N5c{ zg#xU~^bkp0XSvfC>x>S5&TTP!jMkHMn3=k#$aGNQD=?RwQm}e5g;tW=1l^xfEYZ|3-h+_(?0}l4kDQURE){gnd z56k2;)2QFjCW!Q3ifJa|9hjYi276m=h)uSbaZ?mHe`Yd_ zr06YCy$)@vQ_3rxsHZtPV*LT8hVicYYUe(vdBM8)rN_B{8%^t=j}Kjp+kh({J5ESA z6Rwsqx|mkw04o@!Zw@h*EsU!wcZ?J?YCJPrOaCr&y%GG3loOiELJvUW+Es&j90U zn(_Qq)1PtkFq9!M@4UW;H>kp-#g`4EEmq8KMlBG;knGH`r!LeekKeefrExfDptTN* z`IR6yKi+RB6^L5>=Zj*10!}~!Sd5Z{lJxZsExhDVI8Qcyyp39(Yo_xn(VvDf8J z22@Q+bm1_OOMGj0*^cdm2uUVVqJoVRP5tiC{-$#(W^7=yLzF$|?dE8~YMIn8TCe@q zUQ=;0cHu|RfhblF(<~T1omQrOLc|Vcx^0U`XzfZH4B$2k5fNR*gE}1e7N3s!gw$$L z=$YJ%=&l3YagA^NfVFiIghL`Cm89QGv3BcrS<~?O`c{73!Osfe&|2w7?D&Ij^z;q zc;COebn1u-1yc*C`)clf?CU*Y%8-6{!owQ;Ri>TgnX!)?ek!qcY_@zC=X!8L!^jhl zh#@9Raxx~y`y&ol8c9CgY;Q@)ha?q~eXrD?J>jG820XLN#GOn?j{q)uyruD-x>h1i z9^d+)Pjd;e#H2Z4a79B0uIE!)PK&U=lg)$`y8SIQvzcKJmoM$^D?_8ad6P?KlD1Ln zHY}RB2DJ@DR_Szt;m1P4N0-Eu?c3C^2BWA0O+-`ToSef2P<1)VJ)`8~1 zd^+mVVs4=e)5Xm&#s4~ZG|EqC2fti~$W4Bx&R)9rk?=Fw7)|#oOV{Q`wEfAXh?6-| z9AzjA$t1DmAKH)*?eFbr<(!mF(-IZ>0$x$=@!XHTWpZwrgqScl_XqAW<0}x;S*(h9 zo{c_AC@3pkE2D*pzGce`tAM>i_(SNQVjuIF2u!)v(MY#2zp|(0GCPX$JAEtJ03nBu zSrIT3%5*Cyw8O>*;IMOXK~evh>npi@SPLWcPYnRk8<_@ zi_`=UAU`6Og;D@ss$;x4wD9X>I3YFGS)CC3kO2D7!oKwtWxj2b8@n`iw1Y05rEtlz zZ-d$HQ`PFCMxe-N_JkE=5K0C3JtC}Bdw*Q2Rf8vD;32o0$@+oPgImyaBv&m{|iwB2PVcp-v}q`_hb8m zi}Q~C!NAjjitC3IKj7D01yaUnR@ckF130Ddz__weI>oIOYD0k+puBtl(rnqncw52e ze(YB+PVlIXZMe@e`n}L(oW|gPWv?npgv9geb0`QZT0Hdl0^f-P=(u8QcDHMZlv{j7 zaLGPlx1gc-HWqw_=M?(x--Ca|H*uEThcEp#XFto|$KN6a%4>a_V?kK;)5O?XS* zeTsF)o}%ZmC-s|ll?xkt0b)@SIhWP(X*us%T&jq5rsSmGZL=7!2OCPUVA=+-{%=4+ z-=t`T>S>2ta~;@*M-&?ylRcy_4`kuL3tTe*R)?-d*4#VI0a|C1eL;ro8_j1zp`560FKE(MGM{V;c%BMZAHsE9pbgY&f{D}e-@m2B4?Kr1- z@hPsYq*iFkf28VPCDgrrdqa+|-9TTCwV0R~12rwj<GNZDg9nXylJdN?!Oba#H8w(+B9y{266UzO^&+R$YJV6#%2X%*M56(Jnt zZLCDo|O<==uTDS`PXCTbruzB8=Dn!5P$|===o}u z!;u6e^FKNH-_Ef0yUDuef06f}8F}#j@v{Hg^I7^Qoc}-Y|6U)%Pbl(t<&@YmMp=O8 NrYx^6S1n@!`5$xXom&6^ literal 0 HcmV?d00001 diff --git a/assets/firstorderlag.png b/assets/firstorderlag.png new file mode 100644 index 0000000000000000000000000000000000000000..ad0c9ff8dc955bbee7165fff6c484222c5a65eb2 GIT binary patch literal 38160 zcmd3NWmFu@mMsJi7M!37!QEX#aCdiU+}$A|!6mr62X}Y(K;!PNjcdP7?tJ&n%$oJq z{CxF?)xD^$s#E9e+I9A+P(^tO)VBn0p`f5pr6fg_p`hTnp`f5q5aA);Y{)IDK>olw zf00r}gft&S(-6q#_by_ZE-LnBF78H704Q@ids_g5vxyS`VCQUM?{W^)DF_Ai0ZK|# zSk)u_WYyhJRc&eT@;oC&_089J+Hc-WBfU%gKr9Li9kW(liHhA?Ve4DodaFNIArn`4 z&Dib^3oC4y6Z9EVlJ#`$4*i$3;cwa4ln38em9w$*xD@XZ=Sj~fBdx?AA^$W zXwiSSS6Vo3v41|18`5;qkp0u3WuWCT{%J^>Zymz^{Ucq<0V@A=5`B~SCjFm2WSCXh z8`%GJiU}xyD*C5W2rT{o7ekFI{f2utjLb8-zFpCX8)K`tc5EDbzMEIHgt?hz92z1? z!cx0;b*PC}>%y;W%j1@$BC zy_!>l_2PWBD%nDER$)k;+^-~s66ifr)^^)`pO)z-S(%Pq-E>6GUXC2K#R&XpQzX~k zKHnOMih=^)q+??9)08GNyU|lIvUO?g-rsoqF(S=1{XQeEJkjJB{W+kWaRM>0@{6nc+>fUhY|Cf&2aReHm>fQ%D0Hfu+z-V(_n(9>uoeTHBtt{ zCT4{r%#K$tyhyuag%`}*Z;VkP-??>Uy)#Ll1bTfIBCWmVFK*?SKqf(hV7Mn_lss;| ztk-nDwC_(2^%+jXV$b@8ouk?K8Lu}Kap$*y9|>tV=PTnf&S+2Vx;bQ&xiHa@Ez$5s zNo#I)3(_h=EzEWbTs%$J)&nPHgX4h&O1h)WJ9UOuU@_4?f9#F;Y?U$_7+%-YUtPQF zTbo7E;NkX3oBfHARnJQE%`Dw;Ne8wb+TZ!ka9I^MUTqO*bbV78bm??Q?)ld9hE_Vg zB_6Xks@I20L^Yk^AZO1nGO$SOCo>6*NNKB z;UOXG#W#2{LM-Ev5$_vg$YM?{<{KPHZ9YQG_jR(}h#!m7RJp;KN}IarPy8fFK_cfN zE*-}trD~U4T|dqEv-BW z(klb;C!_p~uQfYWE;HDE&Qwn0KdnPAx2dH3hKwdb82s+u=BYC!(hoJ4@gZ~)am>?xgt?j*0u_9 zZJS==07L?Q$?QT=^zDmR?{9kLr77KtH27>4&`r(e6nt3ok?M8O%pZp-`5$-5`~;Gv zk2-LCeC*{K`~~9OT$exx#aS=BjtS26@-?sFI>iQg9AF~vSoPjc)5D3t{K8X{%cMI+ z%So=4sTSyYbmCqnKi{7*;JxE?{pmRolIT$If~pi#3tT zt!FVyn~>Zm_F+WT%xz?khGQswy`%im@LK#!(>&)=$GpnyQwDGjpa^%xb^P5L(aN`R z9jeRKD~3Ab`Dl8&$mYqL-1TteQ0rS(V4;w>(-hmCCVPU;TF-G@W!{58#{28354`1T z14BHMzw0bE)`N3&-D7$tYS3!DM#vh9h<7*6GHmo)15#?|oqk&ydA@5ynsi5D_?#9)@TKfp&#STgB)hm`OTtNk(19-gx z*HV_4BiN;ukr;t%2J0sjKnnri9h}kDaQz`chktN6nxn;VV_KDtM-q5-?)V6DH zcU!`-{R+()NY{Mn8qs}I-NhNU6h&3ez@{Y5S@v;E+fZ!2@Oee21*+wl*H&d0X5ET^ zm!JSGAM=GGmQd&gE{QGf(^Er@%Yen2mlg9kX5Mi0{&wa}i4WHk6d=}ns#IT7&?om^ zWG}Yye*S7JkeV$YG&ye~10UDG1>7R{Qr2P>&e>fK*Y>LQs-VN#L*=}eX&pp(SrI_AwU*aU|Z zbL(^O5+@=QVLqW0*z)qE#3x${jr{FzB)~%=VaSs5i7LWmjfD>t{}_->lTIp3UpV^ zEwkO26G|SA9)jvL`KQmGX!2$=CosvMZC1tEn`Y?Y2>Xv`3cvMs)kM{p_NhkgiSUSo z{`tuvxcszt@^VM)?K?@|+C6MzX+>cupC}`Z9%G(|y3+m{#mVxleVxtCh!)BAar#C2 zl!yk=sz^+fT$38Y380$XBTP=F*)c0lM^QsZI^Gwv?tzEGut>T-u;%b136}M_s>p*yqpISk3o3+ZRgtfaeUsy+Eh_r$M-V328;=G4M}#?^@F^cfu90E@q9P+_`C?BA zdn#vG-{6xAK{-PMxg$nV$F=OF_FUQIrTIsZC~F`uXT~+uJN-IxicgF$1ic{?f{d6j zRb?)mOv^j#Umm6Y4m-i#$ZU4Pn@e~k@nG=Ldoo`j3t@=+96B@#=5A&ll?DI{Up%0hL+A;%mp4@#a8`ikpEUnKP1 zY4v5&+XhA`B4yxc-HBSS{r&vip=6|S^UGI(6TN#516d)_3_p=WHSkumrx+;E`GtGH zeklJ-G_)?M|AS{|#$hnG3q4`w?$r>Cw+B4{Q)WX1g-NtH0~aG^BL_mle%3nCWBE^P zh55Z$kRCsgZ!hezJnt`RJUBhVN11y2qS<8{E0Ps5fnRK~+rd43;;&;M62tYc>A>|s zVNKP11v+CCvJe!ZE8-@pRrh!I$Y1T6q0ni((KiKrofmrYLarTCludV1d|YsO5LBL( zdBG5bc#0c-U7VZ(Pn=UvR|}oe5*zNAta|MJ`0B$AR`F7MbSCM|b0*ndVmz-}1z>_7 z?E6mcnTVZHgTi(YsOZGy%z}&P-BFJmhDB^AAeh*jJnwNPl*Q)UE9^8jDqCW_Py&3> z!Ij1TyaGt#!7uq|v64fhW|ze@CvF-WuOCmTw}96C&zuiPk1Nk;)={3XAgbk)&F_{` z8RqoIh$WU4wP4%EClA$lqd_yFE3srEJ{RtDWV{;LC?cMTlx;ke*406nHWVATr$wBm zir%mH8Gm+*%6irMy8T9iH&S;ju6&z?TYjZRYK7;}zwKU@iPzV=mvqUIim-6PsOWfx zD<+XQ((RvYB7ed(?2Q)>#=xAjT8C}i;cDj2wK)=n2Q_u}=t8lX3V7tP(O z&1`;J#DDv>|CAIQxPvUtjCz7WA!Rk2=|#aYKE$R@IjG<<`C4RjpE@-b^kNeLB;)%e zFd2^9LeCmyo}sg9!{sx8$EmKDWAYeWT=B|5A#fzzhx{9OdmEcCoi3{TRz6KSns3zbgN0jV)kL zDTxF@GrxADS$O4ng7qYn0e_|zYdp5{1Lw1B>6Ym(RWw_-Hx|>{@z&eu&vkD$cSN`2j+%riB+Yi^3ZAvY9Lhv{YyN0xx0 zJ_)VM*JgqNl|``qqxX+;Av*%$E@ly_!%FtHXB{P>=)s#QM5&JocK)t}a_29J?gsBA zPjfrLIo_*6HTPOvQi1j+LmRw;jT|}hf8hsRb~H#g0WdJ0cT~*fCN4B3SEcU=jAEOKjX*Y>#-%mPP8AX z3w-Z>dCb0nIc7-QpkjshTJ6GQ6Vsm3OQKGR|5|Txo#i^)eleEA&xKzc8v0eM^-6`u zA}fpRQIfQdfO47Oc+uy6e$GG^;GGg}2~|76GmrU6R)s>=FtB$}<#Z}k*2n*M*0(gM z3N^Om)<(oxLUnbAtD1jfjwIq0QOZd2A_5JtimTnqz$CPj2MUogf`~UYSEYBFYP+6-9u;DY!5Gb&T&^U+{2axrn)`VMB!4+1 z{|sSh`e0ghB%JeH4HIy9mt^b^xwlG%JcostcZQ7feEpR*B|n06^4SG}82)-wnp8XR zBJ7U&bUsH^bm!KluXoPU`C(k;D)F_N@jEsw*(q@1d3Wu@nBTY6d%J~tV5>I5A; zXAe;knsF7>DEsAu4v#&^!WnkW9dpF>4nbndjbES|gQGOV8-JJQ0w!;txUVN$HgfIS z64Nuro!NoAhuTjK>qx@NwH+HJ{6!YO9lz3(BLhM8(x|>5!%Bpz2GoJ*MCg^gHz}J{ z9Y_|+rJ~UNG@ASOhz*6@+s!>69`afbulsyD?dn4FIVxXxlZ+COZ*ObMRwD>&i3rP^ zjk<6I;Xe_J>Y6%!w>&jmx-S2&Q!Xjpu^_7R+!K z>+*Ft2Kd+vxUP1f1JM0Khi3Bru9$P*z=80@hqU`HmyDq#3M zZl;q|3Xgy06nj+K{E11Tc&-KT(W8qpXQbVm%mlAMxk69KOBLiuv=cJq3SbQ|ACxt- zo5;6VHjVWeqF~(rzaUY2GShbasZc{lM!Im6iH@7aMl`84EDDZj1=az~8dW_S9pj)U zWJjIEwR?Gz(m#g!9=kk6*0+BMlwlNK=;FgoGz3k*!XrN>)A5$R&12Qv?}F1@#9R>ffYBfKDEGl zyZLCCEK1qlYWs8A|2ctTchi$O&|{M%^A`l7zeU%CV3XZ$ zaagX`nhE25BK5epyhbl`$2A|?Af!&9ibIKe0h(1)4(3X?Kk9nMB#3U22DPK?j)-?r zLWQSC$dWo+0%AQu*M;o8!afg9esm@Wj*1n!hqZM10x9oJAFm5EO-;?RUSCnjMkpWu zwIz2#3L`Fs<-9>Zgb!Qv4z;(pM0odWw92B6`l^DKq-o)L*}2%vPP}q^`KH??Quw7z zOdJCafpgoGiB^%nER3BOXXL{}Brg=h_+#Fgdd;(Volu4ixD2lTU zXIZd<^5=BxK^DJlB--l(iNU6}2V$?NF|&aY_MUR>89V$0s`K~S|1sqN6>`{JdeYJF zwpyx3JOS2Wd*kH2{DRT%Wugp!evS;d9vU-8p87Zd9+$> zuoiI_B0OSs=GzZOIP4!?I@0ll2Ze9yd*t4R#O>x$Rs-Wcw|<=8TT};^{~-EBo)cL@9&-4Qod(xY@Y+I~F7(H4g8dSLYSP z5BT}{4!S(F{_DKt=Dr$Dk}UDYVsng~gkC@-DB}@WU}IR(iVQjW6L$MNAIX0rjwtdn z-X&OPZUa3Z##dduy*`9CuPhI$w-2Mv^Y>jz8A{;Li2D12hooO*WRXJnGHu zJ0=Kv4iX5p*p9_wl?OoAH+O7;v!q3rQp~(8=Javyt;KVdLULEs?<~!jOqZTTlDQ>q ze#+Wpwpkziz36v;0cys4HcZ_wkFTzJ9jHm!W*cB}?MzC2c?2?(MN__?ppZ>-hr%MP zc0E>7;aPhdVHBTt9{5s>Y4$1Dl|H%cJh!w=)*6q^%&t37cu~61(Y>?g2p^Ol`MpEr zy{-U!uTw2x$wisb3*Gy{_EDF!RkkN0_1de=910;rr1|XC1ixR38qfK0$AoK5_q7mr zQ0rm~*~aRb9=)!^!A@_o+YyBrgjx?~OHm+g4*D($(@Q-u8)*Mw*fCxT{cgMVB**7b z9i3K!C*`3h&ZqWeJ0ef%>jqGN6DJaIGt!jC$w; z?00U^Lz@SsjICy&E|knveMQ5kHDqBR-QDe;ttO<>0!`@9OON^{sO|Mc-}`70xak1A zI$jYq@RS^uNNr*mJVEO))TCxr=EK2lLU$Gw^Ql_l9_K&+H_|814H*=BoP}V)AAe|n zdLnTehIL?^joJ2NIS35-u!0t~I zEyDrF@phP!6DWtD$*SRWBeS_ctmvtt+%MAIqobR>gFHa*CS`Qzp{sfI6R#*a^RWo* zk(pz$^PMVw+N`);6+DOECKb2i~0AEYW`2hbG?Ch92yT<^okP{wDZNj z^cb+o;Gu4qya|py3jSD52SbU{$IRRqqXnB7UC)~v_BPRPzLPODK3w}B0BI`H-mmp@3zJ1mRe9wE! z*FvG|(PW;|S>a-K?qsv-<<`Ow_MV}+&}8Khe4gF?vVOJv@>-U*BZS_X zC@v$Z7rR}kTN>S52(^G2>QG-xq^CU`B$p`R0v5o}^w2_Us=!-RnuN6@S zcaTo5n7A$RPe)rt@h|ag=?&H`wqCw*?2j$ZGkjXl|HGHwWQoI&{TK`Vaqcvl0jv@W z!Xm*9>NV>95cD0iPqC|@*E58UyLsc~(7Mv(9OiHZZkVdt?~iRuJ0TRxd^p6=70TvH z03Dn)4s9hFpl!f~4b~OdI+y2Cqu7Y)T=blfmfYMEqku0+>uj5oC9*n#85w?IrnDp! zs0i&ABy|{t*9xLX6LllM{Bo)`k={9H3n>`yEUYQsi(BD55qX`eV+hZDq;g+dNFNc4 zssTJ;3;J!UiB~vIgEBFEUd2gi5r%W#L+*3_)jz1N?(eWd{0|osdi4aIZd$%4e_7+Q=X`oK~ zx9jI!es3r%z^UP22T_;!V$}SU=xP6Y;a@9fKv?My*-+s;Nz(Ycb8GEZd_FTCw592C zg9m<{5_83LK_>sPOL!fr6Ay&dE%pTl`iSCG6fbv@Q~QjOA#kM83K(@W62`JAZ%e9J zG0i&bHL4QcwNTzizkDx2h9#s>zOzxwWqe$gKkFs% ztBY(DdJ7sagkUg5VUBxTjQ&9JexWjx)9XrXKg3UHaTq5)2j)mMcRv5_xwbQ&0`(?y z7q7J3P^ceBWwTKalyBcUm6EP4w_Cq4!6T;FT=HAd{CIw5qcfG+20B$rwF}*UZ1qy+ zpIqaq`ZL$)!O|HA1#JCH(onz9jB}5khGAOL8fTXzrgx4E6@B$vi z+2Lg7V)0g=&o@yI1lqD?V*ez^Uoq8d(Ddwni6rrR2~BnY=+_-F(_%h5wGt4}j~MJ2 zEgzg~C8)%|!n7(;qQmUMPm!;3r{@!1oeAs`{RP>OYgv7A@;^ND&ck7ck!Z@#u0%Zlo>~w_xJ|DF5l?9Zu3Nt3M&8Tis0#rPciR))?V{b z+KuK;kHa)kipQZ~U|iPR1m>W4n&HZql8N!%Zr>c|UKUPnwH|u2u!K}7hJrfzZkC4k z6f(_nJrO>&4(>fpkp1kfiHTc0WSo2vS#qxa^zM%k3i?LU5e~}}PQMqOJ|buj;6<^N zG8M*?6cv37%_M6~Q4BlLoXdptS!j-nP%^j%ZQ5UZaNtCRj*sD(yHv0< z?PKMS%OMT)80^AeKrEmA1ev(pitzCFvuhhdz2E(ig~Yte#z`j=o)}9VOdf6xseFcN zPo-;v$VX6{x&kMbXPOs?LQC^kho88v{7coHYbLfMUcBB_m;Q2|CkE%ZUuC%15RJdy zSaa*vP%%yT1y!i^Ah%p74`n2?MbUV#s`_UO$&q2B;Qg_g3WVSe5vOrRSt7KN3$10D zmN!8r0PLZ?-pJd{kX&pEi}cou_qo<1FwlCQxy_u5zU-ZJuQA!RY9Mu0yd6fjP;72$ zcpak9A~IPjUL;~Wo<1yuPql$4T9O^VlSRlwwB|4hBT@#Xu4sADOUeoLMMYmfg!Orq zOO@U2`?J{em$=>3tB!)dNI_lY%k8(O(8OEbqkB>O!1?23qU53n!flf8*j8my9=44} z>JKC;3H~LR`Sak78@*OL5TG7Os0F)4{TcD~_cz9v4`#^L&p%Q*D8%w~Z`quDGQZaLlE2V)tZ65KlUC^%8vSj4Ao)MF0PifI<-^O? z)!A&9=(FCWbJ)OK?unF$lDqs{pO4+Qi7#0Wb#palacb^imX6Wod{?v!&%&Vt^#3fy z->koFG#^W<*|0zTQ4u4ilkT0)G%}l>X(936g%Wx{omy`GTn9wfgfz*o)hbVq`wzE5 zk>4z~e1jruGBUT)<2$&9yX$^EfH56F}rm9L)OUasI zR~OJKmYb<$W;oSkhf|SZevw6Ee2I1M(Cc-q%^roQn`EyAeh``aZB_uP!xrcruEtj@ zj=18Ocaei8#?VvbDxE2b_F*AAc>kfiBD;4?Viu|WjSvhWYq4@`K~Nd}@9^`&R*V`x5fZ;t1crf)LfuoN-;C z3*HSa@P6Y!N)Hoa~6n;^kM(j#cSPkZ!*h_J5Eq#JeIT|NDL7f@5`A{ACD`Pt#* zTU`Hpy|pQ!XY_v|o|fpv_DjwAJ0jm$*X?DQC`?=3C(*BZ{+y}vrGEvH(4Ia7@o95y zJm#3(Q}8u`QX!03>`Tf3+60=yiUwQ=%QSfj$G_|fRmtc& zz1y!9;ZcLZV*bkV_;zUxM5^s()vY&=vN_((u+Zj;xh}B2wZehvLVx_Bw20o=dr1lH zY;Ab29yyuEn*kvMH*p?3n5u2cY<(>olO2Vlwjj}Eod9te#}!DNL+dI zvK{0JyJ)vZ#yDr@SWb0ieGdAMiF?YtbU-5D?2R8>k#oPXx~T_unm?Ot+(#tAMArbv zyY*pf8Fc05e&@Cq%{*kZS7Jcx<=O&OGc9d~78B~`aHs^Ry)4!rqCN?>J*nG~KC+)j zX!qrW6s~}W`S%3ZDGf69Qx4hi1#FoLtZwo(OyryyC&&RkpH?16zBrwndhC=2Pat1p znBXH_dz|ZJ+Ngh9S8pHsof9WX7cjk74oMeC9!xJ#oR_RaaC}%V0D)WJxz2(jSO7Oj zDZROto!S7JddpyD$m`QP#fMOxUMnXkuBH5qAUA`e6jbg^_V{V2vlrVx6ra5 z8tgt1=+g2AL~glSsdO6|YDs9Z8q-Q#<)mY3uXuNwpY*6=E?pNqB{WwK#R21bVvr@d zKBlM6Sb7bo;d@^$k*kHk%ihWn^j?2@oh;u&|D*3K7FNq#DE&n*y^m-Pdl#eecn82H zTB%b~z)28F7)4)9{iTT4TxX*Hq>%J2h@xzaKf}M)lkS&g>37(ihzFsXt?vlTA+pp8 z-?pbaoh1tBBwZGu;(DFUY7f3QcuDDlK%)mp^pjyZhh1m!bbSI+MuwT1V=KE7)d7ej zu|GWyWi5kF-_j-uCAd)ZYLE3aQ$6cSgCV)|@b9dVdfy`dAPdd&+g+NY#3wv)As@P4 zL0xIhdYuQS8=Y$zTDM07(wz#LJD}z7_Vj~>QCApV-2OWf@30fc4z|?{+|Z)+lXG&wo}}b&dR#)v22}%T0h%=un$tGRo7z z6C=#Vq0!-eQ1o;e#Grrnnea#uB z(UcNx<|7*&wr?L;6}PYp_V{%=i}G+@nN0l$ZvG|6rb~|)zSCld&zhrI4pT0(z$bFw zHbU>T6GTcSmn3nlARW9%O;J5y2{_(n^51P^dwCZe1=z0l(aSI~M2{|zH4cUH`3Z<^ zu|)P3C^|Z#R*%PDw=)jI2_Jy>xOB1@o&1~)_wa{yn`>E?rLiZzr}OJqtAS^zIF}1v z>UU~ib2a>E@ZwH6SbDdc2|b)N_JbCrVR?e-GjooIGCAe?e6fl$cQTUWa$}~uUi670 z?BU{WQcym%h}uysp+ipei%ia22W@o%Aj!$7K%W0VE^njH;{fS5h-M(pujkeH(d}A( zIslVHXF9ixzyT6qcTi7gI}TRd7VmIz4uLApfrw}e0sQg`Sv#Ig-S2$nXA#4CGHME z?G?C5YBpd)VzC|`-Dqaa{4GBDrp;O8@(oQZtk7TodwDjGW!<)XTx0v1d+H5r82Kp9 zzZ9vVk3STAB~+kMu;QF;X73SqT%aJ{%nXARDN~@ZrOsD>UO= z=Ov;^#8dKx58ajx6eSgFZ8bf2X2&<2G+o{Gle@g!kWzRD^E4%X4lX#Xxb$lj_EVhB zsRfGS;`K>`LUZCu)F-B0lH>_2+fhRp`eRtC8aetlBK@}SQ1QQJBJJdy?SC@d)>>Sm@qdn2%PL*k%XF3| z&rTtMNH{uPHXRk;x}tjB>^8Pto3EM-F~jJmQ&_AhCEDwop9(1ji3p6GERKYlUuJFD z+wXMNd;uTo!(aVApSgmEw#-+_Q9B|(1|Hux^)NYTLKNk-T4BLnv#aJPx54J@0Gxn3 z2kQA%gB8m-kDEY~YeIKC4tWJT23E}$7dDbEVR9uFe>BQPGD6VMLG*pIrBKJ~te9+x zvaoxl)W_Uvncs??S?jWBk^XT?B`^4n2IaN>gjan|iDg1K7hGh$&Uy>mi_PB)Ix}EV z!nit83#)UQUe!duXytIjPF`2+mR71~3ffKy|2XE2^@(BFHycpKt&|&lBR!+|Du-nJ zM?J=>A?!d?o#>qCaq$M#sAA@hnXuur`H~jIdQF!KpFLzv=w}JW6$M8ZE#+aQ+`mHZ zmQGN*rDn|T_87moo}JgaHZGn*1@Q~MPzai7xVAUX&7G|Wm2cNteSg}$YRDk}U#sn;SH{2FjaEGq3JJp4 zpXSJy&m2n6W9*XuGCJ3sZ^kC2*A$VZOSzG)e9Rfogw5s)sb*E7P8HY>qLE!rL<$(E zmW!Lv(7Q&;abASbIxi?bKx!j@YnU+k0XIZs&ceU-36NQ_I{B+}GZ5qW&80sUz94}>nAOH5L&!XnHbcsPe6S3o$8*>LU+H$&BXfaO9* zl$Qbq63>t9RW_a`Qwl!$N)WX%N3PUpa=7lfac@ro(XA%FILghEe!+7ZW}6Kf(XBI# zH1ODZj-6?L3kE(4F(W(qPBzL`XQ++Cn|qVh7j5N!qN_^6Q7rG+LZfvqy52$wrwbX~dH4siB*`$#*RkvOeAKZXY&X(y`=WDQ;>p`HUwLp1Qwk@W z(I?SCi$q`D(f{s0vvKoT*81;U@!8tDtbV_NXl>CTxXqaypj;$V#}D=~dGZ^}-ijkXb-Y1iH70&9>0uh}6BP;Q zPd98nn`;6w)#1uC^A)55v=0le++>W8P$RV_lx$q)%5}D^QW(O{^RHipr;L^Mzxgmm zM-x^sj9q~=c#WBEH!7=Whgt|1AW#?O_Krk7gmUVZIX5qlC8W=7Q9zAbgWdL}6}-K6 zC9sW4%)@b6z8tPUjJN#7Dz?Lxssf(DLceWe-k#vr0n(>CWZG)Fvzz3-oJ(EW#laW$ zdk9og!`gKkNG|)6;v3;uEZshXw*m7_q4WZq(4W$IU!LOPM<>MYqA2K><52PAEtbM? zDc;HiejtnWe=8gS-0^snl1DW^>Ep8KOTb%vV?<&wwsrHq2xPBrEf(JAOsp}{aQN(y zP2#&mX;nq!)Mjc9hyg5KB;Olx=yfwkOvgu|2gC3L{NNi5^&Hmt`U9`>Y0RKo+~!c( zj~-xA^M1DJZuD|SyFCfZ&cAE}wij3G$3VvO#YEER=lUJ*GhiatJGlK4I_rWBnMgD~$0x|26 zqnX)W9#>1tF1PK6`9)r}3^U@6U+2#Tu>V)UDPVesfq00txfKD)jqIDW;kH0>x}ZeMwCFjjTb8gpM3bQ>EgTTsBF@&4C#Du_6qWoH~7F?IsHYZVq<6!pjXTjBj` z9@7(FV(qB)PT05NG;X=?4!hDD4(K0|y9$mCy!VUi`D~KZRpi&{aFH)-G7@H@i61Y0 zB%5@E_gboDTI(_ur1HQem9O-a`uG$kDM<_K_!$9*E|E`wx>2djRJQ`gC7d2tUQ6;9 z5$Ie2*NOUV{LV{Q9Ixv<6Wui%PY_YcctnEbcb)p;Rp#U?(M4*#+P4J?m1WN6WC ziqw0P_4v~B(RY(<&eRi{FM-!3Tbi--n&F%mmqF+oQXg;XR9nhx2N`DSTd{yz?N&2Y z6gH^1h&q#Ily9$Z;AWY@UQ;k;hL^&@*C~h;hT3nlM@B>>ltwPef1V%S7hc(o^f@v z+bMON+g~b;@4nqNJq1yc&&ubjNAlJkKe1zRWkG%Ly`m;LTZ?FMJ&sYW#n7|&PoqG9 z@gD6Af$jYAZsU7Mp-5AK6hFMaTe-f-9$bZ#&gENQ`!tD^AfyFozW$I%zD5Dx;d!iV zYlEdh>YN(bq^5mG zQwR@T<Cb!@p|Eq_ zGgQ)S{bNq~v$a8^Xtz?NFnttfmB^O}Mtk>bJ zwcIUYUw&d~WIrF}i_$my4H%a~QhkGEA<<}&Bwi8p_nBAW)5-+pR5&z8?eMVF9T^*^FH53RSqyatmU zK5e*K5Ri8dC{@tCEGPBCo06;zJ+>#MDtRqb+aX(0;)^?`qMnH#esL_4`S4%r6)e6O z|Mz-@&Hr9fu~KpP-%2Vd4gOS9CWQh$y%OlA`jQx8jsqrYrjsAH5O%Kp;{9-5?;Ble zj_MIoG@mU6y{oZ8(HvTIH51d~cSjeuAAA)@*xf*yPKp{DM!0bN*2PJu_Q;Z1&;|2ToH^k}7lkgr45`>35 z`~EOHcn7?|=*W7eo!59t0Us}f>E8(snDpA`sI-&A`(lin#1&nADXPJ?yv8^1b-%7-R5Y zrq(&+JUi29xL7%eWs<#WGYA2^>|%v6M6sF7&`*!?x)4p@=hF2tO5EnAJbUzo8e!*X z2PzJw*?h`5SA^Gy?yg#~N#V?h5BH8ay327gH}}G_zV}YiZgV-(pkA| z-4-G27@_tXK+?b}nP*>Cf2lRM9535|jNsZOtEfd^!XuT(Nll*%(;h6(TyX7HWtbB?ArP%o>;p}vs#Y%}5^73aHdj8o`Lw0V9qHGwX*k>gRobyLX z3VY5RV0;jJ@ndEUDG)2w{w~KO8D-7%q}+ZHtae}cWd7+L&r+H~P{ zY|(Af0v8T5;Gy-wZNa$vD*``6Inz=I6GR0%EuSS>gWNO^Q zrSIvw+-Gw=YyZH7eobRlrV{k&1D@o;dT3=T3wwK zE>8*};#&%VPT`bZ8dHP0BIzoYi0NyeeKwNywKR=HzrL474zuZ|wBq|wvflI8 zc;Yo>7r$F;{lgNRcirQ?6#x~jjIEyQrlAR0ze^D`DcTarVG`c7u0mW@_O9jNWCUE62fYVxD!O9`Sn zoA~xijts5A6WF&dV7E}w$HQmQ97y?3C}VCR@` z@G3f=?JG>2$mrT`rq23clQlW`FwUd9<3r7GXEM*>n7`)&vlG9yb6dRpf!w+^IN5u0 zI91FVlDN;&M@}6){`sz%J5uji_{Hy_N@e>t82@>gw&U3qZd*`ud>q{Icp~j{x7pw3 zx1SNwC@>MhlsHv;jz@Gyv^V6)B)Z7W`{b#gsuoVAKL51(U5M-fsc`b~swkyGjb6(a zWfZZpyVyWK>&Fi1mYRfZ4XW7*9+lGlIrr$Y|aARcwKdkGC3OTkKpOn z+dF<&1Nxip4)p5UVUV3xpG=OttgrGVF}rTUH#9T7h=f!pQO$ZEVipHq#t4)lliDx! zY(D{q-S!+nLvLPvpK4`=4jzH^{aD_YCw%TsYR2zJRLj03ICc6fTShm1o#eFNi#ct* zze$?)xqGDZxl`dy+{~68KR%dhg^@c}&4K8jVK|{VE(NKo(?{b!&FPlD;hBLY%LmU5 z?}NeFwxj+0kJkb&mP!djGv)Ldk2Fl}*Qh$_H=Z6li24T_H<$`0J%B5co(s8#r3GjBl#-$=bcMv{$`#@GSLlnbmuMc9hdzWdOKgN>K5$sJU!sl zz5xGz#PpRT8@D4}%vPHaU&s;JuBUjZ@;vKI4)~nVFLS%qFKj$Ir#g|h5e&-}sRv4Y zeEGc;vZslYI^kYyNsk25dQ5<{}fvPE6zdw0RO7@=d zT?5OQPfk8vDxcb~1E=)XjIN>(xPNB;V53TdLDt_VRe0^%6zVS|nmK%ZJGl;w@0$h` zYu3L7yuKR^IlL9rX+Sr5s#ss>@FKG37Ybw0qU7{OI?|sHKAYz#kWZkaCN_vjCc9Mq z<-5C1@0(qt;<}*ecUl+ziK=#Z*e$mDS?*DYb<@4uXc=7VzJ95MZ3{K%?@jR|_51HP zl1XbHt@WA)W8-~I;8%l3?~dH^#wWm`j_$>*e{6r2Fspc zM23X#E@uyZg3sNnYincUX6AQ`Ddy~?@MGE|bmaofgvxw_v_y%=>1&;lsH1o__lK`q`)cl+DGHI)$Xf-6~;4X3ZyE4ad-f; zM=9erXYtjXF7=}?wO9WKHBphT!n1@`(*66cU!CH`^j7ZTQUzPGtmf;YekoU!{ZcH? zv|6jkBH*%4;KgS|h#BG?^{=8*Bd*fg%^>dExwV>HBM zJXaB#ASi#Vv;SqKK~w27qNZ_^)}R3+;h#JALR?|vsnD|QbFg;yIm^AYO4jW=5&~68P(>=M zvPgR~17rWw+=cy&h?uN&UOYj^vlp%mQDq|fujG3ji%hG9yTv;lZmd?okE3lP^#Iz< z$2x7iqJ7tx>5ub_534WJ=le-log(Xb1G7wpU1dw{4OHR2X<`}cjlv8mccH1zn}b%j z&-GT|{_og2dP2=&3=hUFsl3)-m%PY$v7Q=BvDkQNYJ+GGd1PNmvV8Y3_4HJ(yyBIz zO9)mIi(A(}hI^Z6P<0;WwV@81V2RH<{N_ynSq$?AZ)bbW&&ybngXQHC%DKf)hq@eh zLRO0k-61v8sfBMnVTs$c#Ul?RIb^a#E`+Ohuj{8J8N10AJ*O~D9)~F8%-d=HMj=|PH=a3cXtMN z_XKx>yM^HH&ftT)ySuxyC-3vT|Mykxs$KuVKAEaHxaVGLb@$bFt)BLU(RbxtnKWt{ zan^gndoogv^VBe|@tBRt#a0c}Bba1C6NxNS;(M_9-7s)m4m4zvB#83wAG9!s77pBHuM2wc zNDmm^J=k=B?G)+T4E%m?G{#!@QtYBZ+d?Qm#q*Tg&NQcy-={P=`4>2wY}k`e!-0gu z+QJcE!RqpNBM-k9{95kenaeZL!xD#y-NqNuX$jXA%q>YQjx&m`3gYz(wwHw-hkAS9 zlzfvt?h=jkb73L!b75E<4Me%eI=s&mU*RuJeb`c1d)TwHE$E;A-U_=y@UvUQbiIJ; zOtM@Y>uNF*80L^TA?W)D#`N&uUL#rRi04O>pS2OW-!)XElQI5szTk zyTP~-^*2sw(=eJ*J@21#dQ{m*+OxjCDK*hngL>*B)lQy%o{_rpP1J((_r8Elj&*dJ zL^xs*z3LO)u_0kbo{3VTOdc}zB$Ru8#LBp=6qZhN83%_HdrLkddd^@-v|UJuqMdJ# z>@KCBOO+OAF`4QM{82tf-aL;9s#82z4=AiX8WCRi`}CdRl_rVU>J0WXz~fdV6zlLw zR*0>-CNvvkDQx-Wc{HWq<2}a69o%oHUR?VrG+~P>A7*cN%U_P)X296{cg+ND=5Z=0wCeh(sYvBlX%aT9Y8G9kV7kp+EnT z9=F~m<;Y(ghxp?dEz{$T@l8CdvS#^UR~Qk$;pQZF+>2x8sq*u*@d~|;;u_D@nI$H0 zR!OZGO=yP{_C%v4$0?Jo*VbKIUthg(yZE$;ze3o>I+`PUJ}gof?HYv=j|zpl%Sz4h%R6~0UY1fGlD zclX~~L(N4kEd!Oxz}>)CR~DI=rO_R|b`Pg(&Xw@S?RI^&E6d?6Dn1$|GD zC^}3x8^H*298I|^Hc);5K412)6IDpU`eQ}TOvRKI--J#AEJ?yU7xgHMIX0{7*zeo{ ziv*dsDiU8dMo6NBKDE8@yooAjU2Wf<(q=UTX?zJt?}~rEUU-NSImkbF>%vWHn}vIH z!W7z}hz=A;di4(f!WT1HTJE&7h$i%-`37x7^OBJlFMFrl_4MHV1s>syK;W3dFW0kC z4V_&8HEoJVpqof&MgGsa8zGc2vzVM`68SD~80XFRN}g53_c3Kku01bI@8)0m@t!CR zRmkODe8azf>RN0*qo)sb^o0{;jZV!d$1*3h^bXCh8TDzxW8k&-M>57JwL0daPxrZu zIqkXYlspe0L9zRZMOn*kqKAZTSq~(SynbiY&m*jlkZkw7zB|ut@^ak?K;*x)q#4Jj znST{4W`GEgD;NMC?qUfW zU)ith0IV2sJfVY7ds6aOj_>0zFHagZ<_(#75rC?b@_wEs=dbN+OTDZ^R|}w04Td>& z$G`BFnX;}{b(RqYt$!9%S*kMvx5@TqO&x2`Z}s~tP^_%hYw#xqNqUW#l_I!d{f z%8gg3E7|U16UsdrSl_~8sd>$+ONTk`LQeMm`vNYrS@Pnc7IQv^UW6gba6AF8!*MNkaVj z#Y*^?{X3=`FIH0@zMXT-Sj_ph1;&ozRaLp^udO@&>|V=!w10IJd)iCRNdFu_*cg$s z^T^JMHmlv(Ps9A&{Kl=!_Z+|Qjhjg!?^?TU>H90MsNH&&*xTrw<_OT^XU>LSEg44K zCyv^mVh$~BOey`+$;3jfY-kF4ZZk$G6{Ra=fzf!cZvN>ufi~~=aeLmri%cQ zTTf??l2~UHA&#(z2?Jk^FQHzb%^NGFjPR&s#cGEwuLhc7&89t;mc6L=Uuy~R4+SXq zh~UGD-_uJ9E+3v^NW7OJRJB;Fwya2&G>Lvaf?C6F4^(L7J_Y%87m=U+kh_H@>Kw>L z52&Cc;1Bw|j{l6uj(Iv#gypTtwkiK5?$em_+v*+hsy4`JXF@gH)6Mj%a@ak$`rF|! zt(C;kOFFq~BKaxNfc;-@zYR*(H|!c*;MQYRsMwPLjQJ%E9TI-UynA`Xnxwk2!_4zt zF3=nX;$X;3tSkOPEdI5_#G2kTgFiAHqbl+tVYRMYB#Pd0B zQug|YJoymA5$0Fa7t>O-P) zyiyYk=|TvHa)s5Y)Q%JjY~S?!)9-u7COcKYiw9GK#c+m!#YV{2r@w3w^y~w*L;Uxo z%H_~BJ8Ynk6D9d&N{&IWD-OhoFX>S=8Gg*Z;tZ{M*66uZ9hx#h-{y-KMW&^uu4fC2 zw&RxMEpuGYHAj4kiQ^WFCi*ppi-)gZK>TjaX8FQyev8b1wU{qrsh$NeS&0xt z{`kH{-;sUARq6MHl}MO9REI-9$s~fI@}!a%9s=K$99Qv+p!6LCG&@xwr4YAloiOQz=V37;IwmQTTvH50yXg@ldAchU zK}y>2%?F)+v)8YANf%hyTy(yFr|auh`Vbv>tkaC%A5;aibpki4k#Oa*G(nQXtLt@J z=oSJ^l@^BPCv)L?*GCZ(hex$c{Z$$qZD2?#OaM6;l!(9nfUd#LP55BOHpN2p1YF84 zJ}z`(T12@RSePA2cM1iq6(?`v!!AlTLNmHtz$DeXG$Ky>Crwm_HGbj?Y?7A*(w|Y> zKfhLxg!8ZA^t2f>CKO*W#jhbt#6HO}tLA%>xk+Gd)H$S0i`#JGZ+vn(?1=QW#Kbdu z%e1b`9V=GNW_UNS(<`SqWMCS`{W5Z90!F@a%KRZrN!BJ<17{k!Vz@JO#{lDZovsoP zs>7y!G{H@8tBFU6+IMk*#7H^l#wvDuqDe{dOH=7LS(ooAIgpbAu(gH zDPcxTml=J1x%>BB1OrioLcN@U>*r#heR_*HpB1$bv!1qWAi@hGsmzxkXNuGiY}8HS zCVjb3Gk6_vGNm}5CZ>GJQe2klzon0+Q3@g(4kkqL01p(u!J7dVI9tA(zRAivxfR&y zO2m-3MSNcj<9Nec?_f`I1M>HFZ8+g0==G@+0mbJPv#$>S5UR9Dk7&-zqc)MU%)X>| z{I!X1T#WC4+Br@AaxsXEMUi4@YwY>-kJABRY$*&>+=J1ABo%aKXX=&H7BaUy*nJkA zwNg$?>VvoRm_p#)p@2UeCtkgPr64=-pe1@vOV+8EW_j%OLDJb%7M-Fy15TL?;zM_S z=v z`4jYs!OgO#)Qu_{^qkyn`>TqhIXiGKT*sWmv~?g$_9uSp7jZG@yM=KAaA@vsV2*1$uvg!{i8uNooQ}GF6dzUCHnWF(iomWGcS^hiWe5 z%KHVh>^igXX-G{D-q1pzb+T0iy>|Cq_2YPtNH4e2PL)jNn4dVQgE=hzQeEI91@l6( z6?wS(JaLXRX$`YYGhu6d4*DaztcumCJYa5{5u0%5&@eOg=GmLX7O7el^G%B_4f&a` z_k_@bNY%k&XZ>c-@okjZ8lEePfD{8lOPLstF5Qu*69*4Z+S%Dz&QG@Bz|%6I;5=%I zzUFRL58=gx0=6KHhu@Dkn@=&!K3V*s=ADF&;*q*<7d|4T)*Qi?p64rPc}*-Kf!A^O z8X-aaQI$Jb-{gd1h?lY!&=v-X=D)&a9;BpWg}55UQ!qJFhaViI8%v+`itc)w)4jzY zA50n}VV&=mvUQCAib{R_5epFZGrd}ISORJ@o+HQ!KXBFeSAJf=YfmAh5)EKbMqSM9H)Q3f}M zWkj!!%$+t6Wo$$NU%nRAe#75PFB$3sA|xT<9^T-FF6G|l2ybF=NTKwWU2ZDXQQ~!& z*UB<*utc?-lMppK3^k+F@nx zXvX&^u!)N3KRVyyLa!|DJ+xkpgwAN4&YWQ5bY`Ppy)W-TEw-5)#R#Ll;3?+f6Hfmg z{>LQI?BS}h`KHVoO6qE%G@z*6ktC!{lGJ$ePS%^-3K_DXaUki3+SAIx&6<*0J$LtP zpiJb34r^G<+_#C-^7{il&OB0%D0Di-VEU{skjBS+x)Sgg_B+M9T?)KVpW z$dS8Aoen%!AWl4n(R~Ho5$r3C0vF3<=dSF;UN51!jZe@SSqeq1?rBet$p^bUViE|4 zN)&l0E;(g13B*^&AU*o&y&&xFNy=Z+ z^?cvz1{B^#|KR8DH~-qAstleS%@nfuRFH6r9U|9T;J%vY$ed=9`-&cGt@B7R?;K@` z>{3{(ekaoZt~5!+{@#dnek&;GICZwtv4*%CiW=d82$FwoU>_7uZlW4^ z{XA32x%4i3WI}8vxOX7()))ee4%)vcal}olW-zs6E0EkZ;(Xx!uhaRoVt3!_5W;6V z1N!+*A&WTMW+%dz4+j@NUxhN8Zzd&~J%qwzwM$cuNO~aYL*eNQuAcV;P6wxZl#*)p z?(llYMzx8wgO!#CIJk)^299i~OaOsOvF@B z3UG@D+}Tq-N-d1!1qXXMP&Nc1@-CT~yDyHc;IUUK;n0 zGVIB#HDwUt^7pN-NPcX=gM!Hy7boNC**9Z5L;C>BnXA2RPFMtY7^nOh}n*dDnZv1 zR>%M@jeYzR{6)+-ruTxbT&Fg-*49PK4?_qf93E-2CHv!AlW$zI^ts@#5xrec>4uTS=0neU`MZ~M+W zUP+6|z64C>EVzA1jB2#LPml>ER6Vq~G zW@4|r*dXyz7Z9wp6+Z}*V$YpGudSiRI$xR^EwCOdL+EG7E|V~YGjob!3wBXm+j%xz z6`F32yy$VM`%^IPoXQT)1y52cn_?4Bpx2qW_X6=_6%&+`>}RFAG%^XzYD|lNZ({o6LnUZeY(G8>S^J zK9OfVq=SWYOH|6Q*U!nD7y}zCs3@L%kzvP)%hwzp*hUvQ5b}ki)d}_-=`h@G)iQy8 zJE~A!)AH%gU?xO*fxvR`7=kPR;hI~Mmwz|uab9Q$x#n8HPXTM4Zek=rl5>M zi{}gIlNLaZU}LH`YdI+)&YEz)#1Cdwq%RdA4&LYIw67)zylGF&&V$5X>GPcan}DR8uQaGWVX5G+))xVN&0@pPzvCa7AQ4)Am4#tOeRs zVht%^A78xyk%vKc!(A`-JaF;NO@}-4<+Wn)`ZHYXFTcXDw z7~Gf)Ib!_=YcXjJKEjnx0>&SI4QfIiA(zw^K1)ESMb`DYhdf zj#59rv^iqe*Em={ozl}X;17Kvs2I!QDv%4I*co8gcuV{JB8{O$9#HVZ`ORX;fVx5} zYT?fmby$ysgsfLnIJHUJa>tisnH-8P`r8X_!D3s|nwSdlqEWj>RXwPHl0A0KSAzV)no*B> zBMr#i5*$^G_4}DIl?JL%$JR5~Wop)(zzB$h zIyeC9RDC($xo>zabzY6&M!Y5nPQv1>IPdGM=B|X9e#1brP{qxExd8P?k6dJlrHe%fORL++Vb##=w*rZi zmeMby9X$oEvS)v!T2d1PTcuxwrW3Sdmk#^C(~9${X40Um_P3rMi+PJOrz9+%6c83Y z)jW~%(LXaszqnbafcgBe7W&S_oQKqgMeSK)pfrqC&KhySqf1Zft_>Iw%7R zs`jJ>FP~Z^Pw#cFjl~Ujbi6})pS@vVKsGi|2}|>G>RM)%P|Or4pK_~(7XGIuvslIr z@XqnGXLQ|Q`j4QDd0m9OSJKGs6&G~oHGh=hh4``rLxb_i%OneB+EsCW!Q+I}9SJ$U z^>`~cpFwXZl(p6ZWF-%!!=1xk3;br=A9`wzKjnb~KG6&IWBQ@JCCyuUGl=Ty>MJ_3 z=16#I5w~h9f>driQs`1{N9BZQWBCIbWk`teix})!SUMwgO-*TxIEdzy&R#|*U4TZz zdX1_@47xSF6(rt;W>3aQ%F^zGEjeO#_7$B~dsaMw!vz~mT1*(g7>?sWCBTY?B25jjL4w8j3Y~1}udgyL7_MzcnJ1x4oC$1;d?V2*wjKK+O zC_1t|2CiN03XE;i$%T$lo-DSQ0{eukhYCOyOw3Kjjnx+nHG+e#r*U%T?d5D(F5l1T zwk|H!L+)$7CcJIn7G7 zqP1RnaeTZ%Tr&IF4~L62^Z~`J%t+!4q}q4n8JUwSiRWXW3*9(%f{c_+6EnY9;>j*% zkNs!mgM|F)B0&|oeVKDTGZ<3B)E?$x`C7*jbSURkA!#?so6OalK!bv|djD&-sHa!) z3z2$fwG5Vdbk|@)ML6p=J<}Hjb9C4NbXbHpQ>(j zh>`$39XdnEfZ4|`&6Nl|T>!yXLp3&Z7<=T0U&f3?fbp?2Cpy*OYCdNTJuFgTmV0Vv zyl0Hn{;|ESpI;l!R)%whDL9-CsTC)yH4uZS&US;`!fI6PCgOg$zOj^P&;}gOo9K2R z+FQC$ob7VfK_;|x79z9m?2c|W6)myYy4@!xRb;}E?+96F)m4a1u25Ei^C(CuU8BB{ zb57G~s^6@IE+Jcoww0TrAUaux_e)x=ckRx$#LCGlNt~$IcIR&2mkd!*-p?(Tla;-S z*EsdU=sL?O3psoDUK`q12Y=Z`0XtCp{l z=%J#)&LD^AtjN!uc`EQ)vl9Gtctlqp3DW8|bJ=_&wNW$iMA5;0fiA*^B-3>I-;jOB zthtlA*%#OsMcV0b%!)@4{PeH!$6QSc@hzk0ZwsRbis@V!a38sH zt$YoH-Me)3r@(@M;|qwOsYnZ6oUJ#|Vb~{~!ot9xQWJu4pn#;Spu@KBnpFizW3qhS z@*MSLNg=@6`UtsJ4rb`5t+9lD^384x1?J(Kr@_WY;3o*d?4#DZz_%Km{0L5$_wbf+ z%Vq_(5ZOLFINoh?chbkvhrk^H-_Q)u;C< z_;jXY_IoW6{^R*;U&+Ta`W_5#ug((+y``Rh`wK5g!4RLB{O)2tXL_w2M6mva7KSP+ zNB!ZWTqeBV*+!G>&poMAHeYlpJ1Y=zgAKAUG+b#vi%sgPG%75yh_C7H#u{la%?HS! z_IBok$_0hCPkI$$tAcetL|*T51A{_b1jk)K4s0vv&U|xNsiw78<}@{YJ9>5&f#PHQ zH3tSW_*7wV^!IyX8X?jBp>NZS>a^~XBzx!{`45KT zCuqXnl1`cO*1h#Q{e`YEM+DLKb6!u+%F)IKCrBWV-gEnyd#QI zsm&nFTQ6`914E3v)_KK;k9eFb@Oip9y|xZ8m8*Z7SYHZ2_JxyGq#Sm3<&%Ow0P$(f z zmX6)d!deFwak!d^i->!FT({f7_%5rfkDw9ZuFck#{h3=-XyFl`N_Wf=yb414eRSV%q*zQkb*tQpC9M7fQ`~I8kFa#(I6oG`H7; zfJ>%Z6_e;2(a#}us&Dx!*j9SyBBdSKPG1`+Md>OwcE!`Dd^ecJmZqQo1pPYHEz&4K zN7RzrtCAht1gmiDd5_;+&+;N_Qi@-#Na+XM*8FTgC$|kgBMj_|0>$)ToHPKq#&Qpt z-`(su>v{YxW(-BNY$b-!pT4h_IUt=}3$&M$rr>$OWltWQj1*&KiIT*zY8J}FY>Hex!pK4AF1y-y7YI1z zs^Rg&71q{Q5RsajVI$=*j9%D$R|cnzaw4Km-}@bofoVyT%55LF%keNoy=QK%>C>*2 zM8IPw=N@45k~X8~?LkomuUaauShQFiPOH~RTe#_ZUg6`F2!>rT#&)0CKeCLbkF{%U zmoF|fZkQ6{a3ubw_Z|(rTf_eGP_B&4Xbf)%%N5R1p%XgN8XoE|`Oo(Br5?PG;&Q=^IUjAx3cB#9PlNpJ*&1;fx0?J(#N=v$vG)9|idz`>pyK4vWj#@~EceCp z&4N6t%;(sD!ja6s2+!j)TyyBTw%rm&>uZD;&mG@2KV^T*G+`a#3zPg@ zGDQzb{6CS~6~S|mD(ypGe8o>$yL>I>Be-MVl_6Gw$b>?NXWZhoUK*F6&Q9ZnkMSjf z(@4A5&(5-77pmrgzENj?19ITu^+xg&pEo&}Z+&R9}OEaH}Zf+dcA8%lT2C};UkwR_`~jxV~YVgrEu4JOR>ab;dF{mhg!jV;Z>C%L+inh%p-9e)S4fMHA7#u*=Man$GT2pr%h)>GZrA z$Lsx_-?}3dDZwX)-Dl}fRC-DLsW~VBb1samWFXr zF+JE~^Be~w}_vBBb5>8#{ zhOTk#EKOMAjL@#YLHB1dQ8$jM#RoYgTTncUOogLhhAs<2ifkDC9;Lt`7mjTrx4$=( za+ejFS%sG#Q{q84^f9**(C8@Hy@gADU=5z*hY-sj&GfBiZ2^b(e?q$ z)RCamc!RcR?-1lpRgq2_&s4xZRieM(Bu}v}<+*&&d&qKpBhV_ySNu&%`I6+&Hj|$d zj8oBjT49)PvvH9_ZSmntUD3i}utU71kK5{cVtQfL{}dw<&zq9&$#N<{3v5BKV^Q&g2dr3 zHeRC8%fqv!3u_c5)El*M5s%xQ(OJjzCcUglg$B2{1OauN7^C^$5Yt(EezQm=OTBBL zZu#b0RY7gliEVufSoyU>h8dfKIQ<1TB4NjgUZn8uoGG<7(UwGSVoB zh0{i-v}W`Hw!xkj8Z4=KE16miXga!lruRquEv+ZPG*%jT^giYoC>~8$Yl?46P}o$b z`|{tN)*>$)zTbWwO-qD;Qx<~qTP0N=ngKuji2%#Z?rL~82JBNoK8tFPH!psb*86j{ zw)3j!xcNu?LwT%9z(Lg`I6*;BH6%ba9za0$UVzg5xTA%w;1GpqCu=YWbfA=(!Dor2 zTeHwtS&j*;qFCt$o8%#KwY-7ZhJG(KgE^VSLQ93oi6hex?$|mpaW5t0ZONcNdN-#< z|5U>FZ8+$U=&*{DI3pg|vd$+_78Yr+=U1jqWszebk;R&P+f|c=yu8pcg*?jNzqjq` zvV*Ns9XVCO^z0Cq`7#}@rkGzaGqO}$2zz8d zuD21>vbx-38Qw(;49xgA8ZYK?rM-eo8%VGsKER4cren3AzT5N{tsxx1r2P0y(KgjS% zg!ne92TM!tzcdiwH?CqEt@mf&knK$c})q_c^&B@ejb|9M6K^ zd8<;~ly=`x2z`G0OCwA1(2O~y@@P%WPbJn;rK5htu-0DCtu8Mt<`z>HGeRzDIyJ zSwAh0Ay{3Q%}5=KsT#f@mJg!c`PYGF1{JBVI+TX&jusfXNVi8VyXI7xQPRr#xLA@I z>IR!kSoEu}cZ!F(8Lj4mAJf!Qpwnl@HkI}ez+mIM6N+H6{8rS9%BT7|H3BSd8p|S5 zuR7NfQ&+*xs-Xi<%$ggiY&W!!~D0G_s}We3R?I`N~T@^8-V-B zZnK|s`Sh!D0WE$KBQZ$gpM;0{eX25h)4A#M1m#i@W7MkhduC#|!Sfy7BYUwRB>%ZK z`=jTL7$4y!;`3HqLn&c}Y1?#2EI2H%xpV?_?(CMcD1A+ju9##&sEm+#lG4>jvh zWzRG+*y-$P#C_7HfA^j~Tk!hQ$9o}}nC4<>zTOM6y^M!MIc04(S8Gd1RJ+k|7qs;* zjPF-JOzStfH%tipMZH4Zz;h#B(tF|%EMc)t5ps-UvjKle>~pCA4c zPd(Fu0L&ZJj3ciWh|>IiL8;QDw(W%=>%Hgt_stIoX;`K-7?LhT4e-Mr?-7(w9k-wO zu9hRbzWozE`r$|?^$t5X>Z|W}50P0TNPl1npR%M4QHZe%;$x= ze#@ebz$ljwII_sb!HBhn=ZVz)sX3dYshzznd}0IA1iIs4ogcWIf^*XAY_P_r7iRe> z$E=Nyub=Ofi1_vT^mXkH&)b%}TC_W+O1lnLlIDcIga4!MN-$E3wkvz&+lA#4Nc5(G z{s90|jSL>TNn;Df3^GmAlw)XmWH!9|FqF^SFI4&p0)2zl?njef+!>mN;3Sj>xdbUjCl5`lT-|b(?zuBJr z#BekGx{^WV__pB;#mks9Si4_szUb(yQ|+HU7x>NN>(`8cg2dnR6xZ1EB`lj}z>Rz} zEC=#LD$%)#Y@FNf`3%Q|Kf}xL4@Jq5-2Hnr-w+Sk%R3(-M8K1G+iCmK3M$~?Ft z>bGGEpnea|35s~UkJj;;ES$RpoD04vJ?ZYr+R7ena|aD@{HN1a`ZAcKYBuoTtKvM_ zgi`bC+_i7zvLXOpaQfi+z`1QrV|?Y~ETd)kgLHCJMSxQ5%hTMq=oz9hW7x9Ns}9o4(JVYuU%-3}+Me%1sOYppf_tCkpQMOCc+a zS$`e*ZG3gnO_OOCwcHTPPe(zne0OzSI0$AjsNLBtMW>(la>s3HF95H``Ete|hPi%tD3J^i`HKoY|zP_IqRKzK4aZJ>^z#eiPs?WMofp7Z!RGG?R zK`c&-=;3nsh5W8G*h&xUiLX#GgYCSGqH6C`76E5S?&$KDhkp00^U3g`AX1JRCjx!B zjP9v+%$E@Q&Gf?jrGLQ8|zB`ZZ^x(Fu}14lcw@vj1Q-Ka)bs zGQu1k<;bv|@93Wp?V3hAEKAQ`C(rfsPw(2X#M6F;-s99MPb2#ek3YR{oD?B0 zp2OOi#oc3zPN)YzT1#YC0fViJ?yj=g0~MCWn#*MEZQ0;o#qGmx+rkgHZu$CKU~0+AyfWe(t8tc6?{2q$&bxYOyZ0$j%NEXDN%_>Om zLwjqLHTR9>FFsea>RYQGCNoYWM=QUk*zNox8h1vcpbuJI2>ecXLwcT##r&3|sSnHS zD@$L?ULIlCMpTaHvDQtHFc%8t1*d0CORGx3uiy66rOR)bppn#aLa1?`pL$0@5SyOw2ij~ucXWSdlJvM)maD%;eEsri$=Um9P=7#n)7*z((q zd3v?a64LunB`A;a>Z^?xn*=Jhz0N9_%sKh@8jp=II0grkYiFz4!2 z&@}hEfnNsyw%=OkuL34k-G3JpD6#W(YfAM54oi|NkT^U zqfc|8$&K!BlY#6FetQdiNCXE}D8D}p1Xy2@w^_LX6i&wuZS$KG3Poeg%wuzXa4(9c z!n0JhOvOJ2{Ur;7SuLT@2_MhJJtv!YJlTj=yOZAa3IVshb+(G2B!-%M4z`fx2};pC zwm3g!7)6Ew$JGA{CJ>D=+1HD$8wwFMmJ?L1g^TIwwxMBF|?M=8=Z@r;y^QSJ2E6SJTX_Px{VI3k>BE|j{c9}z`6+`{l5hH z|JQeP4%m#<=0LX)=e|Z;)}iFf{^?R$Rv#~hqaLyor1~9~kD`2-F3zyyk4br(@ud<2 z$K4#&|DVhz)=K!4fPa`x&8}2``{*b_=rUh6(0_lJ+(u$_`$b>>Dqc-Imt4L6`O0nq zqayHZYZ%MQ(Wnb%Y1U?V!4&k(oh+_Oln^jGVg_q|i?AN3^L0<@Q$rhF0-DnQEeWXd zs-tvsuF`Wi1_Ke=#-HUY!|)OUPjj$ z({UrtNY!aY|4*Bg7>*04i%R5U&Wxy9+YOI$V~FD7xh|l6?%OQ9lyd6X$eRPi=t^a+ z#ne~w7yPVaQw$IJ#&hE__y8QHEm=NI%mK1_FjwLp+1C#k#WOp^%(d@_+p`hV5Nlu! zN_osXhq+iSu;9DNXb*+`&ihEe11T1%(KE|KX>$kel7Tr7J4^Y0+vwoZKmT9V{4C&n zA+z@QhR$Vr$YP0-I31?cJde{IDn68ZGhK$y97Mo0JAH^fs{456J@UTXdcRRL#1gX& zoL-gWV*m10Bs8anDP{8O*8~9pg-#m1pC8dDuewWED^4Qa-TLeCXB_LXMHR6$Oi@rp z91O4l5sJU;%}_uHie~Nh$e$o~Aik{@jxX{v2?4PpJ?{mrn zv1V1yryJYa`LmI9`bDu<7Rg1v;Nq&?5|g- zG+@kN)n-rZV1&pS|M^ZIyNvXW$q~zGLjA)JcY&X1p$-+T;@1?wLOcIxrWtX_5R=Rc zPiY&Lo02uDdYwdHe&uQY1-CSk&-UKYuE6&+fR8R2l`wAw_MZ{JnYq)W!tLk<)q!{M z=Xlwy!IS|T=r35!5u67!9|YQRI$?V`yzWUxHMOY4mDC#bjuv%X1PD#BGAiZxq${*5 zRBN$HUs!r!Hy(7{k}=z!i>dLcG#{xCrcb^mu|Iq3PEg6l4Px@KqmxQIvpI>h#2j8od|i6;&}@ztd`yhM}llSqVe zyAo05_hcF>(bGgXz%_TSR#vUED+pauDZf>ThOZ*pJ|Q;t@4|8Z_rmLbgtI3V*?N)2 zOgT9w;P>lhl{Hw#E3vngo{ZOBUZ+Vw!EStl=u21e9!UB|X4as(oUnIZT}HcGcR3ul z(}Jl-> zf`knXhpnUdGap4l@_hQpmTc!oZ7=JGRK(l^G|IK|34A0%>I!#C2ZFE}!&dGzP?Z)7 zVs4h4htkzH>#P*fn9UsDj6UifWc;r|7)&3nX9D#28zNB0t{|H6py5C8igF0)go7lIO0jZq^@$BQX zxo&ZKb)ceh{i6hp>DimWyRWVtA|bc<@(J2XAzXQib3RwYsN#5+^35o0#pmdde`S@$ z0>r`mQRJ}N4xT%#@LoHAjCd|KOcQgjv2}RRnN^d7j3j`Kf4b_W0E!;0Zqo~55C87b zw)T|D@{*Iq;DI*P)Z6rI1lI&YwOH?MykSuw!4YG!iLVfM~Hp*IdhA`F{YlsM0M~!_qGnSGe z#+c_SJWY5dS2CF#Tf3|+i5Bi`i2l`1}+n) zXPS2tw4G0$9FYi~71BF%2+REomfNgm!tH9F@VF~(A^G#rHv>+lBW7|^pc%IX5kx34 z(jVCgS-hmxMRM{P@MPw015}Lgn7I1v+n$*&^heEF)0>&Pxb9>pvSv&CJlw#*urut- zuKmE2kz+kNDgT8!HOcROww5{HlPiqRj)KDY+2n%m*^QwmLfQ?D>!ckxfkT>3pu;&& z^Qij!CY5{xyY;hZSMWm~Kp~jb0qgbMo6;#Zgw%y|qgf#<#6YBfxj7?G7b=D*BS5P= z@rHyfLM)7;1qBK8WNZn~t!KcQO%^@s59mO%$9=_5fAUw^;S^4bPV9#;iOyd$ciL&C zYC+XLZFDVBW+JV=^p@>@tV;|lB zQN1%Og}`lz%8q9D5UlPJH=;e>S#f9j7uah6Oi5*@fjPVY!jv&R+i}COkmcS+-nD9O zRy6_B4UsOBCsr}yU0&S5$`M@bJ4z})Iu1<8PsvevldpGq0?u5mqg}6(UIqgn5fsikZeI4;!Vk1!76tjAfjV}=LLu5M&M`kfAsL`sPIrUJdW}>{n6di9Z z7e5A7T*(N)Wmi)cx(7LwLrM92xpS6F*m`)?Mi!t(lv?BEUOt_6(LeSgJpWGZRAqyG z;a`-b992wlQ3=yymU=Nbj{>&msAVM!Fw|^@LU~uzNZxMstQ)tAmsAhTKWKu9AFQ}{Ny=Ob`W*uZ$p*fX2qMLB_ z>E_*7Av;?vzBD_THin?}))ZXPZRh`!@zoD9eiL}qu_q3^akE&AawE&NHVxB;lTFjD znu@<9Zbo%!w8TVtUU0m$KV!{e>=MoC=jb)DWlbfPs8v& z1YGNE9V57K&|T0s3C{;}PW3q}H-dt1ejT97e!gTx3z(7ag#9sVNgr;yD}87M#BiAw zXJmovpZ%1p{NsyY(8p+z;Q z_3n*ZI0grP>xlPlWl_ytPw_A5rPJ0iZqib^IzFA!dEj!sV^we`*9peuJ1)ftjzOI7 zkE)fH3aTvQ@{O&jc9_PYi%I%G>5hFo|1B=Fu^QEY<16*^MMrGOHu@Jjejue**flp~ z_HpjdYLM?NX|gA<8JK>3zdNMQKNw0UK)KTM_4ECY6RA>O4VQV!4OogsWXKKW( z&ER!3>j@;cpvCia%kgRzw~q5J25*CByjKB1tf#F8y#*TJ%Am)+>d)~?#N1ojEODxitQVW&>tDTWq6fVScQyop zK(k?}HnGfYuIQ${s}=#BM$RP)`$2r(1WIa!TN<~i0&2Sv>*Pjsh+zW;BRG1dkAQ&c zB-B_rN58i5O_?K)DZViMQwO2hl|mC9>GnHnCX(h2&09_{@+f%515G(-miSqa&> z(Stzk(SiF-Kg)LWYu0Qw1z`4GYpHuVC@?#0pxuNfG}hbS5>Cq#4zZ&ya{_2BY`@XC zpn}4bd7W;9&dPdHNO<$;%Vz;TxC)D!dn_@}^hjccp5Iqp38gyJWN01&01HI6oYDg> zbu)(V$tI`^^(jJqW+f);grX{~0JHD0udz!_;wB=m@W#I9rphq1E4LY*PlmJ#9f+Li=)v;jlH9k{ zCicInO+Z)GfbPKK)+|8(FY3r{Iq|#Ia*s`p)t;OEGe*A%DJULA!~fNjq~y=h=B1fh7|q8A0h_Bnexh56JR> ztOSsS48NOFXAflci~d_CheOXt(hDEnx7MEqZ1aGuE-|J5Zh@jS|IN=YB^~tt|Dpd| bnNoSpRwI1pV_GB+w4tM^r}6HF)r)@urVe2Y literal 0 HcmV?d00001 diff --git a/assets/twowheeled.png b/assets/twowheeled.png new file mode 100644 index 0000000000000000000000000000000000000000..921e111d1d50fab32255613dce17d06d4ea5af20 GIT binary patch literal 27226 zcmd42WmgfX~;NA}()Oi4i!84(u|3JMBYT1rd>3JMzZG46wh`*@exW}W`{`0OMi z4TS%AdBGcpetZWwi~n?1wKH{gGjKG4GPAX_F=22rax^iqbuzbezJTcxfPx~1k`@yN z{?0gEH~WpDhTVPjerk(Y8i?`T@~8t&UdCPK^NE zwKeVhk+2T7%)OhnOuIgQX+o$~3qKkows`)k_i8}&Byv``bGBSLadt^BO`T zjhaB5R57c!TMPpTT2burYuxqON`hJ?6v8L#Y8ujQ+;-_C&nIHw~C zi!X7QWo-_Go0R>dozufT2EA@WNO?-BA}REV;&1Iu965~9N8h3u=JdjM{AD*U!jCe@ zrD-RO7rXu+lS)8HoT|b9v?C;E`;Rx)8^Q+z23^HhE3{j8$<-^p37vQ{>rlKVFH6&< zFvUG&6xn3k1jxY#D)xCd&t0{5nE3$hljWOnI~E+A!JG8-r7X{QK3RWn~k-NL%;{sZRwp$7^l+wfFOMPW?;g zn34Scfo_TQLSw2iJ%d{RA(^y_16A7_g)}Wz;2T?4*IbraQRd*vxiXvXo%w{1>_vBq zraQ+oT6@;Vx}2#}g%ZezcMu@>NWln1RoP7ciUJ%>k**@H%BKnkY9FUANL?FMyhfW`EVXWJVF*vBlx^a+wn-d*}r;3f$@fhg5ori*%!WMUgN&0 zQx~jv!_c*r9*!<D& zc(ist^J+Un$~#uPx~cYS@8Ae8VtVaeTO-C4>Pc-}*WRHg)qL);jt0w{$yRhoUY>;z za5q`gU%dGYmus?xm+j?uUFz&UIpZ`yZ}TPx@lJk2_l=5p_AwF5r1rsGhU-c;`sq&k z>X7~M94kWo_lz6I1%~c4aS9kcH>B}#zM5Eq5j9e1#lHGR0lNQUnq8K#qyhB##8Y{- z_)c0IN^J}6_q)`}pQ>_T0rfyngYQgp<69SDMAwQU()6E{!jQ6LiaD6-?&49iU+V&3 zRkI6Ai;;7Bat(=@6tu^?BJ_Iij_89QTursiuXhD3q~m3{{&yDfO+G!vR(T~e?)Xg4 ztC)^7_~$6j4UCLj7MQmq%6B#$I$LP$>f?ZWSB<%)&4=5B zA1p}j63G+a+QMr@i|aTyqKgI6`pk)ny&7kfuE144Sqj-n*%O(byC$9<;&JL_6|H`!zLB6s|eHb*%Lsn`TFdu~2kNS#QS(SeZ^g{}HYa3E# z|9uBgs0!D*^L{4m%Aj3~Z%&qrRk*xW{E3ws9pS{3<=d(C$pnjo&1>JJwOI=dyDfH7 z0ENLpxQ$#oS@b_=s+lpy-*tU6!L>$rSEOIoYoZD(ZJogvHh|5ll!)k@$>o1c85{)y zgN;KoI#d|NH*c0!R4M=*)hNq@N^gG~Qp!a#Q}K zCWdRo}CJRX!`+$7Vx(Sbiqi?D3+v7D%k%T0e1v5TFmE?4_K9ej`z`%4=nS5;N< zdP5>IOj5JyHzuzl#jkx8*zD*I@UgyM@A^jJ&d@&yYfrgeYdC|a!Z%C;$)XD0BwA0^ zIs+>Yl+ytHeHBvzX`Cu2>l51K%8lNh*_3AdY~fNCJs@a0GP>h=woX)6XDqFIPUy6U z{iVi`)nL0gG`dZ}G8xOP3iqKAJYJphtipc4IT+0?m#wBhJ|Bsgx&wr&eY}{`jD#|;c44wwD5GAQnJb1{2|5g0eq%z@ z)V-oJcK4@X9wgeA0>VKd-Yp$IcdW^u9EIkqlME0`Me$7x1I~k!4vfglImqI8>=)4%PFI{Vqad zX!RNO1+cU!tAMM{_tI0KOEru6^Sjm~inQq9Iv&xo6$poC-}XZ{A1SzR{h)>A576S&K%7)ji0p;V(f%#L1s0vTF*&}Nb{=_ z4eUb^FGdh^hTt2Y+(i4UIuN`Tqy_8zTz2emCrQ4iuu;|1;0VjAFD=_50lA!^As0V0 z)9)dw9bgrcM9-geM-8tYY)njTg4JG4M;+JHp*WBc)(9n+o_US?uvoq+(Qe46j=u>I z(ulj5ViR{ds6d?XDtW7?anCH0G?sF&Gp>MOo1FEROgY=bU{c09+a21@Fj;cfJ`B?r zf!IyG>)&G+5*|w`iu79pSw=rScrw!}1hyBG?6&nO?ON+N`y{-Ddf%$t55Q*b944?< zohL$I-e|IZ7ZJ0s+o^7xLKWDL-WQ9vWtnEq-e*q_4ZguCl8ieIK2=wyDZhFJbVt^j zUM>&`gPOamn7;nHZiMq{dRBzfm`uNM>n>BU3YN2wUyN1-&peVjepx=0H6}RN3d88e zy=ZMC0+Vp|F>;i2-69 zt$ne844v|&&A5vG%!f$IQ+e}gsRRp_%{8TQzjutjDs6&7Csg7KsMM}(bY+Q!Nz*rR zN6H_tf7Uxd%iqW;RZ`pX%@DQYQK()eRmfQ$2E$2h3S=&Ju1G`*LxKDC zJ5l}#HIOs+SMJQ8SJm8F^JJ+>uzEtoUSu~3fX0N6$v*3w2AdZ<6wBFWs#o(d zDMU}V`_FNasI10&Q|i?IU4YgfjwF5J9?YM2U` zcd2>Wc`6CBCM$F-gFYuZZO+!Cs^+}OTqY&IJpq%HEES20)Q=~KOJg*zh&;~mrbpPw zM=)K&v+hkpO+{Lsei&&~CjPehpU}L2L7>-2pdg5aeJ5(we-01hBXqGL!o6BBilgo( zC^t!nnGNWZadXlcnw=;XZ>SM&r^<@Uhf@1^o*`pp%8T|S5N0dn$_oh78l%4riHI21 zeG`Hk;_~6byZ#KKX%jGb*pnv*x!(SE!VQr7T*{dUf(RDH=!rz!i~hX7gYUdVGL7Gi zdRnw5Z47i=E>Y^6z9M9fX6WqTQL-J>OVGw)(jiu<%Im}AWV)$y^2hNPRamE2{HG-P zP@ovP{G7r#i{Hg_(3O=3$;&84?l1c8dB-=vqco4lyoUg6IM~3fZ{^!;A{4#r6ZlBR z$u;vWnFB-jniP|j-sbO*v>D%d#kFotDgm%Lg@*T?_2aBGZeTqkmiJu^_w7RImxl{S z2~K*s;!5FyViX_1%Tlol;6cPW;!_-f^K=0j3UKMVV%RjJj6+ zV`qtsq4(fVn@u7l5&nK+%CuXq2g}y{*wkB` zSZXdJ8kEbbnWhsq@P(yx-sx)&TIk2bwmy$*Yjr_=pBQZ-R z()&xd|K+xvtts+RiC*1zo_+F^XhkET5b}-mJFLk@(BF$Obe=_p_SXdLB>rnFkI%!> z7VttL{CBPgU!sH2CApI0>k3NMOT}&!#!GdkZ_B?t$y#wa3b+-t?TFQ7o!PTJ&qJM7 z*G)r1i^g*!!Tw~-JiogT`OAwkYrdy$4iYa;az~YpClmmbXu)S%nF+kL!64Hez9*HC zrg?v1H2QpME_bsK1VClLG_zb_Z2Ua52M5ao;;@quMpvX+L3GA{#w56SlI1|Ndf#4) z;+a59DgkzvJgmlO#>wb$d`nf}7+R`1{(Qk^6^g~6mIaVG1oJ-7airh0bsau(IQ>;> zLGbxBZgFs;SjKS%Z@w4AkVB1WA=sW5rh!&ad`K??>VYd0>F3uhR&*q}_vWS*czD8M z6HXs#s8~gq907pO%dHd_Z7UDDaG)9!Yv*&I2FGqi&aE`r)K@Zum7#?O%+I%8+x zK?(};6d%c3Y)m(nNX^wCQ#DVKIy?4o+mZ{pnOL1HL`W+w6(J#9ux~j)Os7K`s-$mV z{k7AlS%lnynlv6Sfd-tB;lObtgjh&(=Cw;QB4qsgGiNVr+4bbr_*zP-Z~lhRQH!eq zlkYooMCmTvY^O9VA0OW3EgkE!4@ub{4dvmnk8zqOTA7bMIeFs6Z4ToIELD0W6Hw7SP{>K1W5%9Rszq`S89}QGafV~)r|?OM zOJwDlH$3l*y2I&6DL)FeTfF>jkQ+HTsQ>(1$me{{1himf|9$SPPb}5QzJ{&0wjAjy zUrtNNZOlXIkZ@x(Zt_J5AaOfaKH15X0giZV6{$6Y5Ch}o)ss^jis1UjFQg*qDor9z z&iem_1?{?94QrnBlT`+fWD4%BPRoZw##KXqsw;Rz>7$sfc^VaBoawzsajvAwjg>0eOciktJTFjVhD#(+m9YN$A?Q!{S82SNd2>mf7%@_xt(k*x zqMSkW;Xwx{ozs@eTAvFI4GmwwBTlRX>a)e7=-+9(Z;Wl6KN_bq*KZJAUAZ+HWw1Qz zh7RCaX6-(2;nL1ks{QIquJ)lw->rp0-Z+!I$@AT|>-M*1sf&acveIt1+u~tT964sg zpT$Efh)XlplTa%th%Y)wj@$Ap4inBvR*d~^iHf&y!Cauws1sWAB+#wbGdJyq#wQ?RDOf^C`0%&j z9XPwjzR zUD3euG9fZC235wITnO572=))pSsT?&~@2;D&}rijP;^xY#cJ<>46U8h5z=ou=sX94kT5UN57(1{QeK zXvMCMVurYRRIXCMsDW$f2m?xMk$)zYN=2odY+LP?P1Yy z{Jg5OJcnl4jtB5VD&xG-QUX0!B^e$Zc!g+ZPYYxGM8c+~aEFby`@Q_O=D1Y)8&9U> z$mN)|q1%pQ>%8V29i`@lJth64Tlg- zvdhj%Nf(3mk$EfbeV8n@@cSKH#6pYbL{#oNKR}D)xj#U63yx8*Swul$Ia)%ofra}U zFrFMNj1eKEwu{k^S9f^xyn|W({HzOY?PMFr=mKL7R(|0%=oXr5Ol_ZOq6(0B?SI?T zW;gVA_UAm^YeoDe%FuQ2IH8CD7tNqEX43WM%+%OmsN#chdi3MX_knwFY!%Sv#%?u{ zrdpCVFu^o*J>1@BeDD@wlkk2uIEy(ARXXzNE-($f6x46GHg)n6e}h@j9hv^p~g!4>yU!IL>07FyH;afYvqI6v~lJ`w3%nea7L2V zgVDn8&bM84zqYiGWZ!Di=rfxPpuPP@KSsybordV`@7SOFtbCoCXZ1qQ8qni+q9|Jh z8rT_e>Mrk^fJD#J{I1qCP1$(xr6IO0keyD3JL~mGUaL(rH+k>v@RWKqE<%6}SJ7Z!SBD zfYc8B1!QfspPd-~K$XhPjucRq@m)XnOG;s(!F|=EWqD~3`;Le2O2p9lvszCJ|$ic5pMRnA_9! zV!PD+{$*@$JSSea>bXG0J_j?j{)xPoi9F2HeW7!1v_=&z2 zVWRP_jQ#~;VwvQxs!hq_;So3tr5ZbSZejGmNB&VRcs%^sXkwicE*G7N`AMU%meS<-HetnI;USVfwaFARc`j)66#UnBEwcl zeiejV44I`fZeUR#{M%UzzIVTa%qO04Wde3B)Bl;TOtp6qnXviyueU8_nx1=PaXfTg zp}f*+IryBBzJ-kz`xw-#h{aQBW6<$fQinj?lh}M3}8MvN3)N z2!(RC*dAikq;iwTzxFBm+lR}%3|}|b9m92PWuJMwVB=Bx&vIwA*LWSE9NQ|M9ZF+|{ zu%7HQUPoG{C4L9=4p7uW)6iJR-}R#O{oku=eoV)&m~!0Qw3l`ff{`lc13hX4ND zyVvMKD>gY%xxNcpKTk#r%r>$Z$w5`3Zcpp52coyr5n`Z1d%&ia0GP5yKDQ4YRHwD` zTjM+FTMiFQx&6IdnSD@e+C2{A|Hx2jvYD1bbORP2Y`|4XF`4pITpK)=STIJXOg<-qa z7|b$G=*%h=A7V)OZYJ|o4jfx062|%yG_)!1OrG00y^b+9UI<7SJL7}H(e>8#x654L zfKJR8X;UpvKMYqagMHJwYqo4o1zp1a23nu`w_fddjw2v~f@J+rg%%#ZzJ+e;`=&9@ zpXEFms}m87563cmz7Q0bYsI?vV23~DjSFHp*|n7b7CW2@bxmOYd|QPT(FjRcuPj`q z5MUf1thtj?^k01K^ShB|Bjo-w+18MooSGfNU5jdMa8l?z!iAFKNmU%;sw2Do^8{cT zRKNe|67lFgjJtt%&A^PHxzy&dt=oi2#F#zKx{gbdPVi9%1{u!H;c$JgO)2}&9ZpwA zDTZlhmIB@NpCT_A?D0Zm-fn$|-_bJTjF;=1fv5#;knS%6@p%lQ9gW_li;dNumL*dj z#F*EFvJOSAWj=GZF4>3vth#!q;zZ?T%wVYwUTQs^7IjFk5WXYlA`&F%LA`W@~pTs*qFJ?#n*%$4hUJ&$u>6ca{z zS0PgvOrU+7T=ss+3K;apCcA;tQ$o~R4Py4!zxN$yh1h;o!kHXB8Ju#TDk~81W@!?b zj|;X*OKN@sO2^w4Q`_D?ToPny-LrIc2t<4$u~Rv$;mF z9&o};h4>EcX%@>d+AGbmD7EKy0QGhRNqVX~9Rq*=Ya z#IF(CM)LZ^u0pg3%P5U?S_2CbA+Pp%fs$b4_RE3mJM@vh7;#(lq6x=ae`**6#HnU$ z@x~@Q_9{txh?tkMTzX=4s>W>HOR&(9?#5;Nr2!_e-_s?4^IhX0iOf3yJaPSMBXx_ct= zSzlvHht*nYO-b_)@F``@OF6exDFxI9_ZC`JI9l?p8h*olR#sgomYG2p?FmySqTd_M zV)oiF!?0q+Y)5(RBcG#Aj=}ATiBr59xRz#P%AHk~MwN(FSQ>(H_mm_?65(Vy+zo5L znJ@dibcCSK=g0J>z|m60Y=u{6c22yJ6OZMR`Z)rJi&{E)x8^g*^4hd0QomokBRm@S z7H1xF)&S&}--hZaPthdMus5FlK|b|h45X8ERT_9a!*3k1gb`ecZ%WdN;iprg>}B%5 zjjiycbgJ!9`_lNPqUp1~@e<@8cDOl7;IgwPeI-#EP(wNA3N9TgJH0#$>^J>{$SBas zMo%JpEi==1jU(|Hhg;xY_N_UVHGFaX*&@r$PX( zpqxTz`PKQ6ds8|wJ`xhDA5c8X5vFH!KSwg+;*FUJAMHp_rg#>z#{geSmH95uR@%Gg zb!%ONYN_1b=4wCr&Ba4X|5Im(E44J5AYq?;&GGHfc4HA;(|TKTgvGopnM?7hklpWc zJFpeG*PWE^Z~i=08>e$37k_>m$_k=o=Dl|ujAaE)>pg7Y{hR`-F5@F^r1ScMV31eY zQvUbcK~q~Z2GBQY^93v8ZKX1E;Yp`bEPo8e&-^BLjPlOec)h6F&}%=zreM9XH6(@M zNVm?Cp#UKn0)Q}Pw>#uR4*@nOj*f>N^APRXT4utx+SX=r2Wp+FRo6% zE*cDlmp0>K4uj6A1!Lxa|IOrE&XQ7_{5RM&6bf({B(&{K?R&z^zf^D02yJvC&@p0( zqWo71Hd5|l?E;B!45OPM#c{qCKfxwRGPCR053|q*2^`xkoJkAiY)w~x;kVo;Dndk4 zG(VF5`X{MG{syI1KrR0ICe#-jvGBB9*-^h$XFLtI$eGpk%-AlRa7v}ogt)Atzkbt%cFu!)(*>os4}tsKY7ad)a(XJ%tkQ-*eCNm_87k1K9#UMJ1YJT-rNdd{ z+9Y!-sQR~gi(H~R{CMuFMJ*fjZpXUH_&Cc!{T`PXPo6|SSRnesZHF`+lY=Bq)DZM2 zODaYCloBt4GjIQ=dQJIdqA+cD_1_%+w!}o>DVYirl=g80N{j6u44a=FhsEdSs3S{@gio zi%Qd8u}si!59AQOc*%sUlbP3GND@ez-Q_*s$Z}ONJuN24ps<5Uv3DHRQyr~m5{nA2 zyCe}DqN=Oco`9CqC55Zw={0G!aTZnMWPGo8LTd8d|JrN#FH1E-wAj<9++GY73f4QL zh*P&L_%9iC{Wh}CscyEr#HBs<2;Fl)({o0rO?Er_5`8U@O%}6@3MI8ra+H@R7J{d$ zLWtstCjX82@v7wy`>2Oe?$X4$%c|6uHU^kM!JyZC0r!tQqxAG90%yaW{Cz&Nhbg;Z zV81guUV86bFqPSYjj4kx_}+}(^j%FANz1>|SzAE+6?xt*D(`)2KrC$o7;j5fsZXVe z`Nv;$AiVi+b028=8G$!8-QC67Uoi`_Vn(#lsa*%@MaK@d#nO~3`yMc8IW%3)?;JSK zlw@$m+4s1asB66Gx>hlk)|nb1Jss%97Eu9Up`*j}jWLPM6`keO>~Q7L1!e!TEGB;H ze8RGeB2YLChTz;r5ZG0$cS~mS*W9~DJk|xP^gVJ3wzFj{ZsJHBcHWe*n4lP?jfBNf zfP0MNocYJa9>;f!i-NCuy07prf2X_Oz$sk`XwmgGtb4Jt{TWo0C*kVJ9DJLXT4M`~ zcF8uB2nA1gXPPORR{TaSX2^fo3~7_{{Buvj&s~3ho;baJBBIvPZit3w#PSJtC^*W( zIukt+ab~H8Be9l%XCDxlH1G!4)jVTKZ6Oj6=guVNl|>~@|CiYoHmr)0Ut>8g`)(E8 z0sS=g`TM?TG7y@ts74BR4Q8-zr^^6;xz%s04_jKL?6Qk!qu5C)i7$0Vh0W(p1I5`R z30d3KiLobHx~wbDiA;k#DukT>PhvnF4%@HqzS-kBmN%TK9S3A9DGeF>VL`Y9@f!NS z7JQ@r`fMTNE@O9&Q9W+m^DREx_|FDB*!PhR){j|m&V6c-vYJZ)ybh|~AMv%e?E6}` zwdVhQT}FYHL^&95T}@@L-a(%|4=tAsWXPUe+gz-<0J1H{t4yD)m7G0ebijQzw10)P7de-l{0*?a?9oZwWsH~%S7nD({t z-A`y$g4CCmmVOyoMN~ww^F)OUXUn^)b7(Fv8=HwfawI&um=cW$L`tYip^n8i=-krT zP(W>4vdWdqY7pJitf$n^Pe#ljLbK)BZkohAJIj3ikhB5WWxO^ARH=!f{0u2pCPX!NT(fH(9MpO+@7zy}tB#@Zo z9+?(nBBB`f`|mvqPN9pbO-3-SwryH!6J7h_X0~1W9;ntl>J$w-{p-BVH$TZ~i`k{? zZCgIvY2KKFWK)PxKEY=iZq!)Tr!(XcZ9R?3PMm*8z;J|d!@`!EvhIS2`DvC756CB? z_4)(vIh8;oT$E8DBS#M+)vp?h%&mu9>XHBpZc`2-XV)$=bW8cn)(!Ik?r28ciK}5` z^Iu86>T1fM%a=K{F_g5ylndLu*%#Zy&dGa|N8paX;10Nx=tkd^PGGe&+`-*c+o1&K zU&Ji*(VQb2L00O(w@rA3D*d5VKgWS?ZMMX-H%u$+C05&O9Rcvpq~E8^QeB<^q;2hG z_evHfua+z~4-N4}I{~WvFIUS8ih$c0fMs!DHQ1iDbBXP=kp)|O^M1MhVDR0<>DM&v z+o(E?c8lO-ea+}0eq;fqnF@3F#kO%Bc^yqSr_no)-2IJ)^yC;h8C}v8pfB}7W6tKx z3e4jD=sYj>l36jmw|EOr29S;u`)p?nei66kP4|ZaisHAud8NF)2Va7N3)_#K?!Vuv z@4pYF&7QU3r17?~V36*{?3RxmQIeCr04KJj$d|Po_w_%6I*gl#Q_QH<4`a4MzLaWmMw0Mk^xkCy!9)=O*O{_7G zQ)6t-kPEwg%q;Rkko|5(z*?13{mDSm>gx5;pS2L=A^x(`Ra-sHhH(+XS6Qwk=s zn(G416u)+^0|v@Y{p8 z`*a4#-BP_9I$2A447(2!@fw{nx)LgOoNZ#rD0jI)9r*CJvYh>8tAuGv0V6SHYj)e6 zoU^ai$=u#$W=w5rGL+@ZD3yH~`3*W|_V26wB_=uEcoxp)$@G!DdXQRBtJbmeKf4y? z78gb~|1-Q-L|RJ9Q|fqkdPx5pFoVHvf^^aG_9f*jZDr*v;IS)>(w`ye_BJx3l8wS| zNw)OSHYr84t>pd83q8C#r2gli;$J zDp7W$Z4i7X+Xqh@;pj#`Kqs~3{160vk3n9?`T)P|_QJ=Wm@l2~pHkh0E$WP8K&3iO zyTN9mQ8-1R6-4r1mQL@_?2UATMI@R_s2j|dZ;w6&;J&)ipclvv{!fDVg2~hRw^g~U zUw2&7h#)sU?e_(H30rH??YS}xi9(I--NJW{|Ci)(J;|;~_5Y)J^qMKviI5e+R04%_ zZaj(so>;qBUN3ke@fVdCnckL69EcyFXxuQ~+Y*t8tF^W}333;mG*mE@=KUqHN}gT= zPg`6UPhk|onS6XulN}UM5XeYJL+hf5d<4W-$*BHkB_h|!^VaPdVOA}!^;SyF^i^q{ zQK@wz(%8SqaHmbo6QFJ9;7FPDTDX17-QB6I(p(XHWsASJcyO=EOkF4Y8@s-sD+EKq zT8*evn@PBeg)}u`;|hgh^m3k48}zhM%xtR-BWc6Vc|l{V`DPFey# zmjWReJqFWmW2zNB{M4Zm96`gbW&INPyR}z$OghRLr5nwbexA6|!8N>;yV1UC_6YFg z-B-da=c%U%C{*&)i3srhla=Om_y0*X!8Pawbw+0>J8H;;6uJ)HF1DJay5 zHftdpF7hFzpysiw1ca7+drWJBG40)n!72tnlX7Xf_Yj6vS%v$qAB6ke+vK0QIR(w! zoE(>NGuCzfJ*EM_-<|JEsShJ;FeF*s_uN7n$lEK0k6BDqfrH4T&J9dQ^4F<;pI%KG)N2G%r2QCl z*s2;RU&9#bQJwCmDvGUe$n!!bTDd2jxOufgeiD=R{c|Qm+zK5s(kb;`9{Erk= zVL`ly(36#wK}%8+zX6d3PS|qKL7_+lsRdprZYBxb!|D6_=OF3+q1Kbt)x}EQ#fAOkYAP>uKc^5D#~%Jku&S+R0{A$dr19Jn7L~_`FRWNDnbVIr zsQMc^q|}B;#QPY`RuAkej&h3=#2FTv?}bO}TXD-WdO;+}%(78@{EHcRaz(f)$Qpx* zlvNlXW+xXb_KynYh|`6x@U_eIbzvHqvS}NZXn#p1ft=oJ`+VNcalqc0HWN#mHDS)W z%jNQmPS&hLs;<UvT4h$h z`AeN*v$LTLqU5znAf~H}zuHAOx^zKmZ?zLsrRWXfl0>ULH7e?O=OJYOay?BXcr7yP zDQE~_JU7udhSLJ6cKEsb?ILS_Nv=IrQjk!Rl!x}5W2`n{#YZ|+QkjtQt)LD`DJ7aG zz!*r7K<1maRV4Pfu&pfd12TRR_9Nj*!|_)5Qb<}}!(eidUfa+CC^2(L`b!6A-;n6% zPLZM-U@*4I9SXpXaoRbhn6W9lZc${=*%$SP9X9k8fRq-}!A`Ms?HHopPSXMIkE=39 z6EM{0K}wPqbBBEU(*gp$(poKF$?C@tb>F!nHY_sFuOO?YI$*YGWsV*jvi9 ze=+i1Vd$?-0)qW$OHEm6X+aq+sClG^VCcu~?dZMisKB?u4RZdR9(LmHQ=$N1hHh-eNOGP+ys6@6LF)p=`KG#;GclT<%uAZ|m>_qcp!$1^rCa%NLCuZ9T*;jmr!~!0O~j+c26?Lj zNV$8q%dc)|B7w1cU>)zmbBrSOgYf>mT={j&{MF zzSI+4vzysc*+8N~F2I>|Jn;W?jPc$rCojFTu=FG9kqnz{C4I9LR1lwLPGglWJ+o^P zxh{U>Jzs3<$nAwL>zh74){@@xH|r*S#$0wbXBMd)vMmPp^p~|ENk;CUt-`?vDi85H zQGF-lqQ_F3R?b(W8(DkL9ixO%Ln7%{Q}=qKTYx#dG3?L=WbI9@<4>r6Vo+BvViAN> z2s%9s7hZc|#%L4++o~!d>FU z%*dVl$)0bvX!(L^X^F&OGTNG__Rno4ftMznm(Z45SQ7*h_W7%xq@mt!uMwN}eB8`t zBc^s@B4%vjWVnhFPdQJWBg|^Q{bCaNr=jhO3DPtzz{vHxhm(kn@a_2|czxfA^?qRo zycmy5nXEYO7UQ^oIY&c&lpo4d#su&KZG@62=78AmZx)ZQ*M2~75cN2P|*8B;&9tS=WOikKyVFG~^KL672L5-jLdXy~4)OI8** zf&NJW*il-KXmgcx-dSggCus_%f})5j2uR!+cHWk|Un&%%5XnyEaJ7^PvKx~Khr9Xz zlVkSn&(kk$$t|9Ba-MX4UR+o1Lhv>*uA;9~j^EYL{YjxaaUBbv$e`NI)_OEk;Ar>$!xAcskm zF*{jO3bo8rWMq0|l&7fze$G4JJ*$>aO`4!mqcz}-*mK6KadoufXMisxb=uQt-!tNfOy(Y9ve zjsh`LBw>(IYU2qb4wu3S37cIgg>FE>P@!ZJGu->r>@LUOF|?PO*Pe>+uO08|{ObVl zSZGbZmG&a9%`C0%w=)@#vopg|>z2GS#3{HvW0Q@&e!`7%w++;CUfF^Crq@JSjn1wn zt7j_Soek&92h}+hE7To`-ywoLST-M3t=v+3?gXD5tA;NFuXu*uQYYseR5g8eaCjLB zjE3|DZ}z_s;M}iUQ{Gp4Om>gk^F*#sKh77!@drN51r#8`RwesA2>L$(WBow?4~Ma* z9$D(>zVG$zLuj@%RmcMTc_iTg{T$rO*qK$T5T0=6KSEu3?* zeJP7c^qpKG%H#xfS{tn}@LQu`j!PoHbP_z<#{I1O;b~&J*xe56bh0g`l6F|G^oTpa?RY%y1S%C!Mi89;PvZ{QHo(%i+ja=MrJK>X}gUhySC(+N`Kdvei zjLw`xwHMYdE)Yz?PmO53BD_yY}QulJ~R48QTKd+FUM$1X<2Y6HeiDX>>mwQhM-; zb6walxUoUlG4;!aj>^#cH{r|EzuesGEvCO6hxDSpONwbw^RXX<4jxyX9Zc6Gw78Mv zBTvQA%?n=pqt-KYZN$AIn(Gp_VRyn05UknoJbi7gBd%IS!y|jPhz`lIqsMto1JL3? zb*rJO2)53|Y{JnWm(QHFo;N6c`kPXDi$nObW@^y-DyaoNzJn66?jNC;>5M!RsQfF_ zJ6W{5C2q_&t=Z)zLpwXvaQ=nb;W(K;bJf*t$Ep=2l64#hU;SGLTAzOD9Y4XYV(T_P z3Yq`NFj@Xbb9=-Q!$`@J{{gi6-;^mbyl+8Du|*JgQ-T%d3M|^fW2_CrLI_J3e^zf9 z5MKKw(P>ovgHaRTRnUDGsx&M4$vf8zA?b$;K7y35XZ{h&wN4PYt;~E!)(OQC5m7XN zDld&uB=P;~Zn0)HQ|n@-66CMVfB!7t26jcgdHU!PynVApT21rrUd^T_ez4xL(KQi~ zKb)D4@_IfHEZ4rHtkdw48*&t%%HSJ&&@c*!lAlns8slL9A}lcXc?aFGagq8QX!WzR zJDAnthUZQGAM{5P;8&C1F}*I&hd=D|3uadirsvEs*$d0R*lGopfrO}+If-!3hkrG5 z8wFx%=peBoqCg?rHl$Cty0CZqS(=!D{{YuaYJ7)2o$DC1M5YM71!XMh^kl6x(BIuT!xL!Wp|y9!75?WU(wuheP1*TY}&6$0W}3X48;PFYh6fbC4=@%^OQ}s zf71MV%;)3`um7V3*!a-*KYHQQ-aS$lem!)pqhiT^0=^5q5akG{#f~+OKM#LH#MEjS zd`Fu|yHSFfN5rJ%i|?*3Kqs#=IuU01d{iR-3w73t)9hl^-RTW@pOa(w!B?k_O3loF zF6UdTfx(DkW%qwlCM($-@6s29pmt3@M%($Wbf*H7Zaj-vjjogqQ19uFx?__3$rPe_ zgmM(6DUojmXXvQS9er^)eydE3Iy;#*Ut{}Phe^QlwZpMG{@i~)c2`PJmDYfz);i5N zS1Z=$Ghee(>FW!&!Jhqy)%D~z2OIz7WGG(;z3MlROMQuS-{XPtdm7n@jdSdE0uWcY zynMq8AA1e9rR3U=1_cu$-oa9@V^z8b4&UmhxjlyR53bt}ef-(kr=U-2{}(M%0WQk7 zMy5}nxK=sxHAQD{iV2baht=)?Bp_%r8qK)hg=CX=hDyHDg`<3l(PFdF3-V+-wa|b~kJ&L?O$ga8Q^oUjB45G)YfJrG#j zCAho0LvRTa++BBZg1h^oi^BqoySsh-zB+aOf^&1O=B>Htx2JoitLN#bYhZ7p{Z2-! z=mK)!aSzc=e<;ElPe4uSnn@O>YMN@>Q%ob)92^jK$np&bWD2S+tZl#Au*~(B#F)tR z_~{9O?i*Xc2lQLttbrZH?J@iQRId}SF^_Stc018k*y=>#3e6#EjQ;pJn3dLMO|ISNP?)kF{C#G9S7tD|73KHkl?M z3w!!okvax^vHPk}_e0b8D~sjuqH!^t%D!R3MR6nGJ$FJ{_I(CZR2iOrgAFG8lR5Q; zB^eDrOQ~DYRD6emtmebk>?AWT&0OWy)NV|5R=Qp1KVOVxXD?=Mp`pCoL*txQGoEug z|6br@PaiEC1=ZixT%H~?^zEVPMpX(% zJ#uX%GaaOFi9_W(OFho~bA^160c%51ch+1WrehCu*-)4NH&}P`w3=C^bEbkSvl$;^ zk{gzh_*emrt(Wl9$t8niAE*?qSz2t4E zE}dxcc&GwoI5NJ?O!eEs!FykQ#RAL~T+A<4i!N%IFJXP^ICRxL>-J!s_;1&|m;k1W@jc@~;T+U! zsO7fknH?sUO(X>`5vkleY2Ft!qau>d0(#lXJvR5A;egTs>FrU_ND4>rTirTP=1Bco zUH{r-)Ow{1e4GyWp06skqoQp5CV)JnMea;A(wx8Lc%&W7FO>_r}^%w(Kdj899heu4{T(Ht~O?Gx@_{_x@R%2f#{<)=S%uFvpY90P`>n^ix+bgmuwzpNhXpsel z{PYF$Y;#|%diYo99e(9K5>s%<(~U`GNLh>)iSb~`tN;W8U2}U8wG?Tv`0YrG*)%DM zn8lFU%I(m2W#=U`l#+CnlbI`A#tI0xbER!yxyoQ>bLWpzOZ3a=x`P>Q)fS{2jwTPu z&PSI>p}0!zLzvLcQVm;(Jbr2sw_$Wz4}GTK&I!F_41XC>WtG9V|?#(sHX5N2TV9>0OSRqt;D=6F6pXE}jQEkkqJm5RJ z+(UP#1aP}OD!sY2ofS!{)b5Fnrz4NryBC}-*X)Ad37zkS>2b$3pI^$&O9^^dy=5b0 zFq#3EXM}rR8iLrM`5qg2yX=%^t|+mS0@=gkq3_qH!SXOJLDez{yyR=&%JyYeoea?e zVaJZoCuV`L680b9u4;-l!KKdr!Y9z*Tn%NCzGiPo*^Q5V6XCjrHqSXeqHg*)C^X)j zEDp~#l4G?kT7ISqO>nqX{zoO7LVnN3GM$+;r&UZd^L)$3 zxr<`mM4ZN5+z&0TX=|B3f*R}KPaOV{yT2G^g-wiC<$LxTHVH7JG3S?d@^77x6xiAN zd!I&02_=+poHN}0#ZL%;97hIltI9KA4Ji->`^Wr)d7;a(^XXbqqh$i^ zuioRf(O<7RnF0y7;44K{=Pl;CfCt`kqn8}TN#+19yR8}{6zZ2JL_79x=PI6?{cFP4 z;zSNkwqgg{9!}_!D>t~$sNm7T=blu75^VLiz_axUIrg%Ym@3s) zfiAzjg;7BsN=7^ePl&BQp<{1=^`-synyF~ zv@+F7CLpDJOqg%^9<&L6+>75st}U-|{pJ}p+I68fMo-QVwwRfL#)aedfMsP$Vi*;? zvv(+9KG8&mxC#)-p2dH;kbzF?vn8j^3&gwIjG{6wqm#3d6K?D|qDAky&87itX)mo|WiG2gbRi7_$bG%}cE4(Z{#GR#fv-wuTnTOxr5O4$EvIzHj4eA^{Te>uxk2@9Nf4$x`O&(lFvdmx^Ehvwu+Vix7izmeUz{Fi!TB!* ztgvD5$nS?Ot!`tylCllzYr#mkv66`$s8#yIBfnN8%vhu+!7|s_;>9nZcNd4R<#zhe z8k5?7yOX#`J5v-?qmNIMI7HeR|I`fF>i439;OGemqJ zfqqgaQ<8^i?16zFPmod&;Q_vei?a&gTC$PTq*N{Fmmn;7M|G31s_J+RJ*|lw3ZW<> zz*B3yU1pgxn-CsI527Ti?5ik(9uqXF$mvt_&R&AAWLlFZsFn4lanWO z(O|O|itSCfDYMGM=3dzCw=g61p1e1{s>!-ErSl6WO&S8a=aOm%LQkZ$yqW z%k3l`$S6* zyrR^!+pM3r?C#fWYWYa$HC7%YH~`8#=rz)&mLEIqUvfxufU&{xuVl@ z?@PEnIWxBo@H}&`ij{`V{*2o%MBqe4dO>E%PECH`6%jk zrAyr~{y~rklPSvMSULweIk9gx!ABP%?eTs+Per*YrC|JUAoT@|9r0xJE=XKVdAk|f z$c@8}p^CP3I;KoOhzR(2^ySOf4+{3BbHCF(jB~`oioY)npw`~fzk6;Hx|CH{Q)${IC$B`Au z@4Mr5^SIOmDaNGZAEwU>bulAD0NQJn^Q$2R!BVX8JZm%+jtwf`2T%6wmrLU0Oz+*P zHlCRXq6MLR8fBU*li84uVT&$dEr4CxA4jH%Cmdtek5TIM*M=6ql$t9uN6GuSN=I+m zh3NP0gg8k^1}~KqMV@kTOe3Y4pc`8ZcEw605p+10Fj(2j! zpYi!nQVFSA2#cOP+<`nFX1!Z{XzYOLw_Gdy4y!*sy&Iz?ROM&n;#2PwSG?@R6)*8< zHFN@0$b+yngsHqo2rAsK3kEK3xJ+4A7CO(rHz@eS3tJ}JB<~LxpuKJHkby-E?_4hm z70ZEKZrCCPgXh8=XWbOKHf$-0$ujO&I)mqWUV;iQ%9Hpz!At{HW&I5Qg`Qj;qDVz%$l&x{D@4~A~UC#`uIX8SuO0~MSMCMhX zRRCLqMcaOl@Gn9@9_Fx>Q7pYuw!``4j?K0vVbhvMFbZyX4cQ|6-MPky0QC;PlgV28 zGTrK!cNm{*n``|FLxN+!;1aqXZKTmr3DsFn_YaECi~LG5@dp0I<|X8e z+`QylbX|Hyp?YR~R*su=k#ex)k`}7m(X$-2efwOVtyzH`Rp1+mB@*^I!P|ziV&w`0;Ll8qt#Q=ST| z3=2!gir)$_aZChNQA>wVs2(x=>(Gv6t@HOs)oIZjok3t;U4|U9RsRmqLKO1WDM!i@ zk3L)+Ct;(zQcmYgxCg!Z#4%Ewy~Xu2m83LX^6qp+ULVQ3_>V`XdIi`Mit`;GbmOwW z1*vMV=A}8?W20S%bd+?9pG$kb_gDjGtUw(RU1V3r*m*bW73Us) z6pJNSxg|%*OkTje4+E#kVnHiYd*SyhtyeX|%8JGH*3UB&z#K^X(83Dk`}~450yzZ* zOW$v*B{L<;*Vm{Ny5?qy@BMteH|!VCH_C{^2Nk)@-2S{IDwQJHNt3BHxL3ai=tZz zN<`b(`84}b4%eJN*iqv(`^ihUH~o$2;0}99=5sHWGmTq5w176yk5{IRp0$Mcic<>? zE#Y)i^Iu`B&N%x!5pF1>T@cf1bqF%5MRVz_%1+$1Jf>&wU!*)jjS#wmKy-H?j&u(p zDa|0U2x;fCx0O-ajMEMVz7siO^7CQhz-2)Tn* zr@6+jfb#32p}D^Czzby#L+(~ns)rs(41ZEO=qxnlG4EqJY(*q7#+PO-hA5JR_wRbV z8f$(BUwX&xKnaJNV{@v=uLOG|Cba&K1?6ro-x3(a4Y=I0N;hR28rls#CR`$UR)k|2 zqgp;|T@vVuNuM3>xA3fdPA_O=@2yNiLj^dfSKwsHv08L5@Sqbt5K3aA=KQVv`2n>E zb^SbzI`^JR&z(1a|n<8R7pYT=krJ4&!XLN*w?XLiU*a{uwWj`U^}uJW|) z#Zrrahuakr|8Ue=OL)11Ux}B2UimltBRot}y^+NYN|2hm=Xf`#x#qj2ewX|?!WR3R zyEvie$1u&Cdf*t4r$arpF_)uVbaC2ETyK$-dnB$rdrfC;VMJiuV*78P^|D7u*q{QV z9`{feiC^{61V*HJ3fsTs$JB!SU9|XlW+9=TfiY7NJ~GT}Yw4MQ588sYQ7eQar}sC0 z%wTB`^pzclYjM5y#cL`b6rCJP>o@7I=$(U;pVUfAeR@;<3++9!oigQ$%cpPHErHx| z@3UME6d702%1tYd7J)V6Z}z1>FvR{5cs=u(6%?{hBl>S-da+1ipYd9YR@N&gjWnF8 zNZ$~SYeJioM=jyEWJ{B2b-4yCuZ~vHs1Q$wPd?3%oi*XGaSW1cDktEA_3*v z2=q89{-AWCoPgt;TK{)a&{iAuIUrYb4mTFD+-H`GBd&6M z;IBr8cQ1BYaYB%bLsY_kol5&@ zAs>c4J9QM$)3Ck`+8nVma;x!@=nCPDJq$A+(SOs$6 zszpyi+aI2Kcl3CadgE3<-#-I?ikb8th?Y6W+}F&&uCXV0L{TH?eHEW{k32VK#)etA zl?yHG!0dI-K~gHl46&2spFA$b%Pm;6n?Cz%RTJ*PzO^w!2lrC5Yc|ETw%gaPzuJku zPmiTSdLiKtW%ZCz)=qq1?<15c>Tq*mHp&9LGf}XD{ZbCq6RsIpYjPnJDqZl#kMhnk1Y*{puhoEGl`a=rr2Dh45s=eqqhm*}T?R_+6 z9xU`^8Y<->LGBpH0Pu9~_S!_9UFhgr8>gP=x?$E?QWYn3%sBGPEK-RX*SK>N0u!nz z03q;DX(l$uA#~)Mn1Q+HFCBJnMw=nnF`L`F8EI#I0WS`(y8=mYl#X-D*#oNC{O$b{Uq*g*gdwhKbtrGM$=u zbNoY)l*`FLcIth=jC;F^;4?o_&(+n)-Gv;}J;6|1do32{SoA&zy`vip0JCFDDG5KB z$cxJ&2G&<^4v_t-+TabgoGF+%Gm<%ee(SI?z?xG|gSk$#Q1AS0b!;9PU;OOiuat-3 znmGSbjdirP;qFK=|QG>_@XZ<%RDj8PNa->vaBf0S8lsLyvYh zJ4=m)`A+YxZ*%d=1IdLK4A#E^goE{M>*l`^`)JRWH<&mgD%ee=csnJ-Cf_d9eUEN$ zD_1ojps1WuF7jg1j9eYdrt#f^)OW!ABqo(%Rty)MH~MxBYTm5^VIa{ZwyS4^MuOwP zgqiHM@A)8#kAvsNa(oSzwFl}L^n1L&5epC8;C1&zUb1b{NC3Br!^Il5H*Y=+{`W?J z@J8{3pw?^Z&9cfQn6AX6Rtj8d&r9UX75@7>`uUoS8j01rY|4=<|6k@h#D+ z%x<8WFH&}42hQ2>(qq*Y84kOG^O%YiOGda*Os)+N=$Ya?q_ujVR-VPd5k}$KSFpT^ z=2f2;H3M)Lk0yJfaT(Dhi58166(tU?5~n)61$otxU@#&{6#o+Ab#83j6h%p4!FAk6 z|KbmJSKFg|fqy)-6UD3 zBIJ(PA5?52Ed_hywgx0XOLoAf`lAvjAqK0Y^HJr((cmsB%_4Gj|bf(?Cy!W!0 z?Vp%nu*iH(c9%uPRcs={r~Muw!B86o66ZpPh}EGY*(9J!eDq^iY;OWP0%9UalgrN9 z<%=U*R7#2aF@E7RJ<&1t!R3vprn1WDv~9|(AZ_uts>FE?={g8Iw+)uM0f5e+3Irlw z-yb*k?3cCLDmr0@Ik|DxtgC1$_?e77RF0P+59H;hGQRsZxUcYG%WE}W6xyqQO&THB z*0nTw*i%00Q=HK^Nvq1&)nMawKE1~+48(phtttLjg+MJs{T>#&u%vl4tN~s5Z=79-%6b>`2Vf@4?@sCp<9T` zVL;&3A6e69y!_NR&%f4aC{1BRA7N088CFCDC|6rTD-@WMnNB6({X;$4(X3khBC_|P zv`*sV+T=CS%O9*Irtbb}%R%J7=Ros+AOh)ur9pN}UAYAbXi=rPNJo5l!~fYoGXRrM zbU2R|V?qUgq@f3;5JSZU8H7kzqdq^=)Cw1x8^-qB|F|sEc}TFiO`(wH`iIJ{qZ7#2 zP3BcLIvJjk)WR3+5s{j%ZWo`j=KBoJXNc@X6O*T0!^*1=cU5LrnD z?@&8pYkyMZjTl`YvGm6&0dho|qP(7_DrbP$Sgi1jsrlD_nnGP#mxMCSzWq?#vjMkmqOSpn*|C6To>hxQJn zU8zaXp!A+RsQh*FnSP?xDSGFLG=ct!0eUnSws}KFV82`fKZFL{6nBVgNUmXVitj82 zsbQeyz8TWqSnL~MDxMluZ*mkUT-NmUKDEjc`lCe`gw;JO`Fa*ItoY?U0t1Scw``s7 zC4J6NidlX4kW~5-39{u4giRL0rRGV4aawQVgerKM>AARZy*H|a)iFFqtI1mYd>c=!M))bc>2ilt4xoCN0Cpx`!2j69yYL2|1F}-X33(ThAR#^=nu>QJWUSM6^$F2t@vLY6I?IMVe6P`hC^1v|b2_HMW_n}8& z5>xh)kZ(VpNcd)Z?hw8VBqy8kk|oda@Z)6A=smy6o;2IH$&1UN)o#V(cm!6vx{@tI zzcCONd@dMYO?JWdacU-d4X-ksn;H z;5NcyXKm!usfeymz_)yMLSsZ)D;|OEF`&=@j)GgHYrbr9b#pHS(Y; z$&d_N;jA3)HO-Ruq}N3<0+7kWi2OJ)8>vD!``oZllztfjX&{1nD1+rB+h9lsnFzm* z=V!EL_D~zzyJIHXzB%J ZX|Ehrpk=Gz^>L^-l45c{D@61I{s$4m>%9N~ literal 0 HcmV?d00001 diff --git a/scripts/show_result.py b/scripts/show_result.py new file mode 100644 index 0000000..e54b9dc --- /dev/null +++ b/scripts/show_result.py @@ -0,0 +1,55 @@ +import os + +import argparse +import pickle +import numpy as np +import matplotlib.pyplot as plt + +from PythonLinearNonlinearControl.plotters.plot_func import load_plot_data, \ + plot_multi_result + +def run(args): + + controllers = ["iLQR", "DDP", "CEM", "MPPI"] + + history_xs = None + history_us = None + history_gs = None + + # load data + for controller in controllers: + history_x, history_u, history_g = \ + load_plot_data(args.env, controller, + result_dir=args.result_dir) + + if history_xs is None: + history_xs = history_x[np.newaxis, :] + history_us = history_u[np.newaxis, :] + history_gs = history_g[np.newaxis, :] + continue + + history_xs = np.concatenate((history_xs, + history_x[np.newaxis, :]), axis=0) + history_us = np.concatenate((history_us, + history_u[np.newaxis, :]), axis=0) + history_gs = np.concatenate((history_gs, + history_g[np.newaxis, :]), axis=0) + + plot_multi_result(history_xs, histories_g=history_gs, labels=controllers, + ylabel="x") + + plot_multi_result(history_us, histories_g=np.zeros_like(history_us), + labels=controllers, ylabel="u", name="input_history") + +def main(): + parser = argparse.ArgumentParser() + + parser.add_argument("--env", type=str, default="FirstOrderLag") + parser.add_argument("--result_dir", type=str, default="./result") + + args = parser.parse_args() + + run(args) + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/scripts/simple_run.py b/scripts/simple_run.py index 0796266..b5af782 100644 --- a/scripts/simple_run.py +++ b/scripts/simple_run.py @@ -7,7 +7,8 @@ from PythonLinearNonlinearControl.configs.make_configs import make_config from PythonLinearNonlinearControl.models.make_models import make_model from PythonLinearNonlinearControl.envs.make_envs import make_env from PythonLinearNonlinearControl.runners.make_runners import make_runner -from PythonLinearNonlinearControl.plotters.plot_func import plot_results +from PythonLinearNonlinearControl.plotters.plot_func import plot_results, \ + save_plot_data def run(args): # logger @@ -36,13 +37,14 @@ def run(args): # plot results plot_results(args, history_x, history_u, history_g=history_g) + save_plot_data(args, history_x, history_u, history_g=history_g) def main(): parser = argparse.ArgumentParser() - parser.add_argument("--controller_type", type=str, default="DDP") + parser.add_argument("--controller_type", type=str, default="MPPIWilliams") parser.add_argument("--planner_type", type=str, default="const") - parser.add_argument("--env", type=str, default="TwoWheeledConst") + parser.add_argument("--env", type=str, default="FirstOrderLag") parser.add_argument("--result_dir", type=str, default="./result") args = parser.parse_args() diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 0000000..6ac0b45 --- /dev/null +++ b/setup.cfg @@ -0,0 +1,5 @@ +[aliases] +test=pytest + +[tool:pytest] +addopts=-s \ No newline at end of file