From 06573d7f67aa19d0e5138e4fb8abb9f6c999c841 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 11:34:01 +0000 Subject: [PATCH 01/31] online training works (loss goes down), remove repeat_action, eval_policy outputs episodes data, eval_policy uses max_episodes_rendered --- lerobot/common/datasets/aloha.py | 2 +- lerobot/common/datasets/pusht.py | 2 +- lerobot/common/datasets/xarm.py | 5 +- lerobot/common/policies/factory.py | 4 +- lerobot/common/policies/tdmpc/policy.py | 89 +---------- lerobot/configs/env/aloha.yaml | 1 - lerobot/configs/env/pusht.yaml | 1 - lerobot/configs/env/xarm.yaml | 1 - lerobot/configs/policy/tdmpc.yaml | 1 + lerobot/scripts/eval.py | 131 +++++++++++----- lerobot/scripts/train.py | 193 ++++++++++++++---------- 11 files changed, 219 insertions(+), 211 deletions(-) diff --git a/lerobot/common/datasets/aloha.py b/lerobot/common/datasets/aloha.py index 639acf1f..1fe27e95 100644 --- a/lerobot/common/datasets/aloha.py +++ b/lerobot/common/datasets/aloha.py @@ -105,7 +105,7 @@ class AlohaDataset(torch.utils.data.Dataset): @property def num_samples(self) -> int: - return len(self.data_dict["index"]) + return len(self.data_dict["index"]) if "index" in self.data_dict else 0 @property def num_episodes(self) -> int: diff --git a/lerobot/common/datasets/pusht.py b/lerobot/common/datasets/pusht.py index b468637e..068b154e 100644 --- a/lerobot/common/datasets/pusht.py +++ b/lerobot/common/datasets/pusht.py @@ -119,7 +119,7 @@ class PushtDataset(torch.utils.data.Dataset): @property def num_samples(self) -> int: - return len(self.data_dict["index"]) + return len(self.data_dict["index"]) if "index" in self.data_dict else 0 @property def num_episodes(self) -> int: diff --git a/lerobot/common/datasets/xarm.py b/lerobot/common/datasets/xarm.py index 733267ab..0dfcc5c9 100644 --- a/lerobot/common/datasets/xarm.py +++ b/lerobot/common/datasets/xarm.py @@ -60,7 +60,7 @@ class XarmDataset(torch.utils.data.Dataset): @property def num_samples(self) -> int: - return len(self.data_dict["index"]) + return len(self.data_dict["index"]) if "index" in self.data_dict else 0 @property def num_episodes(self) -> int: @@ -126,7 +126,8 @@ class XarmDataset(torch.utils.data.Dataset): image = torch.tensor(dataset_dict["observations"]["rgb"][idx0:idx1]) state = torch.tensor(dataset_dict["observations"]["state"][idx0:idx1]) action = torch.tensor(dataset_dict["actions"][idx0:idx1]) - # TODO(rcadene): concat the last "next_observations" to "observations" + # TODO(rcadene): we have a missing last frame which is the observation when the env is done + # it is critical to have this frame for tdmpc to predict a "done observation/state" # next_image = torch.tensor(dataset_dict["next_observations"]["rgb"][idx0:idx1]) # next_state = torch.tensor(dataset_dict["next_observations"]["state"][idx0:idx1]) next_reward = torch.tensor(dataset_dict["rewards"][idx0:idx1]) diff --git a/lerobot/common/policies/factory.py b/lerobot/common/policies/factory.py index 8636aa6e..98880f4a 100644 --- a/lerobot/common/policies/factory.py +++ b/lerobot/common/policies/factory.py @@ -35,9 +35,9 @@ def make_policy(cfg): if cfg.policy.pretrained_model_path: # TODO(rcadene): hack for old pretrained models from fowm if cfg.policy.name == "tdmpc" and "fowm" in cfg.policy.pretrained_model_path: - if "offline" in cfg.pretrained_model_path: + if "offline" in cfg.policy.pretrained_model_path: policy.step[0] = 25000 - elif "final" in cfg.pretrained_model_path: + elif "final" in cfg.policy.pretrained_model_path: policy.step[0] = 100000 else: raise NotImplementedError() diff --git a/lerobot/common/policies/tdmpc/policy.py b/lerobot/common/policies/tdmpc/policy.py index 942ee9b1..14728576 100644 --- a/lerobot/common/policies/tdmpc/policy.py +++ b/lerobot/common/policies/tdmpc/policy.py @@ -333,94 +333,6 @@ class TDMPCPolicy(nn.Module): """Main update function. Corresponds to one iteration of the model learning.""" start_time = time.time() - # num_slices = self.cfg.batch_size - # batch_size = self.cfg.horizon * num_slices - - # if demo_buffer is None: - # demo_batch_size = 0 - # else: - # # Update oversampling ratio - # demo_pc_batch = h.linear_schedule(self.cfg.demo_schedule, step) - # demo_num_slices = int(demo_pc_batch * self.batch_size) - # demo_batch_size = self.cfg.horizon * demo_num_slices - # batch_size -= demo_batch_size - # num_slices -= demo_num_slices - # replay_buffer._sampler.num_slices = num_slices - # demo_buffer._sampler.num_slices = demo_num_slices - - # assert demo_batch_size % self.cfg.horizon == 0 - # assert demo_batch_size % demo_num_slices == 0 - - # assert batch_size % self.cfg.horizon == 0 - # assert batch_size % num_slices == 0 - - # # Sample from interaction dataset - - # def process_batch(batch, horizon, num_slices): - # # trajectory t = 256, horizon h = 5 - # # (t h) ... -> h t ... - # batch = batch.reshape(num_slices, horizon).transpose(1, 0).contiguous() - - # obs = { - # "rgb": batch["observation", "image"][FIRST_FRAME].to(self.device, non_blocking=True), - # "state": batch["observation", "state"][FIRST_FRAME].to(self.device, non_blocking=True), - # } - # action = batch["action"].to(self.device, non_blocking=True) - # next_obses = { - # "rgb": batch["next", "observation", "image"].to(self.device, non_blocking=True), - # "state": batch["next", "observation", "state"].to(self.device, non_blocking=True), - # } - # reward = batch["next", "reward"].to(self.device, non_blocking=True) - - # idxs = batch["index"][FIRST_FRAME].to(self.device, non_blocking=True) - # weights = batch["_weight"][FIRST_FRAME, :, None].to(self.device, non_blocking=True) - - # # TODO(rcadene): rearrange directly in offline dataset - # if reward.ndim == 2: - # reward = einops.rearrange(reward, "h t -> h t 1") - - # assert reward.ndim == 3 - # assert reward.shape == (horizon, num_slices, 1) - # # We dont use `batch["next", "done"]` since it only indicates the end of an - # # episode, but not the end of the trajectory of an episode. - # # Neither does `batch["next", "terminated"]` - # done = torch.zeros_like(reward, dtype=torch.bool, device=reward.device) - # mask = torch.ones_like(reward, dtype=torch.bool, device=reward.device) - # return obs, action, next_obses, reward, mask, done, idxs, weights - - # batch = replay_buffer.sample(batch_size) if self.cfg.balanced_sampling else replay_buffer.sample() - - # obs, action, next_obses, reward, mask, done, idxs, weights = process_batch( - # batch, self.cfg.horizon, num_slices - # ) - - # Sample from demonstration dataset - # if demo_batch_size > 0: - # demo_batch = demo_buffer.sample(demo_batch_size) - # ( - # demo_obs, - # demo_action, - # demo_next_obses, - # demo_reward, - # demo_mask, - # demo_done, - # demo_idxs, - # demo_weights, - # ) = process_batch(demo_batch, self.cfg.horizon, demo_num_slices) - - # if isinstance(obs, dict): - # obs = {k: torch.cat([obs[k], demo_obs[k]]) for k in obs} - # next_obses = {k: torch.cat([next_obses[k], demo_next_obses[k]], dim=1) for k in next_obses} - # else: - # obs = torch.cat([obs, demo_obs]) - # next_obses = torch.cat([next_obses, demo_next_obses], dim=1) - # action = torch.cat([action, demo_action], dim=1) - # reward = torch.cat([reward, demo_reward], dim=1) - # mask = torch.cat([mask, demo_mask], dim=1) - # done = torch.cat([done, demo_done], dim=1) - # idxs = torch.cat([idxs, demo_idxs]) - # weights = torch.cat([weights, demo_weights]) - batch_size = batch["index"].shape[0] # TODO(rcadene): convert tdmpc with (batch size, time/horizon, channels) @@ -534,6 +446,7 @@ class TDMPCPolicy(nn.Module): ) self.optim.step() + # TODO(rcadene): implement PrioritizedSampling by modifying sampler.weights with priorities computed by a criterion # if self.cfg.per: # # Update priorities # priorities = priority_loss.clamp(max=1e4).detach() diff --git a/lerobot/configs/env/aloha.yaml b/lerobot/configs/env/aloha.yaml index 7a8d8b58..6b836795 100644 --- a/lerobot/configs/env/aloha.yaml +++ b/lerobot/configs/env/aloha.yaml @@ -18,7 +18,6 @@ env: from_pixels: True pixels_only: False image_size: [3, 480, 640] - action_repeat: 1 episode_length: 400 fps: ${fps} diff --git a/lerobot/configs/env/pusht.yaml b/lerobot/configs/env/pusht.yaml index a5fbcc25..a7097ffd 100644 --- a/lerobot/configs/env/pusht.yaml +++ b/lerobot/configs/env/pusht.yaml @@ -18,7 +18,6 @@ env: from_pixels: True pixels_only: False image_size: 96 - action_repeat: 1 episode_length: 300 fps: ${fps} diff --git a/lerobot/configs/env/xarm.yaml b/lerobot/configs/env/xarm.yaml index 8b3c72ef..bcba659e 100644 --- a/lerobot/configs/env/xarm.yaml +++ b/lerobot/configs/env/xarm.yaml @@ -17,7 +17,6 @@ env: from_pixels: True pixels_only: False image_size: 84 - # action_repeat: 2 # we can remove if policy has n_action_steps=2 episode_length: 25 fps: ${fps} diff --git a/lerobot/configs/policy/tdmpc.yaml b/lerobot/configs/policy/tdmpc.yaml index 2ebaad9b..4fd2b6bb 100644 --- a/lerobot/configs/policy/tdmpc.yaml +++ b/lerobot/configs/policy/tdmpc.yaml @@ -36,6 +36,7 @@ policy: log_std_max: 2 # learning + batch_size: 256 max_buffer_size: 10000 horizon: 5 reward_coef: 0.5 diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 512bb451..394a5d15 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -32,6 +32,7 @@ import json import logging import threading import time +from copy import deepcopy from datetime import datetime as dt from pathlib import Path @@ -57,14 +58,14 @@ def write_video(video_path, stacked_frames, fps): def eval_policy( env: gym.vector.VectorEnv, policy, - save_video: bool = False, + max_episodes_rendered: int = 0, video_dir: Path = None, # TODO(rcadene): make it possible to overwrite fps? we should use env.fps - fps: int = 15, - return_first_video: bool = False, transform: callable = None, seed=None, ): + fps = env.unwrapped.metadata["render_fps"] + if policy is not None: policy.eval() device = "cpu" if policy is None else next(policy.parameters()).device @@ -83,14 +84,11 @@ def eval_policy( # needed as I'm currently taking a ceil. ep_frames = [] - def maybe_render_frame(env): - if save_video: # noqa: B023 - if return_first_video: - visu = env.envs[0].render() - visu = visu[None, ...] # add batch dim - else: - visu = np.stack([env.render() for env in env.envs]) - ep_frames.append(visu) # noqa: B023 + def render_frame(env): + # noqa: B023 + eps_rendered = min(max_episodes_rendered, len(env.envs)) + visu = np.stack([env.envs[i].render() for i in range(eps_rendered)]) + ep_frames.append(visu) # noqa: B023 for _ in range(num_episodes): seeds.append("TODO") @@ -104,8 +102,14 @@ def eval_policy( # reset the environment observation, info = env.reset(seed=seed) - maybe_render_frame(env) + if max_episodes_rendered > 0: + render_frame(env) + observations = [] + actions = [] + # episode + # frame_id + # timestamp rewards = [] successes = [] dones = [] @@ -113,8 +117,13 @@ def eval_policy( done = torch.tensor([False for _ in env.envs]) step = 0 while not done.all(): + # format from env keys to lerobot keys + observation = preprocess_observation(observation) + observations.append(deepcopy(observation)) + # apply transform to normalize the observations - observation = preprocess_observation(observation, transform) + for key in observation: + observation[key] = torch.stack([transform({key: item})[key] for item in observation[key]]) # send observation to device/gpu observation = {key: observation[key].to(device, non_blocking=True) for key in observation} @@ -128,9 +137,11 @@ def eval_policy( # apply the next observation, reward, terminated, truncated, info = env.step(action) - maybe_render_frame(env) + if max_episodes_rendered > 0: + render_frame(env) # TODO(rcadene): implement a wrapper over env to return torch tensors in float32 (and cuda?) + action = torch.from_numpy(action) reward = torch.from_numpy(reward) terminated = torch.from_numpy(terminated) truncated = torch.from_numpy(truncated) @@ -147,12 +158,24 @@ def eval_policy( success = [False for _ in env.envs] success = torch.tensor(success) + actions.append(action) rewards.append(reward) dones.append(done) successes.append(success) step += 1 + env.close() + + # add the last observation when the env is done + observation = preprocess_observation(observation) + observations.append(deepcopy(observation)) + + new_obses = {} + for key in observations[0].keys(): # noqa: SIM118 + new_obses[key] = torch.stack([obs[key] for obs in observations], dim=1) + observations = new_obses + actions = torch.stack(actions, dim=1) rewards = torch.stack(rewards, dim=1) successes = torch.stack(successes, dim=1) dones = torch.stack(dones, dim=1) @@ -172,29 +195,61 @@ def eval_policy( max_rewards.extend(batch_max_reward.tolist()) all_successes.extend(batch_success.tolist()) - env.close() + # similar logic is implemented in dataset preprocessing + ep_dicts = [] + num_episodes = dones.shape[0] + total_frames = 0 + idx0 = idx1 = 0 + data_ids_per_episode = {} + for ep_id in range(num_episodes): + num_frames = done_indices[ep_id].item() + 1 + # TODO(rcadene): We need to add a missing last frame which is the observation + # of a done state. it is critical to have this frame for tdmpc to predict a "done observation/state" + ep_dict = { + "action": actions[ep_id, :num_frames], + "episode": torch.tensor([ep_id] * num_frames), + "frame_id": torch.arange(0, num_frames, 1), + "timestamp": torch.arange(0, num_frames, 1) / fps, + "next.done": dones[ep_id, :num_frames], + "next.reward": rewards[ep_id, :num_frames].type(torch.float32), + } + for key in observations: + ep_dict[key] = observations[key][ep_id, :num_frames] + ep_dicts.append(ep_dict) - if save_video or return_first_video: + total_frames += num_frames + idx1 += num_frames + + data_ids_per_episode[ep_id] = torch.arange(idx0, idx1, 1) + + idx0 = idx1 + + # similar logic is implemented in dataset preprocessing + data_dict = {} + keys = ep_dicts[0].keys() + for key in keys: + data_dict[key] = torch.cat([x[key] for x in ep_dicts]) + data_dict["index"] = torch.arange(0, total_frames, 1) + + if max_episodes_rendered > 0: batch_stacked_frames = np.stack(ep_frames, 1) # (b, t, *) - if save_video: - for stacked_frames, done_index in zip( - batch_stacked_frames, done_indices.flatten().tolist(), strict=False - ): - if episode_counter >= num_episodes: - continue - video_dir.mkdir(parents=True, exist_ok=True) - video_path = video_dir / f"eval_episode_{episode_counter}.mp4" - thread = threading.Thread( - target=write_video, - args=(str(video_path), stacked_frames[:done_index], fps), - ) - thread.start() - threads.append(thread) - episode_counter += 1 + for stacked_frames, done_index in zip( + batch_stacked_frames, done_indices.flatten().tolist(), strict=False + ): + if episode_counter >= num_episodes: + continue + video_dir.mkdir(parents=True, exist_ok=True) + video_path = video_dir / f"eval_episode_{episode_counter}.mp4" + thread = threading.Thread( + target=write_video, + args=(str(video_path), stacked_frames[:done_index], fps), + ) + thread.start() + threads.append(thread) + episode_counter += 1 - if return_first_video: - first_video = batch_stacked_frames[0].transpose(0, 3, 1, 2) + videos = batch_stacked_frames.transpose(0, 3, 1, 2) for thread in threads: thread.join() @@ -225,9 +280,13 @@ def eval_policy( "eval_s": time.time() - start, "eval_ep_s": (time.time() - start) / num_episodes, }, + "episodes": { + "data_dict": data_dict, + "data_ids_per_episode": data_ids_per_episode, + }, } - if return_first_video: - return info, first_video + if max_episodes_rendered > 0: + info["videos"] = videos return info @@ -259,7 +318,7 @@ def eval(cfg: dict, out_dir=None, stats_path=None): info = eval_policy( env, policy=policy, - save_video=True, + max_episodes_rendered=10, video_dir=Path(out_dir) / "eval", fps=cfg.env.fps, # TODO(rcadene): what should we do with the transform? diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index cca26902..6dfbd12b 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -1,8 +1,8 @@ import logging +from copy import deepcopy from pathlib import Path import hydra -import numpy as np import torch from lerobot.common.datasets.factory import make_dataset @@ -110,6 +110,64 @@ def log_eval_info(logger, info, step, cfg, dataset, is_offline): logger.log_dict(info, step, mode="eval") +def calculate_online_sample_weight(n_off: int, n_on: int, pc_on: float): + """ + Calculate the sampling weight to be assigned to samples so that a specified percentage of the batch comes from online dataset (on average). + + Parameters: + - n_off (int): Number of offline samples, each with a sampling weight of 1. + - n_on (int): Number of online samples. + - pc_on (float): Desired percentage of online samples in decimal form (e.g., 50% as 0.5). + + The total weight of offline samples is n_off * 1.0. + The total weight of offline samples is n_on * w. + The total combined weight of all samples is n_off + n_on * w. + The fraction of the weight that is online is n_on * w / (n_off + n_on * w). + We want this fraction to equal pc_on, so we set up the equation n_on * w / (n_off + n_on * w) = pc_on. + The solution is w = - (n_off * pc_on) / (n_on * (pc_on - 1)) + """ + assert 0.0 <= pc_on <= 1.0 + return -(n_off * pc_on) / (n_on * (pc_on - 1)) + + +def add_episodes_inplace(episodes, online_dataset, concat_dataset, sampler, pc_online_samples): + data_dict = episodes["data_dict"] + data_ids_per_episode = episodes["data_ids_per_episode"] + + if len(online_dataset) == 0: + # initialize online dataset + online_dataset.data_dict = data_dict + online_dataset.data_ids_per_episode = data_ids_per_episode + else: + # find episode index and data frame indices according to previous episode in online_dataset + start_episode = max(online_dataset.data_ids_per_episode.keys()) + 1 + start_index = online_dataset.data_dict["index"][-1].item() + 1 + data_dict["episode"] += start_episode + data_dict["index"] += start_index + + # extend online dataset + for key in data_dict: + # TODO(rcadene): avoid reallocating memory at every step by preallocating memory or changing our data structure + online_dataset.data_dict[key] = torch.cat([online_dataset.data_dict[key], data_dict[key]]) + for ep_id in data_ids_per_episode: + online_dataset.data_ids_per_episode[ep_id + start_episode] = ( + data_ids_per_episode[ep_id] + start_index + ) + + # update the concatenated dataset length used during sampling + concat_dataset.cumulative_sizes = concat_dataset.cumsum(concat_dataset.datasets) + + # update the sampling weights for each frame so that online frames get sampled a certain percentage of times + len_online = len(online_dataset) + len_offline = len(concat_dataset) - len_online + weight_offline = 1.0 + weight_online = calculate_online_sample_weight(len_offline, len_online, pc_online_samples) + sampler.weights = torch.tensor([weight_offline] * len_offline + [weight_online] * len(online_dataset)) + + # update the total number of samples used during sampling + sampler.num_samples = len(concat_dataset) + + def train(cfg: dict, out_dir=None, job_name=None): if out_dir is None: raise NotImplementedError() @@ -128,26 +186,7 @@ def train(cfg: dict, out_dir=None, job_name=None): set_global_seed(cfg.seed) logging.info("make_dataset") - dataset = make_dataset(cfg) - - # TODO(rcadene): move balanced_sampling, per_alpha, per_beta outside policy - # if cfg.policy.balanced_sampling: - # logging.info("make online_buffer") - # num_traj_per_batch = cfg.policy.batch_size - - # online_sampler = PrioritizedSliceSampler( - # max_capacity=100_000, - # alpha=cfg.policy.per_alpha, - # beta=cfg.policy.per_beta, - # num_slices=num_traj_per_batch, - # strict_length=True, - # ) - - # online_buffer = TensorDictReplayBuffer( - # storage=LazyMemmapStorage(100_000), - # sampler=online_sampler, - # transform=dataset.transform, - # ) + offline_dataset = make_dataset(cfg) logging.info("make_env") env = make_env(cfg, num_parallel_envs=cfg.eval_episodes) @@ -165,9 +204,8 @@ def train(cfg: dict, out_dir=None, job_name=None): logging.info(f"{cfg.env.task=}") logging.info(f"{cfg.offline_steps=} ({format_big_number(cfg.offline_steps)})") logging.info(f"{cfg.online_steps=}") - logging.info(f"{cfg.env.action_repeat=}") - logging.info(f"{dataset.num_samples=} ({format_big_number(dataset.num_samples)})") - logging.info(f"{dataset.num_episodes=}") + logging.info(f"{offline_dataset.num_samples=} ({format_big_number(offline_dataset.num_samples)})") + logging.info(f"{offline_dataset.num_episodes=}") logging.info(f"{num_learnable_params=} ({format_big_number(num_learnable_params)})") logging.info(f"{num_total_params=} ({format_big_number(num_total_params)})") @@ -175,18 +213,17 @@ def train(cfg: dict, out_dir=None, job_name=None): def _maybe_eval_and_maybe_save(step): if step % cfg.eval_freq == 0: logging.info(f"Eval policy at step {step}") - eval_info, first_video = eval_policy( + eval_info = eval_policy( env, policy, - return_first_video=True, video_dir=Path(out_dir) / "eval", - save_video=True, - transform=dataset.transform, + max_episodes_rendered=4, + transform=offline_dataset.transform, seed=cfg.seed, ) - log_eval_info(logger, eval_info["aggregated"], step, cfg, dataset, is_offline) + log_eval_info(logger, eval_info["aggregated"], step, cfg, offline_dataset, is_offline) if cfg.wandb.enable: - logger.log_video(first_video, step, mode="eval") + logger.log_video(eval_info["videos"][0], step, mode="eval") logging.info("Resume training") if cfg.save_model and step % cfg.save_freq == 0: @@ -194,11 +231,9 @@ def train(cfg: dict, out_dir=None, job_name=None): logger.save_model(policy, identifier=step) logging.info("Resume training") - step = 0 # number of policy update (forward + backward + optim) - - is_offline = True + # create dataloader for offline training dataloader = torch.utils.data.DataLoader( - dataset, + offline_dataset, num_workers=4, batch_size=cfg.policy.batch_size, shuffle=True, @@ -206,6 +241,9 @@ def train(cfg: dict, out_dir=None, job_name=None): drop_last=True, ) dl_iter = cycle(dataloader) + + step = 0 # number of policy update (forward + backward + optim) + is_offline = True for offline_step in range(cfg.offline_steps): if offline_step == 0: logging.info("Start offline training on a fixed dataset") @@ -219,7 +257,7 @@ def train(cfg: dict, out_dir=None, job_name=None): # TODO(rcadene): is it ok if step_t=0 = 0 and not 1 as previously done? if step % cfg.log_freq == 0: - log_train_info(logger, train_info, step, cfg, dataset, is_offline) + log_train_info(logger, train_info, step, cfg, offline_dataset, is_offline) # Note: _maybe_eval_and_maybe_save happens **after** the `step`th training update has completed, so we pass in # step + 1. @@ -227,61 +265,60 @@ def train(cfg: dict, out_dir=None, job_name=None): step += 1 - raise NotImplementedError() + # create an env dedicated to online episodes collection from policy rollout + rollout_env = make_env(cfg, num_parallel_envs=1) + + # create an empty online dataset similar to offline dataset + online_dataset = deepcopy(offline_dataset) + online_dataset.data_dict = {} + online_dataset.data_ids_per_episode = {} + + # create dataloader for online training + concat_dataset = torch.utils.data.ConcatDataset([offline_dataset, online_dataset]) + weights = [1.0] * len(concat_dataset) + sampler = torch.utils.data.WeightedRandomSampler( + weights, num_samples=len(concat_dataset), replacement=True + ) + dataloader = torch.utils.data.DataLoader( + concat_dataset, + num_workers=4, + batch_size=cfg.policy.batch_size, + sampler=sampler, + pin_memory=cfg.device != "cpu", + drop_last=True, + ) + dl_iter = cycle(dataloader) - demo_buffer = dataset if cfg.policy.balanced_sampling else None online_step = 0 is_offline = False for env_step in range(cfg.online_steps): if env_step == 0: logging.info("Start online training by interacting with environment") - # TODO: add configurable number of rollout? (default=1) + with torch.no_grad(): - rollout = env.rollout( - max_steps=cfg.env.episode_length, - policy=policy, - auto_cast_to_device=True, + eval_info = eval_policy( + rollout_env, + policy, + transform=offline_dataset.transform, + seed=cfg.seed, ) - assert ( - len(rollout.batch_size) == 2 - ), "2 dimensions expected: number of env in parallel x max number of steps during rollout" - - num_parallel_env = rollout.batch_size[0] - if num_parallel_env != 1: - # TODO(rcadene): when num_parallel_env > 1, rollout["episode"] needs to be properly set and we need to add tests - raise NotImplementedError() - - num_max_steps = rollout.batch_size[1] - assert num_max_steps <= cfg.env.episode_length - - # reshape to have a list of steps to insert into online_buffer - rollout = rollout.reshape(num_parallel_env * num_max_steps) - - # set same episode index for all time steps contained in this rollout - rollout["episode"] = torch.tensor([env_step] * len(rollout), dtype=torch.int) - # online_buffer.extend(rollout) - - ep_sum_reward = rollout["next", "reward"].sum() - ep_max_reward = rollout["next", "reward"].max() - ep_success = rollout["next", "success"].any() - rollout_info = { - "avg_sum_reward": np.nanmean(ep_sum_reward), - "avg_max_reward": np.nanmean(ep_max_reward), - "pc_success": np.nanmean(ep_success) * 100, - "env_step": env_step, - "ep_length": len(rollout), - } + online_pc_sampling = cfg.get("demo_schedule", 0.5) + add_episodes_inplace( + eval_info["episodes"], online_dataset, concat_dataset, sampler, online_pc_sampling + ) for _ in range(cfg.policy.utd): - train_info = policy.update( - # online_buffer, - step, - demo_buffer=demo_buffer, - ) + policy.train() + batch = next(dl_iter) + + for key in batch: + batch[key] = batch[key].to(cfg.device, non_blocking=True) + + train_info = policy(batch, step) + if step % cfg.log_freq == 0: - train_info.update(rollout_info) - log_train_info(logger, train_info, step, cfg, dataset, is_offline) + log_train_info(logger, train_info, step, cfg, online_dataset, is_offline) # Note: _maybe_eval_and_maybe_save happens **after** the `step`th training update has completed, so we pass # in step + 1. From 6082a7bc7303d86bd6e5ed49def1e039fbfaf988 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 13:06:48 +0000 Subject: [PATCH 02/31] Enable test_available.py --- lerobot/__init__.py | 21 +++++------ tests/test_available.py | 83 ++++++++++++++++++----------------------- 2 files changed, 45 insertions(+), 59 deletions(-) diff --git a/lerobot/__init__.py b/lerobot/__init__.py index 4673aab0..8ab95df8 100644 --- a/lerobot/__init__.py +++ b/lerobot/__init__.py @@ -12,14 +12,11 @@ Example: print(lerobot.available_policies) ``` -Note: - When implementing a concrete class (e.g. `AlohaDataset`, `PushtEnv`, `DiffusionPolicy`), you need to: - 1. set the required class attributes: - - for classes inheriting from `AbstractDataset`: `available_datasets` - - for classes inheriting from `AbstractEnv`: `name`, `available_tasks` - - for classes inheriting from `AbstractPolicy`: `name` - 2. update variables in `lerobot/__init__.py` (e.g. `available_envs`, `available_datasets_per_envs`, `available_policies`) - 3. update variables in `tests/test_available.py` by importing your new class +When implementing a new dataset (e.g. `AlohaDataset`), policy (e.g. `DiffusionPolicy`), or environment, follow these steps: +- Set the required class attributes: `available_datasets`. +- Set the required class attributes: `name`. +- Update variables in `lerobot/__init__.py` (e.g. `available_envs`, `available_datasets_per_envs`, `available_policies`) +- Update variables in `tests/test_available.py` by importing your new class """ from lerobot.__version__ import __version__ # noqa: F401 @@ -32,11 +29,11 @@ available_envs = [ available_tasks_per_env = { "aloha": [ - "sim_insertion", - "sim_transfer_cube", + "AlohaInsertion-v0", + "AlohaTransferCube-v0", ], - "pusht": ["pusht"], - "xarm": ["lift"], + "pusht": ["PushT-v0"], + "xarm": ["XarmLift-v0"], } available_datasets_per_env = { diff --git a/tests/test_available.py b/tests/test_available.py index 8df2c945..be74a42a 100644 --- a/tests/test_available.py +++ b/tests/test_available.py @@ -1,64 +1,53 @@ """ This test verifies that all environments, datasets, policies listed in `lerobot/__init__.py` can be sucessfully -imported and that their class attributes (eg. `available_datasets`, `name`, `available_tasks`) corresponds. +imported and that their class attributes (eg. `available_datasets`, `name`, `available_tasks`) are valid. -Note: - When implementing a concrete class (e.g. `AlohaDataset`, `PushtEnv`, `DiffusionPolicy`), you need to: - 1. set the required class attributes: - - for classes inheriting from `AbstractDataset`: `available_datasets` - - for classes inheriting from `AbstractEnv`: `name`, `available_tasks` - - for classes inheriting from `AbstractPolicy`: `name` - 2. update variables in `lerobot/__init__.py` (e.g. `available_envs`, `available_datasets_per_envs`, `available_policies`) - 3. update variables in `tests/test_available.py` by importing your new class +When implementing a new dataset (e.g. `AlohaDataset`), policy (e.g. `DiffusionPolicy`), or environment, follow these steps: +- Set the required class attributes: `available_datasets`. +- Set the required class attributes: `name`. +- Update variables in `lerobot/__init__.py` (e.g. `available_envs`, `available_datasets_per_envs`, `available_policies`) +- Update variables in `tests/test_available.py` by importing your new class """ +import importlib import pytest import lerobot +import gymnasium as gym -# from lerobot.common.envs.aloha.env import AlohaEnv -# from gym_pusht.envs import PushtEnv -# from gym_xarm.envs import SimxarmEnv +from lerobot.common.datasets.xarm import XarmDataset +from lerobot.common.datasets.aloha import AlohaDataset +from lerobot.common.datasets.pusht import PushtDataset -# from lerobot.common.datasets.xarm import SimxarmDataset -# from lerobot.common.datasets.aloha import AlohaDataset -# from lerobot.common.datasets.pusht import PushtDataset - -# from lerobot.common.policies.act.policy import ActionChunkingTransformerPolicy -# from lerobot.common.policies.diffusion.policy import DiffusionPolicy -# from lerobot.common.policies.tdmpc.policy import TDMPCPolicy +from lerobot.common.policies.act.policy import ActionChunkingTransformerPolicy +from lerobot.common.policies.diffusion.policy import DiffusionPolicy +from lerobot.common.policies.tdmpc.policy import TDMPCPolicy -# def test_available(): -# pol_classes = [ -# ActionChunkingTransformerPolicy, -# DiffusionPolicy, -# TDMPCPolicy, -# ] +def test_available(): + policy_classes = [ + ActionChunkingTransformerPolicy, + DiffusionPolicy, + TDMPCPolicy, + ] -# env_classes = [ -# AlohaEnv, -# PushtEnv, -# SimxarmEnv, -# ] - -# dat_classes = [ -# AlohaDataset, -# PushtDataset, -# SimxarmDataset, -# ] + dataset_class_per_env = { + "aloha": AlohaDataset, + "pusht": PushtDataset, + "xarm": XarmDataset, + } -# policies = [pol_cls.name for pol_cls in pol_classes] -# assert set(policies) == set(lerobot.available_policies) + policies = [pol_cls.name for pol_cls in policy_classes] + assert set(policies) == set(lerobot.available_policies), policies -# envs = [env_cls.name for env_cls in env_classes] -# assert set(envs) == set(lerobot.available_envs) + for env_name in lerobot.available_envs: + for task_name in lerobot.available_tasks_per_env[env_name]: + package_name = f"gym_{env_name}" + importlib.import_module(package_name) + gym_handle = f"{package_name}/{task_name}" + assert gym_handle in gym.envs.registry.keys(), gym_handle -# tasks_per_env = {env_cls.name: env_cls.available_tasks for env_cls in env_classes} -# for env in envs: -# assert set(tasks_per_env[env]) == set(lerobot.available_tasks_per_env[env]) - -# datasets_per_env = {env_cls.name: dat_cls.available_datasets for env_cls, dat_cls in zip(env_classes, dat_classes)} -# for env in envs: -# assert set(datasets_per_env[env]) == set(lerobot.available_datasets_per_env[env]) + dataset_class = dataset_class_per_env[env_name] + available_datasets = lerobot.available_datasets_per_env[env_name] + assert set(available_datasets) == set(dataset_class.available_datasets), f"{env_name=} {available_datasets=}" From c08003278ed0584f74f0ced9f83b9a9e49a146e1 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 13:45:45 +0000 Subject: [PATCH 03/31] test_examples are passing --- examples/1_visualize_dataset.py | 12 ++-- examples/3_train_policy.py | 31 +++++++--- lerobot/common/datasets/factory.py | 10 ++-- lerobot/scripts/visualize_dataset.py | 88 ++++++++++------------------ 4 files changed, 62 insertions(+), 79 deletions(-) diff --git a/examples/1_visualize_dataset.py b/examples/1_visualize_dataset.py index f52ab76a..a9406d1e 100644 --- a/examples/1_visualize_dataset.py +++ b/examples/1_visualize_dataset.py @@ -1,6 +1,5 @@ import os - -from torchrl.data.replay_buffers import SamplerWithoutReplacement +from pathlib import Path import lerobot from lerobot.common.datasets.aloha import AlohaDataset @@ -9,16 +8,13 @@ from lerobot.scripts.visualize_dataset import render_dataset print(lerobot.available_datasets) # >>> ['aloha_sim_insertion_human', 'aloha_sim_insertion_scripted', 'aloha_sim_transfer_cube_human', 'aloha_sim_transfer_cube_scripted', 'pusht', 'xarm_lift_medium'] -# we use this sampler to sample 1 frame after the other -sampler = SamplerWithoutReplacement(shuffle=False) - -dataset = AlohaDataset("aloha_sim_transfer_cube_human", sampler=sampler, root=os.environ.get("DATA_DIR")) +# TODO(rcadene): remove DATA_DIR +dataset = AlohaDataset("aloha_sim_transfer_cube_human", root=Path(os.environ.get("DATA_DIR"))) video_paths = render_dataset( dataset, out_dir="outputs/visualize_dataset/example", - max_num_samples=300, - fps=50, + max_num_episodes=1, ) print(video_paths) # ['outputs/visualize_dataset/example/episode_0.mp4'] diff --git a/examples/3_train_policy.py b/examples/3_train_policy.py index 6e01a5d5..238f953d 100644 --- a/examples/3_train_policy.py +++ b/examples/3_train_policy.py @@ -9,9 +9,8 @@ from pathlib import Path import torch from omegaconf import OmegaConf -from tqdm import trange -from lerobot.common.datasets.factory import make_offline_buffer +from lerobot.common.datasets.factory import make_dataset from lerobot.common.policies.diffusion.policy import DiffusionPolicy from lerobot.common.utils import init_hydra_config @@ -37,19 +36,33 @@ policy = DiffusionPolicy( cfg_obs_encoder=cfg.obs_encoder, cfg_optimizer=cfg.optimizer, cfg_ema=cfg.ema, - n_action_steps=cfg.n_action_steps, **cfg.policy, ) policy.train() -offline_buffer = make_offline_buffer(cfg) +dataset = make_dataset(cfg) + +# create dataloader for offline training +dataloader = torch.utils.data.DataLoader( + dataset, + num_workers=4, + batch_size=cfg.policy.batch_size, + shuffle=True, + pin_memory=cfg.device != "cpu", + drop_last=True, +) + +for step, batch in enumerate(dataloader): + info = policy(batch, step) + + if step % cfg.log_freq == 0: + num_samples = (step + 1) * cfg.policy.batch_size + loss = info["loss"] + update_s = info["update_s"] + print(f"step:{step} samples:{num_samples} loss:{loss:.3f} update_time:{update_s:.3f}(seconds)") -for offline_step in trange(cfg.offline_steps): - train_info = policy.update(offline_buffer, offline_step) - if offline_step % cfg.log_freq == 0: - print(train_info) # Save the policy, configuration, and normalization stats for later use. policy.save(output_directory / "model.pt") OmegaConf.save(cfg, output_directory / "config.yaml") -torch.save(offline_buffer.transform[-1].stats, output_directory / "stats.pth") +torch.save(dataset.transform.transforms[-1].stats, output_directory / "stats.pth") diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 0dab5d4b..63507cce 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -40,7 +40,8 @@ def make_dataset( if normalize: # TODO(rcadene): make normalization strategy configurable between mean_std, min_max, manual_min_max, # min_max_from_spec - # stats = dataset.compute_or_load_stats() if stats_path is None else torch.load(stats_path) + # TODO(rcadene): remove this and put it in config. Ideally we want to reproduce SOTA results just with mean_std + normalization_mode = "mean_std" if cfg.env.name == "aloha" else "min_max" if cfg.policy.name == "diffusion" and cfg.env.name == "pusht": stats = {} @@ -51,7 +52,7 @@ def make_dataset( stats["action"] = {} stats["action"]["min"] = torch.tensor([12.0, 25.0], dtype=torch.float32) stats["action"]["max"] = torch.tensor([511.0, 511.0], dtype=torch.float32) - else: + elif stats_path is None: # instantiate a one frame dataset with light transform stats_dataset = clsfunc( dataset_id=cfg.dataset_id, @@ -59,9 +60,8 @@ def make_dataset( transform=Prod(in_keys=clsfunc.image_keys, prod=1 / 255.0), ) stats = compute_or_load_stats(stats_dataset) - - # TODO(rcadene): remove this and put it in config. Ideally we want to reproduce SOTA results just with mean_std - normalization_mode = "mean_std" if cfg.env.name == "aloha" else "min_max" + else: + stats = torch.load(stats_path) transforms = v2.Compose( [ diff --git a/lerobot/scripts/visualize_dataset.py b/lerobot/scripts/visualize_dataset.py index 93315e90..ed95b39a 100644 --- a/lerobot/scripts/visualize_dataset.py +++ b/lerobot/scripts/visualize_dataset.py @@ -6,9 +6,6 @@ import einops import hydra import imageio import torch -from torchrl.data.replay_buffers import ( - SamplerWithoutReplacement, -) from lerobot.common.datasets.factory import make_dataset from lerobot.common.logger import log_output_dir @@ -39,19 +36,11 @@ def visualize_dataset(cfg: dict, out_dir=None): init_logging() log_output_dir(out_dir) - # we expect frames of each episode to be stored next to each others sequentially - sampler = SamplerWithoutReplacement( - shuffle=False, - ) - logging.info("make_dataset") dataset = make_dataset( cfg, - overwrite_sampler=sampler, # remove all transformations such as rescale images from [0,255] to [0,1] or normalization normalize=False, - overwrite_batch_size=1, - overwrite_prefetch=12, ) logging.info("Start rendering episodes from offline buffer") @@ -60,64 +49,49 @@ def visualize_dataset(cfg: dict, out_dir=None): logging.info(video_path) -def render_dataset(dataset, out_dir, max_num_samples, fps): +def render_dataset(dataset, out_dir, max_num_episodes): out_dir = Path(out_dir) video_paths = [] threads = [] - frames = {} - current_ep_idx = 0 - logging.info(f"Visualizing episode {current_ep_idx}") - for i in range(max_num_samples): - # TODO(rcadene): make it work with bsize > 1 - ep_td = dataset.sample(1) - ep_idx = ep_td["episode"][FIRST_FRAME].item() - # TODO(rcadene): modify dataset._sampler._sample_list or sampler to randomly sample an episode, but sequentially sample frames - num_frames_left = dataset._sampler._sample_list.numel() - episode_is_done = ep_idx != current_ep_idx + dataloader = torch.utils.data.DataLoader( + dataset, + num_workers=4, + batch_size=1, + shuffle=False, + ) + dl_iter = iter(dataloader) - if episode_is_done: - logging.info(f"Rendering episode {current_ep_idx}") + num_episodes = len(dataset.data_ids_per_episode) + for ep_id in range(min(max_num_episodes, num_episodes)): + logging.info(f"Rendering episode {ep_id}") - for im_key in dataset.image_keys: - if not episode_is_done and num_frames_left > 0 and i < (max_num_samples - 1): + frames = {} + for _ in dataset.data_ids_per_episode[ep_id]: + item = next(dl_iter) + + for im_key in dataset.image_keys: # when first frame of episode, initialize frames dict if im_key not in frames: frames[im_key] = [] # add current frame to list of frames to render - frames[im_key].append(ep_td[im_key]) + frames[im_key].append(item[im_key]) + + out_dir.mkdir(parents=True, exist_ok=True) + for im_key in dataset.image_keys: + if len(dataset.image_keys) > 0: + im_name = im_key.replace("observation.images.", "") + video_path = out_dir / f"episode_{ep_id}_{im_name}.mp4" else: - # When episode has no more frame in its list of observation, - # one frame still remains. It is the result of the last action taken. - # It is stored in `"next"`, so we add it to the list of frames to render. - frames[im_key].append(ep_td["next"][im_key]) + video_path = out_dir / f"episode_{ep_id}.mp4" + video_paths.append(video_path) - out_dir.mkdir(parents=True, exist_ok=True) - if len(dataset.image_keys) > 1: - camera = im_key[-1] - video_path = out_dir / f"episode_{current_ep_idx}_{camera}.mp4" - else: - video_path = out_dir / f"episode_{current_ep_idx}.mp4" - video_paths.append(str(video_path)) - - thread = threading.Thread( - target=cat_and_write_video, - args=(str(video_path), frames[im_key], fps), - ) - thread.start() - threads.append(thread) - - current_ep_idx = ep_idx - - # reset list of frames - del frames[im_key] - - if num_frames_left == 0: - logging.info("Ran out of frames") - break - - if current_ep_idx == NUM_EPISODES_TO_RENDER: - break + thread = threading.Thread( + target=cat_and_write_video, + args=(str(video_path), frames[im_key], dataset.fps), + ) + thread.start() + threads.append(thread) for thread in threads: thread.join() From ec4bf115d0123f7836a5aa92c02e44353947d96c Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 13:55:59 +0000 Subject: [PATCH 04/31] fix example_1 test --- examples/1_visualize_dataset.py | 2 +- tests/test_examples.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/1_visualize_dataset.py b/examples/1_visualize_dataset.py index a9406d1e..bfc2635f 100644 --- a/examples/1_visualize_dataset.py +++ b/examples/1_visualize_dataset.py @@ -17,4 +17,4 @@ video_paths = render_dataset( max_num_episodes=1, ) print(video_paths) -# ['outputs/visualize_dataset/example/episode_0.mp4'] +# ['outputs/visualize_dataset/example/episode_0_top.mp4'] diff --git a/tests/test_examples.py b/tests/test_examples.py index 4263e452..17f6d600 100644 --- a/tests/test_examples.py +++ b/tests/test_examples.py @@ -15,7 +15,7 @@ def test_example_1(): file_contents = file.read() exec(file_contents) - assert Path("outputs/visualize_dataset/example/episode_0.mp4").exists() + assert Path("outputs/visualize_dataset/example/episode_0_top.mp4").exists() def test_examples_3_and_2(): From a18bcb39a7e39cab82f777cc7c27b5244d89a902 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 14:02:11 +0000 Subject: [PATCH 05/31] cfg.env.fps --- lerobot/scripts/eval.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index d684f6b6..b3475167 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -320,7 +320,6 @@ def eval(cfg: dict, out_dir=None, stats_path=None): policy=policy, max_episodes_rendered=10, video_dir=Path(out_dir) / "eval", - fps=cfg.env.fps, # TODO(rcadene): what should we do with the transform? transform=transform, seed=cfg.seed, From 48ec479660510ec9db0ee6081b796bdcd631785e Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 14:26:30 +0000 Subject: [PATCH 06/31] fix end-to-end aloha --- lerobot/scripts/eval.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index b3475167..fa7e1096 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -249,7 +249,7 @@ def eval_policy( threads.append(thread) episode_counter += 1 - videos = batch_stacked_frames.transpose(0, 3, 1, 2) + videos = einops.rearrange(batch_stacked_frames, "b t h w c -> b t c h w") for thread in threads: thread.join() @@ -328,6 +328,9 @@ def eval(cfg: dict, out_dir=None, stats_path=None): # Save info with open(Path(out_dir) / "eval_info.json", "w") as f: + # remove pytorch tensors which are not serializable to save the evaluation results only + del info["episodes"] + del info["videos"] json.dump(info, f, indent=2) logging.info("End of eval") From 79542ecd136de90f3b7ac28ec4a08e7cd0ce97a5 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 14:44:04 +0000 Subject: [PATCH 07/31] eval_episodes=1 env.episode_length=8 --- .github/workflows/test.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index afdcc41f..91319852 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -142,6 +142,7 @@ jobs: wandb.enable=False \ offline_steps=2 \ online_steps=0 \ + eval_episodes=1 \ device=cpu \ save_model=true \ save_freq=2 \ @@ -179,6 +180,7 @@ jobs: wandb.enable=False \ offline_steps=2 \ online_steps=0 \ + eval_episodes=1 \ device=cpu \ save_model=true \ save_freq=2 \ @@ -202,6 +204,7 @@ jobs: policy=diffusion \ env=pusht \ eval_episodes=1 \ + env.episode_length=8 \ device=cpu - name: Test train TDMPC on Simxarm end-to-end @@ -213,6 +216,7 @@ jobs: wandb.enable=False \ offline_steps=1 \ online_steps=1 \ + eval_episodes=1 \ device=cpu \ save_model=true \ save_freq=2 \ From 693f620df04e6a8523f88b323e1dff9881a1a672 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 14:59:54 +0000 Subject: [PATCH 08/31] drop_last=False --- lerobot/scripts/train.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index 67e451d4..03506f2a 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -236,7 +236,7 @@ def train(cfg: dict, out_dir=None, job_name=None): batch_size=cfg.policy.batch_size, shuffle=True, pin_memory=cfg.device != "cpu", - drop_last=True, + drop_last=False, ) dl_iter = cycle(dataloader) @@ -283,7 +283,7 @@ def train(cfg: dict, out_dir=None, job_name=None): batch_size=cfg.policy.batch_size, sampler=sampler, pin_memory=cfg.device != "cpu", - drop_last=True, + drop_last=False, ) dl_iter = cycle(dataloader) From 2186429fa8fce1ec5ba1b60a9334bc33eb259d42 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 15:00:54 +0000 Subject: [PATCH 09/31] policy.batch_size=2 --- .github/workflows/test.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 91319852..8d0b6851 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -184,6 +184,7 @@ jobs: device=cpu \ save_model=true \ save_freq=2 \ + policy.batch_size=2 \ hydra.run.dir=tests/outputs/diffusion/ - name: Test eval Diffusion on PushT end-to-end @@ -220,6 +221,7 @@ jobs: device=cpu \ save_model=true \ save_freq=2 \ + policy.batch_size=2 \ hydra.run.dir=tests/outputs/tdmpc/ - name: Test eval TDMPC on Simxarm end-to-end From 8866b22db18492dc117c525a4b7d52963f3debfa Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 15:09:04 +0000 Subject: [PATCH 10/31] remove policy is None eval end-to-end tests --- .github/workflows/test.yml | 32 -------------------------------- lerobot/scripts/eval.py | 8 ++++---- 2 files changed, 4 insertions(+), 36 deletions(-) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 8d0b6851..b3411e11 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -160,17 +160,6 @@ jobs: device=cpu \ policy.pretrained_model_path=tests/outputs/act/models/2.pt - # TODO(aliberts): This takes ~2mn to run, needs to be improved - # - name: Test eval ACT on ALOHA end-to-end (policy is None) - # run: | - # source .venv/bin/activate - # python lerobot/scripts/eval.py \ - # --config lerobot/configs/default.yaml \ - # policy=act \ - # env=aloha \ - # eval_episodes=1 \ - # device=cpu - - name: Test train Diffusion on PushT end-to-end run: | source .venv/bin/activate @@ -197,17 +186,6 @@ jobs: device=cpu \ policy.pretrained_model_path=tests/outputs/diffusion/models/2.pt - - name: Test eval Diffusion on PushT end-to-end (policy is None) - run: | - source .venv/bin/activate - python lerobot/scripts/eval.py \ - --config lerobot/configs/default.yaml \ - policy=diffusion \ - env=pusht \ - eval_episodes=1 \ - env.episode_length=8 \ - device=cpu - - name: Test train TDMPC on Simxarm end-to-end run: | source .venv/bin/activate @@ -233,13 +211,3 @@ jobs: env.episode_length=8 \ device=cpu \ policy.pretrained_model_path=tests/outputs/tdmpc/models/2.pt - - - name: Test eval TDPMC on Simxarm end-to-end (policy is None) - run: | - source .venv/bin/activate - python lerobot/scripts/eval.py \ - --config lerobot/configs/default.yaml \ - policy=tdmpc \ - env=xarm \ - eval_episodes=1 \ - device=cpu diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index fa7e1096..0e4f7bb3 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -57,7 +57,7 @@ def write_video(video_path, stacked_frames, fps): def eval_policy( env: gym.vector.VectorEnv, - policy, + policy: torch.nn.Module, max_episodes_rendered: int = 0, video_dir: Path = None, # TODO(rcadene): make it possible to overwrite fps? we should use env.fps @@ -312,12 +312,12 @@ def eval(cfg: dict, out_dir=None, stats_path=None): logging.info("Making environment.") env = make_env(cfg, num_parallel_envs=cfg.eval_episodes) - # when policy is None, rollout a random policy - policy = make_policy(cfg) if cfg.policy.pretrained_model_path else None + logging.info("Making policy.") + policy = make_policy(cfg) info = eval_policy( env, - policy=policy, + policy, max_episodes_rendered=10, video_dir=Path(out_dir) / "eval", # TODO(rcadene): what should we do with the transform? From e8622154f8ea9f6a2a32e2083f8271e1283abd6b Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 15:56:18 +0000 Subject: [PATCH 11/31] Replace import gym_pusht in pusht dataset by dynamic import --- lerobot/common/datasets/pusht.py | 80 ++++++-------------------------- 1 file changed, 13 insertions(+), 67 deletions(-) diff --git a/lerobot/common/datasets/pusht.py b/lerobot/common/datasets/pusht.py index 068b154e..0e39a92d 100644 --- a/lerobot/common/datasets/pusht.py +++ b/lerobot/common/datasets/pusht.py @@ -2,11 +2,8 @@ from pathlib import Path import einops import numpy as np -import pygame -import pymunk import torch import tqdm -from gym_pusht.envs.pusht import pymunk_to_shapely from lerobot.common.datasets.utils import download_and_extract_zip, load_data_with_delta_timestamps from lerobot.common.policies.diffusion.replay_buffer import ReplayBuffer as DiffusionPolicyReplayBuffer @@ -18,64 +15,6 @@ PUSHT_URL = "https://diffusion-policy.cs.columbia.edu/data/training/pusht.zip" PUSHT_ZARR = Path("pusht/pusht_cchi_v7_replay.zarr") -def get_goal_pose_body(pose): - mass = 1 - inertia = pymunk.moment_for_box(mass, (50, 100)) - body = pymunk.Body(mass, inertia) - # preserving the legacy assignment order for compatibility - # the order here doesn't matter somehow, maybe because CoM is aligned with body origin - body.position = pose[:2].tolist() - body.angle = pose[2] - return body - - -def add_segment(space, a, b, radius): - shape = pymunk.Segment(space.static_body, a, b, radius) - shape.color = pygame.Color("LightGray") # https://htmlcolorcodes.com/color-names - return shape - - -def add_tee( - space, - position, - angle, - scale=30, - color="LightSlateGray", - mask=None, -): - if mask is None: - mask = pymunk.ShapeFilter.ALL_MASKS() - mass = 1 - length = 4 - vertices1 = [ - (-length * scale / 2, scale), - (length * scale / 2, scale), - (length * scale / 2, 0), - (-length * scale / 2, 0), - ] - inertia1 = pymunk.moment_for_poly(mass, vertices=vertices1) - vertices2 = [ - (-scale / 2, scale), - (-scale / 2, length * scale), - (scale / 2, length * scale), - (scale / 2, scale), - ] - inertia2 = pymunk.moment_for_poly(mass, vertices=vertices1) - body = pymunk.Body(mass, inertia1 + inertia2) - shape1 = pymunk.Poly(body, vertices1) - shape2 = pymunk.Poly(body, vertices2) - shape1.color = pygame.Color(color) - shape2.color = pygame.Color(color) - shape1.filter = pymunk.ShapeFilter(mask=mask) - shape2.filter = pymunk.ShapeFilter(mask=mask) - body.center_of_gravity = (shape1.center_of_gravity + shape2.center_of_gravity) / 2 - body.position = position - body.angle = angle - body.friction = 1 - space.add(body, shape1, shape2) - return body - - class PushtDataset(torch.utils.data.Dataset): """ @@ -156,6 +95,13 @@ class PushtDataset(torch.utils.data.Dataset): return item def _download_and_preproc_obsolete(self): + try: + import pymunk + from gym_pusht.envs.pusht import PushTEnv, pymunk_to_shapely + except ModuleNotFoundError as e: + print("`gym_pusht` is not installed. Please install it with `pip install 'lerobot[gym_pusht]'`") + raise e + assert self.root is not None raw_dir = self.root / f"{self.dataset_id}_raw" zarr_path = (raw_dir / PUSHT_ZARR).resolve() @@ -180,7 +126,7 @@ class PushtDataset(torch.utils.data.Dataset): # TODO: verify that goal pose is expected to be fixed goal_pos_angle = np.array([256, 256, np.pi / 4]) # x, y, theta (in radians) - goal_body = get_goal_pose_body(goal_pos_angle) + goal_body = PushTEnv.get_goal_pose_body(goal_pos_angle) imgs = torch.from_numpy(dataset_dict["img"]) imgs = einops.rearrange(imgs, "b h w c -> b c h w") @@ -215,14 +161,14 @@ class PushtDataset(torch.utils.data.Dataset): # Add walls. walls = [ - add_segment(space, (5, 506), (5, 5), 2), - add_segment(space, (5, 5), (506, 5), 2), - add_segment(space, (506, 5), (506, 506), 2), - add_segment(space, (5, 506), (506, 506), 2), + PushTEnv.add_segment(space, (5, 506), (5, 5), 2), + PushTEnv.add_segment(space, (5, 5), (506, 5), 2), + PushTEnv.add_segment(space, (506, 5), (506, 506), 2), + PushTEnv.add_segment(space, (5, 506), (506, 506), 2), ] space.add(*walls) - block_body = add_tee(space, block_pos[i].tolist(), block_angle[i].item()) + block_body = PushTEnv.add_tee(space, block_pos[i].tolist(), block_angle[i].item()) goal_geom = pymunk_to_shapely(goal_body, block_body.shapes) block_geom = pymunk_to_shapely(block_body, block_body.shapes) intersection_area = goal_geom.intersection(block_geom).area From daecc3b64ce05d8b50db97cd4c9a5c2770e14755 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 15:58:10 +0000 Subject: [PATCH 12/31] Remove sbatch*.sh --- .gitignore | 3 +++ sbatch.sh | 25 ------------------------- sbatch_hopper.sh | 17 ----------------- 3 files changed, 3 insertions(+), 42 deletions(-) delete mode 100644 sbatch.sh delete mode 100644 sbatch_hopper.sh diff --git a/.gitignore b/.gitignore index ad9892d4..3132aba0 100644 --- a/.gitignore +++ b/.gitignore @@ -11,6 +11,9 @@ rl nautilus/*.yaml *.key +# Slurm +sbatch*.sh + # Byte-compiled / optimized / DLL files __pycache__/ *.py[cod] diff --git a/sbatch.sh b/sbatch.sh deleted file mode 100644 index c08f7055..00000000 --- a/sbatch.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/bin/bash -#SBATCH --nodes=1 # total number of nodes (N to be defined) -#SBATCH --ntasks-per-node=1 # number of tasks per node (here 8 tasks, or 1 task per GPU) -#SBATCH --gres=gpu:1 # number of GPUs reserved per node (here 8, or all the GPUs) -#SBATCH --cpus-per-task=8 # number of cores per task (8x8 = 64 cores, or all the cores) -#SBATCH --time=2-00:00:00 -#SBATCH --output=/home/rcadene/slurm/%j.out -#SBATCH --error=/home/rcadene/slurm/%j.err -#SBATCH --qos=low -#SBATCH --mail-user=re.cadene@gmail.com -#SBATCH --mail-type=ALL - -CMD=$@ -echo "command: $CMD" - -apptainer exec --nv \ -~/apptainer/nvidia_cuda:12.2.2-devel-ubuntu22.04.sif $SHELL - -source ~/.bashrc -#conda activate fowm -conda activate lerobot - -export DATA_DIR="data" - -srun $CMD diff --git a/sbatch_hopper.sh b/sbatch_hopper.sh deleted file mode 100644 index cc410048..00000000 --- a/sbatch_hopper.sh +++ /dev/null @@ -1,17 +0,0 @@ -#!/bin/bash -#SBATCH --nodes=1 # total number of nodes (N to be defined) -#SBATCH --ntasks-per-node=1 # number of tasks per node (here 8 tasks, or 1 task per GPU) -#SBATCH --qos=normal # number of GPUs reserved per node (here 8, or all the GPUs) -#SBATCH --partition=hopper-prod -#SBATCH --gres=gpu:1 # number of GPUs reserved per node (here 8, or all the GPUs) -#SBATCH --cpus-per-task=12 # number of cores per task -#SBATCH --mem-per-cpu=11G -#SBATCH --time=12:00:00 -#SBATCH --output=/admin/home/remi_cadene/slurm/%j.out -#SBATCH --error=/admin/home/remi_cadene/slurm/%j.err -#SBATCH --mail-user=remi_cadene@huggingface.co -#SBATCH --mail-type=ALL - -CMD=$@ -echo "command: $CMD" -srun $CMD From 0f0113a7a6b5a59ac92245296f3bbac89d6f7496 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 16:03:39 +0000 Subject: [PATCH 13/31] print_cuda_memory_usage docstring --- README.md | 15 +++++++-------- lerobot/common/utils.py | 1 + 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 51e03d65..6473e1eb 100644 --- a/README.md +++ b/README.md @@ -120,27 +120,26 @@ wandb login You can import our dataset class, download the data from the HuggingFace hub and use our rendering utilities: ```python """ Copy pasted from `examples/1_visualize_dataset.py` """ +import os +from pathlib import Path + import lerobot from lerobot.common.datasets.aloha import AlohaDataset -from torchrl.data.replay_buffers import SamplerWithoutReplacement from lerobot.scripts.visualize_dataset import render_dataset print(lerobot.available_datasets) # >>> ['aloha_sim_insertion_human', 'aloha_sim_insertion_scripted', 'aloha_sim_transfer_cube_human', 'aloha_sim_transfer_cube_scripted', 'pusht', 'xarm_lift_medium'] -# we use this sampler to sample 1 frame after the other -sampler = SamplerWithoutReplacement(shuffle=False) - -dataset = AlohaDataset("aloha_sim_transfer_cube_human", sampler=sampler) +# TODO(rcadene): remove DATA_DIR +dataset = AlohaDataset("aloha_sim_transfer_cube_human", root=Path(os.environ.get("DATA_DIR"))) video_paths = render_dataset( dataset, out_dir="outputs/visualize_dataset/example", - max_num_samples=300, - fps=50, + max_num_episodes=1, ) print(video_paths) -# >>> ['outputs/visualize_dataset/example/episode_0.mp4'] +# ['outputs/visualize_dataset/example/episode_0_top.mp4'] ``` Or you can achieve the same result by executing our script from the command line: diff --git a/lerobot/common/utils.py b/lerobot/common/utils.py index e3e22832..373a3bbc 100644 --- a/lerobot/common/utils.py +++ b/lerobot/common/utils.py @@ -98,6 +98,7 @@ def init_hydra_config(config_path: str, overrides: list[str] | None = None) -> D def print_cuda_memory_usage(): + """Use this function to locate and debug memory leak.""" import gc gc.collect() From 4c3d8b061ed41e5a5e4d172b47e061c6f6386edc Mon Sep 17 00:00:00 2001 From: Remi Date: Wed, 10 Apr 2024 18:07:27 +0200 Subject: [PATCH 14/31] Update lerobot/scripts/eval.py Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- lerobot/scripts/eval.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 0e4f7bb3..8d891115 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -135,7 +135,7 @@ def eval_policy( # apply inverse transform to unnormalize the action action = postprocess_action(action, transform) - # apply the next + # apply the next action observation, reward, terminated, truncated, info = env.step(action) if max_episodes_rendered > 0: render_frame(env) From 9874652c2fb169419306687f1f6e4c4c3e13e1d2 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 17:10:46 +0000 Subject: [PATCH 15/31] enable test_compute_stats enable test_compute_stats --- lerobot/common/datasets/factory.py | 13 ++++- lerobot/common/datasets/utils.py | 26 +++++---- tests/test_datasets.py | 84 +++++++++++++++++++++--------- 3 files changed, 83 insertions(+), 40 deletions(-) diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 63507cce..7e079476 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -1,10 +1,11 @@ +import logging import os from pathlib import Path import torch from torchvision.transforms import v2 -from lerobot.common.datasets.utils import compute_or_load_stats +from lerobot.common.datasets.utils import compute_stats from lerobot.common.transforms import NormalizeTransform, Prod # DATA_DIR specifies to location where datasets are loaded. By default, DATA_DIR is None and @@ -59,7 +60,15 @@ def make_dataset( root=DATA_DIR, transform=Prod(in_keys=clsfunc.image_keys, prod=1 / 255.0), ) - stats = compute_or_load_stats(stats_dataset) + + # load stats if the file exists already or compute stats and save it + precomputed_stats_path = stats_dataset.data_dir / "stats.pth" + if precomputed_stats_path.exists(): + stats = torch.load(precomputed_stats_path) + else: + logging.info(f"compute_stats and save to {precomputed_stats_path}") + stats = compute_stats(stats_dataset) + torch.save(stats, stats_path) else: stats = torch.load(stats_path) diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index 3b4aacfc..cf8caa46 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -1,5 +1,4 @@ import io -import logging import zipfile from copy import deepcopy from math import ceil @@ -103,13 +102,18 @@ def load_data_with_delta_timestamps( return data, is_pad -def compute_or_load_stats(dataset, batch_size=32, max_num_samples=None): - stats_path = dataset.data_dir / "stats.pth" - if stats_path.exists(): - return torch.load(stats_path) +def get_stats_einops_patterns(dataset): + """These einops patterns will be used to aggregate batches and compute statistics.""" + stats_patterns = { + "action": "b c -> c", + "observation.state": "b c -> c", + } + for key in dataset.image_keys: + stats_patterns[key] = "b c h w -> c 1 1" + return stats_patterns - logging.info(f"compute_stats and save to {stats_path}") +def compute_stats(dataset, batch_size=32, max_num_samples=None): if max_num_samples is None: max_num_samples = len(dataset) else: @@ -124,13 +128,8 @@ def compute_or_load_stats(dataset, batch_size=32, max_num_samples=None): drop_last=False, ) - # these einops patterns will be used to aggregate batches and compute statistics - stats_patterns = { - "action": "b c -> c", - "observation.state": "b c -> c", - } - for key in dataset.image_keys: - stats_patterns[key] = "b c h w -> c 1 1" + # get einops patterns to aggregate batches and compute statistics + stats_patterns = get_stats_einops_patterns(dataset) # mean and std will be computed incrementally while max and min will track the running value. mean, std, max, min = {}, {}, {}, {} @@ -201,7 +200,6 @@ def compute_or_load_stats(dataset, batch_size=32, max_num_samples=None): "min": min[key], } - torch.save(stats, stats_path) return stats diff --git a/tests/test_datasets.py b/tests/test_datasets.py index e24d7b4d..9b32ea25 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -1,6 +1,12 @@ +import os +from pathlib import Path +import einops import pytest import torch +from lerobot.common.datasets.utils import compute_stats, get_stats_einops_patterns +from lerobot.common.datasets.xarm import XarmDataset +from lerobot.common.transforms import Prod from lerobot.common.utils import init_hydra_config import logging from lerobot.common.datasets.factory import make_dataset @@ -81,28 +87,58 @@ def test_factory(env_name, dataset_id, policy_name): assert key in item, f"{key}" -# def test_compute_stats(): -# """Check that the statistics are computed correctly according to the stats_patterns property. +def test_compute_stats(): + """Check that the statistics are computed correctly according to the stats_patterns property. -# We compare with taking a straight min, mean, max, std of all the data in one pass (which we can do -# because we are working with a small dataset). -# """ -# cfg = init_hydra_config( -# DEFAULT_CONFIG_PATH, overrides=["env=aloha", "env.task=sim_transfer_cube_human"] -# ) -# dataset = make_dataset(cfg) -# # Get all of the data. -# all_data = dataset.data_dict -# # Note: we set the batch size to be smaller than the whole dataset to make sure we are testing batched -# # computation of the statistics. While doing this, we also make sure it works when we don't divide the -# # dataset into even batches. -# computed_stats = buffer._compute_stats(batch_size=int(len(all_data) * 0.75)) -# for k, pattern in buffer.stats_patterns.items(): -# expected_mean = einops.reduce(all_data[k], pattern, "mean") -# assert torch.allclose(computed_stats[k]["mean"], expected_mean) -# assert torch.allclose( -# computed_stats[k]["std"], -# torch.sqrt(einops.reduce((all_data[k] - expected_mean) ** 2, pattern, "mean")) -# ) -# assert torch.allclose(computed_stats[k]["min"], einops.reduce(all_data[k], pattern, "min")) -# assert torch.allclose(computed_stats[k]["max"], einops.reduce(all_data[k], pattern, "max")) + We compare with taking a straight min, mean, max, std of all the data in one pass (which we can do + because we are working with a small dataset). + """ + DATA_DIR = Path(os.environ["DATA_DIR"]) if "DATA_DIR" in os.environ else None + + # get transform to convert images from uint8 [0,255] to float32 [0,1] + transform = Prod(in_keys=XarmDataset.image_keys, prod=1 / 255.0) + + dataset = XarmDataset( + dataset_id="xarm_lift_medium", + root=DATA_DIR, + transform=transform, + ) + + # Note: we set the batch size to be smaller than the whole dataset to make sure we are testing batched + # computation of the statistics. While doing this, we also make sure it works when we don't divide the + # dataset into even batches. + computed_stats = compute_stats(dataset, batch_size=int(len(dataset) * 0.25)) + + # get einops patterns to aggregate batches and compute statistics + stats_patterns = get_stats_einops_patterns(dataset) + + # get all frames from the dataset in the same dtype and range as during compute_stats + data_dict = transform(dataset.data_dict) + + # compute stats based on all frames from the dataset without any batching + expected_stats = {} + for k, pattern in stats_patterns.items(): + expected_stats[k] = {} + expected_stats[k]["mean"] = einops.reduce(data_dict[k], pattern, "mean") + expected_stats[k]["std"] = torch.sqrt(einops.reduce((data_dict[k] - expected_stats[k]["mean"]) ** 2, pattern, "mean")) + expected_stats[k]["min"] = einops.reduce(data_dict[k], pattern, "min") + expected_stats[k]["max"] = einops.reduce(data_dict[k], pattern, "max") + + # test computed stats match expected stats + for k in stats_patterns: + assert torch.allclose(computed_stats[k]["mean"], expected_stats[k]["mean"]) + assert torch.allclose(computed_stats[k]["std"], expected_stats[k]["std"]) + assert torch.allclose(computed_stats[k]["min"], expected_stats[k]["min"]) + assert torch.allclose(computed_stats[k]["max"], expected_stats[k]["max"]) + + # TODO(rcadene): check that the stats used for training are correct too + # # load stats that are expected to match the ones returned by computed_stats + # assert (dataset.data_dir / "stats.pth").exists() + # loaded_stats = torch.load(dataset.data_dir / "stats.pth") + + # # test loaded stats match expected stats + # for k in stats_patterns: + # assert torch.allclose(loaded_stats[k]["mean"], expected_stats[k]["mean"]) + # assert torch.allclose(loaded_stats[k]["std"], expected_stats[k]["std"]) + # assert torch.allclose(loaded_stats[k]["min"], expected_stats[k]["min"]) + # assert torch.allclose(loaded_stats[k]["max"], expected_stats[k]["max"]) From f8c5a2eb1053d3fe8004b14e049a583a389bfddc Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 17:14:02 +0000 Subject: [PATCH 16/31] remove comment --- lerobot/common/datasets/factory.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 7e079476..4ae161f6 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -74,7 +74,6 @@ def make_dataset( transforms = v2.Compose( [ - # TODO(rcadene): we need to do something about image_keys Prod(in_keys=clsfunc.image_keys, prod=1 / 255.0), NormalizeTransform( stats, From 3914831585fbfbe1d5e863b14eddd8f855078356 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 17:16:44 +0000 Subject: [PATCH 17/31] remove __name__ outside script --- lerobot/common/datasets/pusht.py | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/lerobot/common/datasets/pusht.py b/lerobot/common/datasets/pusht.py index 0e39a92d..ae82c361 100644 --- a/lerobot/common/datasets/pusht.py +++ b/lerobot/common/datasets/pusht.py @@ -209,16 +209,3 @@ class PushtDataset(torch.utils.data.Dataset): self.data_dict[key] = torch.cat([x[key] for x in ep_dicts]) self.data_dict["index"] = torch.arange(0, total_frames, 1) - - -if __name__ == "__main__": - dataset = PushtDataset( - "pusht", - root=Path("data"), - delta_timestamps={ - "observation.image": [0, -1, -0.2, -0.1], - "observation.state": [0, -1, -0.2, -0.1], - "action": [-0.1, 0, 1, 2, 3], - }, - ) - dataset[10] From 949f4d1a5bf1180fd1c014310d460e11875dbfd9 Mon Sep 17 00:00:00 2001 From: Cadene Date: Wed, 10 Apr 2024 17:21:36 +0000 Subject: [PATCH 18/31] remove comment --- lerobot/scripts/eval.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 8d891115..d676623e 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -320,7 +320,6 @@ def eval(cfg: dict, out_dir=None, stats_path=None): policy, max_episodes_rendered=10, video_dir=Path(out_dir) / "eval", - # TODO(rcadene): what should we do with the transform? transform=transform, seed=cfg.seed, ) From 0593d20348c1e4d58a299b30a5fb41686b81d4ca Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 11 Apr 2024 08:51:37 +0200 Subject: [PATCH 19/31] Fix gym-xarm --- poetry.lock | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/poetry.lock b/poetry.lock index faeb70f1..3c02e2f6 100644 --- a/poetry.lock +++ b/poetry.lock @@ -941,7 +941,7 @@ mujoco = "^2.3.7" type = "git" url = "git@github.com:huggingface/gym-xarm.git" reference = "HEAD" -resolved_reference = "ce294c0d30def08414d9237e2bf9f373d448ca07" +resolved_reference = "6a88f7d63833705dfbec4b997bf36cac6b4a448c" [[package]] name = "gymnasium" From 35069bb3e2543ecf39faf468522201c197327b55 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 11 Apr 2024 09:03:58 +0200 Subject: [PATCH 20/31] Update CI dep --- .github/poetry/cpu/poetry.lock | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/poetry/cpu/poetry.lock b/.github/poetry/cpu/poetry.lock index fe4ed7a0..98a3d58d 100644 --- a/.github/poetry/cpu/poetry.lock +++ b/.github/poetry/cpu/poetry.lock @@ -940,7 +940,7 @@ mujoco = "^2.3.7" type = "git" url = "git@github.com:huggingface/gym-xarm.git" reference = "HEAD" -resolved_reference = "08ddd5a9400783a6898bbf3c3014fc5da3961b9d" +resolved_reference = "6a88f7d63833705dfbec4b997bf36cac6b4a448c" [[package]] name = "gymnasium" From 922922652283a03dc1d942cca24e1fc2e01b3e27 Mon Sep 17 00:00:00 2001 From: Remi Date: Thu, 11 Apr 2024 10:35:17 +0200 Subject: [PATCH 21/31] Update lerobot/common/envs/utils.py --- lerobot/common/envs/utils.py | 1 + 1 file changed, 1 insertion(+) diff --git a/lerobot/common/envs/utils.py b/lerobot/common/envs/utils.py index 9d0fb853..4d31ddb2 100644 --- a/lerobot/common/envs/utils.py +++ b/lerobot/common/envs/utils.py @@ -19,6 +19,7 @@ def preprocess_observation(observation, transform=None): img = einops.rearrange(img, "b h w c -> b c h w") obs[imgkey] = img + # TODO(rcadene): enable pixels only baseline with `obs_type="pixels"` in environment by removing requirement for "agent_pos" obs["observation.state"] = torch.from_numpy(observation["agent_pos"]).float() # apply same transforms as in training From 657b27cc8f6c2a3db54b8e643e647b17f27eb25a Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 12:59:09 +0000 Subject: [PATCH 22/31] fix load_data_with_delta_timestamps and add tests --- lerobot/common/datasets/utils.py | 80 +++++++++++++++++--------------- tests/test_datasets.py | 48 ++++++++++++++++++- 2 files changed, 89 insertions(+), 39 deletions(-) diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index cf8caa46..e67d8a04 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -34,52 +34,56 @@ def download_and_extract_zip(url: str, destination_folder: Path) -> bool: return False -def euclidean_distance_matrix(mat0, mat1): - # Compute the square of the distance matrix - sq0 = torch.sum(mat0**2, dim=1, keepdim=True) - sq1 = torch.sum(mat1**2, dim=1, keepdim=True) - distance_sq = sq0 + sq1.transpose(0, 1) - 2 * mat0 @ mat1.transpose(0, 1) - - # Taking the square root to get the euclidean distance - distance = torch.sqrt(torch.clamp(distance_sq, min=0)) - return distance - - -def is_contiguously_true_or_false(bool_vector): - assert bool_vector.ndim == 1 - assert bool_vector.dtype == torch.bool - - # Compare each element with its neighbor to find changes - changes = bool_vector[1:] != bool_vector[:-1] - - # Count the number of changes - num_changes = changes.sum().item() - - # If there's more than one change, the list is not contiguous - return num_changes <= 1 - - # examples = [ - # ([True, False, True, False, False, False], False), - # ([True, True, True, False, False, False], True), - # ([False, False, False, False, False, False], True) - # ] - # for bool_list, expected in examples: - # result = is_contiguously_true_or_false(bool_list) - - def load_data_with_delta_timestamps( - data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode + data_dict: dict[torch.Tensor], + data_ids_per_episode: dict[torch.Tensor], + delta_timestamps: list[float], + key: str, + current_ts: float, + episode: int, + tol: float = 0.04, ): + """ + Given a current timestamp (e.g. current_ts=0.6) and a list of timestamps differences (e.g. delta_timestamps=[-0.8, -0.2, 0, 0.2]), + this function compute the query timestamps (e.g. [-0.2, 0.4, 0.6, 0.8]) and loads the closest frames of the specified modality (e.g. key="observation.image"). + + Importantly, when no frame can be found around a query timestamp within a specified tolerance window (e.g. tol=0.04), this function raises an AssertionError. + When a timestamp is queried before the first available timestamp of the episode or after the last available timestamp, + the violation of the tolerance doesnt raise an AssertionError, and the function populates a boolean array indicating which frames are outside of the episode range. + For instance, this boolean array is useful during batched training to not supervise actions associated to timestamps coming after the end of the episode, + or to pad the observations in a specific way. Note that by default the observation frames before the start of the episode are the same as the first frame of the episode. + + Parameters: + - data_dict (dict): A dictionary containing the data, where each key corresponds to a different modality (e.g., "timestamp", "observation.image", "action"). + - data_ids_per_episode (dict): A dictionary where keys are episode identifiers and values are lists of indices corresponding to frames associated with each episode. + - delta_timestamps (dict): A dictionary containing lists of delta timestamps for each possible key to be retrieved. These deltas are added to the current_ts to form the query timestamps. + - key (str): The key specifying which data modality is to be retrieved from the data_dict. + - current_ts (float): The current timestamp to which the delta timestamps are added to form the query timestamps. + - episode (int): The identifier of the episode from which frames are to be retrieved. + - tol (float, optional): The tolerance level used to determine if a data point is close enough to the query timestamp. Defaults to 0.04. + + Returns: + - tuple: A tuple containing two elements: + - The first element is the data retrieved from the specified modality based on the closest match to the query timestamps. + - The second element is a boolean array indicating which frames were considered as padding (True if the distance to the closest timestamp was greater than the tolerance level). + + Raises: + - AssertionError: If any of the frames unexpectedly violate the tolerance level. This could indicate synchronization issues with timestamps during data collection. + """ # get indices of the frames associated to the episode, and their timestamps ep_data_ids = data_ids_per_episode[episode] ep_timestamps = data_dict["timestamp"][ep_data_ids] + # we make the assumption that the timestamps are sorted + ep_first_ts = ep_timestamps[0] + ep_last_ts = ep_timestamps[-1] + # get timestamps used as query to retrieve data of previous/future frames delta_ts = delta_timestamps[key] query_ts = current_ts + torch.tensor(delta_ts) # compute distances between each query timestamp and all timestamps of all the frames belonging to the episode - dist = euclidean_distance_matrix(query_ts[:, None], ep_timestamps[:, None]) + dist = torch.cdist(query_ts[:, None], ep_timestamps[:, None], p=1) min_, argmin_ = dist.min(1) # get the indices of the data that are closest to the query timestamps @@ -91,11 +95,11 @@ def load_data_with_delta_timestamps( # TODO(rcadene): synchronize timestamps + interpolation if needed - tol = 0.04 is_pad = min_ > tol - assert is_contiguously_true_or_false(is_pad), ( - f"One or several timestamps unexpectedly violate the tolerance ({min_} > {tol=})." + # check violated query timestamps are all outside the episode range + assert ((query_ts[is_pad] < ep_first_ts) | (ep_last_ts < query_ts[is_pad])).all(), ( + f"One or several timestamps unexpectedly violate the tolerance ({min_} > {tol=}) inside episode range." "This might be due to synchronization issues with timestamps during data collection." ) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 9b32ea25..d56e8252 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -4,7 +4,7 @@ import einops import pytest import torch -from lerobot.common.datasets.utils import compute_stats, get_stats_einops_patterns +from lerobot.common.datasets.utils import compute_stats, get_stats_einops_patterns, is_contiguously_true_or_false, load_data_with_delta_timestamps from lerobot.common.datasets.xarm import XarmDataset from lerobot.common.transforms import Prod from lerobot.common.utils import init_hydra_config @@ -142,3 +142,49 @@ def test_compute_stats(): # assert torch.allclose(loaded_stats[k]["std"], expected_stats[k]["std"]) # assert torch.allclose(loaded_stats[k]["min"], expected_stats[k]["min"]) # assert torch.allclose(loaded_stats[k]["max"], expected_stats[k]["max"]) + + +def test_load_data_with_delta_timestamps_within_tolerance(): + data_dict = { + "timestamp": torch.tensor([0.1, 0.2, 0.3, 0.4, 0.5]), + "index": torch.tensor([0, 1, 2, 3, 4]), + } + data_ids_per_episode = {0: torch.tensor([0, 1, 2, 3, 4])} + delta_timestamps = {"index": [-0.2, 0, 0.24]} + key = "index" + current_ts = 0.3 + episode = 0 + tol = 0.04 + data, is_pad = load_data_with_delta_timestamps(data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode, tol) + assert not is_pad.any(), "Unexpected padding detected" + assert torch.equal(data, torch.tensor([0, 2, 4])), "Data does not match expected values" + +def test_load_data_with_delta_timestamps_outside_tolerance_inside_episode_range(): + data_dict = { + "timestamp": torch.tensor([0.1, 0.2, 0.3, 0.4, 0.5]), + "index": torch.tensor([0, 1, 2, 3, 4]), + } + data_ids_per_episode = {0: torch.tensor([0, 1, 2, 3, 4])} + delta_timestamps = {"index": [-0.2, 0, 0.14, 0.2]} + key = "index" + current_ts = 0.3 + episode = 0 + tol = 0.03 + with pytest.raises(AssertionError): + load_data_with_delta_timestamps(data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode, tol) + +def test_load_data_with_delta_timestamps_outside_tolerance_outside_episode_range(): + data_dict = { + "timestamp": torch.tensor([0.1, 0.2, 0.3, 0.4, 0.5]), + "index": torch.tensor([0, 1, 2, 3, 4]), + } + data_ids_per_episode = {0: torch.tensor([0, 1, 2, 3, 4])} + delta_timestamps = {"index": [-0.3, -0.24, 0, 0.26, 0.3]} + key = "index" + current_ts = 0.3 + episode = 0 + tol = 0.04 + data, is_pad = load_data_with_delta_timestamps(data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode, tol) + assert torch.equal(is_pad, torch.tensor([True, False, False, True, True])), "Padding does not match expected values" + assert torch.equal(data, torch.tensor([0, 0, 2, 4, 4])), "Data does not match expected values" + From 92701088a3eec48c9bc09f5c5fe052766febca98 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:04:27 +0000 Subject: [PATCH 23/31] small fix --- tests/test_datasets.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index d56e8252..7c5773f9 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -4,7 +4,7 @@ import einops import pytest import torch -from lerobot.common.datasets.utils import compute_stats, get_stats_einops_patterns, is_contiguously_true_or_false, load_data_with_delta_timestamps +from lerobot.common.datasets.utils import compute_stats, get_stats_einops_patterns, load_data_with_delta_timestamps from lerobot.common.datasets.xarm import XarmDataset from lerobot.common.transforms import Prod from lerobot.common.utils import init_hydra_config From 36de77ac188ecaed4439d81999a1d0ee97f45f44 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:16:47 +0000 Subject: [PATCH 24/31] fix and clarify tests --- tests/test_datasets.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 7c5773f9..f921062b 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -150,7 +150,7 @@ def test_load_data_with_delta_timestamps_within_tolerance(): "index": torch.tensor([0, 1, 2, 3, 4]), } data_ids_per_episode = {0: torch.tensor([0, 1, 2, 3, 4])} - delta_timestamps = {"index": [-0.2, 0, 0.24]} + delta_timestamps = {"index": [-0.2, 0, 0.139]} key = "index" current_ts = 0.3 episode = 0 @@ -165,11 +165,11 @@ def test_load_data_with_delta_timestamps_outside_tolerance_inside_episode_range( "index": torch.tensor([0, 1, 2, 3, 4]), } data_ids_per_episode = {0: torch.tensor([0, 1, 2, 3, 4])} - delta_timestamps = {"index": [-0.2, 0, 0.14, 0.2]} + delta_timestamps = {"index": [-0.2, 0, 0.141]} key = "index" current_ts = 0.3 episode = 0 - tol = 0.03 + tol = 0.04 with pytest.raises(AssertionError): load_data_with_delta_timestamps(data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode, tol) From 2f4af32d3f69d571c7c959a39745dab3fb0e4755 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:21:06 +0000 Subject: [PATCH 25/31] small fix --- tests/test_datasets.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index f921062b..37e320a2 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -157,7 +157,7 @@ def test_load_data_with_delta_timestamps_within_tolerance(): tol = 0.04 data, is_pad = load_data_with_delta_timestamps(data_dict, data_ids_per_episode, delta_timestamps, key, current_ts, episode, tol) assert not is_pad.any(), "Unexpected padding detected" - assert torch.equal(data, torch.tensor([0, 2, 4])), "Data does not match expected values" + assert torch.equal(data, torch.tensor([0, 2, 3])), "Data does not match expected values" def test_load_data_with_delta_timestamps_outside_tolerance_inside_episode_range(): data_dict = { From a605eec7e9416677bdd4d8c7a75046afc7a2ef13 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:36:50 +0000 Subject: [PATCH 26/31] Use pusht as example so it's fast --- README.md | 7 +++---- examples/1_visualize_dataset.py | 4 ++-- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 6473e1eb..25b8d1e4 100644 --- a/README.md +++ b/README.md @@ -131,7 +131,7 @@ print(lerobot.available_datasets) # >>> ['aloha_sim_insertion_human', 'aloha_sim_insertion_scripted', 'aloha_sim_transfer_cube_human', 'aloha_sim_transfer_cube_scripted', 'pusht', 'xarm_lift_medium'] # TODO(rcadene): remove DATA_DIR -dataset = AlohaDataset("aloha_sim_transfer_cube_human", root=Path(os.environ.get("DATA_DIR"))) +dataset = AlohaDataset("pusht", root=Path(os.environ.get("DATA_DIR"))) video_paths = render_dataset( dataset, @@ -139,14 +139,13 @@ video_paths = render_dataset( max_num_episodes=1, ) print(video_paths) -# ['outputs/visualize_dataset/example/episode_0_top.mp4'] +# ['outputs/visualize_dataset/example/episode_0.mp4'] ``` Or you can achieve the same result by executing our script from the command line: ```bash python lerobot/scripts/visualize_dataset.py \ -env=aloha \ -task=sim_sim_transfer_cube_human \ +env=pusht \ hydra.run.dir=outputs/visualize_dataset/example # >>> ['outputs/visualize_dataset/example/episode_0.mp4'] ``` diff --git a/examples/1_visualize_dataset.py b/examples/1_visualize_dataset.py index bfc2635f..e9b62ff1 100644 --- a/examples/1_visualize_dataset.py +++ b/examples/1_visualize_dataset.py @@ -9,7 +9,7 @@ print(lerobot.available_datasets) # >>> ['aloha_sim_insertion_human', 'aloha_sim_insertion_scripted', 'aloha_sim_transfer_cube_human', 'aloha_sim_transfer_cube_scripted', 'pusht', 'xarm_lift_medium'] # TODO(rcadene): remove DATA_DIR -dataset = AlohaDataset("aloha_sim_transfer_cube_human", root=Path(os.environ.get("DATA_DIR"))) +dataset = AlohaDataset("pusht", root=Path(os.environ.get("DATA_DIR"))) video_paths = render_dataset( dataset, @@ -17,4 +17,4 @@ video_paths = render_dataset( max_num_episodes=1, ) print(video_paths) -# ['outputs/visualize_dataset/example/episode_0_top.mp4'] +# ['outputs/visualize_dataset/example/episode_0.mp4'] From 5be83fbff67a227abfd59afc12bac4fb11201cdc Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:46:13 +0000 Subject: [PATCH 27/31] fix --- examples/1_visualize_dataset.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/1_visualize_dataset.py b/examples/1_visualize_dataset.py index e9b62ff1..ec70ac27 100644 --- a/examples/1_visualize_dataset.py +++ b/examples/1_visualize_dataset.py @@ -2,14 +2,14 @@ import os from pathlib import Path import lerobot -from lerobot.common.datasets.aloha import AlohaDataset +from lerobot.common.datasets.aloha import PushtDataset from lerobot.scripts.visualize_dataset import render_dataset print(lerobot.available_datasets) # >>> ['aloha_sim_insertion_human', 'aloha_sim_insertion_scripted', 'aloha_sim_transfer_cube_human', 'aloha_sim_transfer_cube_scripted', 'pusht', 'xarm_lift_medium'] # TODO(rcadene): remove DATA_DIR -dataset = AlohaDataset("pusht", root=Path(os.environ.get("DATA_DIR"))) +dataset = PushtDataset("pusht", root=Path(os.environ.get("DATA_DIR"))) video_paths = render_dataset( dataset, From 84d2468da128ebe90bfcd770e40967fcd535d226 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:51:13 +0000 Subject: [PATCH 28/31] fix --- examples/1_visualize_dataset.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/1_visualize_dataset.py b/examples/1_visualize_dataset.py index ec70ac27..15e0e54d 100644 --- a/examples/1_visualize_dataset.py +++ b/examples/1_visualize_dataset.py @@ -2,7 +2,7 @@ import os from pathlib import Path import lerobot -from lerobot.common.datasets.aloha import PushtDataset +from lerobot.common.datasets.pusht import PushtDataset from lerobot.scripts.visualize_dataset import render_dataset print(lerobot.available_datasets) From 8e5b4365ac02fafe86d517f5bad6d11e38967cc6 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 13:57:22 +0000 Subject: [PATCH 29/31] fix --- lerobot/scripts/visualize_dataset.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/scripts/visualize_dataset.py b/lerobot/scripts/visualize_dataset.py index ed95b39a..4b7b7d6c 100644 --- a/lerobot/scripts/visualize_dataset.py +++ b/lerobot/scripts/visualize_dataset.py @@ -79,7 +79,7 @@ def render_dataset(dataset, out_dir, max_num_episodes): out_dir.mkdir(parents=True, exist_ok=True) for im_key in dataset.image_keys: - if len(dataset.image_keys) > 0: + if len(dataset.image_keys) > 1: im_name = im_key.replace("observation.images.", "") video_path = out_dir / f"episode_{ep_id}_{im_name}.mp4" else: From 42166360844193165193f0908f45b06a6be850a6 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 14:01:23 +0000 Subject: [PATCH 30/31] fix --- tests/test_examples.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_examples.py b/tests/test_examples.py index 17f6d600..4263e452 100644 --- a/tests/test_examples.py +++ b/tests/test_examples.py @@ -15,7 +15,7 @@ def test_example_1(): file_contents = file.read() exec(file_contents) - assert Path("outputs/visualize_dataset/example/episode_0_top.mp4").exists() + assert Path("outputs/visualize_dataset/example/episode_0.mp4").exists() def test_examples_3_and_2(): From c1a618e567a35e401830405a50008768f458c919 Mon Sep 17 00:00:00 2001 From: Cadene Date: Thu, 11 Apr 2024 14:29:16 +0000 Subject: [PATCH 31/31] fix pusht images type from float32 to uint8, update gym-pusht dependencies --- lerobot/common/datasets/pusht.py | 3 +++ poetry.lock | 4 ++-- tests/data/pusht/data_dict.pth | Bin 5535316 -> 1388116 bytes tests/test_datasets.py | 1 + 4 files changed, 6 insertions(+), 2 deletions(-) diff --git a/lerobot/common/datasets/pusht.py b/lerobot/common/datasets/pusht.py index ae82c361..34d92daa 100644 --- a/lerobot/common/datasets/pusht.py +++ b/lerobot/common/datasets/pusht.py @@ -145,6 +145,9 @@ class PushtDataset(torch.utils.data.Dataset): assert (episode_ids[idx0:idx1] == episode_id).all() image = imgs[idx0:idx1] + assert image.min() >= 0.0 + assert image.max() <= 255.0 + image = image.type(torch.uint8) state = states[idx0:idx1] agent_pos = state[:, :2] diff --git a/poetry.lock b/poetry.lock index 3c02e2f6..0133b3ed 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.8.2 and should not be changed by hand. +# This file is automatically @generated by Poetry 1.8.1 and should not be changed by hand. [[package]] name = "absl-py" @@ -921,7 +921,7 @@ shapely = "^2.0.3" type = "git" url = "git@github.com:huggingface/gym-pusht.git" reference = "HEAD" -resolved_reference = "824b22832cc8d71a4b4e96a57563510cf47e30c1" +resolved_reference = "080d4ce4d8d3140b2fd204ed628bda14dc58ff06" [[package]] name = "gym-xarm" diff --git a/tests/data/pusht/data_dict.pth b/tests/data/pusht/data_dict.pth index 40d96a51c744b9a350f972baed736a499303dbb1..a083c86c5742e334da5cfc890758687fad2e46e3 100644 GIT binary patch literal 1388116 zcmeFaTd*zHb)E-Fwj|R^;!Et<&ds^YxyZ77lM_2J0SSTy&=%=jnCL--NyMUXNN58G zrg;%7MU`BXA{XhnY?+B-F_o%Fc3de`84sz-3m)RPJjgG3P?gOX5Kcu%kw6_L1nV3S z%6~8ph9>6hF;?%r*X%iat#8#LID5|CYpwozd_8;h-lzW`dh}a<(*qBD`?o*PJbuRm zzwLn!J%01?ANkOSKX~&G-fMl=k3V_i;RnCtf&Zd-{8!)n6BiGB=lg%Ve*CGw@XQlW z|E0%oe)y@6e%FUT^7vnT;^Lb=c=M^JKlr2H^&`*T{P2xu-t{9-Kk*ly{qT(s{m9KH zKKjg4PyfhY`kr@PeDimH=lj1+Km3f=y!RvDVn6b(2S0xEi9c_B@4EO+@Bb#P^4%A| z`TgIb|Nr2RKYQ`5Kls4!`CSj(y!f{FKKj6SKKeb6e#@gDc=Q7|FTVXd-}AtYN5APk zzyF&a{g#^-zvZVt_`#=c+<4-H_de1y@A`93f9Q#)pZL)CX>;Cn@vcAczKh>_^Wr<+ zckxd(AO4w}kKcUa;-CIeeYPKc`|~_}=KU7tc9 z;+y}<#qW6Zn;-qAzjE_w^Wt~C@8WmA|6BE`AAjppT>NwPsy}M4@I4p5 z$6n$0`YZfCdxd}AUg2N3dGRm4@8Vy23(*rl{^4hy`p^>>|MELN*q{06Z+xuZ|JKL) z!x#UGUi5ozUi_-K{G#?6a=^L-cp*8A`6@c;7Z$3ODKk9_z; z7vK4gSA6WLkN!p9(m(LlOa76If7@R2-?{&i|L(n){P*l7zw743AAH}%cfbF)=p}D{ z_#;mU-$#D@;t#!JL;vW-_t*>k;rlP}NAA7AAGH_wV>d7U`1>xt_x-=cu;!oL2{D(I${-gI@{OPwo!&@)$p{G9j z#KpVcv0V>7_0$dDt_R=Ru0MY9kiF*j-G9yRzxSFC+iU*7&5K9gckyT5{~d3CtY@D6 z;0K?0=9!Bhy#KlEHNN-aQG1QY?!U%+?!CsJwb%G_H!ptZeHZV2|8Lf7eE6dudg3o% zyzl-G8`wW_@#pP_|Ks~V{GZ(W;s4Zr_&>XO@&5N+{O8Yp*AG4VZQuTP|G=OAKc7(f z-}~PWh0^}c2Yz26?O%{YPu;8fhaddi@38ha1ita%n>TMfaqkU&>QBA&d+!zMz5m5; z@Y^2vlf@g{J1YFa?|%5f?+sr4H{K^|{ra!}`qy~`1PsnU{>T6L*LXApghkk1fBkih z2o#TsfUpP-d@3xyXna&c)Q>YM8^VHLC6KC(UlovQ5x*)R)gpdXK&nOjs(@6B_*DU^ z7V)bBQZ3?F1*BTUuL?-Dh+h?uYH_Szuik#+-5>rZU%GXt`c(5Q4)p8uzx0*w`{=Lz z*-!uadp`9IQJRNI`AG))B_@Jn&mVZ^wenNV(;n#8LpN?YA2sH*Y@lCd{ovQ4GQwid z#nBl$2l_R`<{$hF1N}Pq*=ATle7Js?>`Hb@G z@7?};Yd++_bq4zN`LBFl&tG`$7Y1(r!M7eYe;J(l5gDJ2{VL&Dds@-9_p607a}^Eo z>kF@bVUf~=$D$#A>8KbXnoYFr{qiYev4qq)RTT~K%Mq!H{_6kr*IH2XAllxqkA3zF z)wAWJo=HU8-mj1S^nd%g|M7qI=O=#lzhC5|&Kas`d%sjX4o8ho{_NlW!ZmiZ;Nnch-;isG<@+8X73taKB1EfBh?eJvuKMg=hx9ynbxnj}Q$J zZHQk#`8R&4JOmjZKPgfp(yd%)oA#D|eeKP!X~Tc^AN{pz3e#e{u~ijGy>^`qdN%XR z;8%LU;pp__qtB-7B63{`FO+E z>Fw9>4ZP+D=k@9o#{4ZP+Dz^@!2ey!ot@B3H&?(>i0SH6$%YYiX#iYVb% zM8^8@YYiX#iYVb%Lyqkd0g^1pIE0!98;iKwa{@llT-b`~20XSD6-uY?czUn-=8 zkCoX}r;Y>Wug`vg{IBwW<8AW497WqGgNiD}w77T!?NYS%1-I$h%&&4{s`!xqRl-rb z;$u_%HuZ4Xcd_}s-}S>%E2p$CK7!Nl{s82Et*KbA95u-QS|sL(G)n$gi-`QMmPyq^ z{#OM=i<+wJN&Z(0$N2cAu&XtMckz|C>Fj-dqdnEREG4}H`Clb8^1qx0`CsN2`Crk| zlKiiT%xU!Zp1<}^srU7b6X4VJ`o;GV`RU~~S zuLKT$<#3D-ekGLfD}iJ6!@pln5UGCfE9b-auY-J4LMo(WwX+?Ff!wM{4=bT5yN1Kmdtz7CM|7*?hx!>Ps=I=iLs7i?MU&(F~A02$Cp9qoF z4}5YyDj|W2);Z^X{L1$}ey!nyUlAqzipW?$ey!m%&@Y9jC|qXde3^mghwpv%CClHL zHiBoYUn-k2!s+qP+{&wc`%&XF%CCx#;^ej`kiX;D`Rnt)_~nOg+_Dmy^AI%FFWYw_ z^MU!yvd=cwue`Qr7#-`^3<*C54nCAQNpi?jP>K!K|c7E zAi}Q%j)w5-ARqin5aCw>2fuPS#s|L=O8Aw)vHBT!eLnweGmKjO@ck>=7x)#Cv3~Kv zuLKc(C2%w})~`uI91=tW{jxho4!pN~g2jhM`Q^9MRAXjDL;Nb?SbJL0w)d-rV?A?L z(Gb7N8>g4JCPXyEFCG0NM6-#uydeMemNpl5&2(E!y39{Wc4hI$J>*L zw!L5Ee^mujE!rJN{T8g`f8~4xiu|tIi z9S6)`g@5uQhz|E24y75gF^p zuQhz|E24y75gGi-$&`HXD`JIT5t*`nxIaKd$>w+YMLv;Gv=8#XR2%ujN-JOIoJYk+ zn~z_uT^b;zYuYKK0#!Bns<{VMqg6!~A(&Z_uS zqcbdy_3PE!Z#W|Sit1t7@GpH}JO1bptw!|u&$)lBU-Of<`r-Odw5RYZB4hpdb&wC& z=MzNumB7&uejVh4UkM`oO5osE4#)W5S3(KD5;#^r1Fs+EpKXRws~^69Mf(E3A~M!5 zKKPX&!mk95hVbhkAN)!X;a37@xL=cmI3$P$&R=%N$bt8kPq6sVD8Kx6nrh69Xvq9k z!m;+WqHXV23&(oqtfC=)MF|BHA{yeCj(!oM*+kpkFP|EAA=(hX91;0nj=~$dV`TMQ zETl<9+ukqozr0iy8+ON0zXdD#UlpZ_k3f$p0!2H$|KLuL4HhEQ5+F#k5HNmrq7&RD8()D&e$zbP6P5b-~TCZ1a1+ zzn?F)a!OVGOwOn4@4v|ZTH}FNjvC~DEfRA?8YTa$MMVBr%cSZd|EmI`MNL)qB>$_0 zV|@Hl*wq?iPmOwC-)K*DE=x(TK>k+=jr=dCLH?KdMgG^~!C9T;e???Yqrdn3wRcLr zuWy_HpRU(8PJj>p{wvvu_?5uXkoe$Nf{6Jmfn)Wf<4?cq^ZC2aKZ;-ZKEkgxeDEux zgkKRE>&LG(eDEuxgkKRE{L0CceDEt`gl^uJn_<-Ihu^~~SuLO>U@arHS{7MkvR|03aUz3D5 zB!~viUv|gHf%leAu=vm@zx;NZYRrsi$oy5pvG%m0ZSPkL$9m?hq9J}o2?Y}(8se9Z zei5SCMBCmkpBi={+7Q1S5&2(^!W+6{Wc6Guq)9~E-Y@dMyi^t&cE?e_1uOYq6{U)g zK#~7dB5L`lXYml^odeH{wx7QeKIDI?kP<#tW>cLy4w%2l|0)kRMVtJu0!G~|gNiD} zv`GG!Pey7~e8~SQ;k0~o3M686!OgL3^Sgeb!E) zApdKTm?P3C`Cly}^1oUpRS)@J6%Z|Isn~EzsxW4zZMV9>LmXwB6Ax3z2~pJQ|f(v;{^D0y}oe*eE9cY$xg(t1dfKp z2fq?T%wGu{s~;VI`dy#T-+lg3{L1$cey!nyUlAqzipW?$ey!nyUlAqzipbzsPNw98 zUlA+(ipZ4p!~HiRN;bdCFY<|mqJ5D6rP|0JR$BQw=R7Jt+I;+K~~SuLO>U@arHS{7MkvR|01ezrOhV zYl@iBfAfzzWK{Jt)~|;@^5SEkysL;J{a5WF5Rx|??w98`3DJZRX~XBQ$3A(-@~z$~ zp*zX095OWAuQDP{?I947Hy!SmKAW)EGx?mOhKBn!YQtB)?{L3Xe$G*=&EVIlZC~@g z_?1(_uY-KJKA#}MuLO>U@arHS{7MkvR{{sWayZ5ZzY3bhWj;1h(m&C;QVEGj2w7x`2>p(jq=NH zr>Vxwh=$BxB^+x{E86ycwQ#Iw&MF$>SCmjNA)+CE>F5_BnoYFr{qm_{7orXE%Mp?P zA|n5*Wm5H! z|5X9eqNXZ)lK<7hF+P4N>}rj%r$)W6Z?va6m!+gvApfg`M*f%6Apgt!BL8dg;H*ya zzalcH(cgRi+B>D**EddpPuJ@kC%}h)|CQ`S{7T?xNPO@sLB#x(z_I$#@u%PQ`TX7I zAH}bHAK}*;KKK<;!mo&o_2btXKKK<;!mo%7e&u9JKKK=}!mo%-SwGx=Bcf#UyZj=b zNGRF|`CqDy{9&b)uXE0$;-k&SuU0PgkpC4OnXO-lxIUjCGCuN4jbyd69TFD7;ru5m z0Q`!`SU-Lp3b@GFO7d}i>=BY2*B;r7ALyyXfr_$4?V zarNMnFWtHO=9UEV_nKk;D)|VM7W2=%<*4`!_p9RbrCSrFq|M-$>cJ2__K7=F6^}mH z41Sp}IP2$(FHs|QCGml?K-?XE=p!f`*zmBpYon8dLaK^2`$hhjm&#(p z?l|hVU?u;nqEzt_DDuBbL@ginEFOZqbKrT=_VZW5hx{)UQo_f|Y^qbo0rMC6U*+MZ zXp{d{z^I#LP*J6r7Rmqe$w-Zg5BXmuoR*JHfkdn>xH*<>e(!hvu++*aRrNDDAHnH& ze*p5o)_CBRqXzk3i^Lp}M#=wb5t0AZGO2pV|Ehp!QB##Y$^UBM7$3hBcD2UXQ={J3 zH`-I3%Tm%SkpEReBmc{3kpE?Vk^i-La8@VzUlEzp=l-J)r|b2N6X3(& z&nG((zY;ha5+D3Z5HWuxaIAj#_g@Jj{7T?>{q+0&MgH#dk1~Jd`v|`d^5Oh2L4;ok z91Y>uK|c7EAi}Q%4u0iuj1PV#l-w`!iG-qkkpHF2JNd(^D_`fFN5w~*k6*1^>LLFt zIXG)bh?u_;M8-#csgbO9wnM@qI4U9dEY^V44}2EksMGl1SHcIsA~;?@_!S|-uZWEG ziw}M!h?u_;I2yvQgM9ESK{Sg{yv&ZNpAr8r=4fMZ1Sq2qVifNJjFQ1ImsQ8fo zRl;fc=oCoA>VlhN+2;3t*XK*EoKjUklk@5N`!Djp)_CBRqXzk3i^Lp}M#=wb5t0AZ zGO2pV|Ehp!QB##Y$^UBM7$3hBcD2UXQ={J3H`-I3%Tm%SkpEReBmc{3kpE?Vk^i-L za8@VzUlEzp=l-J)r|b2N6X2u257$G5wD)c4@%iy9rz$@9l_0YE!LJAr zenn)gAHNRrd29M&{#xdQU&~zH?!~XSNi6@r)erO6GM&-?{ww-a^Yr6azAx}=4WE90 zzmdQD{G<4l?<4$L!$*FRPoz?5ALM_jHu8rRSia6VkBW~rAHQ0;)ID?x-`2^{>&;TRwM zN+{u10>|n{7gzay5mB=Gfltn7)b;sELL4GEWBsx_Mh?8Ue1gS?M)~Ep(^O+-L__AU z5{|W}6-|6Lp1)c+)-z`n4e={VD3}n@5WjTvixABw+V+0=)UXTDhWO=($p3N_-q0N* ztLI`NO(NR%ev$v>rLx$tJC6D-SjqpYC{=s}iu|twT2IV zMU?O>B4hpdwT2IVMU?O>B7IqpCB?m@=J|mwX+=(7Qx~CCn^B^ipW?$ejVh4 zUkM`oO5kV+zYg-juLKc(C2;U7hhu#3E1`s62^^~*{(d7tr23iDFN;VU9>g=JU-P7- z86TC98cCULIrR8vZg~Wl8e>zyCiLs&SMKG1`Exj*39lczUurz}!tE`qw|cJ${jyK^ z#phoeTRHYICiJV?gJT!1ez?9G?S*Omiazkh{rHsw$FDVfraC{&Kk&w*_>}|4uQhz| zE24y75gF^puQhz|E24y75gGi-$&`HXD`JIT5t*`nxV{llviW_KUz3D5L~ztU&@a1V zSueu{C1jZ%#3J=UnLxCPb=E?ezkC{XU-}b;#ZVVFd?ELe(C5JA(~CJ z?fvqpVHcte@yijB|K%vWp*u!a&&5KTM6~VwBLB-vWwBv*9Q9kUlK)jvs`v;L`ClcX zmXCTC4?*5J@VsdI`77Z={+9|V;bUbs)v4ov`HTFo@^DkM$^R-~)Xg%es8URe{JApdKTm?P3C z`Cly}^1oUpRS)@J6%Z|Isn~E zzsxW4zZMV9>LmXwB6Ax3z2~pJQ|f(v;{^D0y}oe*e01@r-}Rr<;M4E=;R*1;uVg1O zeIc6fI9@+||B4WCei)Il ze*8Mf=ib$g*IyT?e9iM5b-&0b5{mXg{+Fij{9)qc>zwnb_-OO-tCdSVD?x-`2^{>&;TRwM zN+{u10>|n{UoKQa0+p|Mo})y-x|4kV-b2P`PQTv!>`RZ_d~Iw5*vx+Y z;K#l;JOyl8zm#v~a0Zsp%zk-F+E_l*&R+`J6QYN1+!`2^HmzU1C#IFJKeJyeH=*ll z;xnyZT{nE?i{n=g3cn8W!LI}nekE`;gkJ~w;8%hOzY;k3mBTSU_?1w?uLO?O57*}t zM5-VB%K7m3hX?tngj7h$YMq8A32{iaZlGUw$H;;AmQS$w(5U&#Z>Ooo%!rK7#(tG> ztUax0+xykRv7R}rXoz1?LcxTHhWMqUUxa8j(YE)?r-ogKHpDMSME;kf@P_UfSv?mE zX%f-4_lx{5FO|iH-Eq`!!AkyDMXBN=P~?A=h+01CSv&-J=fLx#?dPwA5BXmzq=b)^ z*;J>F1LiOCzskc+(I)?^fKfNgprT4KEt3D`laU$~AM(FSI4vKY0*P2%aC0o%{NC^S zVX2i{JApdKTm?P3C`Cly}^1oUpRS)@J6%Z|Isn~EzsxW4zZMV9>LmXwB6Ax3z2~pJQ|f(v z;{^D0y}oe*eE9p`WGCWR0!KsQgI@_E=C1^f)erwZB|(H=2^_BK!K|Xx{N)X{!0!Ksmb&wB!C5YTF@`;3^eUSg9?+*FH zsw-dToJYk+n~z_uT*o8NQjuf5=6#FeyNeHcD6&pA~<}1j|u?4A~M#GUkCZ% zSAqz?5;z*duY-K>D?x-`2^{>&;TRwMN+{u10>|n{UoKQa0+p|Mo}U zj1PWAly>3Q!ykE3&uA06_D}BDox5*7_~c6#1g3@-yV7W1d~(0a2(Te3V3Yeb1D~0% z&;RNxcOQQG%jTCFT5J{Q+B3Od+V)@mm9MLc^i-oOip3Y7+^@yYyk)1=55K>Nn9uK5 z^vSpB$FH0-ey!od_pgW&enn)gAHUY{!LNuCenn*PD<@O(!LNuFenn);`r-RmM9Jp& zQGQJl;t;`6|3JU&j*$cJEuUcVA*-M5{qoyssxdR7A%2x`tUax0+xykRv7R}rXoz1? zLcxTHhWMqUUxa8j(YE)?r-ogKHpDMSME;kf@P_UfSv?mEX%f-4_lx{5FO|iH-Eq`! z!AkyDMXBN=P~?A=h+01CSv&-J=fLx#?dPwA5BXmzq=b)^*;J>F1LiOCzskc+(I)?^ zfKfNgprT4KEt3D`laU$~AM(FSI4vKY0*P2%aC0o%{NC^Se5sXFs_JKQK7!Nl`ZM`o zYdrAEQG@)iMPiOfqvU_Jh{*qHnN&UGe^o%VsHw`H_D-qy^^FtY)Ajns3GmUypMKYW zPJ>Us>xU=62fvb?$o!SS(Gc_3K|c7EAi}Q%4u0iuj1PV#l<+HoWA&qxXU-2JN~$0H zir{$t@ck=7#Q9-F#`^K=AfJ0zH^_$#Fu7mk6A4B8Apc9#cmA--%GWvPQSs5{<5w$} zddU9@4$Swvg^2kpL1cX7mm0}xXFDV;g2VYwQ~>xDk+FXKI>-mV5=8iwz|jzX9pr;w z2_pPT;NVvd$N1n^LJ7YTI95OUa-k9usC>=y92FM)N_IVdC2%xkeDEuxgkKRE>&LG( zeCGE{`9zQ0d`t7JRa#r|tkPm(( zi0~_cqapk{$Opd?MEI4!!LJ;S@xiZz5`HCctbPXm{%evDhXj%8XOv%d$H;;AmQS$w z&?vwBcA9F;jL7(?gw$|oy&EMQYfmfM_I|Z+tY^+D8sb-!P%t5)A%4l<2+?e!ZSR*K z+;$<_5WgG|`CpF08@gj;^;|5ZNkrS;FY>>oN@(PNISul^%rEl4 z77xzqB>yWSa~l1<=dZm}>V19V1o(8lzHtJ4xW8z!6Y(p7qapFZuLKeER|3cCXW-w@ z=bvqcQT)pH0)DOG)9?3R`Mb|QieLFY!ml-a@GGK(UlAGW$FDVf@GGK(UlAGn%E^>` znS@E8mb#qxhAB#jiDd z`2H19!mo&o_2btXKKK<;!mo%7e&u9JKBN4aB*Y;BHPA1+W8}bl%O_ZTXw>}Wx6@Q( zW<K^2`$hhjm&#(p?l|hVU?u;nqEzt_DDuBbL@ginEFOZqbKrT=_VZW5 zhx{)UQo_f|Y^qbo0rMC6U*+MZXp{d{z^I#LP*J6r7Rmqe$w-Zg5BXmuoR*JHfkdn> zxH*<>e(!hvu++*aRrNDDAHnJO?{mrjTH}FNjvC~DEfRA?8YTa$MMVBr%cSZd|EmI` zMNL)qB>$_0V|@Hl*wq?iPmOwC-)K*DE=x(TK>k+=jr=dCLH?KdMgG^~!C9T;e???Y zqrdn3wRcLruWy_HpRU(8PJoXt{`9;4a~gd5T|YblKKPaFMCPvqj)s`O4)VdT1QC8E zaPTXKV|?%{p@d%v9IGFlJac{+QBwWjR|LoFhwonzBF+yZGS-h@2l?E)xZ2)*Fiq`l_0{e1dfLA>mVQeN)X{!0tdfxIK~IR5=!`$z_I$#mkX7UK;>(m z=cusYSF-EzD}kdS91JC)q_vIl<)Urjqb=Vm5sr%|33VY7mo!Yd7T~2UjzBzS5!hf@=KdA>iEp>2b22Y z`bGpt{rmDO*^o{{JDR^b5y)TG`0Qf-$~UCbD1PN&@oNnq{E8^yS4778@oNpAQGQJl z;*cO3=$G9wa^St?6D&S7$}hj2rW!LNGCmvoRl>3Mw4!bAR}05_=B%P2enkld6CxVo zmyUiBqS-{--Y=gTb|KmjzZ?K zijP2%|5YMt`KV{{5agW$&x^L7zY;#=f2oiXK2~N^ojMMfzsUb84>v`d{I3E=-7JHO zD#f%&{+CZiYE*p4|0?0Md~^yVVs*jIv262uzw3vkR!*s^pUL?MPQSnZA^&TQ2VOa9 zkpHzv%n@mn{I3=f`Cl!Qs)ziq3WydpRoRpLuNIE+@k?P>Ym7ZL>V18qJ=M7^CA|Xq zUnMm1znlj7U*;G2UyBE4b&~%TkvWb2-t*VqDfPa-aRPk0Uf(zYKDzkR@A}Va@acE` z@C5kaSF#hCzY;haV*WbF2fq?T_?5uHuN;o?!LNi8ekE|MesuE8`C&v!^@Cp#9Iqd~ ze?^EmKa9v&KYktLbMNW~`CkDh_ltZYp=clEe`)&8A68lUI_EqpKH7ZzYUNT7`Cq|- z`F^($F@Gh9jF0?MBU$ZihlE9NIRA+X0KXzK){kEY`QTTA2)`0I8p5xGeDEtlgkK39 z{L0}NAN)!v;a393>PKHLR6+ukuX&!M!h&DPuE(zgj)sg6enph|>uBJ#f+g*SA^$m+RRNRx=Ry8|5YAtiZ=OQ1&q2`1{GC`X_5Rd zpN!O~_>liq!fE;F6iCGCf}3O6=J$SoA607Ql&bofoKM&5^W=Z6@xUub4f4Mhi8&&T zlK<5rBLAypQuUDkRRPhWrYd`q|JA}VK7J|eYK^g{M!m0Zw5K|krKDFN|Eq*X{+H7r z|I7R$|7-E!tWNU3A~L7Z-+TVrJEh*&H%@?0*XtW6z=yx@O?D!FC2%w(KKPX&V*X0t zSpDeu)9?Cx{_gXS;#a#Ucg2?#D zFEx_Y&UQ#x1c&pVr~vRQB4hpdb&wB!C5Z4VfukY(I>-mV5=8iwz`?H^j`6{-gc5!w zaIAj#`;7#V>Ic7aK3v~8$VVllLP}OU+adhQcRlmh8b0_HQNpi?jP>K!8b0_HQQE0r zANb5Ig*QF-!tH3gj@7?MzdYsYk!NrBj<_;DJM!z*uYTjvkAK}$(jI*BrDK)K;_K|r zuP@!Y<8aha9N6M^9jkNKe!b^YZ{XKrB?yb23bI@rJ!0qX{5s;cuX(9G`n6`ej!$bt8kPq6sVD8Kx6 znrh69$oOpRR|&`3(~7peUo9N#nX`(9_!T7-Oo(WRUpo3lh-MRQd%t{Y*oA0A{BlI( ze>npVn54>{JApdKTm?P3C`Cly}^1oUpRS)@J z6%Z|Isn~EzsxW4zZMV9>LmXw zB6Ax3z2~pJQ|f(v;{^D0y}oe*e7OHcvJ>$ufukYu!LI}n^H&1L>WBMBC5Z4Vf#dbl z@Ant^yU#z${FUz`{5r^o^TPxYekE`;gkJ~w;8%hOzY;k3mBTSU_?1v{zsM&NiuOVN zmoD$*538Um4gb2SPGS)9X_>~}H{z~9z2)_>U!LI}nekE}5D~Drz@GGH& zUkMzmADuj_gaj&I^E^j|1;3JAk6#HK4H+N&iYVb%M8^8@YYiX#iYVb%L}u@P-MRaw zB6t+%lyBfQM|V1ZDLGEbUlw%LHNt79eu;^vfIaq!jwQ6y`K#n3P+xrhwQG75{rFD( zD*52o;?5NodoGS1t8=G*9c%LszRphlI=EfOT0wlczLCJhuLO>U@arHS{7MkvR|03a zUz3D5B!~viUv|gHf%leAu=vm@zx;NZYRrsi$oy5pvG%m0ZSPkL$9m?hq9J}o2?Y}( z8se9Zei5SCMBCmkpBi={+7Q1S5&2(^!W+6{Wc6Guq)9~E-Y@dMyi^t&cE?e_1uOYq z6{U)gK#~7dB5L`lXYml^odeH{wx7QeKIDI?kP<#tW>cLy4w%2l|0)kRMVtJu0!G~| zgNiD}v`GG!Pey7~e8~SQ;k0~o3M686!OgL3^LxL)KP%+#&Zq0|zsUbu z8svX15_3cvCI72MME+OHr0OC6s{*1$O;z?J|Eq;#eEd?_)f!_@je1|-Xis%6OG&Rl z{#OZ&{4b|L{+Ibh{@3EcS)Js6MPyE+zxVvLcS^mlZ=3+1uGcqCfRFAkp@#}-@7vPj z^W#@eRebO(L1guVUlAhwipW?$ejViV*7U{vwaf{>mbtv$i(hY(SpI*jALg%RI{f>} zh|Amk`1Ll4<^RX8WiD^`8lQfDzw!3_?DhZgE8lbYwT6%UBA-a5(mu%lQf=f9E3kZ> za~>5RZ9aara;b;>uQkVKzJEoOR6>Fyzto7E8&A*5ghg7 zR|3cR;8#S6`70u0{rI(p4}L|I@GByNUpbkQ4}L|g@GBxy)(_vmB1$&D<5$8*aHyYz zkKn*3=YwAfAN-2osGsj&2^{BxUlAqF4&WD*DKV094knY{DXuFQpk6$@S{940j)cN5gAr1+m zfqvN?BM07FKEdKcqx|yQX{s?ZBIC2MUnLxCPb=E?ezkC{XU-}b;#ZVVFd?ELe(C5J zA(~CJ?fvqpVHcte@yijB|K%vWp*u!a&&5KTM6~VwBLB-vWwBv*9Q9kUlK)jvs`v;L z`ClcXmXCTC4?*5J@VsdI`77Z={+9|V;bUbs)v4ov`HTFo@^DkM$^R-~)Xg%es8URe zrYUPxw`k9=M;Pm_bDfwS(Jn+gRY0_;smh+@f3vM@Y(ObPuT!Ie&vwG2fq?T z%wGu{4dK^8KKPX&!mk7le&ukC4}K+-@GF61^`rA=m5@N?Yo6z*u;5p+>+vgrqaovi zUlAqzipW?$ey!mnzsM(2sk9IBzf>Ff!wM{4=bT5yN1Kmdtz7CM|7*?hx!>Ps=I=iL zs7i?MU&(F~A02$Cp9qoF4}5YyDj|W2);Z^X{L1$}ey!nyUlAqzipW?$ey!nyUlAqz zipbzsPNw98UlA+(ipZ4p!}qUL=kNIPl5&;8(&2zalv5=lfRz$NAt_ zM2Yjmh>Z2)*BUKk4^JrvuuUou5ZzW=FLy5Z1Sq2qVifNJjFQ1ImsQ8foRl;fc=oCoA>VlhN+2;3t z*AGjroKjUklk*Xre!t%#|7(p0UO8%z|FuZW5owhCuND#cUoDfWhy1S!h!!ys-RB>*`CWdIPb3uWgZwYm zM*grO&(}HUQSs5{<5w$}ddUCE=LjL<`h0@O_{c9clGV<3NLU1i^Pi{y@GBx?{rGi| z4}K+x@GF6%A^bYX2fq?T_?5uHuN;o?!LNi8ekE|Me)#*11d-|ozj8iY-#ExeC8R=1 zRy*4v{K|Jd^Vb?a_!UvYuZWEG+{`O?o`zqKe*Eh~^zhSPx%k|XuY#U{U#g8S-MXX7dHI#QSFV%j2T#DSXw#0; zKi02FLL3s31O2i)Mh?8Ue1gS?M)~Ep(^O+-L__>4;aGcG(YE)ig=0N)R?!f@qJ)A8 z5e@N6N52TsY@%)Nmro755N(KGj)?p(N8t_KF|v9t7Sbf5ZSNQPUtTJU4ZGv0--4C= zuZmK|N1(|6DiO7O)U$X9^3H+hMcdC`2_N#mR7eRQE3>Ii9S6)`Dn8_Ym2g@ET*TH}FN zjvC~DEfRA?8YTa$MMVBr%cSZd|EmI`MNL)qB>$_0V|@Hl*wq?iPmOwC-)K*DE=x(T zK>k+=jr=dCLH?KdMgG^~!C9T;e???Yqrdn3wRcLruWy_HpRU(8PJqt|{QH!CdjY?4 zw&H_d2_ojN1dfLA>mVQeN)X{!0tdfxIK~IR5=!`$z_I$#`Ljw$pz<}(b5vOHE7|q< zmB7)E@xiZ%5`INwtRKJD@R48S6RA|%2l-#Bjr?H+malWpqvE5@$FEi{^^pIy=J>qp z``hFjc+F9j5Z}KNhT@}x5A_ovvigBf&POFAP|-T)+>c-R-p8*seDEuxgkKRE>&LG( zeDEuxgkKRE{L0CceDEt`gxb`O5ha`7@hjmYI44j) zANb5IMHD^v!tH2FuhxGW=Z794_sFxij~fAY0)D;v)o)n-m!+gV_~c7hE0x8cI)V91 z;a{E~r-tI>7Ps_johRnkdp`BXDfxB85C>t=^OW-S?2eHG?=8Q^xKV!j?KIVx8PSmW ztAu0iBZ{`BD%P*F{ruI!v7R}rXoz1?LcxTHhWMrOju6cz+V+0A`@0Zrh+mF~{4Yo0 z4c#%adM*~yB%*Ea7x`aaDvJ%f&f#*fr&tC~2 z^1oC_2_Gx7sZJdS%wObxm4}<6P5xH_qi&W#MU`S&B>&4NBQ+{MyS>H7O+^1s%2;FY5W`Cp5~9Fa!J|7sDD|J5?7ddUB(fM`)u zl|9M-YT+0kzZ7=0#@JJ%-q$zUQ=Q9F(kqbvRYD{G%W07RWqy(WwRmt=C;49ynbYX+ zJ%8<;Qt#^e=T#uuVpT8_u|*vB$of*>WBGjna-C)(vM&Hp2Dv+eDEuxgkKRE z>&LG(eB>ATL@Jf`LH?I&BY#+d-9_IX?6KE25+l5*+!ZMzqd3 z_X~^QP(M)(SpC2!=YwAfAN-2os2{%)IL-&ZB1+6(5gF^puQhz|E24y75gGi-$&`HX zD`JIT5t*`n`2H19viTjq5eE&+|I3N6qC~wm3vP~Oo8SBW ze!0}jDOL3|IiIfA56S;p8svX15_3cvCI72MME+OHr0OC6s{*1$O;z?J|Eq;# zeEd?_)f!_@je1|-Xis%6OG&Rl{#OZ&{4b|L{+Ibh{@3EcS)Js6MPyE+zxVvLcS^ml zZ=3+1uGcqCfX|S>Kims9{L1%~_~2K9i1{mlqapk{$Opd?MEI4!!LJ;S@xiZz5`HCc ztbTOzwnb_-OO-tCdSVKA*t-H}cKA@~BFP?_UW$@zKGD`iT%({lF*ZqY@IRXq|KJ z$FF?vL=lI@9GBmUjZQe3c%d&X8txlNn=U-FV z9IJBdNWQ&aK7(`;&0qg0jUj&dCnx{QQFudljI5rEg>)U!{JpN<*xoPlzw*6icO3Ow zu#*2(;i~uu6!~8zqLz<(77sz*d7bm3@~yAX-hTc{_>ljlJ(%#Z{oCWz@d}k=KQdtc zBL6GcTjYNQVD5F7K}D5fS|tC=CnGf~KIDIua9Tb(1ro8O_682w{NC^P%cWLMsj8pJ z`ERY0_;smh+@f3vM z@Zs-!lbwiP2^4;aGcG(YE)ig=0NOsiNmzxUKxA4}9j93v$iI5Wk{?f@>lYnMa+JjHNkau45yr_Kl%eJ?lzY;#=e`)t6d~E0TICZ>i+4%Yc<}dQUoc=o- zyA`az0&u z|3&`S8Wp^9)FA(Bk(eXWDEVJ4BJ#glCRGplUlkB7YO1m)`Cly@U#0S3;M9g0a9IGE4fBIdY&)+=aB<0HS+NLD-BAz=|5&VQl;z^{mm_2bt;KKPX&!mk95hVbhkAN)!X z;a36&zj8Rn2fq?Z_?5u1`r+?45=5#W{L1-oed8b>m5>T4S?z3x@GIZ-%wKEx;8#Qm zzalc$k6&x};8#QmzaldDm6Iv?;8(;7zalba{qXz2h?33k_?7Sx9O@_G!}W~_j{5N{ zfn$8|D?w!S!|^9VgkKRE>lYvVN)X{!0!Kq*{kmF+L%v1F9UbVG-7#|Dz2(=C9Oaka zPE(DU5e@OHgk$Y#Mcdx57LN7ISw%zqiV_MYL^Q-N9T+1-vx&C7Up{Me67AuSyr`$Y z%QYKA{PNFy-2AUQci;2~IW@HCZ*=9x_I~M(k=1jtkggz_V!u3JPmQCbfNk$rzx=OG zd^Wy*Xm=d-Td*E6|La#@x%=?bU$zobLyK3|%71W(Uk=9_N6i2FgOR z7~t1uzfkc}MJ*nJymR1rk=4(Z*AFYd#LD@Q|D{q-_?QS&ojMNj>nH!lFO`Z}{gg)u zH>+xt>ul5B(l7GAl6_hR6;+C9k^HaHl!_1eUnLy1D?T=bCABwj$c{h#{(hs>$|>!O zPuJgnk^i-(_`Pz}ApdKTm?P3C`Cly}^1oUpRS)@J6%Z|Isz1QGLB0!Ksmb&wB!C5Z4VfrDQ;9OHvu2_^hW;8^|W{8=R= zQ2CnYIVvppmF#-_O5kY7_~2JW3BMvT){kFn_{cBviBu}>gZwYmM*gq@%hx&QQSs5{ z<5w$}ddUA;b9~2lCXSPw55Z}L&ogzLu_)tF)BC8+xDeH&tUlApn-|;KqBRJGg!bfo6 zlk>r^gb#j2aMaKDuLO?s!LNuC=Z6s)>&LG(eDEuxgkKRE{L0CceDEt`gQ%1Qnb!F_v2T-_nE&A^1-hJ(OAE(5aN(*OOK&}e%T!( z2i{wL4Nt3|?dLDQou(QyBO2mY3CG&ginhI9Egb8avxG?uFY&siN)u zvOA9YEm)73|0N(Ek@m>5x7EHrq9J}c9BUja|LfJSe&f-Pf88VY6hU|tJ{w;@tm;RI z)U$X9^3Ij#MPIsg$Kj~)(2ZM1;j{7ejfBtj^S|7$_k8M&lkv;z$9DHMPaTCt&x_9; z=W_9Y`RlV^ApdJoeDc2*u~=srR8$>;v`GG!Pey7~e8~SQ;k0~gice~9;85@L!%{1! zRMpSqe7c?=lK-`)_`Pz}ApdKTm?P3C`Cly}^1oUpRS)@J6%Z|Is$FQ-BNm-$8hS9G)_|0^PM8vVWJuf0?1eSPBu z_;kI#aRPic{{7d!h~Zbhzr+W>5=6{j2^(m=cusYSF-EzD}kdSLLGY&GC8r`vc^kYMxP*5Z}L&-61|Y_)tF)BC8+xDeH&tUlApn-|;KqBRJGg z!bfo6lk>r^gb#j2aMaKDuLO?s!LNuC=Z6s)>&LG(eDEuxgkKRE{L0CceDEt`ggkJ%e``yf62l?Pvf@rK?lY}_rd`8V*cE`w- z_m)pKq3e*<&-U||-%eAFnGp@~tAu0iX+_(9{%YY^&zw~>#IGo!U_wMg{L&FMLNuFb z+xz9y%`QY6;+G>L|I1N$LwAg9J4TPa)iwUu95H zHHB&Mi1}Y%eEv0&ISL&4yP01;8L3h6A^)p{)AF$?tUcJy&|}A+e&>g!R!*s^pUL@j zy*^L=*BT4Fa?~LIYmt~E(kS^~Eh6&2S|(Kw`Ckk+=jr=dCLH?KdMgCWGv?Tv4B6Ax3z2~pJQ|f(v;{^D0y}oe* zeE9p`WGCWR0!KsQgI@_E=C1^f)sK!p{jSgF?>_%1e&zcJzt-@G=AUYwQJdf87x_d&(LTukQf=f9E9QKia~>5R zZ9aara;b;>uY4{LBCgLTh>VZ?QX^UIY=?wJa5(>o3IM+%GS-h@2l?Pvf(XA7I2yvQ zgM9ESL4;ok9Q?}R7$5vfDB)KE$Lfc_-$)Rte()>j!}X1Wd{jazq-3?T9m21C*E4^u z;e%fhCH#uWSU-NP;e%fhCH#uW;8#wjDuLO?q!LJ07)epy?2oZioWUOC&@GC)tUkMxyjrD7i5QhZOK)>vck(a%j(QKk^@0ZUqyAW-N zUyg|UFGt}G-7&IyE*8=xqHXUN`Cnctiw(QusNaH>{I7~q#YdpX|0)r+eAKge2=dN> z=SADkUkRV<=YN$u;wWw7v*qu<5xx2@Fy$$le#K$Aj zjuLUTnO|j4QKgs`kCp$W@UJpo@A`-~^UEhAH7Y(w%>VM@IaWlY)lb*of0dPElqxof1|7x`an_ECB8A^&TUm?P3C`Cly} z^1oUpRS)@J6%Z|I;nB0P=ow0 zr$PRg`9=O$bd)3iDU!LI}nekE}5D~Drz@GGH&UkMzm zAAPw{2?Z2)*BUB7aza|NBNI(tr%kCIC@ZRzX79SclfBEe+)tDKP@!8m~5{|W}6>WRJ zS~%7-XB7?cD@rJs5YZ67bo7f5%_iFRe)-g}3(}^1oU*>S<4P{L0wM#t~1A7C&L$*?ayv3Lo;n%331-%W07RWqy(W6&>Zs|BA?* zMt|@5Ywwgc`~J04P~x-A_pkl(dF!8ly)IBY-Gr_m8^3bA_;rvEekF+TD}kdS{5r@7 zzY;|FmB7KT9FFn9uY?kQC2*{M`2Lk3vigx?Y9yIVFi}2bIzmUqs_;!Rxb6B|F!1$%=uwNNhKsW@=J|qopbIN7Qvx@q8hOJ zfltl{zY;$96~R$IekE|64}L|In7<-2){kFn_~2JW3BMvT_?43>`QTT?3cn&UW&QB| zE23ocJANg61c&-b_y`Vsaz6N#@WHPLj{5ojmB4X6_!Uv&{4gS8{rI(p4}L|I@GByN zUpbkQ4}L|g@GBxy)(_vmB1$&D<5$8*aHyYz&%LV~{QZ0Y2)_a__q&d-XJ&T7R?;LnuwEg^*@FD+8g_Q8IGMnnualrgV{#SXpDcaVl0^RM{^ zUb7)SUHxiLbv&GCWn=8AQE$JF!iW5?vX;pIavJ1+nP238MbiZNUlEzp=U#0S3;M9g0a9IGE4e^f#Om9Kf8qxhBYcl=tz2frdp z_!W_{e*9X)2frdp_!W`CubfQD2frd#_!W^U>u39aUzvZZc}8u1mtW))2}S!L|4X%z zKdhMZbB4hpdwT2IVMU?O>B7i>e3bG&I()NkSYFL<9Y@ zJ4Oz?w|s)dherA3x6@Q(W<*2$D&bgrTG6)mtA%4db5_w1zoLYK2@wtPOGm#5(QKk^ z@0U*vyAW-NUyg|UFGt}G-7&IyE*8=xqHXUN`Cncti;e1zzT|&Zlqx>DS1tKpC8Cy( zdKM2s-Z}8RX#4pq;Y0qH3Mt`ZWj58RCrUr$8cB7u+1nHoy1#`;Ag7r&QI?*PXj>KKSHIzmcy; z{?|K8#FEjD&Zq1A)lTIePPDSI{?zD8x9&I`HIA4c*YEG6j>2bs{+F02S?^eIRGz)( zuPgAme*V|Vo-`OVr$Fu!#(orJ%8v_;rvEekF+TD}jSwIUM7IUkN4rO5j-i=;EqMNTBjH&vR5* z@GIH%_?5uXknzE**6@*E+6Vbxs*U_%1(vUK&ZFX^&Bw1+F7=TA zwdVNT@9#JAcb|V$CB*lyWH*VA4nEXRgvja#J~**6_ivh!TE9Wbi8|Q}V&Dh!uWCWXk&C`&UHC=6C!`_y`X5lkgE7_~d->E8&A* z5ghgN{VRdveDEux#Q9-F#`^JV4Ili9DB)K`2ETGLB_I5XSm9ShrmP>ne?^pRe#ftb zkKj;037>mcH(q~Tg%quG&i(k6?|tU4gM9ESK{VE{NkSZQKBML@yJO_Qd&?(Se8}o& z`}xanr>Vxwh=%x8!m;+WqHRBawQ#Iw&MF$>SCmjNA)+CE>F5_BnoYFr{qm_{7orXE z%Mp?P8|5YAtiZ=OQ1&q2`1{GC`X_5RdpN!O~_>liq!fE+T zo^Pd#tNnhzTx#W%s`{CnPuJ`79x_53ie zpX26#b>h?Y@1u;*Hu+yi57*NnsJCC+=YJhBT+jG)^=q41xZk_ zmB7)E@lgq>k*|54qxhBYcl=tz2frdp_!W_{e*9X)M}Cn{q*7@gLLHD0-{AtRrVzRtA%5H%50`9w8x$r^}fE*p6Xl{kzQeC{@3CTx@KqZ^TR9f zxmy00I4GIumw)B!*921ic<<{QIiDlue<|Eb`Csq()Emc2jx$i(_|-fA%iwrEnzH1o zGPv?$Z@;$5|El;Lv4nd2b>$s*sUQ6OFMj#4Pu{iq`TnO~dHI#Qm-_K!<=%cJZ++aM zhd=V7%0|y0{`AX7eC6JL9r2?Md8yOzs~@_P@v9Re{K~=N*Fiq~{d|H5zY;ha!mopT z@GC)tUkM!i%HbFv{7NX{R|3cCr|a*R^LL+r)aqyZfB!W<8T*9zmG3F>!LI}nekE`; zUswc( z`iW}5>IXhKAN)%A;8z4k{rHu@aX$DJQDXjz$XGvqt>J@T5heVJ$lzB_rsRWP5i9(P z$dvWN_pgYO&F}b?@DUv9C*dPF@X7h$SHcIsA~@>j`&RK!8b0_H zQNpi?41VQgNK0K%^T%>8cWuY-K> zD?v2YuSr52az3NxFS}#pzOoo%!r2gRl>3Mw4!Z4f3u{Pt3=fDQP1Kb$U6s~7i~X(C49*LQXwULtjwl5bsR8%k^fa5Zi+Vf zUj>Z1Sq2qVifNJjFQ1ImsQ8foRl;fc=oCoA>VlhN+2;3tzh5r3a!OVGOwOn4^?CBY z)_CBRqXzk3i^Lp}M#=wb5t0AZGO2pV|Ehp!QB##Y$^UBM7@x}qT24g_?n%)uW#h_bHx0wYjTKwd>g-d=YK_8cm4j}-@i7<|9bVS z->~GSBgTF?*xr8m8}(}lizmk&9Z_$;`eCtGR+OH@QKJ)|e%Cj8^U>?~=F|21#s+-c zFEw7h{l;D?x-`2^{>&;TRwMN+{u10>|oS@7Fi-4ZP;4)z9|-zVezMd$S*RzsM&N ziuOVNmkuxa!)i5O=bT5yN1Kmdtz7CM|0_S#3lZms2_oYoztl)pJKG^)5gg8cq5{CL zh>Z2)*Fiq`l_0{e1dfLA>mVQeN)X{!0tdfxIK~IR5=!`$z_I$#mkX7UK;>(m=cusY zSF-EzD}kdS`Hb>w zk`RXk)Ih)Nj*$cJEuUcVp;7af-%eAFnGqSEjr}U&SbJL0w)d-rV?A?L(Gb6)gn|hX z4e?7yzX;K6qHXV&PYt^eZHQlvi2N@{;SJqUvwAKT(j=m7?-%)BUMh=?>W-}Be^rz! zKDu)+`ClcXmXCTC4?*5J@VsdI`77Z={+9|V;bUbs)v4ov`HTFo@^DkM$^R-~)Xg%e zs8URerYUPxw`k9=M;Pm_ZAM(G}c;J@A~S&ZJd0C{mx(8fZgx>wHcqC&R<*d+2j1R8K17d|Jr6N`n`)CpP9cR z!pvV08S7{MI>?9lD?x-`2^#UkMxy86W(LDB)K`#`^JV z4Ili9DB)K`2ETGLB_I5XSm9ShrmP=+e-Tl#`5nI!K7vF2Bzy!1J~ljlLQ42pnN4--IAH!F|EoOQ6m9aq3K(^>3@WM=(<1p_J{hS|@ge`KgwyiT zDUgWO1vkgC&F}rLAC_7gy{a(|33KSOUHWU#n(~&?8~n&-MZs&)OhH|t;Ov+R_Ct$de5is zB4hpdwT6%UBA-a5(mu%lQf=f9E3kZ>a~>5RZ9aara;b;> zuQkW#et(~tzx({7Dj~s_?5tMKKK<; zV*ZNASU-NP;e%fhCH#uW;8#wjuClBO?FHQFudljI5rEg*1t1+xtcSmzT<7!|pihw_qjztD;o#5h(J%N<=Lm^(-EO zymR1r(f0FK!iW4X6;i^-%517r#{u&f`CsMXrf8G@Rlum5Wl&M2m=?+Z^2tbziVyi; zC7hOzPJu+MF1R_CZGP|f`{hzAr&QI?Dz25&2&& zld6aOuL_73HC5S@{I3>{@$pMxS8I$tHR^qRqdnEREG4}H`Clb8^1qx0`CsN2`Cp3% zXLXYQ6_GiO{@(M~-YNCIzHtJ4x?bNn0Y3bFZ?Y5j<=1a`f-R}8NVVj){kEY`QTTA2)`0I8p5xGeDEtl zgkK4q(l7FfR4VO*{4X6|@`n{zzRo$1ijOuQzgoG}L;lyAr^gb#j2aMX`q2^{BxUlAqduZWEGL=lI@9GBmUjZQe z3c%d&X8tcLy z4w%2l|0)kRMVtJu0!G~|gNiD}v`GG!Pey7~e8~SQ;k0~o3M686!OgL3^LxMFFPB<5 zrK)}==hOB2Jo#U1Jn+gRY0_;smh+@f3vM@Zs-!lbwiP2^O z&e2DA;n&f(di@LT#jo{Sblf#}dOFiU&tvNn#e}91dQ_VA~5)vHwrN%s;YMxIb zEP_M*M0>>Q2R=C;{7U%XR|H4>_?5tMKKK<;V*ZNASU-NP;e%fhCH#uW;8#wjVxwh=%x8!m;+WqHRBawQ#Iw z&MF$>SCmjNA)+CE>F5_BnoYFr{qm_{7orXE%Mp?PDHYe zc;+=L9yPS+M}}=0llvtI7oYnzRgs=*Y{R5{m&yGqKkAUS)z9|-K4r+pUg1sW_v;E9 zb;KXRuN)?Rt>M$}?>F*ypMMm;@_mF~Yxu}7@`+R`?SuR;)kglX0?XGq=TY&|=Hpi@ zmwL$mT628n`&UFsB_ufVOO0rqbM6-w!J&Sl8nF6-PtFIw5D*$u9oB8V?AN)!XjrD7i5Qm)4sQJt87&-9X@(C6nvijM6 z{_@*tsxdR7A%2x`tUax0+s|Ju9P630iiY?VB@|4EXoz1r`bCIl6K#9Hd}`Q*XhZyR zMC5-t3UBC+k=1jtkR}mrd%wv4@={rB*d0gx7OdodRg@||0!98;iKykHp2b6ucMd!+ z+J62@_>ljlLQ42pnN4--IAH!F|EoOQ6m9aq3K(^>3@WM=(<1p_J{hS|@ge`KgwyiT zDUgWO1vkgC&F}qwzg%kNl&bofoKM&5^W=Z6@xUub4f4Mhi8&&TlK<5rBLAypQuUDk zRRPhWrYd`q|JA}VK7J|eYK^g{M!m0Zw5K|krKDFN|Eq*X{+H7r|I7R$|7-E!tWNU3 zA~L7Z-+TVrJEh*&H%@?0*XtW6z=yx@O?D!FC2%w(KKPX&ntc9J?9M|sZt1_tCUhN| z*)L(Sm+*dnf;oiel)-L`~6q6U)J-9_IX-WHe}Mc`%`>VJn)dp}43xx2 z2OsJu+80(o@X7h8gaj&D=bZcTE8qM0wT2IVMU?O>B4hpdwT2IVMU?O>B7lKoN@(PNISul^%rEl477xzqB>yWSa~l1<=dZm}>V19V1o(8lzHtJ4 z`1{^uC*oHEM?>O+UkRdV=dV|9zoC30dnTX1_t3O{%@E!+tzRXaf#GPzXTteQnN6OI zHUpo2zyG@O@xe<-jaR?=jVr&-HGgpC`AbzKIM>|3YySAO^Vc=E>sUWN?fiAD4ZP;- z%`@GD}4UlEzIe)#?sQL_0RzY;!zL;WOt1P4Aj zAN)%A;8z4k{e1sQ;5Z-riYRe@7?H7l{93~YzamQb6_LTOoJ`3Fzam!n6_F|Hhwonz zC7a*zE8!zJ)K9|a-qj8AzXCw`6@ap( zS^aE3fBEe+)tDL45Wh+|)}B_h?dPu+j`hr0MMM0G5(*|nG{i3*{USuOiMG98J~iw@ zv>|>uBJ#f+g*SA^$m+RRNRx=Ry8|5YAtiZ=OQ1&q2`1{GC`X_5RdpN!O~_>liq z!fE;F6iCGCf}3O6=J$TTUoN$BN>%+#&Zq13dGf#3c;J&F*ol@`X8z;c0>-CKj;KSedCOZ+o5;z(XAN)!X%{hPFx%;M)W%PXc zmAlD@-(YA?zaD(@CChJm`020w@~?b-0}jz!Oz79cA9-<-a4SKZ(60&k^!xo+RJVCQ ze&u{-J3ep!?^AL<^Nh|pe@(@Q^TT9!OgMifpLY8p{K}b&4}K+x@GF6%A@_@XBB5v> zZ2)*BUJ@T5heVJ$lzB_ zrsRWP5i9(P$dvWN_pgYO&F}b?@DUv9C*gDN>IV5=0U-Pez})X<{yNA9zY;`a{hB1i zA?Gt{{<1qp4!pN~g2jidezu>#{C1jZ%#3J=UnLxCPb=E?^H&SUdgiR6A$~;(1rs6~ z;+Kwo5u({d+ukpq8g?Pt5WgG|`CpF08@gj;^;|5ZNkrS;FY>>-8?K(wf-%AVwZwQ!7&UkbZgW9+F>@9P`wsm^67=@rQT zDxs18r1!pB%genp$YvG9Lu+QNRQ4$-^J=GS|ly`PL`h{P)TiK|c7EAR6n}Bq0ttpHcId-7#|Dz2y@uK4kT?{ru&((^O+-L__>4;aGcG(YBwz zS~%7-XB7?cD@rJs5YZ67bo7f5%_iFRe)-g}3($_0V|@Hl*wq?i zPmOwC-)K*DE=x(TK>k+=jr=dCLH?KdMgG^~!C9T;e???Yqrdn3wRcLruWy_HpRU(8 zPJj=8-<#}2{7T?xNPH&r>jR&;m4EEbMrWJ9lq~buC+{k}>A@#o`Un5;YnyS1-e@+z zl=)@JR{HPoa4SKZ$}a`RIUF?}x-s6e3H@?Jlhlvq_kO?sio8zxE!=7bIJ5bcKpQnQ zn_r_iMDIJ>{1tu9QTuK|T|H|H?n}mZSKU({{heClZSGLH?Hx zFZsg?EMMoGN5w~*k6*1^>LLGY&GC8r`vc^kYMxP*&}`Q?=7FP6B0f6!P(RU5vHF2e z&POFAP|-T)+>c-R-p8*seDEuxgkKRE>&LG(eDEuxgkKRE{L0CceDEt`gxb`O5ha`7@hjmYIMh$V=ib!~^1lK=_!WS;-_87WkPm((h{pOg zNr*$vXVm;Z1 zSq2qVifNJjFQ1ImsQ8foRl;fc=oCoA>VlhN+2;3tzh5r3a!OVGOwOn4^?CBY)_CBR zqXzk3i^Lp}M#=wb5t0AZGO2pV|Ehp!QB##Y$^UBM7$3hBcD2UXQ={J3H`-I3%Tm%S zkpEReBmc{3kpE?Vk^i-La8@VzUlEzp=l-J)r|b2N6X3(&_a-}WLciYo z>`QtkpLxq6@tMjm#mZRz&OG@t^Z4a(=0P--Uvu)A$1ml7{lGK#^U>7M;+BV+#rLxM z+5Ye67e9-`v^Qib}^YN>dOFiU&B?o5> z2@&&Gg2?#DFEx_Y&UQ#x1ZSS>W3%lD{L1$TejVh4UkM`oO5kV+zYg-juLKc(C2;U7 zhhu#3E1`s62^^~*eYsEx2~@u3d5#JTekHpezY;haGCuefQNpi?jP>K!8b0_HQNpi? z41VQgNH4r z+1RfVj~6%Fw#N+_5R(Gb6M^otP9CffFX`P8rr(T4cth{*qP6yDGs zBdh0PAx$FM_I{E7<)yONuse?WEm+C_swh=_1d9Bx5>d-XJ&T7R?;LnuwEg^*@FD+8 zg_Q8IGMnnualrgV{#SXpDcawm3vP~O zo8S9gKP%+#&PQl^K<&Sfd-70CZ8p^^XPG|2xlzsUbuJUFY9{I7`2Y4rD= zzxGb4_w|hv;M4W`#tHCw>z{wUu0on&Ta=vg(2ZOA@2j`pnBntG<(IHna+Ch6_9T4f z@k^ECeAFPHsH%{%eja}M%hl+R#i{&y^{d}7L=Qjxm5a|!aXb{CdHk{pnL#VBRjZ$V zzrXM|+G%4dzb0fjpF|<2tibYh&UsXPwE6he%B3Fizt$X|xxNumQV9u;{8A%Y=bZb6MR2H}s0OTl z;FI&guY?bNMR3%QUkM!NgI^IP=C6p1_2btXKKK<;!mo%7e&u9JKKK=}!mo%-SwDRL ziYVFqj$a8M!J&Q$Cj(<>+&c>c_8~JoDE>I&~6%Fw# zN+_5R(Gb6M^otP9CffFX`P8rr(T4cth{*qP6yDGsBdh0PAx$FM_I{E7<)yONuse?W zEm+C_swh=_1d9Bx5>d-XJ&T7R?;LnuwEg^*@FD+8g_Q8IGMnnualrgV{#SXpDcawm3vP~Oo8SBWe!0}jDOL3|IiIfA=gI$C z8svX15_3cvCI72MME+OHr0OC6s{*1$O;z?J|Eq;#eEd?_)f!_@je1|-Xis%6 zOG&Rl{#OZ&{4b|L{+Ibh{@3EcS)Js6MPyE+zxVvLcS^mlZ(NqoFaOHd6`}IQ=U=<* z4|ZB#e7auWxYWn~;ZMJ;*qwV3ML+T8Jo!!Y{C)4cf9yriZ+hg}+js81c`3X-R-VeQ zIrFXN@vF?Y!mmXg-uvuJA~OjbeZr~yS|m2MbE^4kEQ-Z=|9^TYh34jIL-96Np;Cx2LV-8S2WJfl5%X7q$oR-FHImiNc1TzRMN97*axm3W7*Xq@v+7$xB|6j)b_U4Yr{(DULH@Yn7TrBMe|*9FQUp5QOq! zkg+rYlzxF&L>h=iiVOptQKo?k);3@y8KsVON~dG(mmSmoH}}5vX7}w)UNZaMQqE3p z&fRnO?(X~T`R~1N341hrSYKXn?D%1Qc_Ctbd65x*@L_#v5b^k>frBR2SGRmvUm8TL zFAW^lmmZGb!}`)tVtr}gi1@+e86gBv`Yo@_R$yU$X)ZnMO9KZ@f)DGv0{CBkx}D^pU-s?23#=K#rW>u^FviuHYG>=1e_1x`1kh-od2sQIEgP>_=g}t0Z@7G=;{0DRZ_aRX{x2^w{~vz8$FI03At8}SF++3zShxF9Tz!4o*ze~X zahIm5NyD5=c2#jHxli| z6?;By94LMH^cnlITM&wkV z^{~EF8tyvl%gsdfu)b6p?mFws%|!LEzEm3SI_t~LMD?(~R2uHOtuM|`1QhOt^MB#- zseTbbrQhaCZUrBFeAbs+T<~!IFZVrJ^#D29Agye7Qgf z0hE5rE3*|?SYMh;&-&89L6hLa`tqX0`tl+p{H(8@@L_#f^aBM!TFE2_wKlCCa z{H(8@@L_#ER)ZydE>!OHo+9F!b<0E+W}sfgTs;E8z)vYkns z7bSlD((vK@UkD@(9}#AOnmQ(7{Nnsy>g`6UbN(*{hO??BDso5+tDOJK9*j_N@ZtPl zDjYW-Oo2em8F0Z^7vsBs&kt2u*_0gd6L3C&AfZ+*6%+DPa$s|4W6&`M+!$ zoc~Mci}QcQyg9=eZ~iYkf6Ajz2jYDNiGP0RMG}6%5y_kIyR7!o#gG1@**Gyxeve;q zeF~Ki5Med0?tX0S_w$Xo&ROMCzT{tRAAA~DcRw}`l)mr*1tKH@3qtVVd;+B}KLVhS z`wW!6`uJJ==pHnE`SBV1vQO5Ro*wI~TRy%%pVuEf_^qrj{WW5Jb<2nKr9s5{(!fCz z>#JKntS=2B)|Unj>q`$u@L_#vD6zgYa76szkADzCoSz7x;$Ara7h*%dAc`u=uTIII z61l?|Ioz;HMfrfM3?n7Qa4qSEX;jW$H2eO_ngu&;M)N0IAEbt1d(65ymGt$eUod~0T1A6D+GB3cewecM?=`o#%%goxjpoqn7t@K1 zBj(X-R?zv$ubUHYUPINNy=C^Bxt`ulzi95rucJ@z`iJ@cCtGM^M}Jy6dMh;>skD81 z11(NTrBv1lrTJ-DwC}=hI(P9lT6g=;Y4^u@)cm!5^xkVF zbpDO~^j=CiwT?bOWBxpg+H;y{)xk&T-qu&B?i)+V3?HJ7?W^gv+h3(8XKkc`*@tPt zre~@B^kG_cYzM7>_b{C<{29&3I!v36?xhLK4^hEW2Z{dFL?@;np`2Nb^!(i?=$+rZ zM1%f)lBS>DO{c-LC=i4Kx?)wr-wSu(|uokf|`r|K;PQ7jP`Y$ zrSt8}=)cvcsp9WX(Dxfok`)iBWA2z)*UvDlqKk(-XFTMUnUmv;2g9hr_1|O~MiuNX zY4^fbW8JdzVH;tW!X7n^$ST-o*tM`Nup41NMEe%l4%n@*gUN{e5H<~V8|-x`&!db) z`7ufc$}W_#Xx{@n9_1yJFv@-ug1-^=nku(c?MP*$S63g0@|!zi0khqaCw z`4!f249i;k?)1M5YxP5kG{GK&{RPVFD0{Jf3Kr)Rc?GD)J=Yw8IDso(VK1*7Npv_^p|#kw78jf zE(4_N#pu$xjF9$vX-7&s zO4=Kw9WCvR(vFcfL)x39&6GAv+MA^vEA5x0y+zt_(%vfVZPI2-J6_re(oU3ilC+bh zog!_Hw7Jq+aq!~VH!FLkpMu`$=Tvj^)KkqfN*e0xOHePtsZ49AA2lr$3QdE5T6J~x zG{cCXz5)JvtnWhG0r-x=*9_k|_&$K|Z}1tV)zyPaPc;uI4TY{P#ePZ+BNM)H@J)m- z1Ya?HrSO%(Hv_)A;F|^C1MpSDHy6Hz@GXHag8C}>*I<1e+BU#f2j3R>egI!ReA`Pc zZhu*}p{-Z?3HMz;#$~?r>HbrgNPgCtW_<6doAN;1D!Mymy7Nw1RAvt8a;J>{vi0fs z#a_qf`>(hXm(Tron31bQ*JD++3v1@jD>El`39sld>uE!&Ry>_~?xDM_k=H8T@tkSo zC`X*!`4wtmRc+1exiyc^UWB9HUsG9TPK@gWa*D#?P+?(lZb5EwVL?t|ZhojBr#L4k zH!oD27Y^qa6^4t@USOT&uMhk)#TxIdQc>Q|I$8Uh-iz6#zpuii!79-)+-es~*YACk z7tERK?7w>I`=hM6g;kuL3b=v3Xo$2Zwa`sjy3tfA+WVw3hJA11` zX4l^BV_m%w1YIw>_nD8p#nn6P?5*C!yB_#JV-&RFn_woX`(NZ)Q6vcDrNOsw^~+7%>zQHA9(07Ga{%*~sBfq(wj6Mu5JdHmJeWBP?3e{k;NM`w@Tz3~1s@BZ}czdU#Ny|<1oTzu=D zXWsbm=-r=uaN`>n&;9trcYpHs8%O8f|KP&KH$M9P8xK!B{`jlE8Wtwu`r71W5 z@Fy3}9{ux6Pu_U=H(vc-Xr4X1{?+T^@vVao4}a&MZcg2`IXe8^KYVHP_)EY4(seJr z`O=$5hbJHZgUwG~`raRW|9dZ8cXW8ezkchj3qSeExwq1pKDhCpU3~l8#dB}J7}s;- z;f+tca(L6x;mxlc-tt?g|KRBC(YeF_?JC6?k(^n4fdi8hWglB)VJY_gq@x)L*S|@1+&) zyR^dnM~4r*a`@nH@^S9q-48CjeeUp~OG{kN%0GGkuXD2fO-`OW{C+I@`$vZl|7OuY zJ^asJ`re-&K5}Wn|NQ9izj)>F(N|M-&tE+I({pdU`}W~uSFQN+h4=sEU#0o+-z<6h z@QF)HK6!b`r_z#7Ut02S9vwdO%Hi+5dP6LE^zKj3MXG*!aQN(17y7pk|JJ1ie*f|U z&!q)UUs~XAA07UkR}TN~t2f00@1OhQqh~Ij`&VZ#zJ2)oRZIMx!@qZFiU0EQ5-+4B z{{E#U{=w1VfAz}YfBl;?{AP)_FT8*5@CR32*O?0!e)3n>_22yFy8iCrnM-T_!^>;F znAZG9m)88@(cwRSt! z*7)y^4*%IJhd+At`dH)L_uoGE$A^D-dGe*i{=LIjE=~UDmnZ-CY4ZPYY4ZPgbof8L za`@_p&;016-#vM7`?LS=D`E9Cew4jK@7(-N+@U}IpO4O6NDlwunJ2EgMRB+OcKDNb zkB)wFF75fJ|KR_+H+eUW{GPXM{yz3hRQSDTe|YBk@(sUpgw5uE`GJ(6wzD*pY-;67xO@n83d=E7X)f#Dt?Tdwft zyN}eEF?L3+n^P&fadw^^qbI2lU%<=FXn=^B!2d?b_ zvW3iHOpSTGb{@@(dC>#IJwUdQIqZd~F~`GmY|hM?9=Ns#$QCk(ETYCdUOSKG#k}Z& z;T|Ac$Q;JhnB(C&HfQEc4_w;=WDA+YUWgj=cUGb8ODcnI5>d2gnvOhb*GTJYGAG z=Ec0|f#Dt?TgV*7)R^PpIqorM7vkrOFUI&J#%E_Xn=fLVjrffi=VSaVMvv$AOv|bZ z*+S;97ox`c&$s@!1ydf6@qUc|EqL>P#z?jOJRZM|k!t&Y#N+=L<4+)vzi z$QCk(ETX38Yw>Ky-y`G+nUjnE_u$a~6XPIQWNytt3lESjWDa9$TAaZ(r}6eLf+fF> zkzQZrn3H?{jhN%>vT5qHru%_xA#>OZQM0DpEbUr{_CM4wEf-!-A1ozX$Q-hW8tc|a z-D>MVw&dd4J)FM`ue7Wq*+S+prl#dtTwA~DfpvL+Y$0>l3sIv#*5wcDZM|E1fNUXi z$RcW5p2fBGx*k}U2gnvOhcPw!V_p8R-qyRN2gnvOhrJLrEzjcGdR-5!%L8N!nL`#) zqd(T=59@8cTY7+OA#)g0)AB5?t=ILyx;#L(kU8vysL>zm@`v@d-Yq>qwvahw5j8E( z;@Wy$53I`rWDA+Ym>T`DE`L~W>)p}=WDA+YUWl5OXK`)4t_RlT0kVb6A&aQdAM5gm z^|szEJwUdQIgF`kc^22!>v~{a9w1xD9QH!g=#O>z!+KlqmL4Em$Q-hWnwDpAZN07s z*5v`Rh0I}0js94dKdiU)Zs`HCh0I|uL`}=HxVB!`1MBht*+S-!Mbzkzb@{`3Tkn=0 zAX~^B#?-Vti)-t3J+LkhkS$~mdm(D{$1?o!bo@Pw^!EqTqct@L`|<$ULgtV~)a>h= z?puG4q`yCy{`O#cWW0@kPk-YpJ(_28Fr^2`7BYu1HB+9=z3T4;a;7BS$|4y&;s1xo z7BYvu5H&KPo(ZjUSi+eSjjz%AuXSrLwO*fWA#=zgYFeMi^>_1p2~TP?Tl*sWq6U2t z*+S+prba&O#)m2Mc5nFPLX7lS!<^h)S=7G=ru19QUStcI!(ND*n!TJmy>DBy$k%Ao z*K|qu5!piKkVVui>Dt$JExCSXtmn7UZym%)k88`V*SlNI$rdt)F*W9Sw>42dZXui zlWZY#$RcWbzLqtgEivbYV9$LqZjJFsjOPpEuVe1bp?xq0xzQrt#vTVT(&L)z<+Wd` zKiNX&Fs8=5^?Bd0=NZbMZ!Yuap&-anV~V)$uZ~7;6wU3*7V5F(Q^8l=Vj5d`y#T1%waD?%~I~y zrCkTPF_byfbDbPFa=B~GB448|k40n)nL`#)lk=X>@7EjT#&yw`+!f>T7-UOH%yr10 zq4nk57V*&YsNb(YbNMG*$Q;Jh5=z!`uzO080kBNWJn2fsNvkP zYFg75@wMJq=W(5ByjqfHvW3iHFGNkrnrgm1(>(lt28Oh}_`&Ib=&o%yq2$G<9EFp2-$6hrJLrYs*g$ z*IU9Oo|B(jks&3_p@wt0{?IsmFW_v9^D%N~OP`B98Y8{$J#>Bb^UWFALgtV~)L853 zYn^+IR#FQxglx&h>3c-m7^h=!ZcSX$gK_rykl4_oA%Y$01QkMj`2i{)=ZdkeO`NSHS#>|cu2O8Ib;zv)?(aR@V=Y!e(!BB=0T5*>#?5mNw$zV zjH&7QTIP5*-gmt*VaoF`4TgV*tLe!Ys^4yl>iuc`=_j`-I zt`Ako&;#@U z*+S+priOEk^^zXY12rBXTgV*tLe$jk%MWDzx-Ypj>_fF7vv0NFz3 zFs7zvFX!r2J)j5Z0kVb6VJ}1t=NjuJJ)j3_JV3UPIb;zvHG4T%uj&CkKo5{DWDa9$ zIM-M&=>a`Z;{mdT%waD?P0e1;)vJ0y56}Z-3zJ(4+O6rVS~I#1@qeCUC3JV53!HoxQK z*F2g>J&^Z6jydd+>@|1qHO-y5(*sv~fNUX~`CbrnMn)O?UZNh*12rBXTgV*7)YR%M?1iYQ*~__lRS)O^dVp*pbI2lUIM-M&=>a`Z;{mdT%wbGT&0fyct9n2W z&;w)(nZsU)8qPJ=OL{;L)OdhwA#=zgYHId!u3psxdVn4vTgV*7)Nrn`UeW`4pvD7a z3z@@Sh?<(coU2#$fF7U+$QCk(ETV>Ujpys7XXE#+{2<1~7@wWlY`%zb_L$gO&$re+ z*N$uFgr2OS#GRiz3pJ($^o*%M> z%waD?jkzt)ZEv|ELvozSJlokV5;f+wJh$emJXd53nZsU)8gpBo+d1ay z`_UVnj&TrUj_3Ex^Qs%!LgtV~)L7qn)z^Aiubw?XwvaiDspE;50EWn4p~G^&)4GFyw~)=ygWd*kU5O0vA*-Ful2HCJ$ry`A#>OZ zQPcCacsB1fJuoj1kS$~mSwxNXomYLWm-Xt|17r)C!LgtV~)bxBUp3Qqr56sI0WDA+Ym>TOluliaq>(#Rd$QCk(y%04$ zUyEn+Ueg2f@&MUF=8#3ySl@Zo*Lqp6o;^UekU5O0>G@hboA;U?n3o607BYvu5H;3! zUiGzJ)~ja^kS$~mSwv0G*W%f{*Yv==JV3UPIgF{XzVoWD^|D?)dw^^qbJz<})AO}> zHt#h(FfR{~Eo2T^M2+>GSADIQ_3GIJWDA+Yn3|ri#j|;@>4AB9fNUXi*b7l(edkr* zT)m!--!Gs3_Gx;|X?)(?wDthmLgtV~)U-a2>$mg#ZNZxNW28sM+xYkN_b$?-`8Nks zdVp*pa~M-I<=Nb;{$3zwO5&|7lED-He~4@$bJz<}BNOVG&^m`DoGH=x8m<3YxAs!& z^~n}8hb*F|^?6)>H_w;wq(-x~FS0Lc&=-*{WDa9$u1J#ejEMP zL5%dcw%mHXyVaa*A#)g0W1e@*b8mTLUvx|G;>{Sh$B;$KsBdq6%bka8A#>OZQIlK8 z=lAQ|FVAc?Cxah}D>d<0{NXyjM%%A9dcHTw7BYt{qNe9-S@YQvb8ZOs+!y247>~qw zzA*ke=H49I2V;;ME#htLaS$UtuDM=b`=$DmEo2U3YRp@o_YHfVq5S#gGJhTlCZss^ zQ1`@W!5^-f7$l4O^wU)LIoU$yuot3cs&l!|Fkja2hrIeK_>&lMY6AX{MZQKGR_~?U zA7l%eLl#l9l}Wl7A?CkB3sBD_CnMw<$hh-b&wlFnL|C-$#El>yVfl7HQMr6M7EGQ zWDzwv@A>?Gy+LkV7k$ZHF&>XWwv@zNhx{2@U(Rh24?U0i{rWSPf3k(lVN6YK9iN}3 zz8?isK8=wcd0(f`&tHp?zC%cclrV=H&K;|!HGL6Z>y33D*O|tvC3z-W$Q<@U)Re5L zX59Mbm_zON?vWVOuPlm=^=UQj?xpBR)#(a`3 zWDZ$G%^Gvm@|r)1*EZ?>l3sJMS{Pb|WB`o4O`MDJtQo+*H=H^oRKYL4p~HvwVuA#xz}hVwID;tmRy{^N3@M`ItJ&~#3el# z*Dtv)HPidBMb60F3;Uj5QvJ!Qa1;<5KJA zd1n1k?uWVOifkcs*b7lJ_v`KL{JigSFPsC`=gelkOwf9yd&(n^FWDA)? z7Exm@#;pbKyD9JY-u7Z1^w_u_>p7of3z@^1nx3y^j%VY2*BcY2JP-5marAcSJ+Cz8 zSX0kjUN^FZ%waD?jkzt)ZAq?p-%WYHx7h3Y;KivJPsQNtL|$V_T#`36%MWDzx-Ypj>_fF7vv0NFz3Fs7zvFX!r2J)j5Z0kVb6VJ}1t z=NjuJJ)j3_JV3UPIb;zvHG4T%uj&CkKo5{DWDa9$IM-M&=>a`Z;{mdT%waD?P0e1; z)vJ0y56}Z-3z;JwOkTEo2U3YB<+eFX;h2P~!ozh0I|uL`}_J&ef}WKo8IZWDA)? z7E!~w#(GH)=z$s!kS$~mV`^&la;{$01A2fSAX~^B_Cl}6??%5es5jnh%z-)31G{_R z3Rlu2nL|eLdE=||WIoJ?9vH_1WDaBVJ5GMhqj}T=c@N~6!yd_AbN61;+?hK)aJ2`> z7P6V|1uH$4a;{mdT%wbGT&0fyct9n2W&;w)(nZsU)8qPJ=OL{;L)Odhw zA#=zgYHId!u3psxdVn4vTgV*7)Nrn`UeW`4pvD7a3z@@Sh?<(coU2#$fF7U+$QCk( zETV>UjrEcq&;vCdAX~^B#?;j8%M?1iY|Tw}eY2lPOV2gnvOhb*F| zW-sUJRXv~w=mD~Y%wbFo=NjuJJ)j3_JV3UPIqZd~soBf9eR}o#@w*RB$2f@b*_qAe zix_9W6I;7JYd810kS$~mSwzj;uh;Wmx{v-W81t7g-U`nAG9JH<@w13OkH>Fgq&zVu zm&~Co8p{J@3z@^1nz8nEo&9>4JRxUF;=c$!od`aik6|6nL5&B<7BYvu5H&S>Ikz9L z*6`=q;LZ~G@#NiFYHvW3iHFGNktv$%HKTAN?<+nWc- z7BYt{qNca=dmis8JuqJnkS$~mV`{ARd~0p(tX*#&AX~^B_CnP3c7D&}J*5Zc>jAQb z%pr@YvDWjgwY9T$y?KCaA#)g0)7$wykN1=wn6C%O7BYvu5H;3%zO}Y?)~+`XkS$~m zSwu~5=l49`Q+i;&9w1xD9LCgG>-pB&+F85aJV3UPIqZd~>FxZU$9qZ-%+~{C3z?W|pI9w1xD9I}X- z-p=oNyr=ZQd_6$6kU5O0vDWjgwY9T$y?KCaA#>OZQPbP`J&*U49+ z2gnvOhb*FIU*~k+`gCrr!gDE{gwvaiDshRR@?p1#;kTWIm zRu;+N3I9JtwvajOg{YAU^-O4;!xGMvXnc*Ql z>3!RpMZQLxzNSmMkH{7>hb*FIN!Px%YsvL9V?Do(e(NAcdR$v>z24nwPPULajHxlt zyXCpJysjN4<#qGi;#H^1f1L$;7P?1iYwt>g3i_3f8uHk*^dkHnRlcr5;K z9bcpE*Bd?Gn`8@_Ll#lf^R=w`Y>7EH1bgm_achi6Vmx0Me;spg4()?6$c+~9HugA( zksjAvFR%Sl{mB+GhcPwgtOZQ8U%K+-I0CYxqN6eHHvkj5sv`f5;+VqYbO~Qtl73h0Gy~s9DN&FYP+U;t$s$ zAEu1A_C>3CZA!L~IgF`U+I_o}>mfJT&kT*ZPL4Tu1|QPTv8G3Uj+WEcJTHru-4~H9 zWDa{FYL;@pF6}zVjiJn;p6leek;`3c7Wo=&c`PDZ$Q-hWnwF zBtuG=Lk;JSRnwZjh_Cg=I*;p2JcYeRIqqe;AV?WJ^iRxi19E zUX1Z_jInAultp9h>pJ7raLiniEo2T^M9r9cyH=Se$d;0r3@Kp_H8%xo()WO#i*X{x z9Wfq`(V|wlYiY5UYqqIjZC=S1GKVoWwfi|g?}MRzPVWA#;SX8Fb*x*yZsun9+>k9~ z4tpVL%=PZMzEXne@=Ugn zIqZd~SzCU3xZV;L@tpkJiVP`X4mF(1^@qmkdjV%-oR5(^Tl!q=(HQA{@1g6fpKs2{ z7BYt{qQ+WJU+dg!w31qoA!JJ~PTwQi#yA~=b8F&~9*pakT$h^Zeb^%BWDA+Yn3@)6 zaLsZry%St`FGl+LE5^KkOXBo%?l;C755(Z_-^g*P_47Qlekk|D+;c^?kU8vysG0lq z_I7^Wce$9XNIzR~cZ?@uv}VGT>+{-stC8nv$3wD(%pr@Yu@>Xjg7@8&_j_-9F%Nod zT#xmfPqKx~VN6ZW*D}Ym@xJSg2~(bjdH6VbyY!w{8gs0vXD+WB*+S;97ox`8mglx4 zSG@10yx&{wb$#&SRE(!$@O2`uu_P|Zo0@TbxUYPYEo2T^M9sd=xzv4mKek{(ZcVa+ z??3ZALu0-lzSMeoUE^|(Y$0H$4K50EWn4tpVLIM-M&=>a`Z;{mdT%pr@YsoBf9dQ}hT z0eXOJA#)g0!@0(KNe}3O8V`^yWDa{FYHId!u3psxdVn4vTgV);h#Jl{)=PRo57c;o zY$0ko&;#@U*+S;97ovu9jrEcq&;vCdAX~^BvWS|Ry_~C8^?)9r2gnvO zhcPvrYpj>_fF7vv0NFz3uot4HW-sUJRXv~w=mD~Y%pr@Y;ap?AqzCjsjR(jUGKVoW zHG4T%uj&CkKo5{DWDa|w*W-7iUm4UJZ#L$@9O!}FJ#d99>5)p;@>=0gvR z;{h^Vdoma?D|mWUsk%MWDzwrdpTFH>H$4K50EWn z4r6LK*H|y<0Xko&;#@U*+S+priOEk z^^zXY12rBXTgV*tLe$jk<=j5K`q`Py=8G6-<98tB;tTQLK8W!rF|4CG7|R1>3zO`>W zyuFaUV5JAh7BYvu5H)MQXP0#CHT+pp9=w+Q_HtwknL`#)W4-oUud(u<-p{!hfYWfdSF=|AX~^B#?)B_lh1^ zmIufdGKVap#`-U-{?^la?$ZNg3z@^1nth(ty}eiTz_L6*wvajOg{ZOq%c{Tiw4VF) z0NFz3kVVw&^Q`Xey`l$}VB5JJvvg&U=t>->HK(>%MjH%h@S>4-vMGq{?17r)C!(NCQ>%Xk}TTkn`PY;kS zWDZ$G%|6fS-rg&EU|Aj@TgV*7)L8#z)!%wr&wYA;Y$0>l3sJMrv%0tUiXK>&2gnvO zhb*GT`Y)^g*3)|K(*tA+nZuZxeV*05y;tTSxIo-GZ9=R=8^L~u<$aow7eh?!)nrCw`r3c6sGKVoWQ=ZMe>hA?| zrX=3VA{jj4|A)vHGKakoH8P=|39WNj!kH3{uhIIib!#uRUY~3sbI2lUTA#=Dck_G+ zPiiz<`y%_I27M9PLgp~0Mn3Guhbi-RZ}=qrefRWO!<^h)S=7G=ru19QUStcI!(ND* zn!TJmy>DBy$k%Ao*K|qu5!piKkVVui>Dt$JExCSXtmn7UZym%)k88`V*SlNI$rdt) zF*W9Sw>42dZXuilWZY#$RcWbzLqtgEivbYV9$LqZjJFsjOPpEuVe1bp?xq0xzQrt z#vTVT(&L)z<+Wd`KiNX&Fs8=5^?Bd0=NZbMZ!Yuap&-anV~V)$uZ~7;6wU3*7V5F(Q^8l=Vj5d z`y#T1%waD?%~I~yrCkTPF_byfbDbPFa=B~GB448|k40n)nL`#)lk=X>@7EjT#&yw` z+!f>T7-UOH%yr10q4nk57V*&YsNb(YbNMG*$Q;Jh5=z!`uzO0 z80kBNWJn2fsNvkPYFg75@wMJq=W(5ByjqfHvW3iHFGNkrnrgm1(>(lt28Oh}_`&Ib=&o%yq2$G<9EF zp2-$6hrJLrYs*g$*IU9Oo|B(jks&3_p@wt0{?IsmFW_v9^D%N~OP`B98Y8{$J#>Bb z^UWFALgtV~)L853Yn^+IR#FQxglx&h>3c-m7^h=!ZcSX$gK_rykl4_oA%Y$0

1QkMj`2i{)=ZdkeO`NSHS#>|cu2O8Ib;zv)?(aR@V=Y!e(!BB z=0T5*>#?5mNw$zVjH&7QTIP5*-gmt*VaoF`4TgV*tLe!Ys z^4yl>iuc`=_j`-It`Ako&;#@U*+S+priOEk^^zXY12rBXTgV*tLe$jk%MWDzx- zYpj>_fF7vv0NFz3Fs7zvFX!r2J)j5Z0kVb6VJ}1t=NjuJJ)j3_JV3UPIb;zvHG4T% zuj&CkKo5{DWDa9$IM-M&=>a`Z;{mdT%waD?P0e1;)vJ0y56}Z-3zJ(4+O6rVS~I#1@q zeCUC3JV53!HoxQK*F2g>J&^Z6jydd+>@|1qHO-y5(*sv~fNUX~`CbrnMn)O?UZNh* z12rBXTgV*7)YR%M?1iYQ*~__lRS)O^dVp*pbI2lUIM-M&=>a`Z;{mdT z%wbGT&0fyct9n2W&;w)(nZsU)8qPJ=OL{;L)OdhwA#=zgYHId!u3psxdVn4vTgV*7 z)Nrn`UeW`4pvD7a3z@@Sh?<(coZF{YpN-#r@Pil^V|;dIv-u*%+3&;`;@>}r@h35? zqd6GM17r)CLl#jp*1oQ@Uk{Tx|1Nm*WsHx4EuY8Zw=q(E82=)k`*nzkY9CD^4=G?K)<2uXm)zCVUEo2URA!>%Muf9)Tks&3_q2|w`5Bkd( zZ;kl>L4DGvPg>W7Y$0>VB5GQn$MvW2VR}C&z2Eam48FD^XBa15{rea{mN~xu8qot} z3z@^18u>5{ANG}J_C@wN%dYjlJjQ*=7BYvu5H*}@tUvXD9;opE*+S-!Mby;n%MjH%&VW4)vY^gxXV$QCk(y%04udpTFH>H$4K50EWn4p~GE=NjuJJ)j3_ zJV3UPIgF{P*~__lRS)O^dVp*pbJz<}!@0(KNe}3O8V`^yWDZ$GP0e1;)vJ0y56}Z- z3z@^18qPJ=OL{;L)OdhwA#>OZQB$**bM>ko&;#@U*+S-!MbvPvv0l;xdZ5MwWDA+Y zn3|fsoU2#$fF7U+$QCk(y%05=Ypj>_fF7vv0NFz3kVVwg?B!g&st5D{JwUdQIgF{{ zTw}eY2lPOV2gnvOhrJLrHG4T%uj&CkKo5{DWDZ$G4d)u`B|V@AYCJ%;kU5O0soBf9 zdQ}hT0eXOJA#>OZQNy{$dPxuHff^5xEo2T^L`}_J&ef}WKo8IZWDA+Ym>SMC)=PRo z57c;oY$0>l3sFeKNzRMOwyNsrdW9PG;jWDA)?7E!aWbGmQ+J#t&H=KUDy zk?}VE{UAnqG|%Q>N)M1NWDa9$raYT_)!z%`Oi8?zMKXB8{|}KZWDa{FYGgt^6I$o6 zgfk@?U!(P3>(*Xsy*}AO=8#3yv_6mP@8*pvZ#L#OzF3py~q|ahrJLrHG4UCdf&EYk+0FFuj!KRBeI3eA&aP4 z(zUPcT5|o&SkG^x-#Unq9@myzuXnealPzQpV`|LvZh7u4Z|sY130}Mz-hYBef#B^&E{nABXOlB9*aL*$Jc24^+wP4CfP#fkVVw=d@XA} zTVl=)!JhkK+#2JN7|$2RU&q{=L;GM1a-&7OjXe%xq{lVa%WJ<>f3k(lVN8vA>+`;0 z&oh)i-(2R;L&1a;rylB_7%lk2H4}qmQJ;RA>OLo1$Q<@U)J%0Q_ZjBP8vc-1Uj=^> zBTh}gAF{~TXv6Bgl>38hA#=zgYL;@{OS_J-_``L`hbiN&ebH)Oo02VL4r6MTcHb`L zddLm-GecvplVi@E!H4v7tm%=TqviB9&^_eEq2nZsU)nx)*YOS=woV<>Z|=Q=rV z)~wjq9Q>xhuxwG02vZnCp-~L+i`AE#jf)QNLe* z=JHRrkU5O0$*tq_)71B)V9KX4(j)Kd^!fQ~G17Mk$&eD}P{X-n)wHHB;%mLJ&f_}M zc(o+YWDA+YUWl5KHPwt;-yCzuAI4+|*-{d7?hC=P7h}8}W2~AEWzkssy3Tkt95a_> z3zGVw{L^M~sJKw5V0?T3YPonr&)Wn^&@h z%wbGT?S9VB`(S9Fle>Rw_(K+P9qX2_o4MINH)IQ$!(NCQbG>`6uam_rtk8|2B* znCo2Y>^?WH7uJ|hvW3hci>O&+j#^&xC-K@Qy`P*O$&i|u+!)Fn>bXwK9Juy+IYzdS zIgF{%E7N#oD1Z1l5xK$lbI6vGnCn>gY3jbVJd-VC4tpVL)|Q_huD66mJSRW5B11}; zLk;J0{h@LCUclKH=VRo~mOdAIG)8*gd+7S==bJOKh0Gy~sIk`5*E;tat)v!Y2-%X0 z)AxwBF;2(e+?u$g2jluB*QI89AGXLj*+S+prl!RiT(jIu?*td#i;;f*iZSosk~saG z`;D>212OpfH*#ER{XEaCAIkkO_gs-JWDa{FYUX~uy`7);T`ndo($7}h9pi}@t(h?8 z`n>kuYUFv^@sMmGbI2lUti`ys;C(mc{odPN%!3{q*JC~BlWZY#7*o^pwaoEsyzhEr z!j$J>9zKrVF1_cK#vE(vnak@&wvajOg{U#N<+&}%74N$#@AnpaT_3zS72~NGe4WT^ zEQw3A9;p5MXa_w<%@ya$Q;Jh)a>P4 zy{ZTF06jpqkU8vysNq~=y`%^9K#d2;7BYt{qNZjq=jv5Gpam@y) z2WmV(wvajOg{Z07%ei`059k4UfNUXi$RcVu*H|y<0X%M?1iYQ z*~__lRS)O^dVp*pbI2lUIM-M&=>a`Z;{mdT%wbGT&0fyct9n2W&;w)(nZsV__4wWB zR|fUQn~gaz2YO(44_x6&dL(nmC_Zm|b)L+J`OpL7c!11dY<|bduX!|&dLZwC9CO$s z*=z3JYnnTArw6X~0NFw|^SvPEjEpk&y+l2r2WmV(wvaiDsj1n^xq4L(=mC0wY$0>l z3sJ+l#(GH)=z$s!kS$~mSwv0EUe494dO#1*17r)C!SM`7%pa;knGKakoHJod# zm-K)hsPO>VLgtV~)YRy`%^9K#d2;7BYvu5H&S>Ik$hW zem{N>!s!?XF+Mx9*?bY>Y{Y!tI`&`3xzvbkA#=zgYUXlXp0oTO`8UCs{}AKH!I@vi z<2Nxrj`;I<{5D3)C7-9>JeTL$T>W;g$QCk(F*WA!w{tl6octmf^XnMrzQY{yhcWeY zzjn{RUq6#AWDa{FYOL3O>(wIvS9+VD74nDr7Uyxz<#{YuQ?iB3A&aQVt>g3a^$g$V zVV{$WskiR)t$Po(BU{KE#?!WVQ$Us+B`tE zkU3-#HEYX{*DDkBKsyhREo2U3YOF=OT9{jNyEYGyEo2URA!^o^AFo#?=z(?~AX~^B zvWOaM(XJNe*4(bm17r)C!!WVQ$Us+B`tEkU8vys99Tnyk4202ikdnY$0>VB5JHfyIPoA zbGtSVkS$~mV`|oxAFo#?=z(?~AX~^B_CnNHi*~h`GPh61-}<^3BRx*JuX~wqdVp*p zbI2lUIM;YyUb-z<^L~u<$aow7p8no@dbFnIU`h{=Eo2U3YNkA!d)40y+k0I5}wp(w)RE# zMGg8QvW3iHOpScljSo}i?cVUog&66vhB>*pvZ#L#OzF3py~q|ahrJLrHG4UCdf&EY zk+0FFuj!KRBeI3eA&aP4(zUPcT5|o&SkG^x-#Unq9@myzuXnealPzQpV`|LvZh7u4 zZ|sY130}Mz-hYBef#B^&E{nABXOlB9*aL*$Jc24 z^+wP4CfP#fkVVw=d@XA}TVl=)!JhkK+#2JN7|$2RU&q{=L;GM1a-&7OjXe%xq{lVa z%WJ<>f3k(lVN8vA>+`;0&oh)i-(2R;L&1a;rylB_7%lk2H4}qmQJ;RA>OLo1$Q<@U z)J%0Q_ZjBP8vc-1Uj=^>BTh}gAF{~TXv6Bgl>38hA#=zgYL;@{OS_J-_``L`hbiN& zebH)Oo02VL4r6MTcHb`LddLm-GecvplVi@E!H4v7tm%=TqviB9&^_eEq2nZsU) znx)*YOS=woV<>Z|=Q=rV)~wjq9Q>xhuxwG02vZ znCp-~L+i`AE#jf)QNLe*=JHRrkU5O0$*tq_)71B)V9KX4(j)Kd^!fQ~G17Mk$&eD} zP{X-n)wHHB;%mLJ&f_}Mc(o+YWDA+YUWl5KHPwt;-yCzuAI4+|*-{d7?hC=P7h}8} zW2~AEWzkssy3Tkt95a_>3zGVw{L^M~sJK zw5V0?T3YPonr&)Wn^&@h%wbGT?S9VB`(S9Fle>Rw_(K+P9qX2_o4MINH)IQ$!(NCQ zbG>`6uam_rtk8|2B*nCo2Y>^?WH7uJ|hvW3hci>O&+j#^&xC-K@Qy`P*O$&i|u z+!)Fn>bXwK9Juy+IYzdSIgF{%E7N#oD1Z1l5xK$lbI6vGnCn>gY3jbVJd-VC4tpVL z)|Q_huD66mJSRW5B11};Lk;J0{h@LCUclKH=VRo~mOdAIG)8*gd+7S==bJOKh0Gy~ zsIk`5*E;tat)v!Y2-%X0)AxwBF;2(e+?u$g2jluB*QI89AGXLj*+S+prl!RiT(jIu z?*td#i;;f*iZSosk~saG`;D>212OpfH*#ER{XEaCAIkkO_gs-JWDa{FYUX~uy`7); zT`ndo($7}h9pi}@t(h?8`n>kuYUFv^@sMmGbI2lUti`ys;C(mc{odPN%!3{q*JC~B zlWZY#7*o^pwaoEsyzhEr!j$J>9zKrVF1_cK#vE(vnak@&wvajOg{U#N<+&}%74N$# z@AnpaT_3zS72~NGe4WT^EQw3A9;p5MXa_w<%@ya$Q;Jh)a>P4y{ZTF06jpqkU8vysNq~=y`%^9K#d2;7BYt{qNZjq=jv5G zpam@y)2WmV(wvajOg{Z07%ei`059k4UfNUXi$RcVu*H|y<0X%M?1iYQ*~__lRS)O^dVp*pbI2lUIM-M&=>a`Z;{mdT%wbGT&0fyc zt9n2W&;w)(nZsV__4wWBR|fUQn~gaz2YO(44_x6&dL(nmC_Zm|b)L+J`OpL7c!11d zY<|bduX!|&dLZwC9CO$s*=z3JYnnTArw6X~0NFw|^SvPEjEpk&y+l2r2WmV(wvaiD zsj1n^xq4L(=mC0wY$0>l3sJ+l#(GH)=z$s!kS$~mSwv0EUe494dO#1*17r)C! zSM`7%pa;knGKakoHJod#m-K)hsPO>VLgtV~)YRy`%^9 zK#d2;7BYvu5H&S>Iajah0X;wukS$~mSws!z8ZX;RpPkukzKC%)em6@lem4Hw4`N)5 zp&!h_P!EtTWDa9$hOV!EUY;apJ`eVM8za>)7ymr|`>$fW6`G&L_&CO=F|4~eDDeQ< zLgug+qNZd`HS_h}Q2vlhoT~@s>wzh2N4AhTWDzw}p3S|c_b?ekwv@zgMBj5hM(TsC zojEA+0NFz3Fs7ztO*PB#UXDe-jMrOV$4H!^#=0+~?o-y0Y$0>l3sE!W+1#riKYu@1 zb2`R>y^X!yh#nwY$Q-hW8kx`!6Rd@`n7aqa7BYu1HFLjS&+k2}2m0{<*+S;97ox`6 z^;0`*VJ+tF0kVb6A&aP)`}KN$?^!+2j|a#WGKVoW)~=u0Sqp11cMp&)WDa{FYUX~u zp5J>`5A@>!vW3hci>R@7{nXA{Sc|!PfNUXi7*jL%>-GHJvwEN(50EWn4tpVLtX)5~ zvliB3?j9gp$Q-hWnz>)E=l7n~1O0e_Y$0(yr`tbnSLgug+qQ=_wQ#)&6 zE#~e4vW3hci>R6V^?H8qSv}B?2gnvOhcPwQuAkaj3u`fV50EWn4tpVL=6=1N-+NXM z^y2}th0Gy~sIhka)XrL1i@AG%Y$0p0i^)p&qxA#=zgYHId!?tZ;`Td?N+80nGmHvT>RU5oT+jm*K69w1xD z9LCg4c{cZ|zZb}vl6WhNWblOlA0k`G9QH!g$b@<(w9a7(XG%1_M(e-Ut-aKGeX@nj zA&aPKeID1}&GRKZsnKlhi|mUU^hIO~nZuYG`LG)wrp(*D;gbt7(qj#Ca&u)-{~nmq zZ#8?7Eo2URA!=&&a_;oLZOtNIqfKAaCEZ743zf4*&a_1pi$Q<@U)a2Ij`ThF# z%QKtJ$>2xgN=-Z#f4GjX(e~?&p6^Yvh0Gy~sOkAy)_k_aoEw5Y_rRj$K%$GI%A+Np){v<}6nt(rKk+0E))q5%T2iZdA zkVVui<+_)49b@r_>yQsq##{TM)x0((TgV*7)GY13UCQ;48|-I>##|@IoI8UL>E~F} zBR@yW>1&>sMa%As$QCk(y%04^xnGxd9puJP=1|Xda@@$}t~HB%jkY`%ku78nSwv0F zdp^HkZ;%_;MPG7PjK^b;EhRD6A%BL}mvdXhL(ijrzy8eSpKKv>7*ms5$LFW1??=Iu zPh+G<-q-2#^Vede?+}t9CCs6QbH}P_O<%;6 zFo&9(f;H)TK+nZE5#x>+565UxtK7A;*vmEB)UY&^{-3|JLw_ zEaE!WEnhctvwLpH7BYvu5H;p{_gr5qcVjV!EFw3^lc6!!xz^czZd@;{F`r}$nL`#) zv&I~?yyj2hwM}|IIX#jgH8Hs{lsVLMot8Op?e%huY$0@PX z`(f_6B3sBD_CnOm{d#*lKkvI-Oje|yt++eJ6ERvdVaoM+?Y-5=^R(k3*+S-!Mbub} zacjZ*Zp!<;x4oDLJvOe#dd?@=Lgp~0rsr#!hX z*Nto;bJz<}V{XfHTaqi@cT?W)E%v%TcyTJmQ!)5Dk=Ixfm*h>&xIWxhKFJm`hb*FI zU*}xvzPuk>Fd?@lS;6<8d7hy$-w$7Ey}Yh*xkt8;IgF_>|KsML_c&R>&#X^IKXHGI zXJSxa5~t6&Qcv<&jP!TD(&t@I#;}g&pa&0-Eo2URA!>R!^ODYR6fF2KM#??EgU9db zE$Mo_7P&_ckS$~mSws!z8tWxJpa*I^K(>%MjH#*F%ei`059k4UfNUXi*b7m^xyE`) z59om!50EWn4p~G^&0fyct9n2W&;w)(nZuYG&NbFcdO#1%MjH%&VW4)vY^gxXV$QCk(y%04udpTFH>H$4K50EWn z4p~GE=NjuJJ)j3_JV3UPIgF{P*~__lRS)O^dVp*pbJz<}!@0(KNe}3O8V`^yWDZ$G zP0e1;)vJ0y56}Z-3z@^18qPJ=OL{;L)OdhwA#>OZQB$**bM>ko&;#@U*+S-!MbvPv zv0l;xdZ5MwWDA+Yn3|fsoU2#$fF7U+$QCk(z0m9NyV0)<>Ww!Wb6^hi!0sNn!j<$$ z=8#c*-uUV~nGf@!2gdOLnZwxpj+0;WXdd-I-UB)2ut&1j+`ZQ{cjitHT2?~ zLChH$W$b&2dO#1a$Q-hW znwq_wt5@}a9-s%v7BYu1HJod#m-K)hsPO>VLgug+qNZjq=jv5GpaTpT zW4)vY^gxXV$QCk(F*P-NIajah0X;wukS$~mdm(B#*H|y<0XbRxDi>34P5Z2A4|O41$Q-hWnjX&V8K(F1FM~H<$N1SX%pr@Yw_elN zYc4q_TgV*7)Xe3&JmH$5F^8ndG=CBu{Cby2y>oGl`2ZnlpY$0>VB5H=NuU=2;0X>lO0NFz3 zFs3HAj?e2cJ)j4MdVp*pbJz<}Gjx6RdQuPQft&}(7BYt{q9(VF&+9Qgpa+I}fNUXi z7*jKJef4@$59ooM2gnvOhrJLrxpjPAkLdwDFw_HN3z~0X;C(17r)C!(ND*q3f&HlX^f8%M?1iYwt>g20Ob_URp&lSx$Q-hWnxX5f*OPic59B;RwvaiD zsmZP5^Lk7V=z*agAX~^B_CnMQU0=PP)B}1T=K->X%pr@Y$*tq_dQ1=KfuSBCTgV*7 z)C^r;y`IzqdLZWkvW3iHFGNjl9iN|<$DWSg*PMQre0sEY=3rkQAX~^BvWS{}ozs2m z?~&VrHSfnrkBqnR?*}o`qj@$5Q+j}GA#)g0Gv(RbtNvafXG-F&ERw+!{(p#UA#>OZ zQ6m%Tnb10iC7dbI_!_PMTDSI6>-EVNGKVapruBJTe>cyU@T5kwwJ)+SYS0&vEo2U3 zYUIOie3&wC_l8d{#7K`d%*oA_Mg4nVO25_YMYfPR?1iYQ*~_`p`?fWUe2q4JO_y{Z zku78nSwzi}u6=FSlIv&2dVU-I)l3sI9>$LII!+b_>-HYbB0i7PenSp4BSzDC=xH+sG|$rdt) zETX38YgzNz5_4_{_S_fa))~RnyJ+8T4Ui+o`lPzQp zV`|J>pZ5)Wo}v8t<}!aC3MQmD^-%Z3Xu%(@nHVIC`t;LO_c_@@=CBu{W~y_!&oE!s z@Q1wmD)^HaacTnokVU>m8&>b7+#h5MnL`#)vy|&z+I5V@AFe|_Oc`(Oi&pd6lx!h$ z7*n&f`*tbULvFC285(n)9CPjrKBS*xO^^H>EvK(}UKTC8FCtsW9QH!gEaiS(+I5f{ zLzzQ8*U51sm%G+1@-^D>SVXpvIb;zvIq&)We!W3%To--GT`?YyLAI2{T!;J_T3^m> z5f43&`u+Mdmw&Q_%wbGTZXKVWroJBqQ$CH69(iA<&(B|rk-kGnhLkXe8qOW7rZs&L zU+ax^9@m-1t0j3RTgV*tLe!M3sb<{z=9okNFeXFDmXerrUkH}H7~|y_W7Tvhi^kg5 zb;hgVn7Jfd$Q-hWnlblwtujxLEhRA-Qoy zY*WM9ypk)msGt=x^p z9I}YqAWw$IT<2P6_qlPsu*Q6nEo2T^M9ms=)bg4?iPtvi{p9pWhSbF5#!%)^&vjbn zz_r)QF|visVN8u)nZ_$a`NPkN$PK=qL$;K}T*takQ}?yynQS3**b7m!w*2&Py(KK- zIr+I28B)R=YB-nc4~^6J0?x)bA0v0R^tsrhG1B|qL)TY7-<**xWDZ$GjkTV>*16Yc zCAAgV9=XqxRQ0|Ah=Zb70bJz<}GxzK5?fks&axqzvezxN7 z7*E7#&4ek}=e74%BhS;0hhz(xLl#kEEyk?{@4G4Q_ulqm9`x9_9_u-uWDA+Yn3|ri zWsYa#eb*ZkraTYx@Nx8Z={>JB=2%nDTwXV_h0I|uM2)#E&uvMrc;8KVzqi=y`ryT> z7*ECE>qK5-NnDaQHRJklU-=|k$Q-hWnth#fsr&MNY{7)wnq&pvf983H#(Y0~srB-@ z#^oN_Lgp~0#{7?)f8OI{1wXSs8U4ilF`kJ*eMy`?<4QfrV=>a-`AVO6JsHC~nu8uZ zK(>%M?1iZ5;mk`q!%?u{!x$;|{0<(!r?;f*^;+Z}JwUdQIb;zvoNKI?^nf0y@c`LE z<}jwFW-sUJRXv~w=mD~Y%waD?4d)u`B|V@AYCJ%;kU3-#H8p!VSFh>;JwOkTEo2U3 zYB<+eFX;h2P~!ozh0I|uL`}_J&ef}WKo8IZWDA)?7E!~w#(GH)=z$s!kS$~mV`^&l za;{$01A2fSAX~^B_CnNfuCZRy1A3sw17r)CLl#j}vzK%Asvgh-^Z?mH<}jv)bB*P4y{ZTF06jpqkU3-#HJod#m-K)hsPO>VLgp~0re-ha>Qz0U z2j~H^h0I|uL=EQ}>m@y)2WmV(wvahw5j8b?Iajah0X;wukS$~mV`@0pSTE@TJy7ET zvW3iHFGNkvUe494dO#1*17r)CLl#lPxyE`)59om!50EWn4r6L+_HwRX)dPBf9w1xD z9QH!5$L~hJGN?D+Y|Mc<&;z@B;0jmLBbh@+@pVB5G>(a;{$01A2fSAX~^B#?)}Gv0l;xdZ5Mw zWDA+YUWl5Sy_~C8^?)9r2gnvOhb*FobB*Qz0U2j~H^h0I}04d)u`B|V@AYCJ%;kU8vy zsHxe@xq4L(=mC0wY$0>VB5F9-STE@TJy7ETvW3iHOij&R&ef}WKo8IZWDA+YUWgjb zHP%b?z-MPRn=fLVjo)RLi>Wu(KV%D;Ll#k^XY>p`K+b#~?D;lE`tP}zdah%&yq)Lgug+qDG&r(m~B!m%*WLVto7^7X3V)`&Ep$;`x6R;}2te6hr@* z1G0t8VN8vl(K96;`19b+iC~Pcv-Hbxej!`P9QH!g9JiMLO|R(zJut)rWDA)?7Ev=~ zZMAw)59op8JV3UPIgF_}ZY}?tUeg15V2B6E7BYvu5H&;AR;w5FfF3x`17r)CLl#kU z+*Rxj!SJ#d@{$QCk(y%06Wt>u5yYkEKr4DkTjLgtV~ z)C^f$tzOgvdf+$@kS$~mV``3D%m1d=^ne~1;sLUS%waD?&5*U#>P0=E2afXq*+S-! zMbsR(mj6w!=>a`3!~W<2*pN zkU3-#HOH;xf75GvKo1P@0NFz3Fs5e6+G_Qp9?%2Fd4OyobJz<}bKF|~xA}PO>G<8K z7h|MH>t+u2jEenomT&*orC50EWn4r6Mj zJezyf-wWhSNxYRsGI+xO50Nco4tpVLWI{a?TIaBYGbI{dqxE0w)?RA8KG{O%kVVwA zK9B3~=J^ty)M&Q$MfODv`XaK0%wbH8eAtZ-Q|9g7@X3W3>9K}6xw*2ae-BLQx0=1k z7BYvu5H&S>Id^*Bwq}v9(WbBIlI|n2h0Gy~s9DmrukBiL{mfX;Z=>Hjh>;%GmRqlP zx0;hJWDa9$%=2z}?k#WZi*5;Cycy&67_w*?_3h1Xx$}@MWDa{FYI5uN{C<7=W&FMM zlfjR~m6~`g{%{>%qwUulJ>Q#T3zzD;*C8LKjJNhht9flowvaiDsae{6yOir8H`vb%jk!*aId=vh($BG`M}Cf$ z)7LyNi?Qo%%Ps^~ywTS{WCL;eh{FXy(1hn`3Me*KxtKiNX&Fs3HAj?Yh1-;aVRpTrCU-l01_wWDa{FYD(5rGj4rz%prdm zlObeFNzAz~1j}BG@p6o@YC4ofW9{oY3#2^>#Lt{&d3%rhb*GTT2Ei=+-tOwT96@ROD;~|BihC|9fNag;*uVW>z7=Yn(2Mm zBIjfanZuZx7H4qHaxc9TTzD@=`uQuyynjpL^mFbv#u^XA;P2naajEt5JhOf%_ru(C zMYfPR?1iYA`}OvAe%^Pvn5;-YTXA=cCt|c_!j$Xt+Iy>!=V`}7vW3hci>R>{x~Iho`-q(IC{JEo>v-ktf^-%uN&Dy z=CBu{#@v?Ywj@`)@20%pTkLgx@ZwaAr(*DRBCoL|F3FpkaecV2e3C6>4p~IazRtPS zeR)5&U_x$9vV!kF^E^Xiz8}8SdU;*ra*u2wa~M-&{>RNf?{Tt%pIM)be&YTZ&%~g< zBu<}krJm%m80qhPrO&&bjA0$kK@T1vTgV*tLe%td<|UosC|K}ejFfwR2an&=ThjG< zEpm?@AX~^BvWObaHP%adKo8V-fNUXi7*kWTmvi;19?%2y0NFz3uot3+bB*SM`7%pa;knGKVoWoNKI?^nf0y@c`LE=CBu{re-ha>Qz0U2j~H^ zh0Gy~sNq~=y`%^9K#d2;7BYu1H8p!VSFh>;JwOkTEo2URA!<0+STE@TJy7ETvW3hc zi>RsD%ei`059k4UfNUXi7*oT!#(GH)=z$s!kS$~mdm(CS_HwRX)dPBf9w1xD9I}WS z&NbFcdO#1a$Q-hWnwq_w zt5@}a9-s%v7BYu1HJod#m-K)hsPO>VLgug+qNZjq=jv5GpaTpTW4)vY z^gxXV$QCk(F*P-NIajah0X;wukS$~md!g6kccWh!)EjR$=D-~2f!#fDg)8Zi%ps%r zyz$j}G9Ttc4~*jhGKaDG9Vfr$(LCybya#g3VUJ|5xqGi^?#!JYxY`3`3)#%~f|xTh z%Gmc3^?)9z@c`LE<}jwFW-sUJRXv~w=mD~Y%waD?4d)u`B|V@AYCJ%;kU3-#H8p!V zSFh>;JwOkTEo2U3YB<+eFX;h2P~!ozh0I|uL`}_J&ef}WKo8IZWDA)?7E!~w#(GH) z=z$s!kS$~mV`^&la;{$01A2fSAX~^B_CnNfuCZRy1A3sw17r)CLl#j}vzK%Asvgh- z^Z?mH<}jv)bB*P4y{ZTF06jpqkU3-#HJod#m-K)hsPO>V zLgp~0re-ha>Qz0U2j~H^h0I|uL=EQ}>m@y)2WmV(wvahw5j8b?Id`32{p`$U^F@ra z@jEsd|9L!jBAz=RLvO4z2V@JG!OcluH9dtpUH71_q_aBr?1EsGKVaprnQG%f4)9E7yZp2#rXJ`K1cq{x4tdz zO|pf|VN6YnGq~pRJjs5hggMU!vwjfcVhsJTo*a-ZWDa{FYV^i>yfId-zaLCF9pfMd zxir@Lt}|axk}YHoSwxMso^P$Kowe)D17r)C!1M~F&*+S+prp8*&x7OCq+V$oEvW3iHFGNjm=l49` zQ+i;&9w1xD9I}WSYdzmuTRUsln+M1iGKVoWy`A6lcu(np`FenCA#>OZQDd#=TWf1) z?RxV7*+S-!Mbz|me$V4Qr3dEg0kVb6VN8v+o^P$Kowe)D17r)C!(ND*-p=oNyr=ZQ zd_6$6kU3-#HP(8*wYGNFt~U>mEo2U3YI-}r=kcD>1M~F&*+S;97ox^m&$rgr&f4|n z0kVb6A&aQ#?fjm{drA+?*8^k=nZuYGYdzmuTRUsln+M1iGKakoHNBnR^Xzs{JsrP` zF#WF6^k@#v!M;2|wvahw5jFcdr~B65Bew->-j9(U8E@m?)9*%2kLKANOz8o#h0I}0 z&6H43Yu(yQt=A`8$Q-hW zn%3uW{oOoY!jl@!*1pKTs6k&uwvaiDsgV!6@nOom-5Wl+5Fy7skQORk?8>-lZ;TL&@HjeXHA!HYLz+#W*~Eu+4@`7L)IvW3iHFGNjl9iQK?Z@)aV z*_;f1B(BuNWATUU_!@1$-st(>BwNTFvWS|VuVu|=OU$_;*mGZuTVp&DzI3U zXdjG0ZnTKEvByD-^tk4FdF_|#PqvUbjHxkiecm_hd4}@mo6G!pD43Aq)I;49qXmDs zW@3;m>eEkC-REQrnZsU)nyJp^KEr%j!yoeMtKd&!#Hk7RLl*fOZCJgRa(|F5WDZ$G z%~Gy=Y1c6pf4C0$FlD^8FIvrOQ?iB3VNA`^?%SnY54pj9W@yZHa?H6i_>g{%H9hik zw4A=?d0DjVzKCogbJz<}vy}UFY1ct+3}p`WTqnnkT<%)4$k%AgV-eXx=8#3y)a~<+$Xni@iMLhI8>i6ri-xGKVoWxpjPgn)-eeO!+iM zdgOhbK0kjgM*0pR8B)R=YB+bSn%4A1e62Uud0b~2ua@MQY$0>l3sF}U~H4~;>pV!`7jXX~~9+E9&4p~HvwHUV+ zyzi#G-+SAOdC+6ydaUPsk}YHoV`_T7mN}k{_g!yHnDRW#!^hFvrT4tjm}5;nb9vp! z7BYvu5H;quJhvse;(a&e{oZ1)>w_1kVmuXtuM>HVC2>jK)Qs!HedUvEA#=zgYW8)` zrS8l7u>})yYmyaw|C#3*8uR_|rPj;q8kc)y3z@^18uLGH{&|m+75vQlWb_mF$9N_N z^(Aroj4SmdkHtuT=PP~Q^<)g|XbyVt0NFz3uot4Hhchqf3`fC&4`Za<^E-I_p5BtK z*K3h`^Z?mH=8#3yaIUdl(gS*+#sg#vnZuZxn!TK>SM`7%pa;knGKakoHJod#m-K)h zsPO>VLgtV~)YRy`%^9K#d2;7BYvu5H&S>Iajah0X;wu zkS$~mSws!z8tWxJpa*I^K(>%MjH#*F%ei`059k4UfNUXi*b7m^xyE`)59om!50EWn z4p~G^&0fyct9n2W&;w)(nZuYG&NbFcdO#1%MjH%&VW4)vY^gxXV$QCk(y%04udpTFH>H$4K50EWn4p~GE=NjuJ zJ)j3_JV3UPIgF{P*~__lRS)O^dVp*pbJz>L9={v?%AnqOvoQzeKo9Khfh$}|k7N!R z#pjK$&Xf5tA9`RM50E*G&F?t*HIL>|59B?NV-9;Hd(GW@O><}N^uW~~AX~_0z8A!t zkx|CJm#7EyK#d2;7BYu1H8p!VSFh>;JwOkTEo2URA!<0+STE@TJy7ETvW3hci>RsD z%ei`059k4UfNUXi7*oT!#(GH)=z$s!kS$~mdm(CS_HwRX)dPBf9w1xD9I}WS&NbFc zdO#1a$Q-hWnwq_wt5@}a z9-s%v7BYu1HJod#m-K)hsPO>VLgug+qNZjq=jv5GpaTpTW4)vY^gxXV z$QCk(F*P-NIajah0X;wukS$~mdm(B#*H|y<0X zkN+{oLByZO ze@$!dJFKg;$E*+S;97osNTF`r+yPsXY* zd6HuepQnDTGq_GaUL{+|9I}WSYu8Wh=2(k!(FgrejE`fGEx(A@WWSD)-h<}zbG$~+ zTz-#`Eo2U3YRqkUZq1ds(gVkPfNUXi*b7l(K9A3*`7u9wpxgsw3zLJ$~{1~kU3-#HRiTF zx8}-R>4D=tK(>%MjHxl7$LG`hm>)e*?g6re%waD?jkzt)t+_H+df<2ukS$~mSwxNb zJU*Z1$NcDlau1L#WDa9$%x!sY&6T;*1IK%SY$0>l3sGY}kI$$1F+X~s+yi6_nL`#) zV{XfHYp%?d9ys0uWDA+Ym>TnWd_K*O`OyRA9w1xD9QH!gnA`H)_MEGy43Yu(yQt=A`8$Q-hWn%3uW{oOoY z!jl@!*1pKTs6k&uwvaiDsgV!6@nOom-5Wl+5Fy7skQORk?8>-lZ;TL&@HjeXHA!HYLz+#W*~Eu+4@`7L)IvW3iHFGNjl9iQK?Z@-Mc9eOhOk+@P5 zkHsIZ<7>42dZXuilWZY#$RcWbzLqtgEivbYV9$LqZjJFsjOPpEuVe1bp?xq0xzQrt z#vTVT(&L)z<+Wd`KiNX&Fs8=5^?Bd0=NZbMZ!Yuap&-anV~V)$uZ~7;6wU3*7V5F(Q^8l=Vj5d z`y#T1%waD?%~I~yrCkTPF_byfbDbPFa=B~GB448|k40n)nL`#)lk=X>@7EjT#&yw` z+!f>T7-UOH%yr10q4nk57V*&YsNb(YbNMG*$Q;Jh5=z!`uzO0 z80kBNWJn2fsNvkPYFg75@wMJq=W(5ByjqfHvW3iHFGNkrnrgm1(>(lt28Oh}_`&Ib=&o%yq2$G<9EF zp2-$6hrJLrYs*g$*IU9Oo|B(jks&3_p@wt0{?IsmFW_v9^D%N~OP`B98Y8{$J#>Bb z^UWFALgtV~)L853Yn^+IR#FQxglx&h>3c-m7^h=!ZcSX$gK_rykl4_oA%Y$0

1QkMj`2i{)=ZdkeO`NSHS#>|cu2O8Ib;zv)?(aR@V=Y!e(!BB z=0T5*>#?5mNw$zVjH&7QTIP5*-gmt*VaoF`4TgV*tLe!Ys z^4yl>iuc`=_j`-It`Ako&;#@U*+S+priOEk^^zXY12rBXTgV*tLe$jk%MWDzx- zYpj>_fF7vv0NFz3Fs7zvFX!r2J)j5Z0kVb6VJ}1t=NjuJJ)j3_JV3UPIb;zvHG4T% zuj&CkKo5{DWDa9$IM-M&=>a`Z;{mdT%waD?P0e1;)vJ0y56}Z-3zJ(4+O6rVS~I#1@q zeCUC3JV53!HoxQK*F2g>J&^Z6jydd+>@|1qHO-y5(*sv~fNUX~`CbrnMn)O?UZNh* z12rBXTgV*7)YR%M?1iYQ*~__lRS)O^dVp*pbI2lUIM-M&=>a`Z;{mdT z%wbGT&0fyct9n2W&;w)(nZsU)8qPJ=OL{;L)OdhwA#=zgYHId!u3psxdVn4vTgV*7 z)Nrn`UeW`4pvD7a3z@@Sh?<(coU2#$fF7U+$QCk(ETV>UjrEcq&;vCdAX~^B#?;j8 z%M?1iY|Tw}eY2lPOV2gnvOhb*F|W-sUJRXv~w=mD~Y%wbFo=NjuJ zJ)j3_JV3UPIqZd~soBf9dQ}hT0eXOJA#=zgYB<+eFSYQ%zd5tn{D&Anj=zb(xW!(s zxnB>HEo2U3YOL3O>$Rl(|19|Oag0x6{5*K`s~B%Z{CPZn8zWsSV`?~eNjX{DwU8}j z4tpVL)|MZyw;gXk3&wmA?89-i9$X)}mc4rpztbLgtV~)J%Cc_gaR>tfO_zd4Oyo za~M;TTgT`1m>$prLp?yYkU8vys2RGxdOfKJ^gzx7WDA)?7EzO1$LIB!9?%0rJwUdQ zIgF_py1sfnsR#5x&I4o%nZsU)n%p`*ugCO&9vJEYvW3hci>Mj8zIr{W2lPPB17r)C z!H)Ha%waD?&CvDL>q$MJ2XY=DTgV);h??9wKCj30fF2m?0kVb6 zVNA`?_0{W1J)j429w1xD9QH!g%MWDzy{I;Z>A z-y^pLYu=BM9vN@r-w$G>NAqkBrt|>WLgp~0X3Dd;#^n3J0;i~9G#lzyw(i)Lv>2b~V^4c%epKKv> z7*k{3`n+%0^9<$BH<$VIP%t6IsfW5JMhpIM&BP#C)Tf`Oy3ffLGKakoHB+6-eTMn6 zhCk%hSHYjeh*J~rhb;0n+OT>r<^CXB$Q-hWnx$O#(yn7H{%{@gVaj-GU$mOnreq75 z!yp<~roh(E4(2 zi+JdH)bH1yx%`tYWDa9$a_ji~H1+)`nDS|i^vL@VB5Kx{qn6kFNxZg6?n&js z&&kiN$dD4|P{X-ge`uV(7jQPl`53vgrO(A4jgj8>9=g8z`R0slA#=zgYOMA2wa&dp zE2#w;Lbl}M^gW_&jMFhVw!MJ|Ob*Y)&hb?kWwvaiDscCTr*DUwaJHdtbVx*tH zV$A!uBu+o)eq*fhKn(u=jU1O+KhHDkhjKs6Jy&E4nZsU)nz>(ZZ|CQImy5}Y^s^Or z$9N(}YbH#&KCivE8hM^}JS1Dl9I}WSYcXyuc;8KVzxTEm^PtDZ^;pmOBwNTF#?h=OWl|EV+$ta)+8(V{xi=rH0Jx^ORbmJ zH7@ta7BYu1HRgZZ{PP|sEBKl9$>=BUkMT?l>PzDE8CU8_9*dFw&R6=p>&Y0_(H!*P z0kVb6VJ}2Y4`*J|8IFPlAI3a_&@DPg7nw6NSGBPk z12G^2x<%(0n`3QpEX6Sjtl zImYJ9%vEiy#y||nfNs$_?uE>;wm6nzAO>a_&@DPg7nw6NSGBPk12G^2x<%(0n`3Qp zEX6SjtlImYJ9%vEiy#y||n zfNs$_?uE>;wm6nzAO>a_&@DPg7nw6NSGBPk12G^2x<%(0n`3QpEX6SjtlImYJ9%vEiy#y||nfNs$_?uEWRemDAS z!~EjAyLwO$V&LHnyylhVQRnC=pD%uWpXx{bh=F|=&^gBScc1>&$NCrp>kOs`Hzf!8yjTXeJU1=%wlRor`tF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4 zi(@GUVqk^=-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1 zKn8S+&e28YSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4i(@GUVqk^=-J)}J zkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28YSX&%R zF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4i(@GUVqk^=-J)}JkvTJSRU4}@5Cbxx zTXc@GIo1}(QVhhv3Je1Kn8S+&e28YSX&%RF%SbY4Coe}V{FdM zT-C;E48(v8=oX#hUdSA4i(~2B4E+4-cXz)WU%{9-kZqYf$=G61~p4Y>A7z4j&K)2`| z_d@2>x9*)7h=IKr&@DPg7n!ryyd5WoV;}}}i_S4NCuU+M24Y|@26T(gaW7=fUh{UG z7>kO1G+`$xEC@fX0C&oFO8ok|KS+RV{2Lu9*Y6pqH}bSIgfRo z%{zaOymz?f`(rGR#`ojj%kMN@9_w>GIFbR~qH~PRIr7|^YyMu)Gh5>OT$FtGUwdq)A1k1{1%_gaW7=f+HrdRak>4~_!~9P4Sy_NnThxEkH_gX z+T*fu$@ivi(K))voJ+ozTRykNId32C`REw$8ROGqe05{I{H@V3E%%3R(K))voNKx6YrBrU z{Nr)-!;$fQ`=Xn9ZK_*zj=vGpEKLXU#bu7=BoOj&*tTbF{VmndfuS zb?=LGi_UQ`WX`qRuh(`RdgD~*nD24cys_51bGxY5XxHZ=-J)}JkvVJZ_59qy8)JNPjJ?+MR2S_vZ^zkh4fpJ&ZqYfq$ecar?pWKH&@EeH9kRta=Dc&b zX89h_SH^hD81EnBQ)8TCt=6vP9CLNd^Q_@)Uv-PlF*av*zUtRGICY=1cK^=!M;CdV z)@^;=>dnJ@qg!;2dm(e`^}~DpX1&|XIl4%1=#x`pkMm~d-gEo1aEtxaEjmXRnRAOh zI_EY2Y`nHv-cMd0b;wMtH%@hq`5xz-J?PlC>oMJ;bBxW2m19^r)jxhtq&Iv&N4IQ= zJx=R>%(~xNpLL7QaW7=ft@Y;;u6K)zJWoHj(ji-%V~({R|I~Q-UcifEyfntzxho;_uX2oE0&+F_|O=iALHCkIP&;j`=zZ>=W{+E>K2`& zi_B>)_FW6_yCd)SOPk9+#Mr)!U2;Eli_S4N=aR4GDW046-K9C<$n&ueFOR+5@}Ac+ zp5mHz&fC{bx9A-ALgv)l?Y-U7EAP7_@Aq@e^|s-Q=g0Ws7`{&Q8n?t-`c}@q96nY* zb&Jl?Mdm!#d0y+h-jC;S!rC!)h3`LmKBvaMAAYUt)phObJ>8;njLoV4`}W^^Tvzy+ z^>brC@v$+!JcjvO;^i~0Wl!?iF_ypcwS3<7g)v&kdT!_JPX=_0&e28YSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#h zUdSA4i(@GUVqk^=-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28YSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4i(@GUVqk^= z-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28Y zSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4i(@GUVqk^=-J)}JkvTJSRU4}@ z5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28YSX&%RF%SbY4Coe} zV{FdMT-C;E48(v8=oX#hUg+E7ccZ^H%rCyXs|WQU1|H79YhGC%b&ihm`Qq32seaUt z7}$paonu^o_vvqatdB9U&cK>;+#|KueE43o-qpJpcs&EUMK}9ikUi5;#l4pp12Hhe zfNs$_#^%h-Rc)-sKn%!$ZqYgJh0L+GIF@1{24)!0EjmXRnKLt2wXqrlF(3oFMduis zV{LIP#Xtj(Z_ zj(Z_j(Z_Js-QB;8@t5Oo)%|=t{&I{L{~(?@eznK*satf8u{o{L@oRL;J=Zh8 z7{2-47)w9aV)JjgZ%^ggb&Jk%FJ#VBxvtLhIz0Ke!#Dpl#!G+1IcqNZi&3-G{dA0Y zxXd2t7M-Ju%xN7ja~-dBU6%dKe;woBZ1m6HkKE-o+7Dm#&dcNRmHczD{?#oy$Jm@} z<-F^Pi5&z+y=YNgo7ti$i>oV7I?f%j&I>)_`Icvx1 z`KPt+PjS8e)$q%|9%Ers&-}^w_X}e@8{;Wn*Das3ZqYfq$edg5RoCAA9RvF^pj&i~ zu{rgB-~QLn`gzL?=oX#hUdWtV?p4>GD`H?@26T(g(M9Ie|9$&kKkMf$GoV{^ju3GEWd?MM&e28Y+;XqF_FNGI`!b+gbdIq(^?%>~ z*U$QS%M9oio#S4}oLlZy*Pbh4U|$Awi_XzS=G6av`(Hon=Pfg!TXc@GIk()au02=8 zz`hLV7M$ejAWZ~q^wpI;h3E4BQL`11Hz=g_?MUbpBRU1UzoJY8nqJ6!YqF_uT; z`|hr_;d})1iU-a(bi|>r_zA7cyt)6Xb9!EbM8Q-@rx|!Fe zx<%(0n{#dV?X_Hw-f%y2YV2{=ob!R zZP%eUPIZp?9%s!PYrQ+Si+YWAeJ;{1I!70ov&LS}KQ0@3*~^1(4aH->K65_=r| zbL#q9dye?j^C|yv`CRM2ZqYf$=Byp3=Z{(6pA4tGGRE@geZ72s{;e^V?-1&cEzU8= z+P&6vW?$rMy}iz-;~c~4mOkqio#S4}oGr&JXW#W*bB_Ko)*-rOOKk1ehReP&#y7{< zYfVpe(O&a*oc-2t&tB>louiA)*>moWwT%hgvL)6bTbyIgJBMqQ?*V;fjJJ&O{xLo^ z#yQq%?OM(;SI0ch8qW4rx9A*Wb7tqOew~9;_c?3#?~H$Rk;iG>*4M4xJiIr$Md!E| zGN)cYyw`8myS<#Fi}Z#*IW_h;Z+7lIw=WB~*iYS}b99k8x7ed|Uh~h!Yn$c$pj^x9A-A zLgw6Be=gyAx46jj^m8j6vc);(SnKgmjhF8Qyg0^7W2~Lq^10Y&##r9>KK1zJKi!_` z7M-Ju%xSHUU+cBkXj|4ohv=5Ic=;aD{TMHdVeL%3We?`@w_H~_$8&g&p6eE!V{Fbj z&Y@#&XX(4c3*Q@K`S~kj@82!)@^kL*7{~bd82w)61Rd!<`+j(Z_< zp8EA(+WC9mt;M=x`PqsOjq&+0&h3OFkMFf#+8T8}=kuX%(K))voYrFBweY?>@_xUx zx$HxX?aSCD_fxm%9Ak4X`C6Xhxq07RniGyZAN%m~*xN1dc`f59u4(7Iecg16&T%hf zPQBgU+bzBFzB}@MKgV2e8@_mcj4zJi>qM_{OT49TS&SRbDwa)AP zcn&A59aC5M{SK)2`|U1W~6#jz9vF)+h`ZqYf$=FH4hZLG#X49I|P(K+sg%(1pOmSP|VW*E>d zI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-BcKn%<dI!70oGc#AUu^Iz0 zAOpHZ=NOw~ZE-BcKn%<dI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-Bc zKn%< z7cysNu4-d724X-4bc@c>Mdnyr97{0}12YWh7M){k&dglZ#%c`2fDGsso#S4}9BYeX zDF$L-h5_B8b99k8GjmlNt1%D*GN4;@j7cysNu4-d724X-4 zbc@c>Mdnyr97{0}12YWh7M){k&dglZ#%c`2fDGsso#S4}9BYeXDF$L-h5_B8b99k8 zGjmlNt1%D*GN4;@j7cysNu4-d724X-4bc@c>Mdnyr97{0} z12YWh7M){k&dglZ#%c`2fDGsso#S4}9BYeXDF$L-h5_B8b99k8GjmlNt1%D*GN4;@ zj z7cysNu4=E3pCi|_*I(Dik8aU9y2zX(d26og<87}s?fvKLU_-a)9Ak6#;-}+W2S2T2 z>o~)JZqYgJh0K|mtJ+wNff$eh-J)}JkvY~D$5IT$zzhSrMduisGc#AUu^Iz0AOpHZ z=eQR#$J*jpih&rIVL-R&99?A2%v{yRY7E4H4Coe}V{DGK#jz9vF)+h`ZqYgJh0K|m ztJ+wNff$eh-J)}JkvY~D$5IT$zzhSrMduisGc#AUu^Iz0AOpHZ=eQR#$J*kj%hH#| z&w>ANjODR)tOt+9fNs$_y2zZzI?v{vzenCXT(kVXoaNE@e*F8{7|UaQt_Mdlpj&i~ zu{lScTXW6d3wmZte4mSQ@PYpy(k(j2y^uLMVcrSn?%@{CY{}_0+U2kHxmh~*@pX&N z(M9H*`+Pe7!NVQ&YkE!hk#5mBy2zYsy7pVUmbLxNUeDi;{noQF zmd9J`ZP)v-HPTHo9ky?glLJ7c_Wj9hdb>w9Uut(}i<(K+sg%vn25 z&p$4=zZ!pA=DFdI#Va%MUjFeoy+(UnHZJ+z)Gazk7nyU(*K*6}wm9eQ!#y7z<2_@1 zdW^4bjDIs~-!*bSF^1kaM|?l#cs9oJc+2b6wf}zob&Jk1HmAN_=6&Oy=T!gv_ErCU zayVg$mp#;n$2f<7Jm%t{Ty&W{9d)1U7M$eg3jt9ef2a>hUU>es_RizA*tz(2aE z*J!7$_qE&~x<%*cB6F_gy07gz_VSO%(GN$)_w9>r=C!GA(K*KET-$wnE!U$r+|QgE zdz>}rd|>!t`8n3*(a+J=@@JmUMc2JA(k(j2y^uNAa=%{Nb?A*#onyYoS@XtP@6PR_ zUZY)~i*$?5(M9I0vDfpD%ZA=~>)4lkaE#B5pnDxEC^K%Q4H@cYW8KqkoKbh;G>uTl=-)vTuy>%`x^`(^Flv*SsBPzct*mm%2sg z=pu9WoV#OfV?wuViFL>p=a}=(;hN=pKwlZ-En~cYj8Bbmj*?Y+4-tp=itFX!kYy`fJ| zjXlnroqNyi%fc=8Q@7|GU1ZKJ_UN3~{Il`eW_dq(dDI~@vEDe%1W zi_S4NCsvMO)_`Ik(oIOSs-GF7iD6+)9UR zagI6Gdi+!4<$D1yj`7kMYv;CnF7}x*miN6+J%0I5w`aOV=jbAHTI=K2dhIpZmbK6! zx@9e1zDIOF#tUOuI}>l&gL(Wd*HzB(9G;`+x<%(0n{$qH=$PAC`tI<;_r_R${>s?< zcT2qdoclY*F+M(qzkg%ROXq&xbB>4YJUsPY=@y;iUdWuMe!Z7={@!@-!E-0`w(OMGIq)R)Ga#4*qlqg zmZx}b-glSggd@+#KD<2kcFTKS%Xo@w+Bt7uH{GIh+zXjgZ@2e$ORv1|j=bN`G1uFM zFPXV%Y+{lv${`0^O$Z;6-BxRyQ1XUACn&e!sJ*B8cU z9qYj*FrZs>j(Z_I!x26T(g(M9IW%vEiy#y||nfNs$_ z#^zXC97{0}12YWh7M$efwEs*TkchyfYUEjmXRnPY8nEX6I!x26T(g(M9IW%vEiy#y||nfNs$_#^zXC97{0}12YWh z7M$efwEs*TkchyfYUEjmXRnPY8nEX6I!x26T(g(M9IW%vEiy#y||nfNs$_#^zXC97{0}12YWh7M$efwEs*Tkc zhyfYUEjmXRnPY8nEX63RfKVo1X26T>b{oSX(^|3z2z&ZnK&T)^_Ui0C5&3aew zV&L@*=oa1VdqMV0M-}&8VhqH<3ff$%! zK)2`|U1ZM8T-C;E48(v8=oX!0Y>u_Xu@nO_FvEau(K+sg%$b?1+E|T&7?1(oqH}bS zIo1}(QVhhv3ff$%!K)2`|U1ZM8T-C;E z48(v8=oX!0Y>u_Xu@nO_FvEau(K+sg%$b?1+E|T&7?1(oqH}bSIo1}(QVhhv3ff$%!K)2`|U1ZM8T-C;E48(v8=oX!0Y>u_X zu@nO_FvEau(K+sg%$b?1+E|T&7?1(oqH}bSIo1}(QVhhv3ff$%!K)2`|U1ZM8T-C;E48(v8=oX!0Y>u_Xu@nO_FvEau(K+sg z%$b?1+E_g|1ONQ>ySw*{zva6y`|}b1a*P*8eC~NW{=<5#TXc>tGN(R2tk3oBe0|e1 zzZkyx-55*1jm>E-&bJn)_Exv(9Ak4%J%0I@v)0$N7XSHG&-~RNct+=}#kuHmnA9yg z$Gwm_*TitwaycBHx)wTQ%`WnV5-z7}$#e-J)}JkvV(K+i_wz24XHq8>aJ1G+`$=pu6->pYux{vLVnaLxC}SRRe<$G?}Kg<2l# zb3Hhc0o|f=jLkXn+?s3tUeGgJ;`>~bgAe@wkZ#dA?uE?B3G+@kcMrFCW=l@5(Jp_j z&&|@gkFQ&FjxI9i+~?ErAIAI^pUmXkw=Zg6bcTJAZqYf$=H!Qm`QgaEePnR*gE5xJ z8Rx9k=Az4I;7HzP=F%-X$Gwm_GjmmYJh$g|QLoXCU(;*4k93R9(M9H5)3x8)wXE%D z_Imz)?6;ncu{_>dZ@b=yt+{T|ImYJH=ZE$A()#AU=-tB?-x=e5W8|XiSl>(IZS8z? zi_UQ`WX{@gdj4^_{nhyWqR$O~EMA$3_wtX&={4HpvT@1xrf$(Wy2zYMzLr})x5YVc zAMW|+7|Y+^`}7!J-54*wm;GHM_Y-62jdR5JV~%HIERVOmUS0d|*I&2j9Ak6p+hyK2 z?s-o2&+@z37yo>6j3r+7P#+%S9RBf`i-U5}W%6{?eXd({j(Z_VzY=%QYuownZBa)0O+ouiA)xt8m`w(Ho-KORRv92wuYFS?o6rn*Jv7@Ko# z_wBV@kKS-Ub875y)|~T!;fLktSeHjXM_bFEc|I3i_r6HC=p6S#=3LADdTrOCH%@hq z`5tG@8*9Bgw~Km>c6~0=EjmXRnX|@T&p$33dgHBQU-H2*J~xJL*%Esk{d4O2T6>Q8 z)blC-ars>9zi!bv#^$UYr{|AZ-=7SpyfVh}=zYC>e)X*}mhTYikS)$J$J)KtbY@@V zYrVbBr{f&M>Xtt17M$eb<5EN9>KU2~59G1eivWlL=B*M`f!F~&E?*lSHsbNbtA3q>Q};P*_wS57c!?_KfKp( z*1Nr&ql@&0J~=h^IB$0DJ-06lx7bhJqH}bSIk(uOb6)e$#%r79{p96Qhs?x!<5cIE z?{UuAgN}W>9@8y4$Jm@$Ifj)}{p06Edc*f~bjz05t>EV)@yM4~_BpG0yFTBaiR3U)maVKIikHZqYfq$eh+<-?i|*JMwU78b)JRke;^4Qxg?|CibDXwYfynWqti_UQ`WKO-^-rFs` z^1eIrem}=tZyUaNevB`U;p;@NaZ9|VZ{_UE;bZkvx9A*QWX@xq=e5r3{df*1tQ}KV z`2Mr!b877S;n%ueUDv+e(=9s3*qr*mZ~wi=b%mcj(Z_j(Z_ zj(Z_PP*EfqfXzImY#OpZ?az`WOT246HfF zJyLtkhwnA(UA>Ee*E677bhGaT*)ttg+J5Cby|=oX!0Y|hMF)y8TJ#DEOw7M z$Q)~nV<`q=V1@zRqH}bSIWu!r8>=x812UjnbdIq())vQ748*_;1G+`$xEC^KX0B>u zH3nip26T(g(M9H1TO3O<5Cby|=oX!0Y|hMF)y8TJ#DEOw7M$Q)~nV<`q=V1@zR zqH}bSIWu!r8>=x812UjnbdIq())vQ748*_;1G+`$xEC^KX0B>uH3nip26T(g(M9H1 zTO3O<5Cby|=oX!0Y|hMF)y8TJ#DEOw7M$Q)~nV<`q=V1@zRqH}bSIWu!r8>=x8 z12UjnbdIq())vQ748*_;1G+`$xEC^KX0B>uH3nip26T(g(M9H1TO3O<5Cby|=oX!0 zY|hMF)y8TJ#DEOw7M$Q)~nV<`q=V1@zRqH}bSIWu!r8>=x812UjnbdIq())vQ7 z48*_;1G+`$xEC^KX0B>uH3nip26T(g(M9H1TO3Q5%)o#7`rX}I#@`ixX^fwb_?Kh6 zIO0DYLVzl^c?$Nbj) z_;uGUI>)_`Ijzz0YgEtwc+Y<@Jo4|x`1fP{hvAi9kFoHpbJpU&8M*&B#$S&7`h0v3 zbc@c>Mdq|d$FEU6|KmOXi{XytHP%lzI!71%?QqXOjj`0%=i_^zTXc@GIjzz0YgEs- z_uSW0ddB!a4&VIGF@83jV}5(;KdyEF!Li_S4N=hDu<^XZ<7fv3xWZqYgJh0JNKpYB?> zcCFo|F`!#?jxI9i($2s0>7I&#r^|qD(K*KEwAN2|ty{a+?$Q|0Ejq`&kU5uj{+-Xm z?x`=0@7^sxf4Mx?!+P*o4Coe}ql?UWtn+N%`FrHO!!_R@V|g^bAOC(f#`0L7>%ox> z=oX!0Y|fGA)?D-Vf}YtD-{+zneBl3wbc@b$FJw+mn0Latd$`3jTXK4hcKK_4ZkEn{ zeBGjRbdfpdKA(>NFy^=TWG3gneNp?OGwh3Wi_S4NCqF#Q4@dUxBZHIWcXBO{GtOD7 z%|(~bz>&Po%%xj&j(Z_V|l!_-gdnYTXWr_bBxWY&kyVKrS;8y(YuE)zB9)A#>hq2vA&na+uHf)7M z$egv~^!(#;`>XLg{hk~CSiCY5@8utl(`&THW#f|XP2Hk%bdfoid@Z+pZi{o?KHT%s zF_zyg`sp#gx-tIEsD0PS{lpl0;~eq*nB&)6Xb9!EbM8Q-@rx|!Fex<%(0n{#dV?X_Hw z-f%y2YV2{=ob!RZP%eUPIZp?9%s!P zYrQ+Si+YWAeJ;{1I!70ov&LS}KQ0@3*~^1(4aH->K65_=r|bL#q9dye?j^C|yv z`CRM2ZqYf$=Byp3=Z{(6pA4tGGRE@geZ72s{;e^V?-1&cEzU8=+P&6vW?$rMy}iz- z;~c~4mOkqio#S4}oGr&JXW#W*bB_Ko)*-rOOKk1ehReP&#y7{louiA)*>moWwT%hgvL)6bTbyIgJBMqQ?*V;fjJJ&O{xLo^#yQq%?OM(;SI0ch z8qW4rx9A*Wb7tqOew~9;_c?3#?~H$Rk;iG>*4M4xJiIr$Md!E|GN)cYyw`8myS<#F zi}Z#*IW_h;Z+7lIw=WB~*iYS}b99k8x7ed|Uh~h!Yn$c$pj^x9A-ALgw6Be=gyAx46jj z^m8j6vc);(SnKgmjhF8Qyg0^7W2~Lq^10Y&##r9>KK1zJKi!_`7M-Ju%xSHUU+cBk zXj|4ohv=5Ic=;aD{TMHdVeL%3We?`@w_H~_$8&g&p6eE!V{Fbj&Y@#&XX(4c3*Q@K z`S~kj@82!)@^kL*7{~bd82w)61Rd!<`+j(Z_@_xUxx$HxX?aSCD_fxm% z9Ak4X`C6Xhxq07RniGyZAN%m~*xN1dc`f59u4(7Iecg16&T%hfPQBgU+bzBFzB}@M zKgV2e8@_mcj4zJi>qM_{OT49TS&SRbDwa)APcn&A59aC5M{SK)2`|U1W~6 z#jz9vF)+h`ZqYf$=FH4hZLG#X49I|P(K+sg%(1pOmSP|VW*E>dI!70oGc#AUu^Iz0 zAOpHZ=NOw~ZE-BcKn%<dI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-Bc zKn%<dI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-BcKn%<7cysNu4-d724X-4 zbc@c>Mdnyr97{0}12YWh7M){k&dglZ#%c`2fDGsso#S4}9BYeXDF$L-h5_B8b99k8 zGjmlNt1%D*GN4;@j7cysNu4-d724X-4bc@c>Mdnyr97{0} z12YWh7M){k&dglZ#%c`2fDGsso#S4}9BYeXDF$L-h5_B8b99k8GjmlNt1%D*GN4;@ zj7cysNu4-d724X-4bc@c>Mdnyr97{0}12YWh7M){k&dglZ z#%c`2fDGsso#S4}9BYeXDF$L-h5_B8b99k8GjmlNt1%D*GN4;@j7cysNu4-d724X-4bc@c>Mdnyr97{0}12YWh7M){k&dglZ#_D4+@Y6rPyL)+z zSH}4H*YECrImU}4{);hQ8e{qIk9BUhJg;uiIqrqbx#eDU?N93-{nO!;KO5tRWBkqV z%|DLumm~hgc>LWM%X%8?rPlhGwbm^SfArFyjJ?qdV>}z9{+_P~x<%)>7c!@{INw^-+kJa` zs(;LHE%sfDwSMXrouiA)SvyY8AG2Qd`C)z5Eo*VTeOPa2`lefSj$ec^Qmd>qvEe4(z1G+`$=pu7k->0>{tyk-H$qeWgonvgyC0|SD*1Z-3 zPm2NFqI28}nbZ0{t@UlaTCYoHK)2`|U1ZKBUrXoKy%qyciviuDbBxVteV^9)wqC8* zB{QH~bdGx=b1wN>I=Aij+Ly-ndY7MzS|00LJ$Nhzbc@c>Mdm!#c{cC-J@Ve+n(vRX zJR0ARe=k30usqi1dT=BIx<%(0n{(v3HP`&Tpl7zk_qiwsANc=ACfv z9&Yi>mYiOrUH)31o27FfU$^KSU1ZL=&!^)*jQK4-naR0tU(~+n4ErM8qH~PR$qx_n z!;yXa$l&A$V=Rv|&RMI?MVHUOk-W{!rCW54dm(dX=BoC1ZqMzaUZWkqrq^^I=@y-% zi_E#EYrnN?S=-O-_5A(VZ#^4hdAzmWcD)ZKCFIh?S>%O2{(W1Pc39&>R}F1k#fj=Ilvi_UQ`WX@6N z)jX$hIpZIF_3PoE#SzaR;2&MoYqZnW`&#Y~-J)}JkvZ3L-Pd**?Ywd3^sG3)!2;gna#SRTEvm(S0?HOBHCLLIWj zIp$cq*P71ki+ruO*ZFjuV_4nNXWgQ6+zXkr<(TE{yS{7A(LcsIM7L~-t^L|?**C`c z<`{de>8UQ-Yu=8t-x}`OOWmS#bdfoG&fT%LF`-+w#5!b)bIf_?aLw{Pps$SamNDKx z#;3+O$6Bpj%Q@!inCDr;*}m!)onvgy?0nU)b8zZDXYKx-@sBR@IIY|Iy49P9_eQtq z9QQ)z)a!@$`ptT`mveNH-q0tf#vbR*&b{aMW#Jb4satf8E;8p9dvwlg{@HkKv%H_Y zJnE2{SZ|!_9P>TSIeXBtZ`WhGMduis6D!BCa;ks)oJeo@evWS05__E1{g`#XwLa?> zo#S4}oLlS9C0y?o7kQq3Zly!EIL91oJ^rcj^1Xl;$9QRswR2lO7yHZ@%lqD^9>4sj z+cVvwb99k8t@ZJ1z4jVy%Ub9V-Le)h-y^yoni7X4$skZ-J)}h z%{j+8bj;Img3x9-exybc@b$ zFJ#VBzurqbfA71sSXV4RTk)YWK0n5}op9vwz4l96qt54iKGZEbM;DpXTI{K2`2Y|bTL%Tqiz@4HKL!jb1=A6_1NyX8HvWjw_-?VPu-n{LrL z?uE>$x7&NWrB~i}N8az}nCorB7tfFJ#W8%H=rwMMxAd)?eK~xre(DyTql?UWtn<9q zdA%Rc;e@qg>I&a~_Iyr_eLwtK*Q@K=*L%7}=NOw)|M%^`_qeX`GwbKZe&S zx5Ue5T+5#1vtulO=WF@A>kDJFj`iRY7|<;`$Gwm_mvGM4bPhinF8J{nOYi*-p5N2E zrt9rm@}3On7M-Ju%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_; z1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6j-?ogff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju z%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_;1G+`$=pu7w=BhSU zV;}}(K)2`|V{@!6j-?ogff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju%(1pOmSP|VW*E>d zI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_;1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6 zj-?ogff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y z8PF{{$Gycf!DmUJn9@B<@3d_?^FG#A2F~G13JgJ{_fM? z`dA-hV4Z-}TZhI!70oQ~&qvfBihBpE_iV zbIh@}_1bs6bc@b0HmCmY+yDA`d_VQc;+g+7#w)MB{(3Dor!_j?8tE3D<6g*|*5Z6? zQE!j$?Vk?s{Mi`GdqKvn#W8E4TXc>tGN*MpW?kxYeZB<-bc@b0Hs=<4(lvJP$G|ZR z=oX#hUdWu*<(PG;&-M8h7|<;`M;DoM3q9!?yZ2+@7zT8U&M`Kpbvb5T>T`X*1qO7B z&T%hf&Moxh7OwG2uYTsUJl?|fc8!<0&bmeC=pu7k$ID#DE$i~$;hOJ{u{;{zkAFWK zV|mhj??%|8?jPbrPa?$0l z-8J1`x<%)>7c%FXuKk*>BxIrx9A-ALgpNKZq2ow&l&&dt6vZQERJ~o z0RQNsUZZVa>ub6%bc@c>Mdn=7wO`Yw==e?R8PMVHCk9^C5|o#S4}oIU33 z82j_2H%@hq`5tG@8*A%#ZWr|$ZGUdo*7B(5b&Jl?MdloJUd?kFYkK3YW6$uxF+Mkj zZrKuh9Q||ZdRTjo_|)?$|1_SC>X&ZOImYH3bzaT$=DaL_KY00DRm-FI_44`ox5ik$ zL#RWxIL91o_gaIQeUY#A_Bx-A^X6o-gz0@r_M;Dp1=iD7@8xy)^ORPh-ILDlK4%aN-1NzDs zZyDqLV|;3ibF9_cwVY$Fj(MInob9V_(K*KE%+6Q+ItQojbJp(P8UN@akJGxXuUox& zcyDxz&T%hfPQ8A3uivb9dpSoJ=?#5yYV2{|?A&{9Ulwk$pSnfo=pu7&u}9~;=AVt% zHp~0T%cBmNiS@>*&N1KPoU;cV`*uC1TXc@GIk9pKE2sL$&x!Pg@8{^2EwRUG-H%!K zTkErK(K+sg%(=DxT*CEkagpcg=Tha5ex;@h^I!70o(^?1TYBYvcjWzkj=A18eDVAkUmU~NiC*KDcuU{P*_Xq|>ZfkeIl9Q4 z$2!kzo!9&E98Op}rmpb)XV2%<*!RP)b-lW-eZ8k!bdIq(^?%>~dynf1KeK*r>?b}p z#+S!1e@nc4#sSvifdSp3bKDD=a|!2sP3Q2V;esEJvGm^W z;Q2khYr5X9CGW|AZqYfq$Q)~nV<`q=V1@zRqH~PRnVGBFSdD=gkOAGIbKDD=V{LIP z#XtjxI81X0B>uH3nip26T(gF*e8A;#i7-7?@!|x9A-ALgviORc)-sKn%!$ zZqYfq$Q)~nV<`q=V1@zRqH~PRnVGBFSdD=gkOAGIbKDD=V{LIP#XtjxI81 zX0B>uH3nip26T(gF*e8A;#i7-7?@!|x9A-ALgviORc)-sKn%!$ZqYfq$Q)~nV<`q= zV1@zRqH~PRnVGBFSdD=gkOAGIbKDD=V{LIP#XtjxI81X0B>uH3nip26T(g zF*e8A;#i7-7?@!|x9A-ALgviORc)-sKn%!$ZqYfq$Q)~nV<`q=V1@zRqH~PRnVGBF zSdD=gkOAGIbKDDkd;D(n*M|AUcX#!m9>l=I8F+e4Ot&jCF2G$u^bB=qY_L>jhYu3AZ7XzdI>*?Y znYpTs)fk8Y8PF{{$Gwm_))vQ748*_;1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6j-?og zff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y8PF{{ z$Gwm_))vQ748*_;1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6j-?ogff)vLi_UQ`WX{Z7 z)y8TJ#DEOw7M-Ju%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_; z1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6j-?ogff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju z%(1pOmSP|VW*E>dI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_;1G+`$=pu7w=BhSU zV;}}(K)2`|V{@!6j-?ogff)vLi_UQ`WX{Z7)y8TJ#DEOw7M-Ju%(1pOmSP|VW*E>d zI>*?YnYpTs)fk8Y8PF{{$Gwm_))vQ748*_;1G+`$=pu7w=BhSUV;}}(K)2`|V{@!6 zj-?ogff)vLi_UQ`WX{Z7)yC?jG4P+hes}jTWBlcx-`)Mqc>Kp#*?YdOqLtdic0KbU(A^nYHJwZ5`*=QMc$E_d@2>^ZB0F z!^iF6pNzfB3u7#=t^VWK%lywV{{4v8oa6KPXWzBcEjmXRnbWyGtF*c|E@7w?SSwC-?0o|f=+zXj=%f0H_b43j7%YbgtIl9Q4 z`oC}g>u3GEWd?MM&M`LUmV4E;=ZYBEmjT_PbKDD=Q~&qv|6}#@OXEG(<@+zo<71se z^VWOaqH}bSIWhBenR)MU&G*Mx9*ytEzn9OVm&ew(9vsPlZqYf$<{Wu$%{6~7=$S3? zeJ;wu2mXIZx9A-ALgwUzc_*B^hg&?eC8yVDm%rBMX6f9=*DX3n7nyVJ^Xd2xV}6TI zW^(S^7qu@s!@fwj=p18n^25XYaAe;;GC29c7|Y{~bJl8e(d9F6ByTfw=@y;iUdWu8 zxvD*$+jG09*J#JD={4O)x<%*cB6F_k+HdVz*7h@dJ%2y;ThGQ=9&fF;UGKxzT({^P zV{_{B!}@$_eRE&*?%|8?jPbrPa?y3H@1^m!c0RgA=eQR#XYDvW|G3;PzeDS};g7{D zGx1*j@i@Ikdt5dy`QFqmI!70obII3o%jdQ@=k3EiA06X8V|;pyuWpQgGiu*8az8PK z-Z)2mKjwHg#`1W}>(#aYe*JZe&M`KpzFp>h*z3+#k9{=jbAH zuI0L~?K<}IkH^suN5=Q3p3g)_`IoEQ(UfXr(jZ>XtzQG@;UclkSc zuZ*!gdS5S}pMPtNOjd6~(TDz8W%+)c^vxc*M)h#;5*qqtcc=pwzLPfm?J&YPWk&+W^?E%sBl z=p0>S&Mo%noY(xb@!Dp2KY4l7Av3YwIMq4kdz^Fjpkv>z$8?L%F*YYwj$!3g|M)qP z-the#-LfV2IIa6J>war})-5{6y^uM#)}Kqb-YqWjJpJ5Chiq|^~IEndDybU(%mV^}*A zZ`p%+{4Lj2&hZ?cqvyIs=NOxFj&tak+gbYV@WS`TSbqM>*!y=&y!@Q|JH|0SK8C-4 zW6ewFe%^DAhwVH(^tGN-lJcP+f{j=bM5Z7%x|WBW38$^FzVI>*?YOTLz;cy8Wzm*#{c&&NKz zJoa|WdtS?Uifh_AZ(ldvqI28}nNx4K_jXIKyzh>@-_J4E+lDWmALEN-_&U*R+!Al; zTRHo3_*nhaEjmXRne$lZd9Cw$Kc2%0Ysb_TzW?m`oErOn__eNA*R`+rbc@b0HmCmY z+kfwIUEyce&yD@W$Hw^b80K$@m(RGCJ;`UsSpLq}@_E-6#%LYu!6h)DTXc?lA#*O_ zoUiE|el%S0<1v=r`yD*Lr*}=)+qL998PF{{M;Do6ZE-BcKn%<L1hjsDs&zxeL19@K*vcsK*Ed1ZOjIXcSc zi(lWT`cXe(U>^o_j&c3nr@!^FKE}X018dH4kJMiC;d{+`SMOrr^$h41-Ryfo_Dn|= z_g-QQ#J~&#x<%(0n=><4wXqrlF(3oFMd!E|GRNBDSc-udm|;M-=p0>S&dglZ#%c`2 zfDGssonvf{wZ*X%12HhefNs$_?uE>mnXB4Zje!`D0o|f=bdfpM7ROQy#J~&#x<%(0 zn=><4wXqrlF(3oFMd!E|GRNBDSc-udm|;M-=p0>S&dglZ#%c`2fDGssonvf{wZ*X% z12HhefNs$_?uE>mnXB4Zje!`D0o|f=bdfpM7ROQy#J~&#x<%(0n=><4wXqrlF(3oF zMd!E|GRNBDSc-udm|;M-=p0>S&dglZ#%c`2fDGssonvf{wZ*X%12HhefNs$_?uE>m znXB4Zje!`D0o|f=bdfpM7ROQy#J~&#x<%(0n=><4wXqrlF(3oFMd!E|GRNBDSc-ud zm|;M-=p0>S&dglZ#%c`2fDGssonvf{wZ*X%12HhefNs$_?uE>mnXB4Zje!`D0o|f= zbdfpM7ROQy#J~&#x<%(0n=><4wXqrlF(3oFMd!E|GRNBDSc-udm|;M-=p0>S&dglZ z#%c`2fDGssonvf{wZ*X%12HhefNs$_?uE>mnXB4Zje!`D0o|f=bdfpM7ROQy#J~&# zx<%(0n=><4wXynC82I_u@9us%#*2S`cefTlm20`=^VBUm$Gwm_mwYXqTYj5iK+pVQ zxaW6cEXP}m&7Ya~mTPs3&e28Y+;XqF_UrcBnrGIY|G$Qx{=YGv4M)Ys!+M}wbdIq( z_4#3au5Xv$x4#`O`KK{n`XhTDUDW<(eob|Y&T%hfPWRD#&+Fl3_E4YvhvA`LkFneb zI_K}kbN_ve?~mvIc|5*nJTCV~Yx=Mr=oX!$i_EFd59@P%ds=<_i{X@IAN12P^wM9A zfB*FuFOSih&i6pK=p18n>iK-n>tQ{Nf!{NrTXc?lA#>{6b=*5&8vpvKIgk^$YKbBxV7^4ywh{$9{C zTjKj%l!Fia|B!CcIqrqb$qDmLICl@XcxFpZuhA}lt)_` zIWu!rdpx)2c2Tdsa4Q<8AGHbc@b$FJ#WzaeDr7x&77nS)}KN zKNhdd#C!S2!u*AzA>ceB4 z!#^H#aZoP0OrDOq&vlE=aW7=fQRme>r*S#sAAPm_&WXhl&mZ6)UDRu|)7JZ1?hoCf zb99k8*K*z0b{%{9$K&XSBjfw_MK|->RJZ6HV{@+UzP*;~(Hrh(PK`aznsYud{IL8S z>+o#S4}oNKvXukAYY#;MLR-{Y)#W36}Rc2TdqI28}nX~1X z#yUi|Y>BP?+Hl!7#`xwKd#&lIF4}9}jXx zTeieHWQ%jmdFOD=@;#uhjPaH+-ap2t#yH1XtzFAG=IWT|S;N`B>K2`2Y|iX_)vt4K z>ON=f{+;oUF7i07+xoiIn}_#Cx9A-ALgv)#hxhu;dbgKzbdlcBC#S|9=grQ&=k{gc z7W=7NbdD}E=N5Z(&TIbJcx|)1pS(QkkeOI-oa!9&J7@HF-$FOp$ zfBc+CZ}@(WZrKuhoYwuAb-%Sf>lU5kUdWtV>(3=z?-mz%o_=nnL$)}_9BV!Psqyl? zfEUMD{+{UCxho;_uX2oE0&+F_|O=iALHCkIP&;j z`=zZ>=W{+E>K2`&i_B>)_FW6_yCd)SOPk9+#Mr)!U2;Eli_S4N=aR4GDW046-K9C< z$n&ueFOR+5@}Ac+p5mHz&fC{bx9A-ALgv)l?Y-U7EAP7_@Aq@e^|s-Q=g0Ws7`{&Q z8n?t-`c}@q96nY*b&Jl?Mdm!#d0y+h-jC;S!rC!)h3`LmKBvaMAAYUt)phObJ>8;n zjLoV4`}W^^Tvzy+^>brC@v$+!JcjvO;^i~0Wl!?iF_ypcwS3<7g)v&kdT!_JPX=_0&e28YSX&%RF%SbY4Coe}V{FdM zT-C;E48(v8=oX#hUdSA4i(@GUVqk^=-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv z3Je1Kn8S+&e28YSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#h zUdSA4i(@GUVqk^=-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28YSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUdSA4i(@GUVqk^= z-J)}JkvTJSRU4}@5CbxxTXc@GIo1}(QVhhv3Je1Kn8S+&e28Y zSX&%RF%SbY4Coe}V{FdMT-C;E48(v8=oX#hUg+E7ccZ^H%rCyXs|WQU1|H79YhGC% zb&ihm`Qq32seaUt7}$paonu^o_vvqatdB9U&cK>;+#|KueE43o-qpJpcs&EUMK}9i zkUi5;#l4pp12HhefNs$_#^%h-Rc)-sKn%!$ZqYgJh0L+GIF@1{24)!0EjmXRnKLt2 zwXqrlF(3oFMduisV{LIP#Xtj(Z_j(Z_ zj(Z_j(Z_j(Z_ zzq@WFaEzyTU6*jqx<%(0n{x^0+&RSixf#$izZkyx z-5AT9#(zJa`lU5kUdWtly7sOmkIBFfhDZM082^5Z|1iAr>oJ!5 zKSPW}Aj{j5Jvw?BU|+_AjI`sqgJ=%T+J?)j%N zmiidj-UHpDbBxWYx7&MLubytNd_ARSjQ`{C&Ho(ZXTv$>x9;25UAO2Q_d@2>+wHx* zS|)V}Bp`y$<7cysNu4<3x_S`P&HQMoOdQJC{ zZqYfq$ee4s_FKD_wf)Rq&)<*z*0V8|$6M=d*ZZ(F*DX57*qr+Ous&Z}-`p3yd-&oz zW4v#STy!1lduhC_osVwOIqrqbSvyY8KQ6bw8sCL`Zun#I%1peMe>_gF(H@tLOTIUC zi_XzS=3Mf%-150C&UyQA&qv2tzLWduF}}Jn{>`X;*U0_E7<%Iz@%@XUEjq{8oceZ|_l<)P1g7bdGx= zbB;Q%<~fba8UN_3<#$djj(Gk6|LCG#qn)%VT%ImYI!9jE7yS>K-wr@S)8^5}iNe186|F_!NT z>X0qYF~{1y)^uiHlU5kUdWs+$1G>x^<8t0{xQ}ex@Ajj?bn9O zzA?r($JlF4Pj%5=^LCv5)^N{W>K2`&i_F<`?vAyM3Ei?K)*)M*W6nE=YnJZ;ePxX0 zZ(hBBj8Bbmj*?Y+4-tp=itFX!kYy`fJ|jXlnroqNyi%fc=8Q@7|GU1ZKJ_UN3~y!`E! z<^AO4QHRXLdgD~*nD24U*@KRKyB^amI>*?YSUHB3Q~l%TM0&&bb9Bp=*yFVB$E^FU z^;x&*9QQ)z+**Gw;d-~Y$n*4bD;=`MIp$dF@lTDH?*+U##`3p8*UoMET7Y&@s2O^xffw?~Sqi{FSly@0NJ^Irn#rV|;uJfB(jsm(KmX=Nu2)d3fr* z(k(j2y^uLi{dzC${JrniVqLNPY{iGh`1}~>cEXXz_u4OQjXIz6`B1m$99?8iYq9TI zc;6j)zhBy1_94dhW$cpssatf8u{oD~El=^>yzef}2}hofeRz57?UwhvmhlwVv~%9R zZn{P1xEC^~-fr*hmR@<^9eKZ>W3IOiUpzm?7sv2*qSv@3-qN>n_T})g`l(xVjxI9i zvCi{a=kk2&yKPDov-Edt}l$yI@W_rU_iI%9QQ)zT*5hD(>eTTxZuZQEWP(T zcz#dsny$BN$$K)OTXc>tGRNBDSc-udm|;M-=p18nX6C9kR%0LrWI(s*9QQ)zSX&%R zF%SbY4Coe}ql?U$nXB4Zje!`D0o|f=jLosOIF@1{24)!0Ejq`&kU2ARRU4}@5Cbxx zTXc>tGRNBDSc-udm|;M-=p18nX6C9kR%0LrWI(s*9QQ)zSX&%RF%SbY4Coe}ql?U$ znXB4Zje!`D0o|f=jLosOIF@1{24)!0Ejq`&kU2ARRU4}@5CbxxTXc>tGRNBDSc-ud zm|;M-=p18nX6C9kR%0LrWI(s*9QQ)zSX&%RF%SbY4Coe}ql?U$nXB4Zje!`D0o|f= zjLosOIF@1{24)!0Ejq`&kU2ARRU4}@5CbxxTXc>tGRNBDSc-udm|;M-=p18nX6C9k zR%0LrWI(s*9QQ)s9={v?wPAko-CaGX2Qlz)243^Z@~Crkl+PExzEAa|e#F2&4Cox= z`nykm>tlV4fprGfoZ}v;z2?LBn)R;U#lY(s&@H;z_k!%1jwuH3nip26T(gaW7EHG&@DR0*c@w%V<`q= zV1@zRqI28}nKLt2wXqrlF(3oFMd#=ubF3|nr5K2T83uHV&M`J;X0B>uH3nip26T(g zaW7EHG&@DR0*c@w%V<`q=V1@zRqI28}nKLt2 zwXqrlF(3oFMd#=ubF3|nr5K2T83uHV&M`J;X0B>uH3nip26T(gaW7EHG&@DR0*c@w%V<`q=V1@zRqI28}nKLt2wXqrlF(3oFMd#=u zbF3|nr5K2T83uHV&M`J;X0B>uH3nip26T(gaW7EHG&@DR0*c@w%V<`q=V1@zRqI28}nKLt2wXqrlF(3oFMd#=ubF3|nr5K2T83uHV z&M`J;X0B>uH3nip26T(gaW7EHG&@DR0*c@w% zV<`q=V1@zRqI28}nKLt2wXqrlF(3oFMd#=ubF3|nr5K2T83uHV&M`J;X0B>uH3nip z26T(gaW7EHG&@DR0*c@w%V<`q=V1@zRqI28} znKLt2wXqrlF(3oFMd#=ubF3|nrCVd*=U>0O`{fuf{`uXV@qZc5y=6T2(ipealbP$) zEjq{8oSC_*jm@XXfS&oq@XYVVSgvC&{(o}OW(VsQo#S4}oTtc7=ln+ReQDf3KOAFu ztUqt;!Ku#CMb_5aH}=+^=oX!$i_EdM_>cGY()#n>;hOJ{u{;{zkAFWKV|l!^bAGJz zS^D$YG5+lsx@Ak8f3|a^TXc@GIgiCd^KM^Ld!=W##P{QV%SEs6wLV$%k2&_g`1QT~ z!+z)%o#S4}oIkAZ-+#QnkI|nkp4pPqYqU46?b5f;jj`+_bIu$4b1Lt;Md#=ub51>e z`SWYErH5O5GLv)PzNpuxgMlq9o|2eCtnx<%)>7cyty+*stb$=@Nqi)eTy2zZTa$TM08}Ey? z{mfp^-?uMnKX~GvShwgLV{^K%-*{g?#h$n?diP-FJ7c_Wj9hdb>-$ug)Ga#4y^uLi z<+^U|JbyL5bNk%z$KsWlcrX8WoL-~lw6*(Dx9A*QWX{@gdj4@4Tb%Ru;hv9<@t!e0 zJ;qlz#=jZ0?;5$E7(;KIBfcMVJR4(qjG20%TXc@GIWcpY%(&+{)jz*|)jyvcPFUh) z5B1?O&fy=AnTsxyr6ccg-J)~c3z>7|xi!~zK4<)+uYNuJvpC}U1N@_ldX2Vyt*`06 z&@DPg7nyTS*M3dcvX_56j(#{Yz8~&;HpcRJO>5M(ym38si_S4NryjnshnLV3z2Sc5 z)Y#*!Ip+hz3(L+7~xn0z2wEekRTg#)K*DX3n7nyU^c{R^ztm%!njy=N%$5?(&Qnzf0J&yi4bv>*- zM||q}lz$peNA*j$=p18njykXAd2?QVGMw_t7|Wyg_44`ox5ik$L#RWxIL91o_gaIQ zeUY#A_Bx-A^X6o-gz0@r_M;Dp1=iD7@8xy)^ORPh-ILDlK4%aN-1NzDs%kNWv{}`Vd;~Z+4o;9^M<>qI28}nNzPH z-s?B(-CoYoMS4S@oEm$aH#_&9+n0q~?5A$gIl9Q4TkO#}ulZ-=waxN=^75!dW@5c@ zs&mZuIOps^$G%;U=@y-1Y)-5k!^)}t@pB@*;rltdWlQXFTK8kt{nq-dTXc?lA#-l6 zKbLU5TU_LM`ni=3+2R~?to8V(#>@8tmcJLe{B6*+b6Y+a`^*^2``)J>zx=1$Gu@(d zbdfo&_3>-H_8M)=TIdknvKBAjBf1~sg)yw1iMQ;*JpPvJD(83(&(U+;qH~PRImbD4 z%5c{T<^NA0NZtzp>_}b3gAn$HR6Wo_eozi_UQ`WX@B+ z-b*`w@4K~FS1dnU@u4w3KgPM8aOCm5_Dfr%&gXnS)Gazk7n##q?7J4;cSqjumo}Gu zh_QVcyX1cA7M){k&Lv;VQ#?2CyGwJzk>_I{ULJe9utjq&yVrNF?^lqHExNw^sStIIee^s>K2`&i_Cef^Ssu1y&uov zgtcSp3g3VBd`^vhKm1zPtLxg=d%8vE7@Jf7_wB#;xUTRs>*vOP;$vfcc?|Qn#LH(~ z%bw)3V=RB?Yx%tE3uCm7_23d1&@DR0y^uMVaL(6s4nG<$`0*G^@BI#*-_yIM>+M?d zo($*~ouiA)v9>stVju=)7|<;`$Jm^ixvGuT7>EHG&@DR0y^uN97ROQy#J~&#x<%*c zB6DWusy0?*AO>VWx9A*WbF3|nr5K2T83uHV&T%hf&dglZ#%c`2fDGssouiA)v9>st zVju=)7|<;`$Jm^ixvGuT7>EHG&@DR0y^uN97ROQy#J~&#x<%*cB6DWusy0?*AO>VW zx9A*WbF3|nr5K2T83uHV&T%hf&dglZ#%c`2fDGssouiA)v9>stVju=)7|<;`$Jm^i zxvGuT7>EHG&@DR0y^uN97ROQy#J~&#x<%*cB6DWusy0?*AO>VWx9A*WbF3|nr5K2T z83uHV&T%hf&dglZ#%c`2fDGssouiA)v9>stVju=)7|<;`$Jm^ixvGuT7>EHG&@DR0 zz0kME??!)Zm|uK%R}bnz3_P5H*SxYk>Kq;A^Tn_4Q~jtPF|ZE)&F?$h7;SRZ3x zoq;vyxJPQQ`S87Fy{mUI@OlPxi*EM4AbX~xihD0H24Y}_0o|f=jLn&utJ+wNff$eh z-J)~c3z=hWaV*6^49qZ~TXc>tGG}J4YGXA9Vn7CTi_S4N$J*jpih&rIVL-R&9QQ)z z%*<77tj0hL$bfFqIl9OkYl~wk24Y}_0o|f=jLn&utJ+wNff$eh-J)~c3z=hWaV*6^ z49qZ~TXc>tGG}J4YGXA9Vn7CTi_S4N$J*jpih&rIVL-R&9QQ)z%*<77tj0hL$bfFq zIl9OkYl~wk24Y}_0o|f=jLn&utJ+wNff$eh-J)~c3z=hWaV*6^49qZ~TXc>tGG}J4 zYGXA9Vn7CTi_S4N$J*jpih&rIVL-R&9QQ)z%*<77tj0hL$bfFqIl9OkYl~wk24Y}_ z0o|f=jLn&utJ+wNff$eh-J)~c3z=hWaV*6^49qZ~TXc>tGG}J4YGXA9Vn7CTi_S4N z$J*jpih&rIVL-R&9QQ)z%*<77tj0hL$bfFqIl9OkYl~wk24Y}_0o|f=jLn&utJ+wN zff$eh-J)~c3z=hWaV*6^49qZ~TXc>tGG}J4YGXA9Vn7CTi_S4N$J*jpih&rIVL-R& z9QQ)z%*<77tj0hL$bfFqIl9OkYl~wk24Y}_0o|f=jLn&utJ+wNff$eh-J)~c3z=hW zaV*6^49qZ~TXc>tGG}J4YGXA9Vn7CTi_S4N$J*jpih&rIVL-R&9QQ)z%*<77tj0hL z$bfFqIl9OkYl~wk24Y}_0o|f=jLn&utJ+wNff$eh-J)~c3z=hW@zZ7LOMiZM_ro!k z$JVhPJQf4GMd#=ua~|tFn|J;mdGBz|_s3Wsjqk_5pN+9R*5~a#`1#lG?tVGOi=%J< zc|87ZjK8XfCo!a3bdIq(@wuJPOX!uJ*%B`f%0;hVOI3x%RLmI zZ|s3?(K))voO<}i9$rFEw)kWw=YHHj&&F6DFX4KRJck+oSbO9-Kb5(3i_S4N=c!!R zEuZH{h9iD3#_~AhoVD8faok&S(Qn5d=ELKfm)BtbFyh~g@zW8n?SFF4_Wwue7M z$edfgub<+zpW8*Z_8RR^hId{VWAU$^F@B1iJk~ku7M-Ju%z3QyY~JnvPg(2L+J0uQ z=kH&=FPF!)bLjbcBLlic=NOw~ZSm7($$inghcCV}#{0&|MNfB4pW^+fTXc?lA#*?Yn7K@5-1D63pXKwN#Xp}M zV~LkN)Q877hkra~F1k#Xj=aZpi_UQ`WX_T2)?C~9obivo`t|V7;)v%D@Q*I)HQM&I zzNY&^x9A*QWX?5R`!!w5UjFeo`r*j*?Ydicg3UP4dw zhWnXQV~?}uoDU2yEI-G(Jo-7>TK>%Q_hXJ+beYWU!M$$LIqrqb*<;R*u|H3G<5cIE z?{U_=v9^Bac2Td<_UC48EsuI$x9A*QWX@6N)jX%MrZ?U?_6#2!<8x!^mMyWz(LblI zhqdR3Pd%UVPvhyRe(4sSV{Fb*=hZxK&dX1RQ(hTkdGx+sKEL|b7|VAEb;uUym}Bi; zYcR7f^0nSx=hJcCoUO;`i*C_5?uE>GjB~v8IoF({e~fjAZrKuB`?cY+Z;bKHG4@)6 zQ(d&zyd7u1HQck8x<%*cB6IefyJKx*Lbq&*b;uUynDfrzn&o>yUm4>qW4wQiPmOVo zwOYHDbIjE-&$EWJebp^G$Jm_N`Kn*%;M9H2+WkA@A6?{eTDSFet2Yntjc(C7?uE>$ z*AMUYoAqul=jbB6p-)bYJ)2=$zO5v+>$yc|Uo1)FCsm z-Z<4c=6jrT_Ml_muE%tX&M`J8R*qriRR8!nk>2qA9Nn@d_BgHkG3$P7eby~H$Gwm_ zx7MFaxZW);@;v?AN{4K5jycwP{8QuQdjZSes9FAI#M-$npNoBFjOBgrQ;%Q%)9smV z(K))voYwmIwO)ITwq-4Jh;CVnm+ukXkForYQEO-7EqgGJzva5hIiACF^jx>-9Ak6N zaSk1GJ4@dkUijV^%g+^($=W+IiC-8i_XzS=Cl_3u7&sAk@x$h z&1D~AY+uGMxu3d4=NOxF$=C7}&&~Vp(wuPQ`Phf$?;J1hc`f59u4(7Iecg16&T%hf zPQBgU+bzBFzB}@MKgV2e8@_mcj4zJi>qM_{OT49TS&SRbDwa)AP zcn&A59aC5M{SK)2`|U1W~6#jz9vF)+h`ZqYf$=FH4hZLG#X49I|P(K+sg%(1pOmSP|VW*E>d zI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-BcKn%<dI!70oGc#AUu^Iz0 zAOpHZ=NOw~ZE-BcKn%<dI!70oGc#AUu^Iz0AOpHZ=NOw~ZE-Bc zKn%<Y!X4iUT~0ooAk1ZvYpwi7fpB1$AAJRgSIP{W1~+Km&u5CbxxTXc?RA#?0o97{0}12YWh7M-Ju%$b?1zOfnuF(3oFMduisW8dOfih&rI zVL-R&9M3}L%*<8aSdD=gkOAGIb99k8_AQR37>I!x26T(gF*avruKLDm48(v8=oX#h zS;!pw7ROQy#J~&#x<%*cB6DWus&A~uKn%!$ZqYf$=GeD5mSP|VW*E>dI>)n+IWu$B zH&$aH24q0D=p0>Sj(v+`DF$L-h5_B8bBxWInXA6B8UryP1G+`$cos6pzQwT=12Hhe zfNs$_y2zZFx#}CMF%SbXpj&i~u{riFj-?ogff)vLi_Y;ZWX{Z7^^MgShyfYUEjmXR znPcDLSc-udm|;M-=p18nX6CAItj0hL$bfFqIi7{gv2SrK#XtjxI81X0H0i zY7E4H4Coe}V{DFni(@GUVqk^=-J)|m3z;)BSAAnO24X-4bc@c>MdsMIIF@1{24)!0 zEjq{8oSC`m8>=x812UjnbdF~sbL?9jOEC}wGYse!ouiA)nVGA;u^Iz0AOpHZ=NOw~ z-{M$`ff$%!K)2`|&qC(R%vIl5je!`D0o|f=bdfpsEsmuah=Cafbc@b0HfLt8`o?Mu z#DEOw7M+{Z49I|P(K*KE*ta;AVju=)7|<;` z$Fq<*Gjr89R%0LrWI(s*99?9NeT!o$24Y}_0o|f=jLn&utG=-s12G^2x<%)B7Ba`a z#ZQ-|FMR#(?nk37kL_bMcq|5Vi_XzS<~-Iqn|J;mdG~P54@X-bjqk_*em2_jSe>iE zIT_F`I>*?YbFQtq=I;ePvn9UIMLGD4{|@OEo#R=^oSZQ4grjS?#WP!SdX0AZdwn!Z zM~|;tbdD}E=jin`{==Bx;**)2`_4tros0f_)Z{NlTi!?e)z|Lselyy4NBqy@@lE6L zd!xnki))};bdIq()$_&myoCCEXmJ0^Xv^b_bJqIavWxW0e;A(m@1rgL`Sp1G<7mtN z8=HR#Y+TwJbc@dMEM(55t-tlW*oQ~E=+<7N{ljp~zmE1-|C48Qj`4pSxxX82xu2GQ z6aH?rzaK4bU#)>|(K))voa**;*;zZ!?DhQpxUZg#wme=dC;vEH@?S<iFef=Dp~-=$+$!_|9nW87&vRc)xr-^`C}^{>Ny)7e#8uec84?Sai z32a>Q8gz@!(M9H5^0nOZ+7{=$b=(IZ9&NcNJ~`S~Hpagnecv&1KQ@})I3m6ub37Yu zdA#NQ>e^r3f8C;UjLoTTmwDfK<~h|rfB2JsK0chV#LF4#gQFecAIDrAl#4Etr*qxs zx<%)B7Bc5t>uR3UxSa8izFI!3Ssd~58T_M*uJtuq9KV=j-J)}JkvY}##r1rw`t0Q& z$I%bxjPE-a-OOuK-J)}h&3UZ*t9f7SJ-y+1=G546)|~Uc;fLjStjnXHqpju7JfDkR zyzfu_zR)c?$Fq<*PyKqYb^UtdROguQIBVWmtKrcu>NVQ+xk$I@99?A28hbtexNPW+ zH;;44`$zlCXu4%f>^S=8)cv*Z5%H<(DgSZ#T&urs(K*KEtc}z2=h@$%4yXKbwB^zJ zdinhPTca)CA=DvToMVoC_uA8$bCIw0_F7NloQKsdb=EC9$Fq<*TgEJB-~C;4j{Y&$ zA-ZKtY~QaAmwjWjZ;rOto}TKWz2^ql?VhbMD64#)NL!66=sH&N1ih z!!^tIfW9=^@;4;jJK85kJ7TZauH}fi8uOSvoUN;F(K*KE%+6Q;bq-EF=d9hoGyc&< zj?=!a?_0Hbcx`lx&hac{PPKk`t>372dpSoJ=?#5yYV0^~wDz9cmxWubr*6?Xy2zYc ztkIFzy!>{0c|Uo1)FCsm-Z<4c<~z=jHE8VH^_XtaImYJ1%6V8h)jxhtq&Iv&N4IQ= z9jARi&%WPUopp=O@hoJ{t<~oeu6K)zT&JH~>5whXF~`1+e`>sZFJSq*$jjf}T3g%l zx!9*hTi*9Rb^P+5Zq0Oy&e28YwAbg~>$TTtTlPYS=$5s3`5w{zXkQ-9zBBQbGnnIV zxvp}~&*2d@*DX57*qkHQ(3sm<`u_034@O&le`W0byCq(J=l-@a#z#lFDQO zb3AP4;i=b3x9A+tLgqa6>%Fw~d*7|ax?=fl#Ro?F>}W?j;hf`p?U%Mkt>-u&>K2`& zi_B>+_T3BbyK~;}mo}Gmh_QVcyX1Q67M){k&Lv;VQ(T+(-K9CQ>Ia96nY( zb&Jl?Mdm!#IKm&u5CbxxTXc@GIrc4%r5K2T83uHV&hac{&dgl( zjnx>40U6LOI!70oW8dOfih&rIVL-R&9Ak54=BjV3#y||nfNs$_o`uY@Z*eTeKn%<< zpj&i~E;46kuKLDm48(v8=oX!0Y>s`4V<`q=V1@zRqH{b8nKLt2ePcBSVn7CTi_XzS z=GeD5mSP|VW*E>dI>*?YnYrp4t1%D*GN4;@j%Oir>{}d5F%SbY4Coe}ql?U$nXA6B z8UryP1G+`$7@K3?;#i7-7?@!|x9A+tLgviORo_^Rff$eh-J)}JkvaA)j-?ogff)vL zi_S4NXJ)SY#%c`2fDGsso#R>P+v9Jezt+qzzPqai)gT5Q&cJJ4Ssrzcj`I29*Vn0f zRF4?ghXI{qTz&VcZ*{DWF|f|SnsYoOb=G|NS+m+zyBK&q1G+^w`(BVW(^18}mly*v zFvEau(K*KE%*<8aSdD=gkOAGIb36-~W8dOfih&rIVL-R&99?A2%v|-2)fk8Y8PF{{ z$JiYE7ROQy#J~&#x<%)B7BXjMuKLDm48(v8=oX!$i_EcaaV*6^49qZ~TXc@GIWu$B zH&$aH24q0D=p4^N=GeD5mSP|VW*E>dI!70oGc#9xV>Je1Kn8S+&M`K}zQwT=12Hhe zfNs$_o`uYrnXA6B8UryP1G+`$=pu9MTO3O<5Cby|=oX!0Y|hMF^^MgShyfYUEjq`u zkU91(j-?ogff)vLi_XzS=FH4h-&l=-7?1(oqH~PRv2SrK#Xtj%OirX6CAI ztj0hL$bfFqIl9Ok`xeJi48*_;1G+`$7@IRQSAAnO24X-4bc@dMEM$&-i(@GUVqk^= z-J)}JkvTJS)i+jSAO>VWx9A*WbL?9jOEC}wGYse!o#R=^oSC`m8>=x812UjnbdD}E z$G*j}6az6Z!+>tlImYJ9%vIl5je!`D0o|f=JPVm)-{M$`ff$%!K)2`|U1ZM8T=k9B z7>EHG&@DR0*c|&7$5IT$zzhSrMdx@HGG}J4`o?Mu#DEOw7M-Ju%&~8AEX64 z0U6LOI>)n+Irc4nx-5O+>vwlQ8f|%OAFIJ*F`!#?jxI9ivDVqV^Y_TRhiiT~+VW_8 zKmPZ#(U!;RTn*02fNs$_#^#)JZOt`*FX)*q@qI4J!Dsw;NVn)5&qC(pgn1_%UBfM& z*^<+1w9DV?qggt7eBGjRbdfnnucz@J#{3qa%;em6F6vx#z`01b=p18n^25XYaL&4Y zXmIk%Xv^b_bJqIiqRVICoV?A^q+4{3E;8qu zuKm`oW$iq(*Yo$|y!C9fUc*KjwHg+Vc1m_fChb zd1mc-`#!~MKVr?gMduisbHo}NbN*iR%yX)L{_rRNe0(@ziI+3f2S+=?KaP1n=6Gr@ z`s=agzZq?L4Ys_`^M8-_wUZOQS{(86 zXu9I)_$j_d`!}OT|8}(HUh!;WY|at;{?y0REjmXRne)`I_gdG#mwz1RXy>ere?RW$ zXQM5T*ScR_*Ne|T`R8e|uQxo;oEkgMnjhXbys-R^b$Rr2w6*-1=X251;_y_jdbZIy zo`uXgb^P+r!;juL)j8%n&YCyY_Vj2MJ;m2(Yqje6=g&VnM;GOv^EhONNxkvraV~lP zXrCEPw`_?WNB^9a`IY<8(>k!?tCARNZhs(Y( z+BZkrYp+jr(O&a5&VGBiXDxM$&e28Y>^XO1ZDT^WY>9Qq7U!7r_Tif4dq7_r?Ml~bV&RM&EXZ)j!9H)I--?wV>@Y?7W zo#R=^oNE2>TE9{4_HvFc(i{5Z)Yx&}Xze|>FAKL=Pu-$(bdfo?SfeAa`4{80&GLTo z@~A^*V!d&ybIf;~BWuvux9c(8qH~PRiIwxPa;ks)oJeo@evWS05<5=&ex7~5wL0q- zo#R=^oLj5UC0y?o7r9P9x6&b7oMVoC9sksL`Ch>C_bR?O+S=Nd&&579+VZ~lspFUb zbZe$tbdD}Er@cP^Ua!4I+p-rrM7ONP%lC-xNBi<<_MM5hoWUG_%XO7=eh!bQxo*)p z#^xNchQ{2^()WiKelXhd`zvGb-!1X-JNLJZF+Mt)e}7}mOGiKNn&V+R4^O>Tx<%)B z7Bc6lU+<-@-}`PY))mWdD?TvVXGc5Q3FjQ&YrnKTYCXsKP`BtDU1UysvF~1Z-<|V* zzqGlmLyYaq*d^Cfx9A*Wb1wN>p5ofP?=H;==Uk65XYrdv6{CK$FC!;O3_d9rgPw$$p zw`<9JGN4;@jxI9CzQwT=12HhefNs$_#^%h-Ro_^Rff$eh-J)|m3z=iz;#i7-7?@!| zx9A*QWX{Z7^^MgShyfYUEjq{89Qzi>QVhhv3jXw!AO>a_&@DPg7nw6NSAAnO z24X-4bc@b0Hpjlju@nO_FvEau(K()l%$b?1zOfnuF(3oFMd#=ubL?9jOEC}wGYse! zonvgy%v|-2)fk8Y8PF{{$Fq<*_AQR37>I!x26T(g(M9IW%vIl5je!`D0o|f=jLorc zaV*6^49qZ~TXc?RA#-Nts&A~uKn%!$ZqYfq$Q=6?$5IT$zzhSrMduisGc#9xV>Je1 zKn8S+&haet?eVwKUu)(U-`!P%Y7hetXW%ujERQ-zNBMm5>+4iKsz(g$!+_2)uD<)! zw>nnG7+7au%{iWtI%_`stXb`8Rq~ON@aSm|;M-=p18nX6CAI ztj0hL$bfFqIi7{gv2SrK#XtjxI81X0H0iY7E4H4Coe}V{DFni(@GUVqk^= z-J)|m3z;)BSAAnO24X-4bc@c>MdsMIIF@1{24)!0Ejq{8oSC`m8>=x812UjnbdF~s zbL?9jOEC}wGYse!ouiA)nVGA;u^Iz0AOpHZ=NOw~-{M$`ff$%!K)2`|&qC(R%vIl5 zje!`D0o|f=bdfpsEsmuah=Cafbc@b0HfLt8`o?Mu#DEOw7M+{Z49I|P(K*KE*ta;AVju=)7|<;`$Fq<*Gjr89R%0LrWI(s*99?9N zeT!o$24Y}_0o|f=jLn&utG=-s12G^2x<%)B7Ba`a#jz9vF)+h`ZqYfq$efwE>Km&u z5CbxxTXc@GIrc4%r5K2T83uHV&hac{&dgl(jnx>40U6LOI!70oW8dOfih&rIVL-R& z9Ak54=BjV3#y||nfNs$_o`uY@Z*eTeKn%<s`4 zV<`q=V1@zRqH{b8nKLt2ePcBSVn7CTi_XzS=GeD5mSP|VW*E>dI>*?YnYrp4t1%D* zGN4;@j%Oir>{}d5F%SbY4Coe}ql?U$nXA6B8UryP1G+`$7@K3?;#i7-7?@!|x9A+t zLgviORo_^Rff$eh-J)}JkvaA)j-?ogff)vLi_S4NXJ)SY#%c`2fDGsso#R=^9QzhO zU6#J^^}D+tjkY|tkJaF@7|<;`M;Dp%SnF)w`FrHu!!wB>QeIct4$ z(d9F6PTpqb(k(j2vyeG6bJh3!+#c-qa} z-g-9L@_1{t?Rp=!=ekAb7@Jd_A6Dl}tDEPdcMe~CXSDZ>mW!@qe=m)6u@Ty8Usqg=^#gFrNGGqb>e1KmK2>m2S~Fo`uY*Zu@#;uX@h-M_>JJ+$)PCULH+X z934NE*J#W48vbsyzaQ;Cj#@4CTJ9B{vljou$o<#R{%Yj!weL@T9NnUGbdfnv{d%u; z{d@VxagKJ*+W7b5{(Lst@_1?c_3y@-me*K68*R-qYtR4VaL<1kZRvk$*Y#NI(Jea1 z*qp~&XY;<8S-s(T=G546*8K3kasMp8V_hEo9BnOs=K1?E$ECW+*HdfG`A@?)|6{aY zjO#Ezo?qozx9A+tLgrMr7kl8b>Z3PKb&mOtv*wMpYdqRTm;4${w;2Do;hv?w%RRJK zw_AQ*x9A*QWX>(u>XNTrZ@hW1{{GQEGn#JM5<8CmIrZA@dqjNdddj~{|LGQ;V{A_Q z__+J{)8Uj~j0XFx<%*cB6IefyRo)0 zpxb9+jcT`-b99m3&?l$Hj`K!q@40oYkx9A+tLgw6BeJ@8t zmfwOezdKl4+w!^Cr$$@e_da#}@}F+abc@c>Mdq~E=ilqK*JxYzLWk&I>*?YBi7KE+gbYl@WKy9TYi6K?ESkXUVgXzwlT&> zNAvG*ta<6^=UsC=Z0F&r*GjkO9M3}LJoW3nwDo)6t;M=x`EA7qM*Hk&M?2x1<9qFw zwnwe!I3Ma3ouiA)X)pHO3-7yg-tU(-mvxA-eHpvtdg>OPV{FbPU&~WmoA=$NIpLh^ zu?{~UXS?M+ucbZ3J#Ed~_f5Cx9M3}LRNL*f-BK&>yK~;}N6ht>;ft3?`}}CWPV^eL z#9QiC&b}NzRy}o#&e28YJk~m|bzbksBb=}{rmpb)XV-IT?EB%@x?f$_zTVR*?Y z>c4OOy~lNhpIN^&&J!OQ?Te$Cza?Hi<66!npB`=b?|dzvcYSWO_OTjV0t325=Xe$} z=MvU@O>6k^aKTSTTWarj@cf?MHC=DllJ{glx9A*QWR87{V<`q=V1@zRqH~PRnVGA; zu^Iz0AOpHZ=Xe$}$G*j}6az6Z!+>tlIl9Q4nYrp4t1%D*GN4;@jEHG&@DPg7nx(<;#i7-7?@!|x9A*Wb7tnMZ>+{Z49I|P(K()l z%&~8AEX6Xw!AO>a_&@DR0*qoWU>Km&u5CbxxTXc?RA#?0o97{0}12YWh z7M-Ju%$b?1zOfnuF(3oFMduisW8dOfih&rIVL-R&9M3}L%*<8aSdD=gkOAGIb99k8 z_AQR37>I!x26T(gF*avruKLDm48(v8=oX#hS?Js2Z==7~%rCyXs|M8|1|H79YhGC% zb&ihm`Qq2tsd`k87}$paonu^m_o;7ntd23T&cK>;JR^11eE3QVhhv3jXw!AO>a_&@DPg7nw6NSAAnO24X-4bc@b0 zHpjlju@nO_FvEau(K()l%$b?1zOfnuF(3oFMd#=ubL?9jOEC}wGYse!onvgy%v|-2 z)fk8Y8PF{{$Fq<*_AQR37>I!x26T(g(M9IW%vIl5je!`D0o|f=jLorcaV*6^49qZ~ zTXc?RA#-Nts&A~uKn%!$ZqYfq$Q=6?$5IT$zzhSrMduisGc#9xV>Je1Kn8S+&hac{ zj(v+`DF$L-h5_B8b99k8Gjr89R%0LrWI(s*9Ak6rTO3O<5Cby|=oX#hS;(B3x#}CM zF%SbXpj&i~E;7fy#jz9vF)+h`ZqYf$=FH4h-&l=-7?1(oqH{b8nPcDLSc-udm|;M- z=p0>S&dgl(jnx>40U6LOI>*=?`xeJi48*_;1G+`$cos5eX0H0iY7E4H4Coe}ql?V3 zZ*eTeKn%<VWx9A+tLgv`FIF@1{24)!0EjmXRnKLt2ePcBS zVn7CTi_S4N$G*j}6az6Z!+>tlIi7{gnVGA;u^Iz0AOpHZ=jbAH>{}d5F%SbY4Coe} zV{FdMT=k9B7>EHG&@DR0vyeIVEq=Nzec|hOcRw0!d2Ao6!DBI?TXc>tGUu_@*}U`j z$h(JYemL6lXna5Z_p{NK$Ld@S&dGpo(K*KEoO5l>HGePYnJw{sF3Q1Y{C7yV=p4^N z=H!HVCmdbFEuPtu(`&TL-|M4UI(mHFqH}bSIY+Oj@gK(g7N5-I+;=YOTy(&>NVn)5 zV{`Ju!~Ag0x_xMH^2%t-_Gj?-(j$7SP^ z?@isJb99k8mwYX^ytc(TZyoOW@M!NE?USQ@Wn=vN(f1uA_hX~!jU(dwF~_sfmd9J( zude;o{nsrz$Jm_ecA58$XP#62^M^nA=i|c(OT3(+J~-MD{&CF3LAmHMc{97jK# zGroV~=b~Q?hyP}@?~d#E=kfTa@%X*bu8p}pu1B}%9Ak6#n6okVXHjo>o;fvkoHggX zZ`@1E?^u^dKSx{3pLza%%<*irEGTxaluOTmA;h zT0L*!dEKIObdfo?P?M*4je6tFgX#B=_Lui=KnMvm+vwBY{YBlAAPmg8lL(%x<%)B7Bc6lU++^~|C)33kFgHX zEn8yyes$bS-x%$iqwQ6S>{FvH?|Yv*e)&(gX1Yb^=pu94>+|pR+H15ed!a*g%UZmAkLZ51 z<+Eh_&cs{JV2;1#y2?2}hey<0x9A*WbB_}qn~%p@vxnTr(P@FqH{b8ne)`I_tMtyeYY0tisiQz9~kYkqaE#pbB^z| zU)mnEp5uI|TXc>tGN--RcQ3r}&UwFI+FaHl#`b0GlIy8kbdIq(mwYWxac$mrm*#|X zuE#q3e4Oo;_q>+&6!)|>Z{IiFqH{b8nNw}I*LF*-yzkC=zaKHzTZS)Q9_{m^`8v^S z+!Al8TRHo3_*nJSEjmXRne$ldyw-WWACGXt+L*e+_n%$Qsj=^eU+aE#UHf`Zx9A*W zbE^No_4gjv6@F&@(l}3iWVA1iX8x9V`HX8hlPrIyZ~5Km&u5CbxxTXc@GIrc4%r5K2T z83uHV&hac{&dgl(jnx>40U6LOI!70oW8dOfih&rIVL-R&9Ak54=BjV3#y||nfNs$_ zo`uY@Z*eTeKn%<s`4V<`q=V1@zRqH{b8nKLt2 zePcBSVn7CTi_XzS=GeD5mSP|VW*E>dI>*?YnYrp4t1%D*GN4;@j%Oir>{}d5F%SbY z4Coe}ql?U$nXA6B8UryP1G+`$7@K3?;#i7-7?@!|x9A+tLgviORo_^Rff$eh-J)}J zkvaA)j-?ogff)vLi_S4NXJ)SY#%c`2fDGsso#R>P+v9Jezt+qzzPqai)gT5Q&cJJ4 zSsrzcj`I29*Vn0fRF4?ghXI{qTz&VcZ*{DWF|f|SnsYoOb=G|NS+m+zyBK&q1G+^w z`(BVW(^18}mly*vFvEau(K*KE%*<8aSdD=gkOAGIb36-~W8dOfih&rIVL-R&99?A2 z%v|-2)fk8Y8PF{{$JiYE7ROQy#J~&#x<%)B7BXjMuKLDm48(v8=oX!$i_EcaaV*6^ z49qZ~TXc@GIWu$BH&$aH24q0D=p4^N=GeD5mSP|VW*E>dI!70oGc#9xV>Je1Kn8S+ z&M`K}zQwT=12HhefNs$_o`uYrnXA6B8UryP1G+`$=pu9MTO3O<5Cby|=oX!0Y|hMF z^^MgShyfYUEjq`ukU91(j-?ogff)vLi_XzS=FH4h-&l=-7?1(oqH~PRv2SrK#Xtj%OirX6CAItj0hL$bfFqIl9Ok`xeJi48*_;1G+`$7@IRQSAAnO24X-4bc@dM zEM$&-i(@GUVqk^=-J)}JkvTJS)i+jSAO>VWx9A*WbL?9jOEC}wGYse!o#R=^oSC`m z8>=x812UjnbdD}E$G*j}6az6Z!+>tlImYJ9%vIl5je!`D0o|f=JPVm)-{M$`ff$%! zK)2`|U1ZM8T=k9B7>EHG&@DR0*c|&7$5IT$zzhSrMdx@HGG}J4`o?Mu#DEOw7M-Ju z%&~8AEX640U6LOI>)n+Irc4nx-5O+>vwlQ8f|%OAFIJ*F`!#?jxI9ivDVqV z^Y_TRhiiT~+VW_8KmPZ#(U!;RTn*02fNs$_#^#)JZOt`*FX)*q@qI4J!Dsw;NVn)5 z&qC(pgn1_%UBfM&*^<+1w9DV?qggt7eBGjRbdfnnucz@J#{3qa%;em6F6vx#z`01b z=p18n^25XYaL&4YXmIk%Xv^b_bJqIiqRVICoV?A^q+4{3E;8quuKm`oW$iq(*Yo$|y!C9fu$Ef-zK{$3hyYwOW1I>)n+Icwwe{Nr-_+ppc-y)^u>cx5Ku%Ri3OYqZB@ zu=rVaa*L|*A zbdF~sbI!G{<~fba8UN_3-wppPj(GVD{?SFfMmuf4ujT&GEjmXRnR6}IeQnpVmwy~b zKb$kZ?_6{N>Z$9%_G^Tt~3j&@P6(XP)$x<%*cB6HT*>-ooJLvOr!oJ-z6 z+Gj@7En8y8(Lbl|uYHe*PhHPB^Z$C({clG5`Dp(<-cNhec>LaI=Ul^6nM=3m9Ak5y z%5`1qI)6Gi{^e-Pqxbdl`T4g-TfRf6L$)}_9Q*E7!1qkVVO z|JUR3kE1Q~7@Kp%8lK{qx<%)B7Bc54UgJ|=^O|$?kFgHXEn8yyes$bG-x%$iqwQ70 zQ(d&zyhn`lXQM7(9_`s^dS*+Ui(X|)x9A*QWX=)$*qATAzje!&SchzJjyZ21_tNq` zpf8QKyl!~!XrCDEh&@`nmLujmVoV*f#X08K_lUJUl`(aT&M`LUsa)4nT<59hoVELR z#y`5qah_s5&$(uOqG#6Pe;KdOdSB@7PPgbB&qC&$b5Cz!uDzV2i}Z#*IW=~iTiA=4 zYy9(ZM*NG>mcQw*i`L?qxvr_NZqYfq$ee4s_Di^yUkqNC_mh`L9WoQ^jZ>XtzT;d% zty;q|uY(`6uDV6%7@PB$YrUnpPxX(V6X^}#&(SSgV#m3q+IOwz^PFzcIi7{gX>ZQA zH?P%ti;G^%T^{}1N{4K5jyd*q{8QuQdjZSm(#v;X*4DOsF7~O>miN6+9l!jiTQl9F zb99k8?e+QhdhIpZmc7s+x@9e1zDIOF+VZ)weP`k=XE4X#a$V(|pTi?+u3L1Du{lSq zp)t3!^!?$5AB?vA{>s?tGUu_@d9Cw$KOW(P zwJ~*t??1bqQ)Ax`zt;Wgy7u*+ZqYf$=2ZWE>+e0TEBws*rE#A4$Y@_2&HOF#@)_51 zCi(Pe%YWx<`Mm3MqqUFK;1U?nEjq`ukU5vI=4)ERkB19>GTKsmzk}!Z^sec8yOz8s z1G+`$=pu9MTO3O<5Cby|=oX!0Y|hMF^^MgShyfYUEjq`ukU91(j-?ogff)vLi_XzS z=FH4h-&l=-7?1(oqH~PRv2SrK#Xtj%OirX6CAItj0hL$bfFqIl9Ok`xeJi z48*_;1G+`$7@IRQSAAnO24X-4bc@dMEM$&-i(@GUVqk^=-J)}JkvTJS)i+jSAO>VW zx9A*WbL?9jOEC}wGYse!o#R=^oSC`m8>=x812UjnbdD}E$G*j}6az6Z!+>tlImYJ9 z%vIl5je!`D0o|f=JPVm)-{M$`ff$%!K)2`|U1ZM8T=k9B7>EHG&@DR0*c|&7$5IT$ zzzhSrMdx@HGG}J4`o?Mu#DEOw7M-Ju%&~8AEX6bp;Ut7CPH zfprGfoZ}g(v*yFkn$@n_#lY(s&@H;z_kygMjwVWx9A*QWR87{V<`q=V1@zRqH~PRnVGA;u^Iz0AOpHZ=Xe$}$G*j} z6az6Z!+>tlIl9Q4nYrp4t1%D*GN4;@jEHG z&@DPg7nx(<;#i7-7?@!|x9A*Wb7tnMZ>+{Z49I|P(K()l%&~8AEX6Xw! zAO>a_&@DR0*qoWU>Km&u5CbxxTXc?RA#?0o97{0}12YWh7M-Ju%$b?1zOfnuF(3oF zMduisW8dOfih&rIVL-R&9M3}L%*<8aSdD=gkOAGIb99k8_AQR37>I!x26T(gF*avr zuKLDm48(v8=oX#hS;!pw7ROQy#J~&#x<%*cB6DWus&A~uKn%!$ZqYf$=GeD5mSP|V zW*E>dI>)n+IWu$BH&$aH24q0D=p0>Sj(v+`DF$L-h5_B8bBxWInXA6B8UryP1G+`$ zcos6pzQwT=12HhefNs$_y2zZFx#}CMF%SbXpj&i~u{riFj-?ogff)vLi_Y;ZWX{Z7 z^^MgShyfYUEjmXRnPcDLSc-udm|;M-=p18nX6CAItj0hL$bfFqIi7{gv2XFyW$6oF zzq|XlU4( zi_AHCJ&pe`=C}A{Cg;9$QRkuq&PBRK=NOxlA0Fn1bJp!cgOgWATOMbev(`5kT|NWn zVku3L1Du{qWGVRgQ=x_K^o=kUdMMtjd_x#&9f_tJPLz4{&AdMqdhJgmwa#P7M-Ju%(>)ix#hJj&Ux!_&xc2Q*Jz&{ z?JFDO-;ciU7`Y!CO>Z0#-;X(-jkY}A@_u#gukOEY(K*KERJY5#Z#?sy>YqRS$v+<- zPFUjQ4E4d$j_{9TE)L2?m&wz)?sMIub36-~bFOtY&uLuF_(xy;Zun<$#LH*!k1pyp z+G+cJE%%3R(K))voNKx6YrBrU{Np(K;hgb(=c1c=ZK_*zj=HGpELm zv*w)l4L>ZuV_hEo9BnOs=J{N7-RC0RqH{b8nR6}o>$P2n-Z<4c<~z=sH`Z!*w2OL; zc6~0=EjmXRnX|@T&p$33dgIOGT=M?WJ~Ntb*%CXB{yBAj?R!Lg>Uzq5Tt3(8uUmAE zu{mqw^!$1D_ou@tzZ`9O^uAs`KmXQf%XbKM$QI|AW8b~@bmm;-YrVbJ(>Uj0bxWOf zi_Y;ZWX_f`%h`8-*PNq&jCF`^*%I6LtHWjA810**?X{<;x@fO?8)v^g+_RRtMd#=u zbM~COv9>XxTeieHWQ%jmdHZn9@;#t0jrOL|-aFbSMmu7!)~@A1cJr^b%6-}}_@FD-xBujRW} z%Xh?c&Wra`x9A*QWX`4S^)0Mt?KRq#Yu6#VWi4L5M|3~hmq)YjOuXd`=J;E#tDG0# z*H5KBx<%(0oAXqz>sr_O{o#cljJEvSYV7^HC0>5#{)Lg=;vMYweDTl z^}I86i_Y;ZWKK1FzJ@b3@xEJ&b;a`AiVuwT+0l-6!a2wH+Gpxn-+lQ!x}Lg4=jbAH zj$Y5LjqiPT&inn+=CTgA#=tFKuWr#f#^&5|t&X^M@4HKL!a3Jt9ezH}cFTKSOFN?G zjd?kB)h#;5vyeIM-M)M0eRt0L{fN2VGJNs!XrCX=*NI-^mN>@tW$cpcsatf8E;8qm zujMJO&HM2PC#;RBD}4Xi^_&{}e)v<|i`IO8@97quV{A@)wC^5ykLwCQvwmruCq6RT z7e_OHOT2u>wVX+o@98f8ov-EduFs9uK30QEU_iI%9M3}LT*8{KX$?OfF8Il4OYQv* zp5N2Ert9rm@}3On7M-Ju%&~8AEX640U6LOI>)n+Irc4%r5K2T83uHV&e28Y z%*<8aSdD=gkOAGIbBxWgZ*eTeKn%<+7ROQy z#J~&#x<%(0n=><4ePcBSVn7CTi_Y;ZWR87{V<`q=V1@zRqH}bSIWu$BH&$aH24q0D z=p18n>{}d5F%SbY4Coe}<5|d@nYrp4t1%D*GN4;@jxI9CzQwT=12HhefNs$_#^%h- zRo_^Rff$eh-J)|m3w?Y1ZS>cg`Nem4)u0;0z{44M%`3~J&e2gmU;O$yRgdZs1N$(b zbBwF+KJ~4R)iDOv8CY|UXQa-W4?k;GyJ{B$uV+BF=w{ywvSvD}xc3rcAO>a_&@DR0 z*qoWU>Km&u5CbxxTXc?RA#?0o97{0}12YWh7M-Ju%$b?1zOfnuF(3oFMduisW8dOf zih&rIVL-R&9M3}L%*<8aSdD=gkOAGIb99k8_AQR37>I!x26T(gF*avruKLDm48(v8 z=oX#hS;!pw7ROQy#J~&#x<%*cB6DWus&A~uKn%!$ZqYf$=GeD5mSP|VW*E>dI>)n+ zIWu$BH&$aH24q0D=p0>Sj(v+`DF$L-h5_B8bBxWInXA6B8UryP1G+`$cos6pzQwT= z12HhefNs$_y2zZFx#}CMF%SbXpj&i~u{riFj-?ogff)vLi_Y;ZWX{Z7^^MgShyfYU zEjmXRnPcDLSc-udm|;M-=p18nX6CAItj0hL$bfFqIi7{gv2SrK#XtjxI81 zX0H0iY7E4H4Coe}V{DFni(@GUVqk^=-J)|m3z;)BSAAnO24X-4bc@c>MdsMIIF@1{ z24)!0Ejq{8oSC`m8>=x812UjnbdF~sbL?9jOEC}wGYse!ouiA)nVGA;u^Iz0AOpHZ z=NOw~-{M$`ff$%!K)2`|&qC(R%vIl5je!`D0o|f=bdfpsEsmuah=Cafbc@b0HfLt8 z`o?Mu#DEOw7M+{Z49I|P(K*KE*ta;AVju=) z7|<;`$Fq<*Gjr89R%0LrWI(s*99?9NeT!o$24Y}_0o|f=jLn&utG=-s12G^2x<%)B z7Ba`a#ZQ-|FMR#(?nk37kL_bMcq|5Vi_XzS<~-Iqn|J;mdG~P54@X-bjqk_*em2_j zSe>iEIT_F`I>*?YbFQtq=I;ePvn9UIMLGD4{|@OEo#R=^oSZQ4grjS?#WP!SdX0AZ zdwn!ZM~|;tbdD}E=jin`{==Bx;**)2`_4t3iw-y!=@y-1Y)*c7m>-t-&}P044jj)78*<85s{ zx<%)B7BXjToSuJNZh!l=yStZ$KNhdd#C!S2ae9sRxNKbVy{TJtjxI9ilCR~K*S0w4 zt;0PZ9_?MDeR8y~Y>aLEOPv^SNb&JmNEM(5P*3~?xaXI53ef7KH zpT!X`pTR%6sMlzx?f13ZAG$^7=pu8j<+`u!I`;C96j7dGvF%wfvdqbJ2C5i*$?5@hoJ{wcM}Qb{%@-ROguQ zIBVWmtKHEq>NVQ+xk$I@99?A28hbtexNPW+H;;44`$zlCXu4%f>^S=8)cv*Z5%H<( zDgSZ#T&urs(K*KEtc}z2=h@$%4yXKbwB^zJdinhPTca)CA=DvToMVoC_uA8$bCIw0 z_F7NloQKsdb=EC9$Fq<*TgEJB-~C;4j{Y&$A-ZKtY~QaAmwjWjZ;rOto}TKWz2^ql?VhbMD64#)NL!66=sH&N1ih!!^tIfW9=^n?`%@XrCDEh`n07mLukB z%wzU&wywHG=NOwaJ74|RIXLy4vv&W^_(vBxPW!gLZ`J1Ewb3m)$Fq<*)%xMJexus$ zce6(x0<~^=Kx9A*WbM~0CG5-JgJJmmaPNX+{ zKS#H0i5;gsdw$RK%&&)g{y5rFr?q&=|IefSW&Zj9{Ht4Zj%Oir;_!J6kFLoU7r6#M zx6&b7oMVoC9sksL`ChB zCCsZ^bdD}E=MvU@Yin40jkcu@Iz+du#mo1I?nnFbX!f0nx17Nof6H}ULe7kTE@Azb zum;_tbBxWogf-vt8oocg@PpBo-(MMf|89ww-?_hSjPcRY{QDbgUOM`D*ZdUscg;or zH0r$keWjm`I-BzpuknaA>lU5kS;(9t)^N*Xdf%}W?j;hf`p?N6PD zKO1|qoFAW!_SCQC==JLsouiA)IeI;}Hoo`WIq&yNo69=f8Uwd{y}Cu`7@Kp;wL0S3 zz3(o~3Flmobyz;1Uf%Os+7UHx%*&~(ZqYfOh0JO1_T4-0yK~;}N6ht>;ft3?`}}CW zPV^eL#4)xnW0zb{-J)}JkvW%qEl+W6-j7E(VQoxZ;rq|7=hWEu!=K__wC3}BPq*kC zV{_W0efP+FTvzy+^-JSC@sZKKIGXue;^i~0!_JPX=_0&e28Y*ta;AVju=)7|<;`$Jm^i zx#}CMF%SbXpj&i~XCZU!TO3O<5Cby|=oX!$i_DpstG=-s12G^2x<%(0n`7VNSc-ud zm|;M-=p4^N=FH4h-&l=-7?1(oqH}bSIrc4%r5K2T83uHV&M`J;X0H0iY7E4H4Coe} z<5|cY`xeJi48*_;1G+`$=pu7w=BjV3#y||nfNs$_#^%_!IF@1{24)!0Ejq`ukU2AR z)i+jSAO>VWx9A*QWR87{V<`q=V1@zRqH~PRnVGA;u^Iz0AOpHZ=Xe$}$G*j}6az6Z z!+>tlIl9Q4nYrp4t1%D*GN4;@jEHG&@DPg z7nx(<;#i7-7?@!|x9A*Wb7tnMZ>+{Z49I|P(K()lzCHdn`fJVn;=8+QPz_?>;S9Xy zmE}?A=qR5retn&)NA-w-eHhR=#?^P9`c}v47z67JtU1RsQfJMFpEavpwTpq*GoV{^ zv+o62GaXgjdx40U6LOI>)n+Irc4%r5K2T83uHV&e28Y z%*<8aSdD=gkOAGIbBxWgZ*eTeKn%<+7ROQy z#J~&#x<%(0n=><4ePcBSVn7CTi_Y;ZWR87{V<`q=V1@zRqH}bSIWu$BH&$aH24q0D z=p18n>{}d5F%SbY4Coe}<5|d@nYrp4t1%D*GN4;@jxI9CzQwT=12HhefNs$_#^%h- zRo_^Rff$eh-J)|m3z=iz;#i7-7?@!|x9A*QWX{Z7^^MgShyfYUEjq{89Qzi>QVhhv z3jXw!AO>a_&@DPg7nw6NSAAnO24X-4bc@b0Hpjlju@nO_FvEau(K()l%$b?1 zzOfnuF(3oFMd#=ubL?9jOEC}wGYse!onvgy%v|-2)fk8Y8PF{{$Fq<*_AQR37>I!x z26T(g(M9IW%vIl5je!`D0o|f=jLorcaV*6^49qZ~TXc?RA#-Nts&A~uKn%!$ZqYfq z$Q=6?$5IT$zzhSrMduisGc#9xV>Je1Kn8S+&hac{j(v+`DF$L-h5_B8b99k8Gjr89 zR%0LrWI(s*9Ak6rTO3O<5Cby|=oX#hS;(B3x#}CMF%SbXpj&i~E;7fy#jz9vF)+h` zZqYf$=FH4h-&l=-7?1(oqH{b8nPcDLr_0h8zJ7Q2qtTYf_OTi~76ZCP=jbAH9&4S= zJAaS7d${I@qb-ld_v3#*8*O>4&ehd9DK%qhjfe1 z@hoIcPMCMX(KX!SnJqcJM!WpIKANSY$JZ@7M;DoM^m-cqVa#vw$xP0D=c3L<2b_y^ zi_S4NCqF#Q59h4ghXyCFjJ7<^IA^VIF1maM&dJ-%T)IW)cos5eX0H04pWCBd)N8c! z@98z&N4iDl=pu8j>Dq7YTGq}pdp&an?~L}I(Q?ss?C+)VwzeMKqH{b8nX@)d&p$4=zx~?X-AltCi&tjiz5L@iy+(Un zHZJ+z)Gazk7nyU(*K*5iTb%RO;hqnV_O8)BIoek?#=jqZ-!XDOHk#fzBEBDUJR5C! zyygAs+F#v&-J)}h&8cpedEa>EIn_UZ_>+G=KAf<`%Ngo}qaEQN$6Oqgi!PI=bKU2< zMdx@HGUr_DYM#@$obivo`rYu);)s{e;2&MoYqZn$`&#Y~-J)}JkvZ3L-Pd*<~a=(^8E zx<%)B7Bc5r?$>L(4!v=zbIf;~HE*od?r0bF8twXAq+4{3E;470y`FzuHuT1u$GPPF zqkU#H-LfTi9Q||Z{@VA5_|)~3|G0dv)nB*h9Ak6V#_9RX0qYF~`1p?di<9$k%#%t*3F$!|Ikg>lU5kS;(9%W0te;{;oMk{}}5K-LfUN z?^lP*zA@T2N84*pPj%5=^ES?Yd$?yUb&Jl?Mds`|cVlg1Lbq&*b;uUynDh4Gn&o>y zUmERAqrG>uPmFfNUaeir5py->F?%>$SKXp>jLn&yum0;CoO;e#yMJf=ql+A;eOuqR zYV+{g=oX#hS;(Af{qS19QSJ6}jxN$0`sCEuao%X{J-06lw^&czqH}bSIk#A&Bd_@v zlU5kS;(AQtIs7|?-m!iPCvKOAzPedj(r{f)Oh(`z;{Rc-e_xUTRs>2)M(55 z-lvXV{?o0QZqYfq$ei~2{CmCj8g0v7=n&nq7BAl;x*zS!quF;R-f{+W{4LjY2|0g0 zYV;SQE&m_}qn~%pm%OJx8}<76Xv=$c|1fI!ucQ6dh<`mE|2W#R_O)0qUGg=a zb8Wgs=Xe$}=bUT1g}J=%)?!_;{I=o)qkVR?qn&Wh@xAs--gh0c=9#tU?R&}Bc+R!y z7M-Ju%sJ=UZecF(yK~;}mo}Gmxa58Rcf*?YOJ?IK zuFd=I(wuP4^;n1H_0960*U~O|PxZ+^jn`hw-?9Cly=2ZMU&~{yO}FSA&qC%r);h0s zUhlhe-tR}u^_Jm_mq+{jXueML8n?txeXsv)T>tX^{j<@Y`n4Rre%+#Tbdfnnujkgr z_kKLW32S5O3g3TrJ*URLAAW25*!4clwYo*;7@Jd_A6DnJx_OW53O}=cY5Y6-kWslDI9 z^Lu)?P=~JZHod1?bdD}ECr)mYllHxRKY{_>qH~PRIbscs8QU>%n+)g{o#R=^oH)5n zPTKeO{Rjqhi_XzS<{Ytx#*FP4xJ?Fhi_S4NCr)mYllHxRKY{_>qH{b8nRCP%8Z)+I z;5Hf1EjmXRnG+|s$w~X(z8}GWZqYf$<{Ytx#*FP4xJ?Fhi_Y;ZWKNviCMWHC`+fui zx<%*cB6E&dLu1Bv4BRFIx<%(0n-eFu$w~X(z8}GWZqYfOh0Hl(4UHMwF>sp<=oX!$ zi_D3W+vKEuZ{Lq#K)2`|V{?vJLu1Bv4BRFIx<%)B7BVMJZj+Pty?sA|0o|f=bdfnn ztf4VuI|go(0o|f=jLnIY+vKEuZ{Lq#K)2`|&qC%Lv4+Ns?HIUC26T(g(M9IO$!&7d zzPIm3FrZs>j$fX1M3W|Ima_nXU&J7HLG2o#R=^oS2E37>I$r7|<;`M;Dp1*Sw7r z!!Zy8x<%(0n-eoJ69X}@7X!LQ=Xe$}XRmo1Cx&An26T(g(M9IOOw7bU4D7{#ZqYf$ z=Ik|ZMdrjz%)~$p?8Sg?(K*KE>@{!W#BdD6fNs$_o`uYbnV5-z7}$#e-J)}JkvV(K z+c+^C12LdmbdIq(F%vT}5CeNLpj&i~XCZU;nzwOcI0j-sx9A*QWKPV)Obo=pUJU3K zonvgyUh_6i497qW=oX#hS;(B2iJ2IPfxQ^eEjmXRnX}itjT6H$5CghJ=NOw4Gcgkb zF|Zc{x<%)B7BXkAc^fB&V;}}}i_XzS=EO|Q#6S$}#eiSPRzti48*`*4Coe}V{Fb|^EOTl$3P6|7MwB>QeIct4$(d9F6PTpqb(k(j2 zvyeG6bJh3!+#c-qa}-g-9L@_1{t?Rp=! z=ekAb7@Jd_A6Dl}tDEPdcMe~CXSDZ>mW!@qe=m)&?{_6hg7M){kPIbG?`^GcRss8!HpZxRj;e;h#&QKp5 z?Fj!k=Hj4SbeTMz>ps^lI>)n+Ip>{`$K`Xa{<=ly7@M;;PS2lb ze}6ih^2^bdNAK(9^Yd?wwtRtGH1`Z8*3XA zx@AkOL$)}_oVO3xEZ+nA(r9lQ?Y*OYVzeXnYVBH%n5!|5*~8ho>K2`2Y|iX_^oYkx9A+tLgw6BeJ@8t zzB}6YMq69k^10ZjMqA$ZK6U)^pKi@`i_XzS=Cs%6-|My4Xj}F|hv=5Ic=;aD{b*kv z&Av17mNS^+Z@I2=&d=cyHPO1J17&qC%r_3OQ~^?To~#kykoZN&#h`|M~(JK>z;d+nFD zN3G{LAL6MJJLmm=#9VI~_uKOW(PwJ~*t??1bqQ)Ax`f9m_Pw*EEGtUaH9 zw);ot80ViC*Km#1Ezf(8>k2=!erf!>`;pPUIGXue;^i~0$&I>*?YTdPmkn-gN- zI0kf!&hac{PJ40OUR2v^dut5n7M-Ju%(=DtbiFwt299Gux9A*WbJ~mJ_M+NW+goEm zx9A+tLgw6BeY)P95Cg|Cpj&i~E;6URIBqYhZMD5M26T(gF*fJc>eKb+gcvxE0o|f= zJPVoAUL3a<)wbH+8UwmT=jbAHZmm9DZ%&AT;~3B_I>*?Y_Tsp`sJ7Mi))>$&I>)n+ zIk#4yt~V#dz;O)d7M-Ju%xN!<+ly*jZEuYM-J)}h&AGMubiFwt299Gux9A+tLgus= z$L&S6t+uzufNs$_y2zYct54UP6Jp>v26T(gF*c{YIBqYhZMD5M26T(g@htT1@i(r_3eM-1%4fX*?lzWda-I#$ORSZ83(Ii8U^ zYd-v}S?#J_47{EJ-J+X)FUXqdsN&u)je!`LVL-R&9Ak54=BjV3#y||nfNs$_o`uY@ zZ*eTeKn%<s`4V<`q=V1@zRqH{b8nKLt2ePcBS zVn7CTi_XzS=GeD5mSP|VW*E>dI>*?YnYrp4t1%D*GN4;@j%Oir>{}d5F%SbY4Coe} zql?U$nXA6B8UryP1G+`$7@K3?;#i7-7?@!|x9A+tLgviORo_^Rff$eh-J)}JkvaA) zj-?ogff)vLi_S4NXJ)SY#%c`2fDGsso#R=^9Qzi>QVhhv3Xw!AO>a_&@DR0vyeG6bJaIiV;}}(K)2`|U1W}Zi(@GUVqk^=-J)}h z&6%02zOfnuF(3oFMdx@HGRMBfu@nO_FvEau(K))voSC`m8>=x812UjnbdIq(_AQR3 z7>I!x26T(g@hoJ{%v|-2)fk8Y8PF{{M;Do6-{M$`ff$%!K)2`|V{>Nas&A~uKn%!$ zZqYfOh0L*UaV*6^49qZ~TXc>tGG}J4`o?Mu#DEOw7M){kj(v+`DF$L-h5_B8b36-~ zGc#9xV>Je1Kn8S+&e28Y*ta;AVju=)7|<;`$Jm^ix#}CMF%SbXpj&i~XCZU!TO3O< z5Cby|=oX!$i_DpstG=-s12G^2x<%(0n`7VNSc-udm|;M-=p4^N=FH4h-&l=-7?1(o zqH}bSIrc4%r5K2T83uHV&M`J;X0H0iY7E4H4Coe}<5|cY`xZZ4mcH=yySpEawmi0v z)!?xh&@DPg7n$=|>ulcnd*t22H9s6}c{IKs|NGf!%VTw}2Ipizx9A*WbI!T8=9<43 z^vss{J{RTSGyXfITXc?RA#-xVyc3SD;TF$q$>}xP;EFC?*ZqYfq$eg3s)A$c# zev40La_&19buK#KT%=ocj_mTFO9dg_2?Fz<5|d@wQ+j>ak>5N*Y56K z8vai+8%onvfHb-T>_#xu{U{`te7{PXeQge6|iP#+xa z2>&?d;-Fk~nLM5AKG!We$Fq<*=UP|uoW|vhfArPwhJO}EynF`#=%QYuowncCa)0O+ zouiA)xt8m`w(Ho-KaQgx&Kci#F1nf5rn*Jv7@Ko#_wBV@kKXV+b8753YtDJ!@Wb*u z*5%R9(bn>3p3g)n+IoEQ(UfXr(jZ>XtzT>QUW36^ayQtS_*XJVLqH}bS zIcx0o{Nu8rH{LwXCGQ{YGo$I2EwSV1pHuhOzDLBTuBZIR<#Vn6x<%(0o3l1f&!1<1 ze>$A<%h8rc@9X9B^KXr|e1}knY;le`_T6hwXU;{w*4t}6jdLDWx71m;=p4^N=4=_W zoPGCq%{ltVScmAAEwO#SI$ZXR(Y`s_UVD0~i}sqgarWE8J!`33bdD}EXV1ACYa0`~ zWlO9>wm8R}w-47W-vj#6Xm1+ry`z0%v?KOv?OKkQt1*w+!`Zs(7M){k&g^{kU+3V| zbI#iRJL4Z+1cJr^b%+Mr-f6eOb80 zdg>OPql?VB#Tp%X&A%A0ZI<_wmq#5k6YGsronyY^99e_LzFm*$7M){kPOO}Vl~euW z=R|tL_j7d1me_IH_w(%gt<_n#=p4^N=G-eX}%l87l zJKFa~TU*=mx!9*hTi*9Rb^P+5Zq0Oy&e28YwAbg~>$TTtTlPYS=$5s3`5w{zXkQ-9 zzBBQbGnnIVxvp}~&*2d@*DX57*qkHQ(3sm<`u_034@O&le`W0byCq(J=l-@a#z#l< z?{BPm>FDQOb3AP4;i=b3x9A+tLgqa6>%Fw~d*7|ax?=fl#Ro?F>}W?j;hf`p?U%Mk zt>-u&>K2`&i_B>+_T3BbyK~;}mo}Gmh_QVcyX1Q67M){k&Lv;VQ(T+(-K9Ch@SUe>Sddd2jyNX#Zxke>>W8uRPXzp8CAHMd#=ubDsM3UfTM-ACGXt+L*e+_n%$Q zsj=^eUs|1K*7K|JUj1)ITfRf^>+$%<(U$T4(|G(Jqb=t&b7tncwZ6JV=NOxFYxOz$ zdcDVWg`Zi!H2D6=XkQ%7{4MeF8P{?q`SfVZf9GrYyz6tL9erI-eSCeQbGF3)GMu#h zc6a%{(^Id*(d*YOI>)n+IY+PO*2e$wVDu-WEw%SMcz#ds)@pJI*E{1M`(DDeT=E)p zi_XzS=3Mf%w6^}e-HUfqxonvgywbr5Q>Rwr6;NK6g{MXU`a`?ovjq(36{{Q8Dp~XFGg|b&G-L8PF{{$Jm@|_RjEbTMRtUfNs$_y2zYr_MdnoJht;{dRks*;o&nvWbBxWYhR@fqnpBe* zco+k^Mdx@HGN(E}tj^V~y2Zfr4Coe}ql?U`hR@fqnpBe*co+k^MduisQ=K1H=jvA7 zV&HiObc@dMEcEU1Hzi+d<`>`HRfB2}0}p55HLom>I!9OgeDUk+R6VLk4D7>z&M~gO z`_#8OR>v4vXJE}ao{>6hKK!g%?W$c2yq*EwqMLm$$eQV>;^*H_t0vVX2DUSxTXc@G zIn{Q1ZL3waih&n1pj&i~XCZT{=ZouEeX36kY-d2X=p0>SPPN@$+iF#z>68sEjmXRnNvMqT+ixLePUoc1G+`$ z7@JdVx7W5>RjU|yF$20q=Xe$}r+U7)p4F%N#K3k2bc@c>Mdno7?X|5|)hY&F%z$pu zImYHx&llIT`c$77*v^1%(K()l%&E59Yg?_VRSdkC0o|f=bdfpL^TqY7KGi1%wlknx zbdIq()pmPrt5vm%ffqBNTXc?RA#sfuOPYi5lK)2`|U1UzR-Co;jRjp#+ z#SG{convfH^?Y$Xt55Zbf$a?F7MJzreU>QjAU zU^@f4MduisQ*F1`wpvxI7*hiiT~+VW_8KmPZ#(U!;dw;G(20o|f=jLkXc+L~+rUeGgJ;`>~b zgU|TykZ#dAo`uZG3G+@kx`takvn8k3XqUg&N3(SF__{^s=pu8DUQgpcjQK4-naR2D zT-3SffOC;<(K*KE zb9=OldX0AeJ-w#;NVn)5U1ZKRUHh$F%i4KnujlW_dF$C|%j2!pw(EV^p6eE!V{A@! zepsC^t!|!+-Z^~nozdPiS}wYd{k=5a*4Cq2bdF~sbJoV``N!qXq}TXc@GIo0hl?;FoNr~2m)fAY`AhZB}~IYWJLv?KiEn2UpQ z(Pi>tGUr;Z z``WH!FaJ1>emG}*-?`{!UYqI`onvgywcWSZay@#(^USHSMdqxr*Yl6d zhTeGdIG4PCw9kyDTeifGqkm4_U;7>rpSqs%AD7Ry`s)^*V{FdaI6Z%!{r%~1$}dM- z9=)%Z&(FU#+VUMj9kRta=Gb?yJ)Joh`C4zU^)$|TSlv=*-J)|m3z@TJ%yRbK-!@U-p1K)5BIF4ZqYfq$ecarZmexg=$0+94%y-y zbKX8&vwRQeOQXGMwD*qoiP4VOtF>!6Vy?zKW)ElUs#|o9u{pEz)qkCXQ_neT_wS5< zbdlqs@-1B(M5VgpPU*y&Ks@0=k{gc7VD{7bdD}E z=N4;p6k^|^%W-QptG>E~8DWQ%jmv9IHw8ZX}q`0i-m8*OcE z%jaUB8f|&s`_%Evf4Vi(EjmXRnbTgMf3MeGqixv>9im&-;^lip_oIDzH2coPTh3sP zzva5hIX{O-)Lggd9Ak5iSVLoOXX*RH3qKfb`Tdo#_wSZ?`JMaQ#uy(R&A-2~=B1;b zcg^vzorkAhE8U`VJPVog)UWr_*6)3{7VC=Tw-p~4?X#mD?SylV@3mjr9<`q1e5hM= zjxI8%z1VjzyzkC=zhBy1)*;6BW$cpcsatf8u{oD~El+W6-glSggmbRPI{bW`?Uwhv zmi83)v^8(vH{GIhJPVmqZMWBUORc=`&UwEdG1ps$FJ2z)^P~AX(QDiiZ>d{3`*QeL z_0%moM;Dp%SnIsjdA%QxaKhS{y2AILUC*hp?}uOOesx{@dQZ3L9Ak5;|GxG29@iCq zX8qDQPkdywFOFvZmU#J$YdMpAdbH)g^R;~5^|{g7$7*m14Coe}<5|d@OIY(Yt>MSR z1wR>WslDI9^Lu*NbiJ2+Ew79{_`A{mezaeW?t~Yw;yt%TrmKZqYfq$egEg zU9Gc!-%n*g&-{A0=Z~W;W30vIpE_6huhv$#=p18ns$2KIa+=jvgVn! z=kw3}y`Wokj%Oiru8F;_WuBjFs^OYv)}GHl^Ze)*ouiA)xhCGamU(`zsfPMwi*uIu zi+(g(-&1-xN4iDl7@KoVymc)P=jN7b_s_gWyQS+s$F=Gfo#R=^oO7(HIr2gb+y(=> zMd#=ubK>GQxM-i-=W{TiTXc@GIpMdx@HGAAx>gNydLeLe>Rx<%*c zB6H5MrsjzK7`P1vbc@b0HYYA_gNydLeLe>Rx<%)B7Bc4?Yif?zkAd4@K)2`|U1UyN z+y)ozbNhS_26T(gF*fHMYif?zkAd4@K)2`|&qC(J#cgoWKDW>3U_iI%99?A2Io8x1 zu^$7s!GLbjImYJ1#cgoWKDW>3U_iI%9M3}LoMTPR5&JQ48w}_couiA)iHqCdqJ3_k z&%uCh(K*KEoMTPR5&JQ48w}_co#R>P+v9I6z1GYxzPqai)gT5Q&cJJ4Ssrzc|Ni)V z@$2hUJ*r0x?8AW0F|NM*)VDfT#~4^=V9hz6kveNW{H$5+s$C4co&nvWn|&|Hn(3(G z+jx(#eQuwRVnDa(9Ak5iT1Vr?cnsVg1G+`$cos4zMsAOh_PjkmiUHlCb99k8N3ElA zV>||Kj{)7HbBxW2k=tXWJ#WvCVnDa(9M3}L9JP+djqw<`JqC1(&e28Y#K`S2(w?{H zM=_vVbdIq(N3ElAV>||Kj{)7Hb36-~6C=0BNPFI%AH{%f(K))voTJv!xG^3Bx5t2P z(K*KE#K`S2(w?{HM=_vVbdF~sbBfNs$_y2zXuxjjbO^Y;8G26T(gF*fI@bu?~_$H46|pj&i~ zXCZT9|M5V?ej)99?8ijNBe0?Rk5C6a%_N=NOxF)H)hB#$(|27|<;`$Fq<*F>-s1 zwCC;lQ4Hu7ouiA)Icgn^8{;u>dkp9nonvfHjNBe0?Rk5C6a%_N=Xe$}=csiwZj8sk z?J=NRbdD}ECq{0Mk@mbjKZ*g}qH~PRIcgn^8{;u>dkp9no#R=^oEW(dM!xX%ySpEa zwmi0{)!?xh&@DPg7n$=|>ulcnd*t22H9s6}c{IKs|NGf!%VTw}2Ipizx9A*WbI!T8 z=9<43^vss{J{RTSGyXfITXc?RA#-xVyc3SD;TF$q$>}xP;EFC?*ZqYfq$eg3s z)A$c#ev40La_&19buK#KT%=ocj_mTFO9dg_2?Fz<5|d@wQ+j>ak>5N z*Y56K8vai+8%onvfHb-T>_#xu{U{`te7{PXeQge6|i zP#+xa2>&?d;-Fk~nLM5AKG!We$Fq<*=UP|uoW|vhfArPwhJO}EynF`#=%QYuowncC za)0O+ouiA)xt8m`w(Ho-KaQgx&Kci#F1nf5rn*Jv7@Ko#_wBV@kKXV+b8753YtDJ! z@Wb*u*5%R9(bn>3p3g)n+IoEQ(UfXr(jZ>XtzT>QUW36^ayQtS_*XJVL zqH}bSIcx0o{Nu8rH{LwXCGQ{YGo$I2EwSV1pHuhOzDLBTuBZIR<#Vn6x<%(0o3l1f z&!1<1e>$A<%h8rc@9X9B^KXr|e1}knY;le`_T6hwXU;{w*4t}6jdLDWx71m;=p4^N z=4=_WoPGCq%{ltVScmAAEwO#SI$ZXR(Y`s_UVD0~i}sqgarWE8J!`33bdD}EXV1AC zYa0`~WlO9>wm8R}w-47W-vj#6Xm1+ry`z0%v?KOv?OKkQt1*w+!`Zs(7M){k&g^{k zU+3V|bI#iRJL4Z+1cJr^b%+Mr-f6 zeOb80dg>OPql?VB#Tp%X&A%A0ZI<_wmq#5k6YGsronyY^99e_LzFm*$7M){kPOO}V zl~euW=R|tL_j7d1me_IH_w(%gt<_n#=p4^N=G-eX} z%l87lJKFa~TU*=mx!9*hTi*9Rb^P+5Zq0Oy&e28YwAbg~>$TTtTlPYS=$5s3`5w{z zXkQ-9zBBQbGnnIVxvp}~&*2d@*DX57*qkHQ(3sm<`u_034@O&le`W0byCq(J=l-@a z#z#lFDQOb3AP4;i=b3x9A+tLgqa6>%Fw~d*7|ax?=fl#Ro?F>}W?j;hf`p z?U%Mkt>-u&>K2`&i_B>+_T3BbyK~;}mo}Gmh_QVcyX1Q67M){k&Lv;VQ(T+(-K9C< zoa?a;KObkiQ>Ia96nY(b&Jl?Mdm!#I5$n1|=NOywMq~8cW$b19&^|mh26T(g z@hoJ{Q@g&_+dUZrm&<@|(K))voc8i^_p-fdZ=M_%o{WLZWk9#+99?8idwIEg+1|7_PmKZHqH~PRd1}|!db=lM;BpzzEjq`u zkU8z;~__bz!@vDDBuR2tR71uX$y8)H!<8=Zjxor|MBXVqhNzbdGWL-KW0Qu{y@U zIsQ>!i;CTjgi*EM4AnT^1ihI8^24Y}_0o|f=jLn&utG=-s12G^2 zx<%)B7Ba`a#jz9vF)+h`ZqYfq$efwE>Km&u5CbxxTXc@GIrc4%r5K2T83uHV&hac{ z&dgl(jnx>40U6LOI!70oW8dOfih&rIVL-R&9Ak54=BjV3#y||nfNs$_o`uY@Z*eTe zKn%<s`4V<`q=V1@zRqH{b8nKLt2ePcBSVn7CT zi_XzS=GeD5mSP|VW*E>dI>*?YnYrp4t1%D*GN4;@j%Oir>{}d5F%SbY4Coe}ql?U$ znXA6B8UryP1G+`$7@K3?;#i7-7?@!|x9A+tLgviORo_^Rff$eh-J)}JkvaA)j-?og zff)vLi_S4NXJ)SY#%c`2fDGsso#R=^9Qzi>QVhhv3Xw!AO>a_&@DR0vyeG6bJaIiV;}}(K)2`|U1W}Zi(@GUVqk^=-J)}h&6%02 zzOfnuF(3oFMdx@HGRMBfu@nO_FvEau(K))voSC`m8>=x812UjnbdIq(_AQR37>I!x z26T(g@hoJ{%v|-2)fk8Y8PF{{M;Do6-{M$`ff$%!K)2`|V{>Nas&A~uKn%!$ZqYfO zh0L*UaV*6^49qZ~TXc>tGG}J4`o?Mu#DEOw7M){kj(v+`DF$L-h5_B8b36-~Gc#9x zV>Je1Kn8S+&e28Y*ta;AVju=)7|<;`$Jm^ix#}CMF%SbXpj&i~XQBUxy?c4NrCRfR z|Dp)X8{SZt*EdD*jwEP9u#>2#XQNKHz*}xgB&Bp=s*SB_Lz3Mnk|G<2LsHnvKcd?8 zH^?E`RO2*~q)4)1Lqv*$jq?n2!Nj!XME%9n73DR?3?&> zS$g61i;GXHwa4sZYH%zDbc@c>Mdlo9otd})9=W?*^HH_-Xna}!e63o0Or2AMH5t$? zI>*?YHP@E8`tJojGbX-_i{juF|2w2xbdF~sbK-=4CoEmVF`gNdlh~YRe-?(V| z46Mmp&s@4i=Xe$}r)RG8U7y>fU6j{o>+k8F?jzlzb99k8d%E^>yOyEz%v{f3)_Ln% zwf1;!waxV&w&%J<=NOxlIv-Z&t<}wQ(VgXscdOk~EiT%}{%(!8q4nq%o#R=^oS|{@ z{BgPc?zM}HE9H;om7aJm|2R%wqaBxxE#I5EMd#=ubGCdf=e)M&oLkF14_CXZ+LP5@ z85#djeebB;$ExX#CF0AP<65=$c+UHkYyWxwb&Jk1HYau4=6&OtXR3dG{KY?ymlImt z&QK3lTf#q%*&GxXZIh?9?sMIub36-~v(~yY&onN3{G+eFFaI=0TwTFGx+t&FrtSA$ z?hoCfb99k8d%5ntUB_JhaUA`yW_+1*(b>E<)h#;5*qpuHw|luBz2SLgYV0^e&bhDr z(0<3-9{n6`D8J|VxM<(!BHf~MJPVn#m-}^Z*P%D2I>&s+8S=(Z?Ur^?UZd^LMY=`j z=pu85*vs?BWkYY=T<4Pet36Xqw~UD$NB>OSU;8c*PhC&)kIUy!{dJ4ZF*avtoIJnI z{(fFg`Knrb^uBJNpTAYDeTPtojB$=R_MK}_d(K6^)|+cR8D||<$JAN3=p4^N=8PFL zIrHxCkaP5pu@2EKV`BThS}uE|+MCtp+S92nnrq&SGv6N0Sxeobb99k8bIzTy#xbE= z#>6^gjC0Jny#AFHj%xS&e27BL!V5I9p^@C&vWy#aE|rV zEjmXRnRAXcTJoB|tk*W}{p9wjLwaJpG1WQdJI<0d$k^xWG2NnbjLiuv>##D_KYmW6 zH+(-ww~UD$C;Pt6zMos2b&JmNEM(5P)n^OWJH|z>)6cDR$Qb9CV_(Og8n^ESyjSi0 zYC~&lpNl!H_ZWA;La=$4_leUIp}+RN4K+Y^sD zgE{_~>q^f094=9F-J)}h%~@g%8FM^KACwn9tk!;iW$gVsCT_oTzpci2w3>f^W5`QO zKku5u!+0J}y;izK=Xe$}=hUxvYwP#E8;W&B`)$Po)t;@kv=i1G-)rC69%Vht`B1m$ z99?8i_F~?>@V;B~e&5<$)*+0|%h;Cdsatf8u{m45mQ!4t_ubZZpoRK!(-J` zx9A*QWX`eHxz~BUAD3{#(3rZy_n%$Q)Y$jK_qt!Xu6ezuTXc@GIjR4=_4gjv6@F%Y zrOp$NRC}?S`D5bt8CN@#JYB8*f4&>;qdorL~bdD}E$G(ZfQWyvWJq+j;onvfH&s^ynR>MFTkOAGIb36-~ zW8cJKDGY>x9tL!a&e28Y^vspMVRcOg{zv`Br2P%Y_Pf`wEB>}x`yK3`SNn@#bXKjuP^f?f)*XwBO4$es#`J{I`|+Pt|@?`Kj~zHP9_OM;DosJz9T{ zQuBYm=I@j{+H0)ej&zPL`dzu__tjee)Or0H=oX!0Y)*?Y?DgsHb@ncMw>1WIi_Y;ZWX{&spY`OP3InIhfNs$_y2zaD z_37?)_AYz3H3oEx&M`J;YwOQ?a!-YU(`7)n=p4^NZ`bc+t~c`&|NI-G)FE{U1BWqi z-7D=;=lI_gpHKYjI;9?|M;Mrg0i9!<`p#3|)G>7o1H%jqIma_n&Y6duGgG(JEe!lI z1G+^w`(BWB(@}{}_kF+YUG{DZ4Coe}V{FbA)|@ru-U$QyU_iI%9M3}LWZ(C(@7c%f z;}#guEjmXRnX`p8XAQY`!oWTl&@DR0*qrS9KK4EPn0?#=1G+`$cos5e3v13Aa_@wJ zeK4R~bdD}EC;PsSea}8-AGg4OZqYf$=4@fjSwrrfFt85>bc@dMEM!jheINUteat>? zfdSp3b99k8TUc|}kb5T#?1KT_qH~PR$-eJn-?NX|$1O0RTXc?RA#=8{=By$2P8iq+ z1G+`$=pu8n@B7&I>|^$E3k>KMonvgy7S^0KtGAH}KkA2TRW*@h}fNs$_#^!8c%~?b4oiMNu26T(g@hoIc_I)4wo_)+dZh-;a zqH}bSIa^qB){uKA4D5pe-J)}h&B?y+W8brn*~cv~pj&i~XCZU8u;#2G_f8nt2LrlA z=jbAHvhVxY_v~Z#aSIIS7M){k&KB03HRRq21N&e=x9A+tLgr-O_p$HU$L!-47|<;` zM;Dp1g*9glxp%_AJ{Zs~I>*?Y?E60UJ^Pq_+yVo-Mdx@HGG_~G&Kh#>gn@l9pj&i~ zE;1+kzK?y+K4u@cz<_SiImYH}Va-`X?wv5O4+eCL&hac{PWF8t`<{KwK5l^l-J)}J zkvUsfbJmc1Ck*U^0o|f=jLpfu?_=MykJ-m9FrZs>j%Oirwy@@`A@@!g*ari;Md#=u zbF%OI*!S#X_Hhdg=oX!0Y|a+eoHgX$2?P6JK)2`|&qC&8-}kZaFT8$n@kzDzm_1Dm zj>Uj((K))voMWvs^Y-5(cb98Es@5KjFYBMLRcnu_b84_A1G+`$7@M=^+A>%Fy`X2t z#FueV9K7Oxhjfe1@hoIcoY3!trE56GGh=e{8g2V~y);WpkFQ&FjxI81>Gfp%!AoNq+4{3E;46N*M4r-GIXAq>-oz%Z(Xa_9?z||x!%L}T({^P zV{=mH!|J@Xx_K_TvwZPxwR@_?Mf=#_t?@Rr9^ImIJPVmKG)|sBF1O#kc5!i~{L#G9 z6VK%z$H{B7cMJD_{TAugW{rX z^0d}{u3L1DXCZUeT36q-7``5dahZqYf$<_wLK=hxZa&&w%aRcnvl*X{H3 zx2m=85bBUI&N0WnbM0x*xyaXgbFC-iti$S|t+Rb&Jk1Hm7&K^dIJ6>N#iV{_XLPE^?gg+wi`n zHiy?nx9A+tLgu8_hu8W>wVTU1x=3&6lc}-e+-U82ZeAA7v7Wj`=jbAH≈IUh|jr z+NQmq+#YpEPpmhlI>&s+S+WKh`+Pm7TXc@GIbmfTR;K#L&x!Pg@8{^2F|p%h-`Cmq zbE~s%(K()l%sIFEY~gyxxX5+-xs?tX;~aDB>-baS_Pv1js=Z%rXl?Ctv8SrF_r0f% zpZwFUnQqZJy2zaD_4<1~^crokAU2}LC&%>$LO1J17 z&qC&$`t@#Y{oZ#&v94&pt$3i?v(=V%!kXiI?OWTUtYK2`&i_FPh%)1xfcWd77 zTbs)|gt2)U+j2d1i_S4NXUo@eifi+}+nN*BT#t45qRw{hJ+IbIaZj`6@%yG*bdF~s zb5h&!wH;F{@4Gec_a)}KrF?O<+Vj6NzQ&;%@v+J1}`+oRd_bb;mulIC|&M`J8^`E!?-s8H$&#bT1dE$|3FIF>uOx!-> zYG;zCtF`~nSNpu{xoX+R)L;t?=oX#hS;(9%ta(ps__SQ`S+!Pszk}!Z^!9YUxt4fO z26T(g(M9IiH*r`B17VZ|mfiTd+fNs$_ zy2zZKxzabRhJi331G+`$7@K3?#9=86gn=Fgbc@dMEM!j4T-V$&R_!prTtyB_S)*d)mi3$SNofahn(Z{@y|Bd z&@DPg7nzfLe4G1tZu_E7{!4l2|E=~{f8Zi>&aFPDa=p4m=NOxFD%X{D#*<-S`wZw7 zo#R=^ob2iL_cVKyJvtQzbc@c>MdqB!b!DBo2gAVj8PF{{$Jm_g>GtMjw1G+`$7@Lzl-Tt0tkFrOn!hmkk zIi7{yuJ5&9Z{{byxJV6BgD`M71J}LM9(9iX^!dcUu2brfdW3;_7|=P!sqZ}XO&wFm zFfh!(kaIjE<*a%5Su?du?ZUvX8PF}d+4q91nT|@F_c_Br80cX@x9A*Wb9&}V->@16 z!hj6u7MLdTXc>tGN)&*^bM`$%FdzfEMdx@H zGRMA&!%`Rs13e7r7M-Ju%;}jceZy)P2m>;pTXc@GIrdE)mcl?7=wU#&=p4^N=Jd>! zzF{>CgaH}QEjmXRnPcC?VJQrRfgT2Qi_S4Nr)RG84Xa@w49I|P(K()l%&~9cuoMQu zKo0}DMd#=ub9&}V->@16!hj6u7M){kj(rn{r7#c%dKl0xI>)n+IX!cwZ&(cjVL%3S zi_XzS=GZrJSPBDSpoan7qH~PR>6t5i!)h1^12UjnbdF~sbL^WqEQNtE(8GXk(K))v zoSwPTH>`$%FdzfEMduisW8cJKDGY>x9tL!a&hac{PS0HF8&<Sj(rn{r7#c%dKl0x zI>*?Yp1IODtcHOwAOpHZ=Xe$}$G(ZfQWyvWJq+j;ouiA)>6t5i!)h1^12UjnbdIq( z_Dvj?!ax}4VL-R&9M3}L^vspMVKoed0U6LOI!70oW8cJKDGY>x9tL!a&M`KpXRh=O zt6?Av$bfFqIi7{gv2WtjW$A_2FD^c*)*iEusll-r&@DPg7nyUcb!OiFd*tqN%}3SR zqw!_^^R;U2F?CK2)?`4p=p18n)?8cW>c1EC%$WExE{cO!{O^!%(K()l%!w2Fov?Hb z$9QH;PF|yJf3KHjY3cEGi_XzS<}AIQjDHyOV|>z+bD48d&P5BHi*$?5F*YZDILr@g z*6pF<edD6-Gq5IaJ#*<6o#R=^oSwPTcYSV`c2QoVt-q&xx{q{=&e28Y z?CILi?OKM;GjlzES?8^5)!O5^)i&3A*q-YaonvfH>U>z8w^ldLMR%4j-mP{|wYX>> z`@1#XhSsB7bdF~sbB4yr^T*}(yVou*u9QETS9;>P{Np%zjdol%wtR2u7M-Ju%-Qm_ zob%e6b8ap7JY4OrYEM>sWn}zA^}VBVAFHM}mWVHFj%(H0<2mnFuKnlz*DX57*qqdD zoA-@po~i!%@fZI*UQTFnJ3~EKZ3+K4W^+(nv`wDYy3cis&hac{&RXlrJkz-B@sGax zzWmc1adid%=%Tzvo3`J3xj%G^&e28Y?B%-mb{%v1$8q$-n(<}MMQ8KcRJZ6HV{`U) z-|ppl^oHk|sj=e>Ip@CeL;D?Td-QX(q5PibKyYO zXUH2vwOiUnd5yL|7wHzAql?TLVlU4hmkqsfbDc}>ul7te-7+S29Q`wOf9<7zTIY$@i z4Sg~-cAOinJP?_mkVB4(W;Y##HB+?>I}=AY-4e z$8?L%F*YZxti#Gw|M)qP-the#-7+S2ob3BL`+jb9)-5{6vyeIGR-Y|g?-&=kPCvKO zA!D3lj(r_}YTUjT@Lsj|s|~HKeJ=J?wf4UE)bW#lx;4`+I!70olf7PluZLcvjoAww zqFaXI_C2D@YA;u_Z%;ht4CeS_t}8j~bGSs!b&Jk1HfM=7WX$m_eNbNbuv+{5m9h8l zn7IAU{k9t8(Q5wvjUg{B{k&@q594__^;+o`o#R=^oKwHvt*zhtZYb6j?Y9*VRC~7C z(oR@&e6M|LdzAGo=R@71b99k8*^7Di!uxK``+aM3S%)w-FJoJ-r*6?X#^!AKT266o z-gjGb!kX)`4qw#SuD$2g+9~d7);xaSbc@dMEM!hm=Ka3JT(^`ju2y@# zny(YR#xe1jx+P~`4v$q&-J)}JkvYd&=U(Uaeq6!{Lu2X+-+y*JQ)Ax`-|K$my5{ws zZqYf$=A{1f*57+vSNNIrl{!y6QticR=8uWnXI$+}@^rQK|M_a4cRg1v`tlIi7{g>6t5i!)h1^12UjnbdD}E$G(Zf($WlkUBA=+wp#o9K|^u-{^W!8 z@BgaW((B3i^VV3m=p18nQvZ4DpL+grJ^y?8=`>gyyHB2ThMY6>ynV;cm%QWgqg!;2E;1*3b-cYg zm)h%)AhUPY${0AL{j1d*7%1tqyat z$EUT&x<%)B7BVOMds_Rur~UG5)86O#>uP_KbIwVh^K^^O(M9I$iRWBPTp9+B%Ybgt zImYH>zmB_KsekIfCkAwj&hac{&YrG4*OGfV3>=pM-J)}JkvZ9~t1P(I!DL)eBxi%DfLJ_ z!oWNX=p5tJcb@vDj;Ui97-nF|Ii8Vn);#>IncAgxVc^#c=oa1VdqLJrMtlIi7{g>6t5i!)h1^12UjnbdD}E$G(ZfQWyvWJq+j;onvfH z&s^ynR>MFTkOAGIb36-~W8cJKDGY>x9tL!a&e28Y^vspMVKoed0U6LOI>*=?`z8)c zVIU0jFrZs>j%Oirdge;suo?!!fDGssouiA)v2WtA6b8aT4+FYI=NOyQGgtbC)i4kS zWI(s*9M3}L*f()l3Ik!FhXLK9b99k8J#(dRSPcVVKn8S+&M`K}zKO$97zhJB4Coe} z<5|d@p1IODtcHOwAOpHZ=jbAH?3*|&g@G{8!+>tlImYJn%$2@jH4KCS8PF{{$Fq<* z_Dvj?!ax}4VL-R&99?8i&s^ynR>MFTkOAGIbBxWgZ{n~N2EsrO1G+`$cos6JXRh=O zt6?Av$bfFqIl9Ok`z8)cVIU0jFrZs>jZ|mfiTd+fNs$_o`uZmnJaz6Y8VIuGN4;@ zjxI9CzKO$97zhJB4Coe}V{A^(T{pj&i~XCZTX=1SkN8V16E4Coe}ql?V3Z{n~N z2EsrO1G+`$7@N~GSNew4Fc1c0K)2`|&qC(dH}UDR^up^G7oSvXkJ-o6;8+ak7M-Ju z%sJLNGjIPra(B7rqiXHZ__F@_TDA6=I;RF}GN4;@j(MPb$Fq<*L*wN6<8u4mYZn(+${)=uJ@H)rah$wH zJ1!erzBhG?&e28YZ24Nwd2P)(x0ZVzu69?oC#$_OGXA0Z-ch-aRnr?w#FsV4wQBA0 zocAl&{`3Cp7M){kPU^PJ`^GcRRR8?=i+>(3C$zYop&qQZgnt~fIVdjLCQobK=ekAb zcos5et#xIdX+wZ;HAG$^7=pu9Wa@~8oj=B8fIQn7D z_%i3Bvw3Z*TXc@GIeWWr_i{aY!}HA4*l~uOb6@$P{f@Og`Z?NAe$Vr9(Z0_`x<%)B z7BXiq_v_xSLvKuVj`@x=Mdl2#m*{+YVJ_FW>Lx}M}8m(QX4>lU43Y|hX)d48S!{k)v=Rkil$ece7kf2&&i4xtVi z;~aDBJJ+7}oQr&|H`jVH&N{4)sk3g;Ii7{g88c>b=H1^R=jb0}9im&t#P)r)T=qt_ zH>=IHr&C=t*Sr~LzCE0?mbyjf=pu9GoI7KUV?wu#iFL>r=a_SQxu$&&=%s2mRlB#^ z6V;a3tD$RIVy=w2%pUgERk!FIV{>}vOaEaGrk-<#?%y8&=px6-z76kNYIAsPbc@dM zEM!hJRJ*yHql@&0KA9Rj&W+Zd=jLVM9P6oDbdD}E=NxOaMduisv&0%Q z=6IGqC@*|it^NMW*!y=(+EMRy2zaD#k_mreYfWQzO}imLl~Qv zu`SnAx9A*WbGCdfr?@unyRA84&GlG^FY0X9-t%hh6!$c19=~t8Mdx@HGAFeiU)wRY z^1fU1eqUm)Tgn$#t36-M*NI-^n0QRxk~1%d$Ev4p(K))voMWwXuk(68F5!fsF?EIS zKf9i(vG0fPb-!|5^LkIW=p18nQvZ4D?>(+7{LK1FohKft_F^^j$HeV3u68DQx?21H ze6`QJo~xF9ObxccfNs$_o`uZW!kYKAhEK}{pH*wM_d9rgPj64xn`?>pWI(s*99?9N zeG`YJFc1cM7|<;`$Jm^nxzabRhJi331G+`$cos6pzKO$97zhJB4Coe}ql?VxnJaz6 zY8VIuGN4;@jU;4{y}oLH6Z*H+{%gJ7`d`(q{lRN4onwxDPrVN3ynfxH zb36-~bI!HOwJ+!1e=hg5-`_UYJlhzXlf77OFV?KBZqYfq$ecCTmbv!9SoSgdIK+T% z(K*KE42_fL!&n#y15+8$Ejq`ukU3MwPkxvT17To@0o|f=bdfnjiEeIlVKnX3^AZvbdF~sbB4yr^IyzNb36;ZUEc}2-po(@^Y`Uahtweq9LB(Pue3**i^j&bTcPkmFz)G-VUGce>F&qz6E9(K-5-BPzO@W%}37TxT7LDo%2CC>Ye zVIU0jFrZs>jZ|mfiTd+fNs$_o`uZmnJaz6Y8VIuGN4;@jxI9CzKO$97zhJB4Coe} zV{A^(T{pj&i~XCZTX=1SkN8V16E4Coe}ql?V3Z{n~N2EsrO1G+`$7@N~GSNew4 zFc1c0K)2`|&qC(dH*r`B17VZ|mfiTd+fNs$_#^&_QmA+v$41@t0&@DR0 zvyeIVO&pfOKp5y@K)2`|U1UzrT+CJswsAPn>{pj&i~u{k|+rEgdb17Sc0bc@dMEM$&-6NjZR z5C(b}&@DPg7n##DSNew4Fc1c0K)2`|V{`1AI4p&MFwnz*ZqYfOh0N)hD}BRi7zhJ0 zpj&i~E;7fyiNjJD2m?I~=oX!0Y);Qy=^IwVKp2n#-J)|m3z=iz#9=86gn=Fgbc@c> zMdtL(mA+v$41@t0&@DR0*c|&N4ohJm4D>LdTXc?RA#-}>O5d;=2Eu?0=oX!$i_Eca z;;pj&i~u{mq5EpzqX3wmZud>I$T z!7KiENVn)5&qC(J3H?r3x`tysGbSgm(YC+WOS81}__{^s=pu8LUQfn9jQKG>>B+gw zxhUtN1>isx<%*cB6Ie1?dNtaL+6>fp1-W~*0pNw@!V>g>pg7Gb&Jk1HYasH ztj=4jo9CiC%NOrfyQf-Qw2%GW8gE1E(Jea1vyeGM+= zYVGly_bb=_^Zx4=onvfH>bA}M#xu`U|NQuie;zLTUZYLh@4eg~x<%*cB6Id~-Fv%^x%}fe z`eDuZGUuYRd2Om&bdIq(d%JJ)x(IZ%lQL`HnN>jiK5t?V`L!+nkp5z~w&!PJ37M){k&d@k{ex3dOyqxk?wf5+J-9A5mt6KXG zp$-}29CPeD*PiyAi+rs&*LpI}I;@VVvu@Ejo`uXAGiGw;-QOYS=pSPpqFctq_I*c&%?#ySbdBi}Z#*nHoFJjn#19GjxI9i9BZ`XHGf&JZQA?E z?NNvH#Cl_@bIf;~C2Nqe&(~wRMduis6IRw?WvYMtoJeo@evWP#6FW}!eVu(jw>s+< zo#R=^oO7$s7Or=Ui(IFlTj`K7&N0Wnjz2YS-wSxJ+WXap*4923d#YM{-+Su#$v@qi z=@y-%i_FPhufNwruhGWrg$~gzLvi~a(Pg!ltJ$|F9&-kB{4v*+ob@?eqUO3q=NOx_ z#2PZ@c$PjWFML?7{r<|>`*%#-e&>E$jqzwT|Nh31mzI9sHHU}sJe+#1bc@dMEM(59 zU+>n|?|nBE>x%ZTK8E^J?uB_cUuBzi+xl=Xe$}C$$}4 z+cCBBzFYHtUt+FX$`@CwJzve&iC*KFcud`rGcSk7s;6$zIl9Q4W36+q^Ljrn;e??v zb%pOgyPm1B?}zVozj9skdQZ3L9Ak4*|9R{0J+3SK%=${5CmyNxVm0%}#O*V#b|!hc zTKoTewa>ertCoFC4Yt65ZqYfOh0NK)n)kGZPs;_LRcp2PJ9vIiZ%@~oYl-({K)2`| zU1W}Z6NjZR5C(b}&@DR0*qolZ(l@MzfiNHgx<%)B7Ba`aiNjJD2m?I~=oX!$i_Gbn zD}BRi7zhJ0pj&i~u{ril9G1dB80cX@x9A+tLgw_$mA+v$41@t0&@DPg7nx(<#9=86 zgn=Fgbc@b0Hm7H<^bM;r@OAwSkZ-HCzfJbLdi;I0_BYCW-u%S-<43pX9M3}Lgn|7r zu;!lXmT$^8KUHh<55?xMxz5bB4(GZ>=jbAHvM=lG%U*?YbFNjcz2Ci_XY|ZaY<}wBU;nMuP`BtD&qC&GZT(r#X)*cdb?*6#YM)g5 z+d2pRQ?=jx!CA=X&Cgz+)?Sae@3I%!i&JMn zx9A*Wb58wwv;N$(VPHE9=oX#hS;(C1-FEgady&03bp~{c&e28Yoci@<{kdnuz;+nW zEjq{8ob26p_AYyoy*PCSbc@dMEcAALC*yiEKk>yyYLFU)fx{WN?v?habM&guC;oMv zQjgRl49vrT&M{7X=c#Y%m^y}mVFrer;~6Pu&BM={satl zImYJn%$2@jH4KCS8PF{{$Fq<*_Dvj?!ax}4VL-R&99?8i&s^ynR>MFTkOAGIbBxWg zZ{n~N2EsrO1G+`$cos6JXRh=Ot6?Av$bfFqIl9Ok`z8)cVIU0jFrZs>jZ|mfiTd+ zfNs$_o`uZmnJaz6Y8VIuGN4;@jxI9CzKO$97zhJB4Coe}V{A^(T{pj&i~XCZTX z=1SkN8V16E4Coe}ql?V3Z{n~N2EsrO1G+`$7@N~GSNew4Fc1c0K)2`|&qC(dH*r`B z17VZ|mfiTd+fNs$_#^&_QmA+v$41@t0&@DR0vyeIVO&pfOKp5y@K)2`| zU1UzrT+ zCJswsAPn>{pj&i~u{k|+rEgdb17Sc0bc@dMEM$&-6Q3?iFT8$n@kzDzn0-tQj>Uj( z(K))voMWvs^Y-5(cb98Es@5KjFYBMLRcnu_b84_A1G+`$7@M=^+A>%Fy`X2t#FueV z9K7Oxhjfe1@hoIcoY3!trE56GGh=e{8g2V~y);WpkFQ&FjxI81>Gfp%!AoNq+4{3E;46N*M4r-GIXAq>-oz%Z(Xa_9?z||x!%L}T({^PV{=mH z!|J@Xx_K_TvwZPxwR@_?Mf=#_t?@Rr9^ImIJPVmKG)|sBF1O#kc5!i~{L#G96VK%z z$H{B7cMJD_{TAugW{rX^0d}{ zu3L1DXCZUeT36q-7``5dahZqYf$<_wLK=hxZa&&w%aRcnvl*X{H3x2m=8 z5bBUI&N0WnbM0x*xyaXgbFC-iti$S|t+Rb&Jk1Hm7&K^dIJ6>N#iV{_XLPE^?gg+wi`nHiy?n zx9A+tLgu8_hu8W>wVTU1x=3&6lc}-e+-U82ZeAA7v7Wj`=jbAH≈IUh|jr+NQmq z+#YpEPpmhlI>&s+S+WKh`+Pm7TXc@GIbmfTR;K#L&x!Pg@8{^2F|p%h-`CmqbE~s% z(K()l%sIFEY~gyxxX5+-xs?tX;~aDB>-baS_Pv1js=Z%rXl?Ctv8SrF_r0f%pZwFU znQqZJy2zaD_4<1~^crokAU2}LC&%>$LO1J17&qC&$ z`t@#Y{oZ#&v94&pt$3i?v(=V%!kXiI?OWTUtYK2`&i_FPh%)1xfcWd77Tbs)| zgt2)U+j2d1i_S4NXUo@eifi+}+nN*BT#t45qRw{hJ+IbIaZj`6@%yG*bdF~sb5h&! zwH;F{@4Gec_a)}KrF?O<+Vj6Nz zQ&;%@v+J1}`+oRd_bb;mulIC|&M`J8^`E!?-s8H$&#bT1dE$|3FIF>uOx!->YG;zC ztF`~nSNpu{xoX+R)L;t?=oX#hS;(9%ta(ps__SQ`S+!Pszk}!Z^!9YUxt4fO26T(g z(M9IiH*r`B17VZ|mfiTd+fNs$_y2zZK zxzabRhJi331G+`$7@K3?#9=86gn=Fgbc@dMEM!j4T}uO5gKj_2c?((MTZP|X6SkQZtc3Vo_YD# zEjq{8oYa5b`tP-#@6`FG{k`Yk{yXQK_$Mss7MZR&AB(jz&07s zEjq`ukU81MZSG_CCHr!U4Coe}ql?Tr#cRx(b8m)$Z8D%+bdIq(*~e|}WA-Kca*7P- z7M#`R`?;){#aAT#Cgv%41|Fm26T(gF*c`XuJjG7 zVIU01fNs$_o`uY@Z{n~N2EsrO1G+`$=pu7^=1SkN8V16E4Coe}V{DFn6NjZR5C(b} z&@DR0vyeGGbER)s4Fh3726T(g(M9IiH*r`B17VZ|mfiTd+fNs$_y2zZKxzabRhJi331G+`$7@K3?#9=86gn=Fgbc@dMEM!j4 zT}uO5d;=2Eu?0=oX#hS;!pwCJsws zAPn>{pj&i~E;6TQuJjG7VIU01fNs$_#^%^JaaaliVW5Wr-J)|m3z^e1SNew4Fc1c0 zK)2`|U1W}Z6NjZR5C(b}&@DR0*qolZ(l@MzfiNHgx<%)B7Ba`aiNjJD2m?I~=oX!$ zi_GbnD}BRi7zhJ0pj&i~u{ril9G1dB80cX@x9A+tLgw_$mA+v$41@t0&@DPg7nx(< z#9=86gn=Fgbc@b0Hm7H<^bMs^shovwO26`CKEjq`ukU2ebrEgdb17Sc0bc@c>MdsKyaaaliVW5Wr z-J)}h&FPsdeZy)P2m>;pTXc?RA#?1TI4p&MFwnz*ZqYfq$ef@16!hj6u7MUtylWOfT`2vLC=hdFXN&(c*Xw?=@y;iS;(9?q2CEh z*Kmwy#^mHR+V=N)X_l5AU$^KSU1ZME>&f_sF+av9Jvo;-7v)^Ez`01b=p18n;)lch zux8yJDo#GG)*gGDGt@UO+CBqo^42q#ZqYfOh0N)hD}C4Jc4-&oHQM@nx~Ka{x9A*Q zWX_(h{oJl)=sYvm^Otqrx>l_{o?C5my@&0&ZqYf$=A_Pt)p=`m^IUXi`QqJb_f(6E z_OZWP<85d?x<%)B7BXjOoIHPAZohl&;^IpAqj{w#p36UulhV~&02+S8tMk+1dU zT2IDVht)B4)-5{6vyeGs#!Sw<`#a;H1cJQ)9=u(c1Ieyeyn!J#~xD(M9H*V~v))<}d5DO?yANJ?fC2SZ_>qj`@zWWDPR* z`Fc#Z=p18n!pb_VO!beS6X^}#&(SSoV#mq8ue0yxR%hL!b36-~b8hw7!u5`Ek?Ztx zD;+Y%Ip)~c@u$Y^djaoNd%xPy+S=!0PgQI0druud`KMbm-J)}JkvZAx_4j({HQJcH z&>^~IC~n^)x~%qcHT(9&W6ofXKjylUvp$DQ)Lggd9Ak5qSVP7f&(a6wg%7K>-(MMf z|Bi{<@7!;zF&?ev-`^PW($den=I}6{hf}YWZqYfOh0Hni>)qP=z3+x%UD1A9@j$g_ zt1az>HOKebx3))F&vHK0EjmXRnUlSkcQ3r}*1X@hHkWk>WAie$<$CHConvgymapX$ z*XDh8M_0%moM;DoMtaa{nUhl^xoG>(|uJHY5*E2Qt{qVi+SFUSb z@97quV{A_9KX3iL$909DSzoF1#3R*StY-e0xP8Xe&LmG)YyY3G_IcNH)v}MN!4??M zEjq`ukU3je^Pbl5X}RFDYOVHu2hZ>6?df`RE%BZV=oX!$i_Eca;;!zURa0 zZ|nO^?RQ-5Z_9pNf9vDhYVB{38ULsH=fA4f^1{Y>)2+Wa_^EZTaS( zs{N+i@=ZPdRIQC+{CD--zf@~~%jiE;`;XNccT?v|{^{0Cx9A*QWKQ<_boYAcy=y-C zpVj`d9HM8&#GZ?mUT4PN4#T=d=NOxlz1z;-ZEY{&pRh5NN!_AzJPVmKb^PR?CzE;o zb)Ne^^?uhaI!70oGj;srpC^ZT|M@)ked_(LTXc@GIa9|^emD#RVPJ>>-J)|m3z;)C zPM!~AVIT}lWk9#+99?A2)bW!aCc{7&7-B%T=p18nhQ`VBVJr-UfvF7W7M)on+x30= z>&^Vc7Z<5PY7hnvXW+V5+M~|VS3aNk*L6xgQjah&4+A>KIQ5;UzNusC7zTzJ7;=th zq?|PmKWnCTsa+WOH3PauH~U_YHPcav^S)vj2m?I~=oX!0Y);Qy=^IwVKp2n#-J)|m z3z=iz#9=86gn=Fgbc@c>MdtL(mA+v$41@t0&@DR0*c|&N4ohJm4D>LdTXc?RA#-}> zO5d;=2Eu?0=oX!$i_Eca;;!zF{>CgaH}QEjq`ukU92E9G1dB80cX@x9A*Q zWKPdq=^IwVKp2n#-J)}h&9QIduoMQuKo0}DMdx@HGN)&*^bMLdTXc@GIX!cwZ&(cjVL%3Si_Y;ZWR86khovwO26`CKEjmXRnbR{@`i9jo z5C&vGx9A*WbL^WqEQNtE(8GXk(K()l%;}jceZy)P2m>;pTXc>tGRMA&!%`Rs13e7r z7M){kPS0HF8&<!zF{>CgaH}QEjq{8 z9Q!5?OJN`k^e~`XbdF~sb9&}V->@16!hj6u7M-Ju%&~9cuoMQuKo0}DMduis(=%84 zhSe|-24q0D=p4^N=GZrJSPBDSpoan7qH}bSIX!cwZ&(cjVL%3Si_S4N$G(ZfQWyvW zJq+j;o#R=^oSwPTH>`$%FdzfEMd#=ubL^WqEQNtE(8GXk(K*KE^vspMVKoed0U6LO zI>)n+IrdF_x-7l$`o+a3)!JkBF*P_A1G+`$=pu8Dwa(1je~;WT>bZgo*5Hg#zk@PivJzbEjq`ukU4QezY~_O;TX@1$;oT9 z?eF!{EG<30ZqYfq$eg9ulkpE@evD6gaxQZ&%DHHPbCGV*ImYJ14~O|-&AL5QoP1oZ zJ@z=OW#rb99k8L+s`G-*?Y z-ucphn1iY3oT2--$3MErak6j2`l@W>F6ZbXy`fL0#*TBN zwdc8cSvbdf>K2`&i_AI48ZCLvU)F1z_I`4E)FC~w-k9nf^Brf&8f5JA^_XtaImYIM zm33H|>K{KR(i^^?qg%$rj+1>~XW!4Q&bmeCcos6}-0HK1>mB1F*Xie0I%JG<%(1WI zPmSC60^Y0kezl>swa>+#s@C53o;rT=Pq${eMd#=ubF$a#@Ac4Yv@v_3Lv+hf+`dP2 zS?%R&_U(zsoWUG_%ylJaeGZqXxo*)p#^x-shKxC$r4PyrA69F>zcTjz9TT_Tx!+b} zJX+1azcJ*crJr}r;bA-vr(P@FqH{b8nRDvbyS4Ru-wnmOqW!kwfojiITiOY0j_yWn{LrLo`uXwZO7MkOs%}{*1X@BnCq7E#no!hSMznE*El8~ zQ@7;I%i*!=satf8E;8p>>)h+S-j7Q-VQ5TU;rq|7XKL*G;d|Y$T-Utb(=9s3*qqdV z-uiow>k2=!zEbCjN2a=~ZSTJ8M~p5N2k)Ai@16!hj6u7M){kj(rn{r7#c%dKl0x zI>)n+IX!cwZ&(cjVL%3Si_XzS=GZrJSPBDSpoan7qH~PR>6t5i&xh5o>+gGfTdn=w zG2?gYpWELd`)#%GkQ(R~o#R=^oG=q+h8WN@-;{fPs@8Ii|Gu94*J{`5`9H7r7u7zg zHZ*3Q-*;_vi_XzS=7fiR^DuRP|FK;1Z`FQN4$(7XVtqAr-sJCtL*1ftjLpfu?_=NR z+Q;}OJoK=nTXc?RA#-}>O5c66>Un19{FB#T`(|M3J+51HjxI81>iEe&Pu_Hq@jLZ8 zE$=^{Clfbvfo{<`#^&5;j64^f!ax`}gaO^6b36-~bI2U&6E?#@7`PDwx<%*cB6Dsu zMxF~>VIT|~!hmkkImYH3GDrG^%`gxKZp46Y(K()l%(>ARc`j^)fiQ3g1G+`$=pu6t znInC|W*7(qH)24y=p18nZZt-o3tM3z3>?CMZqYfOh2F03Y+P^VC%(8y4N`+Ja5w|k zz0w|ajxO{0#J{dn>XCYcfq59vImW5)JoQZ-Q^znc%)pRyJR{|-dH7i~wM*^7z^@t5 zExOtFf~=X2N}Tr`!$275VL-R&9Ak5O=1SkN8V16E4Coe}<5|cY`z8)cVIU0jFrZs> zjxI8%XRh=Ot6?Av$bfFqImYJLH*r`B17VZ|mfiTd+fNs$_y2zZKxzabRhJi331G+`$7@K3?#9=86 zgn=Fgbc@dMEM!j4T}uO5d;=2Eu?0 z=oX#hS;!pwCJswsAPn>{pj&i~E;6TQuJjG7VIU01fNs$_#^%^JaaaliVW5Wr-J)|m z3z^e1SNew4Fc1c0K)2`|U1W}Z6NjZR5C(b}&@DR0*qolZ(l@MzfiNHgx<%)B7Ba`a ziNjJD2m?I~=oX!$i_GbnD}BRi7zhJ0pj&i~u{ril9G1dB80cX@x9A+tLgw_$mA+v$ z41@t0&@DPg7nx(<#9=86gn=Fgbc@b0Hm7H<^bM!?sCmX)!L)+W&QKDYV9#~P7T&%K)2`|V{_JA zTjuJ&7xc`S_%bevgIE0TkZ#dAo`uYb6Z)O7bPdONW=u|Aqiuh$mu6|{@pX&N(M9Gg zy`GGJ81rL%(vx$Ub5YJk3!IB|i_S4NCw@504{O%#q2lD@YVEPdIYWKpqU|%VCT~4+ z=@y;iS;(B8xzcxiZkKjZUZbtQr+d1Obc@c>Mds}3+RyD;hR!o{J%3r}t!vfVlU43Y)_4H_t_PmM`9|c2BjqXdnB#HQt8Sqg!;2XCZTj#>w-?<@USR zE-tQ=Kblv1;<^0eIC+hBTsF3RZ|WAEql?Vh^0l1v+M082E%!WJ?XGH1R(oY+{6qD< zqjDdsrZ<*|FKdo#)!O4Z?^mw<=l$0$I>*?Y)NPyhjc1;z{`v72|2$q!XmLA3Jy>lC z|2SrIP+YW4p4Ph0b&JmNEM(4F>&iUSxa{$dzWToW(;RVi1^?)xyhfY0-+Q?~bc@c> zMds|~y7zV+bNR<{^uwC*WzI!s^V(Fm=p18n_IBUy<$Cmn=b5Ro;|w|HzVbu+9cz2^ zbF`uSp6BDDeV>bTi_Y;ZWX@jh*S%eb-k9nf^Brf%8$-2Q+C_Pdwm%o?7M-Ju%o$=Y z&mWf!y>WA$OYX1sOf}syCUzYCGj)IMyF@&7J;^^VpF{Q6Ejq{8oS|{@{5t#lc{$~) zYVFbcx_y5BR<-sWLLD;3Ip)}Ru08EJ7x`LmuJvS`byyu!XWgQ6JPVmKX3XTwyT3!u z(LcsIM7NBI?fYuE?2T$~R-0>2r@Cmac{9#@dpKt;b&Jl?Mdr*ocg7mWgl-uV>yRF6W99?A2 zIo4>&YyPrc+qCzS+oKNYiS@=*=a}y}OV%J`pRdPsi_S4NC#)n+Ip+VJmw7M_+zds zIqP${M9p=J&M`J;i8W-*@hp8%Uih$D`~8)%_wSgv{m%Wi8spJw{{4+1FD?DNYYq?N zc{uf2=@y;iS;(AIzuv8_-}`PT))noy6%SNW(K*KEZ24MFac$mrTXVvi>#+`B)Y-1R=hfON?rGLM ze&2M9&hac{PHH>8wqt7LeYfWQzQkO&lrOGUd%l{l6TQYU@tC?LXI>7ERZrcbb99k8 z$6DuJ=kI&a~c0E&L-w)sGe&xF6^`36gImYIs{`1z~dt6uene~-APdrlX z#cJk{iQ8vf?M(7?wf6t{YM*yKS1tRP8f<|9-J)|m3z@TpHScK+pOyE*Anl^fNs$_y2u>+CJswsAPn>{pj&i~u{k|+rEgdb17Sc0bc@dMEM$&-6NjZR z5C(b}&@DPg7n##DSNew4Fc1c0K)2`|V{`1AI4p&MFwnz*ZqYfOh0N)hD}BRi7zhJ0 zpj&i~E;7fyiNn$m1OKCbU*G+;OE)!N?|`-ggL z-=%K9-}^_$=UETkqH{b8nG;UVlarx+|NHXF zzgD|eKG8WtvA!A_GtZw7W4cA>=pu8%#`&-@wAb&HYuf9o-;Q*SF8W=$>i5<1x-1+u zzI2PuF*aw2$vl6aJb9kcGefcYVdgxUao=@|&hac{j(rn{9~sasL$UdZ!;fy!Il9Q4 zFcW6NKp2>d0o|f=jLn&A-i#B5!$26&Ejq`ukU3!{%!Gk3Fc$;5Md#=ubLN^isaEjq{8 zoVn)BIAJ&pgaO^6b36;ZUEh+g@J9;rtdn8v_$ue3*<tlIl9Q4p1IODtcHOwAOpHZ z=NOw~-^5`l41|Fm26T(g@hoIc&s^ynR>MFTkOAGIb99k8_Dvj?!ax}4VL-R&9Ak5O z=1SkN8V16E4Coe}<5|cY`z8)cVIU0jFrZs>jxI8%XRh=Ot6?Av$bfFqImYJLH*r`B z17VZ|mfiTd+ zfNs$_y2zZKxzabRhJi331G+`$7@K3?#9=86gn=Fgbc@dMEM!j4T}uO5d;=2Eu?0=oX#hS;!pwCJswsAPn>{pj&i~E;6TQ zuJjG7VIU01fNs$_#^%^JaaaliVW5Wr-J)|m3z^e1SNew4Fc1c0K)2`|U1W}Z6NjZR z5C(b}&@DR0*qolZ(l@MzfiNHgx<%)B7Ba`aiBFfM7hb=(_@r8U%s!?D$6`RY=p0>S z&au{+dHe5?yUR5nRcnvNm-Wxrs)-w4qoxU zL%K!hcos4zPUv^S(ls38nK3zejkf*0UYez)$JZ@7M;Dp1^m;P>Va$*5Nl(sY&P6#F zEpRTx2{!dkLOm~T<>9fu3L1Du{o*pVRhbG z-8>iFS-yC;+CA0cqJ8Y|)_5CQk8aU9o`uXA8Yj;mm)q}NySTVg{%Bt5iRbc<>(kn%-C`sc@A{PTD@p~dYC^)zXS%;g`)(GP3J zmpK=m&1+NLqH~PR+1q`)m+R3Ro@b`Ujx*$(`^pdPcdYHv&(VhRd!CPr_I)nWEjq`u zkU4v~U-xz$dSj|{%y*n2Zw%FLX&2=++WuUmTXc>tGG~arJbzp^^v2C~F1f$jGu3p< znAmaj&(!_3?-KFU^(6ned=AxLx9A*WbB4yr^Xu&I=jD{Is-PEiTh-ck2zAI9 z=a^&Px%RZ@T;yxLxz>|$)?sx_opp=O@hoJ{m@$(x@BR)sNB5Zy8+w(qOuvNx)| zS#7R8o$8{w=FK?s?ctoY)Gazk7nw8X+!<>e6S`$gtV6~)$DG^CHSK#qFIBs#+P&4D zsJ6sj4PDC;b7jnB_OQ3Ex<%(0o6|dA`VVt3^_(+w|MvJt7dcM$ZFt{Oo5O3PTXc?R zA#+me!)tw`+Rf!0U8Fbk$<)|!ZnXA1H!ln4SWn%eb99k8=UAg9uldV*ZPVUQZjU;o zC)OKNonyY^ELnq$eZC&kEjq{8oUpPED^vaB=R|tL_j7d1nAmZ$@9XUQxz$;>=p4^N z=A2u7ws5^;T;w|a+)9UxagI6mb^NJu`(D6%)!wf*w6^xS*i+To``%N>PyXrFOt*?YCDxEJ z$FuZ7dEvuq?e|y4-oInw_B;36YK%v#`S&-5ytMT5t~or6=i$_ArCW54XCZS={d%{y ze($@XSXZ>)Ryyz9xTjh3_)n+IjQaV+K#D} z_uZQJ`x0~AQogua?fGiHPV^eb#AE7~oOwAsRy}o#&e28Y9BZ9>o!9$u2`3DVsVjW{ z+4W3~eLsA!`<3gO*L%7}=NOxl`p;W`?{Qt>XVzEhJn=}i7ps{+CT^c`wKK`n)!P5( zt9{<}T(#_DYOnZ|mfiTd+fNs$_#^&_QmA+v$41@t0&@DR0vyeIVO&pfOKp5y@K)2`|U1UzrT`LX-&SjX-{+fp{Ha>oXJd21!2THM*;C!3bBxXDnJazw!Ja0!VjxI8%XRh?!2XF7x z>#O#+RDWCTzt-!m|5feUAH3$$Ip)|mJnVyqo_*9UI>*?Yp1IO@f4u#9dFL;xeNxS{ zjj=glV1Eqs?5S?iIi7{g>6t5i!(JE&12UjnbdD}E$G(ZfQWyvWJq+j;onvfH&s^yn zR>MFTkOAGIb36-~W8cJKDGY>x9tL!a&e28Y^vspMVKoed0U6LOI>*=?`z8)cVIU0j zFrZs>j%Oirdge;suo?!!fDGssouiA)v2WtA6b8aT4+FYI=NOyQGgtbC)i4kSWI(s* z9M3{;*LPd5H}ex;T%-o6K^Qokf$Lsrk2*(3`F!GE*D3W#J;J~|4Cox=)OVixrjDs& z7#LEn4D>LdTXc@GIX!cwZ&(cj zVL%3Si_Y;ZWR86khovwO26`CKEjmXRnbR{@`i9jo5C&vGx9A*WbL^WqEQNtE(8GXk z(K()l%;}jceZy)P2m>;pTXc>tGRMA&!%`Rs13e7r7M){kPS0HF8&<!zF{>CgaH}QEjq{89Q!5?OJN`k^e~`XbdF~sb9&}V z->@16!hj6u7M-Ju%&~9cuoMQuKo0}DMduis(=%84hSe|-24q0D=p4^N=GZrJSPBDS zpoan7qH}bSIX!cwZ&(cjVL%3Si_S4N$G(ZfQWyvWJq+j;o#R=^oSwPTH>`$%FdzfE zMd#=ubL^WqEQNtE(8GXk(K*KE^vspMVKoed0U6LOI>)n+IrdE)mcl?7=wU#&=p0>S zPS0HF8&<tlIi7{g>6t5i!)h1^12UjnbdD}E$G(ZfQWyvWJq+j; zonvfH&s^ynR>MFTkOAGIb36-~W8cJKDGY>x9tL!a&e28Y^vspMVKoed0U6LOI>*=? z`z8)cVIU0jFrZs>j%Oirdge;suo?!!fDGssouiA)v2WtA6b8aT4+FYI=NOyQGgtbC z)i4kSWI(s*9M3}L*f;U%vh>317Z;yYYmeE-)ZkbQ=oX!$i_AIJIx}zoJ#u%s=A&xu z(fG3d`C7I1m^!BhYcil)bdIq(YpyMG_1_D6W=wn;7sbIV{&z^X=p4^N=EMp8PFT8z zV>~k^C$G`Azt>B%wDkD8Md#=ubCzCD#y^btF+S-JD_@^Q8H*yEg`zH!m^8Ca9Ip1E|3&hac{PS0HFyFRx|yC|>G*5A`T-AB4b=jbAH z_H^y%b}d8anYo_7tn=2jYVGmdYMbjlY|nLz&M`J8bv~@lTdSMrqC3kM?^e5~T3ob` z{oNXGL+jBkI>)n+IYZ;*`Qvi?-D?*YSIQsFD?RaC{&AeVMmsJWTfR4Si_XzS=4|;| z&UtOkIk%R39lU43Y)#xy~i`S9_+KZW$9hj{cdtzxG`sp1Pjo zAD7Re`s)^*V{FdQIC*}Z{r$Y0@>R9==zZNjKYy!Q`wpQF8RHyt>^s+<_MD4+tvADo0wOsZ_wKuEHwWm{EG}pWtXTCk0 zvzEF==jbAH=A1iYjblQ$jEQx~80VOCd%32459p<8H&wg0+7s25*sGyySz@k?xy&B+ z)>XIY9Ak5O=S%-#4yK-ShVI`U|L7ve$-WKmTWWK7ZFGyy@hoIcYJGUEZ&bUvoTH2M zhCZ1ZJI;;Pp6BLe;T-F!TXc>tGUps?wB$8^S+8x{`^oK5hxEjHW2$q^cbp|_kg?C# zW4cA>7@HGT)?sC;fBc+CZ}@(WZW$9hPWFABeLuH4>lU5kS;(AotIrm$cZ`c%r=MHt zkTK3N$G(m~HE!Pvc(2;~)rQvAJ{NncT6^Dn>iEe&-J0nZouiA)$zHF&*F&$-#_WX- z(Je!9`ySC{wU?{ew{Qhw(g|daZPe&hac{&Z%GT*4FQRHx%oN_S=dFsy$n6 zX(y~XzSq9BJ<58P^Pz6hIl9Q4?8Ur$;eEH}{l2xitV0-^m$5C^Q@7|GV{^8AEvL9P z@4KxzVa@eehcD`E*WUAL?G*PkYaYLEx<%)B7BVNb9belqwer4O^L}4qu3O3%SF1f= z&DV)u+e0TEBws*N}VSjsrF(u^T)*PGp=?fdAeHr|9rL2yPm6-eM}9uz<_Si zIi7{g*}|Ilw1!X11)o)Gwf8%Ceot>t*PCmJ_hdk~=p0>Sj(rn{r7#c%dKl0xI>*?Y zp1IODtcHOwAOpHZ=Xe$}$G(ZfQWyvWJq+j;ouiA)>6t5i!)h1^12UjnbdIq(_Dvj? zzOLVqeOs;lzWsOg`1@+@ckVv_asBfr)$)D9@bZVw&@DR0vyeG|*gyY#eoX0>Z^}16 zRcjm!#pZ{X^W){;+jHHbb99k8|K3>ncjv*D=bRzu3_br&d8(a{ep@ZPqz1Z0=NOw4 zX2Oi;nIX^k{NL62=wGV+=Qt9b?3CdQ}oZ} zp7!1D#!>i54P-#K=p0>Sj(rn{B^h|9{F2vJVL~SURIFQcjQ{&~|hq*8i2F5a=TXc@GIb+97UKk7mVc<_O zpj&i~XCZU`)Oh*#VJ-}Wfw2te7M-Ju%o#gw^1@&k2m^nL0o|f=jLrE|y&z=9${b}26T>b z>N`(;Q^(XX3=A_cw=nR>4Cof!?0Z4hO-Cip`-@>94D>LdTXc@G zIX!cwZ&(cjVL%3Si_Y;ZWR86khovwO26`CKEjmXRnbR{@`i9jo5C&vGx9A*WbL^Wq zEQNtE(8GXk(K()l%;}jceZy)P2m>;pTXc>tGRMA&!%`Rs13e7r7M){kPS0HF8&<!zF{>CgaH}QEjq{89Q!5?OJN`k^e~`X zbdF~sb9&}V->@16!hj6u7M-Ju%&~9cuoMQuKo0}DMduis(=%84hSe|-24q0D=p4^N z=GZrJSPBDSpoan7qH}bSIX!cwZ&(cjVL%3Si_S4N$G(ZfQWyvWJq+j;o#R=^oSwPT zH>`$%FdzfEMd#=ubL^WqEQNtE(8GXk(K*KE^vspMVKoed0U6LOI>)n+IrdE)mcl?7 z=wU#&=p0>SPS0HF8&<tlIi7{g>6t5i!)h1^12UjnbdD}E$G(Zf zQWyvWJq+j;onvfH&s^ynR>MFTkOAGIb36-~W8cJKDGY>x9tL!a&e28Y^vspMVKoed z0U6LOI>*=?`z8)cVIU0jFrZs>j%Oirdge;suo?!!fDGssouiA)v2WtA6b8aT4+FYI z=NOyQGgtbC)i4kSWI(s*9M3}L*f;U%vh>317Z;yYYmeE-)ZkbQ=oX!$i_AIJIx}zo zJ#u%s=A&xu(fG3d`C7I1m^!BhYcil)bdIq(YpyMG_1_D6W=wn;7sbIV{&z^X=p4^N z=EMp8PFT8zV>~k^C$G`Azt>B%wDkD8Md#=ubCzCD#y^btF+S-JD_@^Q8H*yEg`zH!m^8Ca9Ip1E|3&hac{PS0HFyFRx|yC|>G*5A`T z-AB4b=jbAH_H^y%b}d8anYo_7tn=2jYVGmdYMbjlY|nLz&M`J8bv~@lTdSMrqC3kM z?^e5~T3ob`{oNXGL+jBkI>)n+IYZ;*`Qvi?-D?*YSIQsFD?RaC{&AeVMmsJWTfR4S zi_XzS=4|;|&UtOkIk%R39lU43Y)#xy~i`S9_+KZW$9hj{cdt zzxG`sp1PjoAD7Re`s)^*V{FdQIC*}Z{r$Y0@>R9==zZNjKYy!Q`wpQF8RHyt>^s+< z_MD4+tvADo0wOsZ_wKuEHwWm{E zG}pWtXTCk0vzEF==jbAH=A1iYjblQ$jEQx~80VOCd%32459p<8H&wg0+7s25*sGyy zSz@k?xy&B+)>XIY9Ak5O=S%-#4yK-ShVI`U|L7ve$-WKmTWWK7ZFGyy@hoIcYJGUE zZ&bUvoTH2MhCZ1ZJI;;Pp6BLe;T-F!TXc>tGUps?wB$8^S+8x{`^oK5hxEjHW2$q^ zcbp|_kg?C#W4cA>7@HGT)?sC;fBc+CZ}@(WZW$9hPWFABeLuH4>lU5kS;(AotIrm$ zcZ`c%r=MHtkTK3N$G(m~HE!Pvc(2;~)rQvAJ{NncT6^Dn>iEe&-J0nZouiA)$zHF& z*F&$-#_WX-(Je!9`ySC{wU?{ew{Qhw(g|daZPe&hac{&Z%GT*4FQRHx%oN z_S=dFsy$n6X(y~XzSq9BJ<58P^Pz6hIl9Q4?8Ur$;eEH}{l2xitV0-^m$5C^Q@7|G zV{^8AEvL9P@4KxzVa@eehcD`E*WUAL?G*PkYaYLEx<%)B7BVNb9belqwer4O^L}4q zu3O3%SF1f=&DV)u+e0TEBws*N}VSjsrF(u^T)*PGp=?fdAeHr|9rL2yPm6- zeM}9uz<_SiIi7{g*}|Ilw1!X11)o)Gwf8%Ceot>t*PCmJ_hdk~=p0>Sj(rn{r7#c% zdKl0xI>*?Yp1IODtcHOwAOpHZ=Xe$}$G(Zf(toJejsLM)yzNb36-~Gj;srhsiJy28I~WEjmXR znKLv_o)2STAPh`pK)2`|V{@jCpZqWx2ExD)1G+`$cos5eXq-GB#=<}tn96`|(K))v zoT=j{KTL*!Ffhb`ZqYf$<_wLK=fhYS2m@0Y&@DR0vyeGc$4`Ek3Fz*Giwi_S4NXX^OL50haa3=A=#TXc?Rp||U|h1Z+;i7zfvgVZ1l9L~UX zue3**i^j&bTcPkmFz)G-VUGce>F&qz6I9)8wL?NYli@M{Ki zi*EM4AZwZ|mfiTd+fNs$_y2zZKxzabRhJi331G+`$ z7@K3?#9=86gn=Fgbc@dMEM!j4T}u zO5d;=2Eu?0=oX#hS;!pwCJswsAPn>{pj&i~E;6TQuJjG7VIU01fNs$_#^%^Jaaali zVW5Wr-J)|m3z^e1SNew4Fc1c0K)2`|U1W}Z6NjZR5C(b}&@DR0*qolZ(l@MzfiNHg zx<%)B7Ba`aiNjJD2m?I~=oX!$i_GbnD}BRi7zhJ0pj&i~u{ril9G1dB80cX@x9A+t zLgw_$mA+v$41@t0&@DPg7nx(<#9=86gn=Fgbc@b0Hm7H<^bMs^shovwO26`CKEjq`ukU2ebrEgdb z17Sc0bc@c>MdsKyaaaliVW5Wr-J)}h&FPsdeZy)P2m>;pTXc?RA#?1T_;gu%;q{A) zPpY-Y>|<(hECzIo&e28Y9BZAKxBniwyIk{8wf1OyS^s>kT6;{LQ-d`b&@DR0*qk-j zmbv=x1wAt+zKo0F;1&Nnq+4{3XCZUqgnlP1UBfY+8IzOOXxrcGrCC~feBGjRbdfnr zuP5Ul#{3wc^yFOTT$FRs0_P&#qH~PRi60L0!+ofHU*J$hS>7MQ*-J)}JkvV(1_H(sqz;cy6`L z^&Yn8x<%(0o0B>pR_CqN&2!P6<%@T#-BT?t+Q5V1g%bMd_wf1<<`;}||dH;2b&M`J8b=&5Bfz!{jg?ynRC(Eyf)P>I>*?Yz1_EaxgNdYd1h+tI7804ul&${$J!qK z9BnAS=lQs3-{&ITqH{b8nX{Msb#K?9H>Ntre8(B`#!&5+c2QoV?axKJMd#=ubB5T< z^T%aFZ`@qxlKZPYQ%$#wi5*A(Ox<7mE)h>%Px6n;=TQB1i_S4NXK0)}zs~-CUQYR{ zT6^@qZl9mORjqx8P=}0hjyd+7YfpR5MZVUXYdslf9ahKGS-0q%|G&NS53;MM^7tc| z7y`irBqRhfiR=bKVwj(qWR+xmtwBw!%A!^Yy9m)_ObC!M1PTe@5G2C#V+Sb2grMl| zg6tx)0bGnoQSgUSJ7FcRwIN25Ldrr*{R7de-O}uyp1E)N%uFtI-}JqA?tAY$RVRI> zbI$F)r@#G~e!pgT7Gg}2Ybqw)^^Ic=`9q%!AzPC8%zdA+?1N@2&C*)aYFU)lxVlby zYnWy&$rdt)EMiQWW9wSUG(ol`@yU=R%wf#2#v1=VpflVLms?F$YL$;7PJPR>KwH|$~k5s#~ zm_rtk8{|o~KCg46xvMW-Ei__1$rdt)EMiO})+oz+zSbVw_~(;-ONNB_Une3r_zYepgIoU$y&}U2*bI>)DYiXTv zVS}0f{1tuf-z2{OockoZ#;Iof{Tp#y%DSI(mL8Jpq1J0fwvahI3o)kF@3(04=e~>c z$qN73ifLx^%(7-ep4aES7j2C+pX_)@wvahw5o5F#>8=I$U7q{BXk)Ps(pb70D{?)_ z7BYuEV~Tt)wKzBKyP`26&-t(pTkLG-pY!roi)*SmCto+Rh0Nhuh%u^d^4cb;75819 z`#p=X#v3oDo6R@l<3!$L5a{#7wh=W{gkb``5VqndA&J|98Ip z>s@D=X&qIAB4~hYA#->ZVoVX{Tu*b@Y%I9a%-5dp!Q=b%>gj%UFXA3GK(>%MWD#SS zD_>fY2Bd)y4UjEl4t>UijHTTA(CRgIR`ah>`OnR6wf8aZHS?dZ*lF#b%=|iUvv!}^ zTJ!zqNBrZz%gm$!)qolxTgV)qg&4zJ`HiWiIOdQ)^lvr}9We7cl4eu`YJhAZbI2mb zFjszKYN>Lz@t-FpXOj3AS&q;1XDI1MH6UBa9QurrW~7;F&p(Wpexx62fNUXicot#| zbLC4*WJ{kt#(LeX$IdqFUuEB4VCFR?&8P;{0NFz3kVTAPu6$`p8juD;G(fhHIrJG5 zGL~|sRcSyPpa#emGKXg&#xPgDv?L8k10fn9TgV);h%q5!DOXyR2BZOMfNUXi=re}7 z@}(tdKpF_q0NFz3@GQibkg=32tx5yZ05w3ikU3-#W0)&nT9O8&fe;OlEo2UT#)OQe zTxnGrkOrs$vW3jyS%@*rl`kzx1JXc<2FMmNhb&@D$XLpiR;2-HfEplM$Q=5NVXk~> zNg9v_LNq|OkU2aHF(zazC{(sR2`*(cn!ochi4?6Ge>vMRNYiJX<(!V$QH7h&jqn=WR!e8mnaQL10fn9 zTgV*xj0qV_xzegMAPrChWDA+Yvk+sLD_>fY2Bd)y4UjEl4q3#Qkg=32tx5yZ05w3i zkU8`j!(92&k~AOZVobNg9v_LNq|OkU3-#V?xGKuCyu*NCVUW*+S;fXAE=Y zOH0y#G!UWzvW3jyS%@(qV<}f!l?J2%YJhAZbI2mbFju~`Bn?OdAsQfC$Q=5N2^mYd z(yBBd4NwDQ3z@^S5M!7tUs{p|q=66(kS$~mS;Ux-v6L&VN(0gWH9)qIIrJIBT=~+H zG$0LxXn<@Xb9feFOvqTul~$zzX@D9aTgV);h%wBSFD*#}(m;p?$QCk(K4U`0Qm(Wr z4M+pj0NFz3@GQg_=E|3rqycFlL<3|CnL`#aCS)w-N~_X%MWD#S=YMvT5e2+{q)?9ApTl!7* zeUF)MRcF;8PYsYQWDb4CZVvLv&&V;OMn1nM) zV)PiT_-mcDma@J+*+S-!MU2UMKDz$sG@pbgAu&xl7wKG-!MTWRA#><6Mtm3@AM&i* z4AaR*Gv9_VCoWekD!vBt)LY0{WDA+Yvk+rK#!_zny3LwJdW@F;n%2`kB3sBDvWPMD zbnlIJFLCFYwECOuywzjo+eWLc?ss%+PPULa^ckZ%kFL%|s~gWnlZ_V_n@u$ni|S*2 zi>9}@`H(GS4$nf2iMx*a$5yw$E0;~yom3H>)M_c)6^&5Yd0!f&!Mddz&=$m^whA6$R3h0LMP7}c$q z`-W$pYWefWh(EK83EuZ-sFTgI;193q86*}JQ%`yAbFziZ;aP|=dCg1XRHw@j{*YI1 z7=Jt?rsu#PvPh57s$1`R*&k#JnL`#are5y5-tHqU{_r~FL!N$<&P5IL*pzG`bLcas z-u7+1+z+|I^GvlquM@|d6O9l4bF9AQ>u7QDA^l=eeV>cS7BYutA;#3peyz9rAUCRI z4&!;9IBvw%E^8L)Fz};2h?UZ&g=xUIc8a`RouN~ zF_x~G%^HT*m24q%=rbmCJmtshpxSdz-2M&W4_Ux8~=Q=Z^@7lpWLXH zIgICZvaErw-MAbhTgV*xjFDFI(Mq-a;p;@?2A|I%Tax&^j@CV&b#JsflPzQp&q9o8 zwE7g`ev`0>^W^JRWJnU`FowCjezm@TU%+a!ZnL<#`Paqfn)&CwtG&MBYqw@(3z|sR$n*NV_oA(l=93){$rdt)EMkn-BHgv%zRPpJ7i}!oK^jX} zV@0kf*+S;fXH1drr55MLeOELl|9=j7`~wvahI3o%BuOVBF2o>JnMB_?#C>c5O+0n~eomn)%xEJ$QVdUXky2tG$lD*UZ1a zu+Q4p&3epd|Et#L+3Iyv<6Mr)M+8WpYP)$)g2Vs6pyOY_NJ+hhxw!?O@$ zv_|=_QPFBnhLA0B{#Wem(KJA| zkU3-#V~RF^%}0Am8mL_jkS$~mea2|5Yj>@+c3QilX@G1Yb9feFOws1A`Djl`1GTFG zvW3hcix{J|uHCiP+G*{IrU9~r%%RViqRn6P(Vmh9YF7hf3z@^S5M#8~wY%0@JFQ*O zG(fhHIb;!IiZ*}EM|(;ds9g<^Eo2UT#%Qf;cdfN{TDziYfNUXicot$z(dMuDXirH4 zwW|TLh0Gy~7^AhW-L=-*Y3+)p0kVb6q0gA2&0q7;o{|P?R|8}VnZvUXW3<+_yVhDe ztzFSHK(>%MWD#SEHh;}WdrBIpT@8>eWDb4CXsv5^t+jSqyP|1;Y$0=a7W%aP4ylSU zUjESE-==z~9@0Q{8mMr^w`2}E$$t4m>!f<99@0QM8hDF2t5&>oV&9SlCzme%M9JH# z6-U3LRGK)kG~#PYsa#sKdh_aw)~x^R=Ci$bcFXee($WP%UxVkZ=gRkYt#yG*L!{s~Yt#fl8d!)Q`-{tPnCwG;PKly6+{H&+T z&zx|B+rRLK<@xW~=DPp;JdExV_RH#(Npg5&YRp1 z-v2%KrSorh zPr1jPxAK7NnBC`|pZtouj2Pfa) z?wb3G+jid<-RBPPcNc!>de^`Bzue#4cb$9m@Lsq7&~@&AyI*vx{&2nfyB#k$uZKye zec-&lqwKHjn7y4IT8HbQb$NMVm3kQb8G48P{?@hjbMe8beI)vQuD;!9{kyF7e@Ek) za;f)5Yx}Le*;@O(uf4Zh>;D$e-PRtq_Fij`ai!j`T5Ep?t@l1_-);7Fv*~8vG@E7i zpxNp6{|{U1|4!Ps%@&zGX6CGam$iRw_JrAm_WgIQ-DLKZ*;cdfS>G+z?l!yAd~5xf zz2CR*Z4BS~YY+5)$6B9f*88Nj&szJhW}B)qK6($Bf0wnd zSZnv$d(g~}dC1yrgKf#`(d)mzVX!UrTEE4WuCwp=N9|9e_NA!px7HXiFuuk2K4<3h zpB-5L4?lj+mQk&L+i2E*1ZZlq!|$7`zV-PReq^)v_ICT`uZHiN_T}Y8RqmS#bSuTO ztvc{EE^3dCT7&t(*Z8QN5Vh}&+6w58iN2o{wZ}&7aZx)tYLAcFcSY@#sGSj(&ZGCgCZ-Mo-S>F=t>$1M(*0<97K5l*ITi?aj z*KK{5THh7c_XX?gHUCEI-)7(6V*huW_4Qfb-PZRN>)UR9JG*?{es|q%2S>Gk7KQJh zQjLEF@uxG-`uUm8y7tRWtyXbwZ%4{0!%4Y#dHJ{@q^y3~g2rDGH@^5gxDvI)->Ib* zsOze=o32>D@$%*6_YRR)<;QGn+cwGT>7}oI?vwr}ueW$T&n`7%#DxP7p{`iFY5nR; z*I%=GvyFby`ZdeT3#ytx^WsH|+B!Rzv~;vA>Fj9kY-w-nXl`ro>}+rESkltGxV5vT zxwW-piJ#?HuNZ%U|9R(a)rzD1WdHw>UeDC#-=1fO25*(0;r{;zzlJ{UTiCPV(&70x zo%4$s{%ql`^0R+1_nUUbxAH&ph0SX>Zd$W;)9?%ML1^VrF?fM#c7}QD0s~cR9-hsI zEJL&V)_h`kcFXW=9(adlKhQlQyLEUrkA1_k*Nw<-8=lR>!qDt}>qlg_56|Y0%%Rzb zHjK#b7@i$J^XZq3$X+x&n-Cv5_NOi%k=>a*d)&qm*^7r~$5(CZ$ZQk;P_c8nRt~O% zTD$o396N%-@O18@*@Jn}zk7$IA9;tbS}|cl