From 18240240fbf62eb3c8719c24f76165641289ba4d Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 6 Mar 2024 17:46:38 +0100 Subject: [PATCH 001/338] Robotiq Environment setup and first tests --- examples/robotiq_first_tests/record_demo.py | 38 ++ serl_robot_infra/robotiq_env/__init__.py | 8 + serl_robot_infra/robotiq_env/envs/__init__.py | 1 + .../robotiq_env/envs/robotiq_env.py | 325 ++++++++++++++++++ .../robotiq_env/envs/test_env/__init__.py | 1 + .../robotiq_env/envs/test_env/config.py | 21 ++ .../robotiq_env/envs/test_env/robotiq_test.py | 11 + serl_robot_infra/robotiq_env/envs/wrappers.py | 74 ++++ .../robotiq_env/utils/__init__.py | 0 .../robotiq_env/utils/rotations.py | 11 + 10 files changed, 490 insertions(+) create mode 100644 examples/robotiq_first_tests/record_demo.py create mode 100644 serl_robot_infra/robotiq_env/__init__.py create mode 100644 serl_robot_infra/robotiq_env/envs/__init__.py create mode 100644 serl_robot_infra/robotiq_env/envs/robotiq_env.py create mode 100644 serl_robot_infra/robotiq_env/envs/test_env/__init__.py create mode 100644 serl_robot_infra/robotiq_env/envs/test_env/config.py create mode 100644 serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py create mode 100644 serl_robot_infra/robotiq_env/envs/wrappers.py create mode 100644 serl_robot_infra/robotiq_env/utils/__init__.py create mode 100644 serl_robot_infra/robotiq_env/utils/rotations.py diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_first_tests/record_demo.py new file mode 100644 index 00000000..923832d7 --- /dev/null +++ b/examples/robotiq_first_tests/record_demo.py @@ -0,0 +1,38 @@ +import gymnasium as gym +import numpy as np +import copy + +from robotiq_env.envs.wrappers import SpacemouseIntervention +from pprint import pprint + + +if __name__ == "__main__": + env = gym.make("robotiq_test") + env = SpacemouseIntervention(env) + + obs, _ = env.reset() + transitions = [] + + while True: + next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) + actions = info["intervene_action"] + + transition = copy.deepcopy( + dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=rew, + masks=1.0 - done, + dones=done, + ) + ) + transitions.append(transition) + pprint(transition) + + obs = next_obs + + if done: + break + + env.close() diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py new file mode 100644 index 00000000..9ee39520 --- /dev/null +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -0,0 +1,8 @@ +from gymnasium.envs.registration import register +import numpy as np + +register( + id="robotiq_test", + entry_point="robotiq_env.envs.test_env:RobotiqTest", + max_episode_steps=100, +) \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/__init__.py b/serl_robot_infra/robotiq_env/envs/__init__.py new file mode 100644 index 00000000..17307002 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/__init__.py @@ -0,0 +1 @@ +from robotiq_env.envs.robotiq_env import RobotiqEnv, DefaultEnvConfig diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py new file mode 100644 index 00000000..d59cb71b --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -0,0 +1,325 @@ +"""Gym Interface for Robotiq""" + +import numpy as np +import gymnasium as gym +import copy +import time +from typing import Dict +from rtde_control import RTDEControlInterface as RTDEControl +from rtde_receive import RTDEReceiveInterface as RTDEReceive + +from robotiq_env.utils.rotations import rotvev_2_quat, quat_2_rotvec + +############################################################################## + + +class DefaultEnvConfig: + """Default configuration for RobotiqEnv. Fill in the values below.""" + + TARGET_POSE: np.ndarray = np.zeros((6,)) # might change as well + REWARD_THRESHOLD: np.ndarray = np.zeros((6,)) + RESET_POSE = np.zeros((6,)) + RANDOM_RESET = (False,) + RANDOM_XY_RANGE = (0.0,) + RANDOM_RZ_RANGE = (0.0,) + ABS_POSE_LIMIT_HIGH = np.zeros((6,)) + ABS_POSE_LIMIT_LOW = np.zeros((6,)) + + ROBOT_IP: str = "localhost" + FORCEMODE_DAMPING: float = 0.1 + FORCEMODE_TASK_FRAME = np.zeros(6, ) + FORCEMODE_SELECTION_VECTOR = np.ones(6, ) + FORCEMODE_FORCE_TYPE: int = 2 + FORCEMODE_LIMITS = np.zeros(6, ) + FORCEMODE_SCALING = np.ones(6, ) + + # not used for now + REALSENSE_CAMERAS: Dict = { + "wrist_1": "130322274175", + "wrist_2": "127122270572", + } + + +############################################################################## + + +class RobotiqEnv(gym.Env): + def __init__( + self, + hz: int = 10, + save_video: bool = False, + config=DefaultEnvConfig, + max_episode_length: int = 100 + ): + self._TARGET_POSE = config.TARGET_POSE + self._REWARD_THRESHOLD = config.REWARD_THRESHOLD + self.max_episode_length = max_episode_length + + self.robot_ip = config.ROBOT_IP + self.FM_DAMPING = config.FORCEMODE_DAMPING + self.FM_TASK_FRAME = config.FORCEMODE_TASK_FRAME + self.FM_SELECTION_VECTOR = config.FORCEMODE_SELECTION_VECTOR + self.FM_FORCE_TYPE = config.FORCEMODE_FORCE_TYPE + self.FM_LIMITS = config.FORCEMODE_LIMITS + self.FM_SCALING = config.FORCEMODE_SCALING + + self.robotiq_control = None + self.robotiq_receive = None + self.robotiq_gripper = None + + # convert last 3 elements from axis angle to quat, from size (6,) to (7,) + self.resetpos = np.concatenate( + [config.RESET_POSE[:3], rotvev_2_quat(config.RESET_POSE[3:])] + ).astype(np.float32) + + self.currpos = self.resetpos.copy().astype(np.float32) + self.currvel = np.zeros((6,), dtype=np.float32) + self.q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq + self.dq = np.zeros((6,), dtype=np.float32) + self.currforce = np.zeros((3,), dtype=np.float32) + self.currtorque = np.zeros((3,), dtype=np.float32) + self.currjacobian = np.zeros((6, 7), dtype=np.float32) + + self.curr_gripper_pos = 0 + self.lastsent = time.time() + self.randomreset = config.RANDOM_RESET + self.random_xy_range = config.RANDOM_XY_RANGE + self.random_rz_range = config.RANDOM_RZ_RANGE + self.hz = hz + self.joint_reset_cycle = 200 # reset the robot joint every 200 cycles + + if save_video: + print("Saving videos!") + self.save_video = save_video + self.recording_frames = [] + + self.xyz_bounding_box = gym.spaces.Box( + config.ABS_POSE_LIMIT_LOW[:3], + config.ABS_POSE_LIMIT_HIGH[:3], + dtype=np.float64, + ) + self.rpy_bounding_box = gym.spaces.Box( + config.ABS_POSE_LIMIT_LOW[3:], + config.ABS_POSE_LIMIT_HIGH[3:], + dtype=np.float64, + ) + # Action/Observation Space + self.action_space = gym.spaces.Box( + np.ones((7,), dtype=np.float32) * -1, + np.ones((7,), dtype=np.float32), + ) + + self.observation_space = gym.spaces.Dict( + { + "state": gym.spaces.Dict( + { + "tcp_pose": gym.spaces.Box( + -np.inf, np.inf, shape=(7,) + ), # xyz + quat + "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), + "gripper_pose": gym.spaces.Box(-1, 1, shape=(1,)), + "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + } + ) + # "images": gym.spaces.Dict( # Images are ignored for now + # { + # "wrist_1": gym.spaces.Box( + # 0, 255, shape=(128, 128, 3), dtype=np.uint8 + # ), + # "wrist_2": gym.spaces.Box( + # 0, 255, shape=(128, 128, 3), dtype=np.uint8 + # ), + # } + # ), + } + ) + self.cycle_count = 0 + + self.start_robotiq_interfaces() + + def start_robotiq_interfaces(self): + self.robotiq_control = RTDEControl(self.robot_ip) + self.robotiq_receive = RTDEReceive(self.robot_ip) + # self.robotiq_gripper = VacuumGripper(self.robot_ip) + # TODO gripper + print("UR-RTDE interfaces ready") + + + def pose_r2q(self, pose: np.ndarray) -> np.ndarray: + return np.concatenate([pose[:3], rotvev_2_quat(pose[3:])]) + + def pose_q2r(self, pose: np.ndarray) -> np.ndarray: + return np.concatenate([pose[:3], quat_2_rotvec(pose[3:])]) + + def clip_safety_box(self, action: np.ndarray) -> np.ndarray: + """Clip the action to not move outside the safety box.""" + + # check for position limits (prevent, but do not stop) + adverse_move = 0.1 + for i, (low, high) in enumerate(zip(self.xyz_bounding_box.low, self.xyz_bounding_box.high)): + if low and self.currpos[i] < low and action[i] < adverse_move: + action[i] = adverse_move + print(f"lower {i} set new") + elif high and self.currpos[i] > high and action[i] > -adverse_move: + action[i] = -adverse_move + print("upper set new") + + # TODO apply quaternion limits + # TODO test + return action + + def step(self, action: np.ndarray) -> tuple: + """standard gym step function.""" + t_start_robotiq = self.robotiq_control.initPeriod() + start_time = time.time() + action = np.clip(action, self.action_space.low, self.action_space.high) + + safe_action = self.clip_safety_box(action) + self._send_force_command(safe_action[:6]) + self._send_gripper_command(safe_action[6]) + + self.curr_path_length += 1 + self.robotiq_control.waitPeriod(t_start_robotiq) + + dt = time.time() - start_time + time.sleep(max(0, (1.0 / self.hz) - dt)) + + self._update_currpos() + ob = self._get_obs() + reward = self.compute_reward(ob) + done = self.curr_path_length >= self.max_episode_length or reward + return ob, int(reward), done, False, {} + + def compute_reward(self, obs) -> bool: + current_pose = obs["state"]["tcp_pose"] + # convert from quat to axis angle representation first + current_pose = self.pose_q2r(current_pose) + delta = np.abs(current_pose - self._TARGET_POSE) + if np.all(delta < self._REWARD_THRESHOLD): + return True + else: + # print(f'Goal not reached, the difference is {delta}, the desired threshold is {_REWARD_THRESHOLD}') + return False + + # TODO adapt get_im(), crop_image(), init_cameras(), close_cameras(), + + def move_to(self, goal: np.ndarray): + """Move the robot to the goal position with moveL (linear in tool-space)""" + goal_ur = self.pose_q2r(goal) + self.robotiq_control.moveL(list(goal_ur), speed=0.05, acceleration=0.3) # command will block until finished + self._update_currpos() + + def go_to_rest(self, joint_reset=False): + """ + The concrete steps to perform reset should be + implemented each subclass for the specific task. + Should override this method if custom reset procedure is needed. + """ + + # Perform joint reset if needed + if joint_reset: + pass + # TODO joint reset + + # Perform Carteasian reset + if self.randomreset[0]: # randomize reset position in xy plane TODO is most likely bug in codebase, no ...[0] + # reset_pose = self.resetpos.copy()ss + # reset_pose[:2] += np.random.uniform( + # np.negative(self.random_xy_range), self.random_xy_range, (2,) + # ) + # euler_random = self._TARGET_POSE[3:].copy() + # euler_random[-1] += np.random.uniform( + # np.negative(self.random_rz_range), self.random_rz_range + # ) + # reset_pose[3:] = euler_2_quat(euler_random) + # self.move_to(reset_pose) + pass + else: + reset_pose = self.resetpos.copy() + self.move_to(reset_pose) + + def reset(self, joint_reset=False, **kwargs): + if self.save_video: + # TODO adapt save_video_recording() + pass + + self.cycle_count += 1 + if self.cycle_count % self.joint_reset_cycle == 0: + self.cycle_count = 0 + joint_reset = True + + self.go_to_rest(joint_reset=joint_reset) + self._recover() + self.curr_path_length = 0 + + self._update_currpos() + obs = self._get_obs() + + return obs, {} + + def _recover(self): + """Internal function to recover the robot from error state.""" + # TODO make recover function + pass + + def _send_force_command(self, action: np.ndarray): + """Internal function to send force command to the robot.""" + force = action * self.FM_SCALING + self.robotiq_control.forceModeSetDamping(self.FM_DAMPING) + self.robotiq_control.forceMode( + self.FM_TASK_FRAME, + self.FM_SELECTION_VECTOR, + force, + self.FM_FORCE_TYPE, + self.FM_LIMITS + ) + + def _send_gripper_command(self, pos: float): + """Internal function to send gripper command to the robot.""" + if (pos >= -1) and (pos <= -0.9): # close gripper + pass # TODO gripper command + elif (pos >= 0.9) and (pos <= 1): # open gripper + pass + else: # do nothing to the gripper + return + + def _update_currpos(self): + """ + Internal function to get the latest state of the robot and its gripper. + """ + pose = self.robotiq_receive.getActualTCPPose() + vel = self.robotiq_receive.getActualTCPSpeed() + pose_quat = self.pose_r2q(pose) + + force = self.robotiq_receive.getActualTCPForce() + q = self.robotiq_receive.getActualQ() + qd = self.robotiq_receive.getActualQd() + + self.currpos[:] = np.array(pose_quat) + self.currvel[:] = np.array(vel) + + self.currforce[:] = np.array(force[:3]) + self.currtorque[:] = np.array(force[3:]) + # self.currjacobian[:] = np.reshape(np.array(ps["jacobian"]), (6, 7)) # TODO jacobian? + + self.q[:] = np.array(q) + self.dq[:] = np.array(qd) + + # TODO get gripper pos + self.curr_gripper_pos = np.zeros(1, dtype=np.float32) + + def _get_obs(self) -> dict: + state_observation = { + "tcp_pose": self.currpos, + "tcp_vel": self.currvel, + "gripper_pose": self.curr_gripper_pos, + "tcp_force": self.currforce, + "tcp_torque": self.currtorque, + } + return copy.deepcopy(dict(state=state_observation)) + + def close(self): + self.robotiq_control.forceModeStop() + print("force mode stopped") + super().close() diff --git a/serl_robot_infra/robotiq_env/envs/test_env/__init__.py b/serl_robot_infra/robotiq_env/envs/test_env/__init__.py new file mode 100644 index 00000000..daa38c69 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/test_env/__init__.py @@ -0,0 +1 @@ +from robotiq_env.envs.test_env.robotiq_test import RobotiqTest \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/test_env/config.py new file mode 100644 index 00000000..fa700c4c --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/test_env/config.py @@ -0,0 +1,21 @@ +from robotiq_env.envs.robotiq_env import DefaultEnvConfig +import numpy as np + + +class TestConfig(DefaultEnvConfig): + TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) + REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) + RESET_POSE = np.array([-0.2, -0.7, 0.133, 2.58, -1.63, -0.03]) + RANDOM_RESET = (False,) + RANDOM_XY_RANGE = (0.0,) + RANDOM_RZ_RANGE = (0.0,) + ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., 3., 1., 1.]) + ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -3., -1., -1.]) + + ROBOT_IP: str = "172.22.22.3" + FORCEMODE_DAMPING: float = 0.1 + FORCEMODE_TASK_FRAME = np.zeros(6) + FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) + FORCEMODE_FORCE_TYPE: int = 2 + FORCEMODE_LIMITS = np.array([8., 8., 8., 4., 4., 4.]) + FORCEMODE_SCALING = np.array([1e3, 1e3, 1e3, 5, 5, 5]) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py b/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py new file mode 100644 index 00000000..d35fe58b --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py @@ -0,0 +1,11 @@ +from robotiq_env.envs.robotiq_env import RobotiqEnv +from robotiq_env.envs.test_env.config import TestConfig + + +class RobotiqTest(RobotiqEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, config=TestConfig) + + def go_to_rest(self, joint_reset=False): + # how to overwrite without blocking the old function + super().go_to_rest(joint_reset) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py new file mode 100644 index 00000000..1afa1551 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -0,0 +1,74 @@ +import gymnasium as gym +import numpy as np +from franka_env.spacemouse.spacemouse_expert import SpaceMouseExpert +import time +from scipy.spatial.transform import Rotation as R + + +class SpacemouseIntervention(gym.ActionWrapper): + def __init__(self, env): + super().__init__(env) + + self.gripper_enabled = False + + self.expert = SpaceMouseExpert() + self.last_intervene = 0 + self.left, self.right = False, False + + self.invert_axes = [1, 1, 1, 1, 1, 1] + + def action(self, action: np.ndarray) -> np.ndarray: + """ + Input: + - action: policy action + Output: + - action: spacemouse action if nonezero; else, policy action + """ + expert_a, buttons = self.expert.get_action() + self.left, self.right = tuple(buttons) + + if np.linalg.norm(expert_a) > 0.001: + self.last_intervene = time.time() + + if self.gripper_enabled: + if self.left: # close gripper + gripper_action = np.random.uniform(-1, -0.9, size=(1,)) + self.last_intervene = time.time() + elif self.right: # open gripper + gripper_action = np.random.uniform(0.9, 1, size=(1,)) + self.last_intervene = time.time() + else: + gripper_action = np.zeros((1,)) + expert_a = np.concatenate((expert_a, gripper_action), axis=0) + + if time.time() - self.last_intervene < 0.5: + expert_a = self.adapt_spacemouse_output(expert_a) + return np.concatenate((expert_a, np.array([0]))) # TODO add gripper + + return action + + def adapt_spacemouse_output(self, expert_a: np.ndarray) -> np.ndarray: + """ + Input: + - expert_a: spacemouse raw output + Output: + - expert_a: spacemouse output adapted to force space (action) + """ + + position = [1.]*6 # TODO get position + z_angle = np.arctan2(position[1], position[0]) # get first joint angle + + z_rot = R.from_rotvec(np.array([0, 0, z_angle])) + expert_a *= self.invert_axes # if some want to be inverted + expert_a[:3] = z_rot.apply(expert_a[:3]) # z rotation invariant translation + expert_a[3:] = z_rot.apply(expert_a[3:]) # z rotation invariant rotation + + return expert_a + + def step(self, action): + new_action = self.action(action) + obs, rew, done, truncated, info = self.env.step(new_action) + info["intervene_action"] = new_action + info["left"] = self.left + info["right"] = self.right + return obs, rew, done, truncated, info diff --git a/serl_robot_infra/robotiq_env/utils/__init__.py b/serl_robot_infra/robotiq_env/utils/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/robotiq_env/utils/rotations.py new file mode 100644 index 00000000..db384f4b --- /dev/null +++ b/serl_robot_infra/robotiq_env/utils/rotations.py @@ -0,0 +1,11 @@ +from scipy.spatial.transform import Rotation as R + +""" +Robotiq UR5 represents the orientation in axis angle representation +""" + +def rotvev_2_quat(rotvec): + return R.from_rotvec(rotvec).as_quat() + +def quat_2_rotvec(quat): + return R.from_quat(quat).as_rotvec() \ No newline at end of file From ffc92a74972acb46b7d325dc82b15eecd55b9581 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 8 Mar 2024 17:09:47 +0100 Subject: [PATCH 002/338] spacemouse wrapper in robotiq env --- .../robotiq_env/spacemouse/__init__.py | 0 .../spacemouse/spacemouse_expert.py | 36 +++++++++++++++++++ .../robotiq_env/spacemouse/spacemouse_test.py | 29 +++++++++++++++ 3 files changed, 65 insertions(+) create mode 100644 serl_robot_infra/robotiq_env/spacemouse/__init__.py create mode 100644 serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py create mode 100644 serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py diff --git a/serl_robot_infra/robotiq_env/spacemouse/__init__.py b/serl_robot_infra/robotiq_env/spacemouse/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py new file mode 100644 index 00000000..f7225bee --- /dev/null +++ b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py @@ -0,0 +1,36 @@ +import threading +import pyspacemouse +import numpy as np +from typing import Tuple + + +class SpaceMouseExpert: + """ + This class provides an interface to the SpaceMouse. + It continuously reads the SpaceMouse state and provide + a "get_action" method to get the latest action and button state. + """ + + def __init__(self): + pyspacemouse.open() + + self.state_lock = threading.Lock() + self.latest_data = {"action": np.zeros(6), "buttons": [0, 0]} + # Start a thread to continuously read the SpaceMouse state + self.thread = threading.Thread(target=self._read_spacemouse) + self.thread.daemon = True + self.thread.start() + + def _read_spacemouse(self): + while True: + state = pyspacemouse.read() + with self.state_lock: + self.latest_data["action"] = np.array( + [-state.y, state.x, state.z, -state.roll, -state.pitch, -state.yaw] + ) # spacemouse axis matched with robot base frame + self.latest_data["buttons"] = state.buttons + + def get_action(self) -> Tuple[np.ndarray, list]: + """Returns the latest action and button state of the SpaceMouse.""" + with self.state_lock: + return self.latest_data["action"], self.latest_data["buttons"] diff --git a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py new file mode 100644 index 00000000..8c9cb638 --- /dev/null +++ b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py @@ -0,0 +1,29 @@ +""" Test the spacemouse output. """ +import time +import numpy as np +from serl_robot_infra.franka_env.spacemouse.spacemouse_expert import SpaceMouseExpert + + +def test_spacemouse(): + """Test the SpaceMouseExpert class. + + This interactive test prints the action and buttons of the spacemouse at a rate of 10Hz. + The user is expected to move the spacemouse and press its buttons while the test is running. + It keeps running until the user stops it. + + """ + spacemouse = SpaceMouseExpert() + with np.printoptions(precision=3, suppress=True): + while True: + action, buttons = spacemouse.get_action() + print(f"Spacemouse action: {action}, buttons: {buttons}") + time.sleep(0.1) + + +def main(): + """Call spacemouse test.""" + test_spacemouse() + + +if __name__ == "__main__": + main() From aeebb4fafad70325de8dbb6403d5ad42e18dc703 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 8 Mar 2024 17:10:05 +0100 Subject: [PATCH 003/338] typo --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index d59cb71b..b5b00ea5 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -8,7 +8,7 @@ from rtde_control import RTDEControlInterface as RTDEControl from rtde_receive import RTDEReceiveInterface as RTDEReceive -from robotiq_env.utils.rotations import rotvev_2_quat, quat_2_rotvec +from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec ############################################################################## @@ -69,7 +69,7 @@ def __init__( # convert last 3 elements from axis angle to quat, from size (6,) to (7,) self.resetpos = np.concatenate( - [config.RESET_POSE[:3], rotvev_2_quat(config.RESET_POSE[3:])] + [config.RESET_POSE[:3], rotvec_2_quat(config.RESET_POSE[3:])] ).astype(np.float32) self.currpos = self.resetpos.copy().astype(np.float32) @@ -147,7 +147,7 @@ def start_robotiq_interfaces(self): def pose_r2q(self, pose: np.ndarray) -> np.ndarray: - return np.concatenate([pose[:3], rotvev_2_quat(pose[3:])]) + return np.concatenate([pose[:3], rotvec_2_quat(pose[3:])]) def pose_q2r(self, pose: np.ndarray) -> np.ndarray: return np.concatenate([pose[:3], quat_2_rotvec(pose[3:])]) From 1156d6555899584e9b818fbbdc3c47575302b9f6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 8 Mar 2024 17:10:25 +0100 Subject: [PATCH 004/338] typo --- serl_robot_infra/robotiq_env/utils/rotations.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/robotiq_env/utils/rotations.py index db384f4b..7d10821f 100644 --- a/serl_robot_infra/robotiq_env/utils/rotations.py +++ b/serl_robot_infra/robotiq_env/utils/rotations.py @@ -1,11 +1,14 @@ +import numpy as np from scipy.spatial.transform import Rotation as R """ Robotiq UR5 represents the orientation in axis angle representation """ -def rotvev_2_quat(rotvec): + +def rotvec_2_quat(rotvec): return R.from_rotvec(rotvec).as_quat() + def quat_2_rotvec(quat): - return R.from_quat(quat).as_rotvec() \ No newline at end of file + return R.from_quat(quat).as_rotvec() From f571e4fd4c029b048cee97b23eead80292c5750d Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 8 Mar 2024 17:10:37 +0100 Subject: [PATCH 005/338] added vacuum gripper to robotiq env --- .../robotiq_env/utils/vacuum_gripper.py | 269 ++++++++++++++++++ 1 file changed, 269 insertions(+) create mode 100644 serl_robot_infra/robotiq_env/utils/vacuum_gripper.py diff --git a/serl_robot_infra/robotiq_env/utils/vacuum_gripper.py b/serl_robot_infra/robotiq_env/utils/vacuum_gripper.py new file mode 100644 index 00000000..b6ebca30 --- /dev/null +++ b/serl_robot_infra/robotiq_env/utils/vacuum_gripper.py @@ -0,0 +1,269 @@ +""" +MIT License + +Copyright (c) 2019 Anders Prier Lindvig - SDU Robotics +Copyright (c) 2020 Fabian Freihube - DavinciKitchen GmbH + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +Module to control Robotiq's gripper 2F-85 and Hand-E. +Originally from here: https://sdurobotics.gitlab.io/ur_rtde/_static/gripper_2f85.py +Adjusted for use with asyncio +""" + +import asyncio +from enum import Enum +from typing import Union, Tuple, OrderedDict + +# TODO: add blocking to release, gripping + +class VacuumGripper: + """ + Communicates with the gripper directly, via socket with string commands, leveraging string names for variables. + """ + + # WRITE VARIABLES (CAN ALSO READ) + ACT = "ACT" # act : activate (1 while activated, can be reset to clear fault status) + GTO = "GTO" # gto : go to (will perform go to with the actions set in pos, for, spe) + ATR = "ATR" # atr : auto-release (emergency slow move) + FOR = "FOR" # for : vacuum minimum relative pressure (0-255) + SPE = "SPE" # spe : grip timeout/release delay + POS = "POS" # pos : vacuum max pressure (0-255) + MOD = "MOD" # mod : mode - automatic vs advanced mode + + # READ VARIABLES + STA = "STA" # status (0 = is reset, 1 = activating, 3 = active) + PRE = "PRE" # position request (echo of last commanded position) + OBJ = "OBJ" # object detection (0 = unknown, 1 = minimum pressure value reached, 2 = maximum pressure reached, 3 = no obj detected) + FLT = "FLT" # fault (0=ok, see manual for errors if not zero) + + ENCODING = "UTF-8" # ASCII and UTF-8 both seem to work + + class GripperStatus(Enum): + """Gripper status reported by the gripper. The integer values have to match what the gripper sends.""" + + RESET = 0 + ACTIVATING = 1 + # UNUSED = 2 # This value is currently not used by the gripper firmware + ACTIVE = 3 + + class ObjectStatus(Enum): + """Object status reported by the gripper. The integer values have to match what the gripper sends.""" + + MOVING = 0 + DETECTED_MIN = 1 + DETECTED_MAX = 2 + NO_OBJ_DETECTED = 3 + + def __init__(self, hostname: str, port: int = 63352) -> None: + """Constructor. + + :param hostname: Hostname or ip of the robot arm. + :param port: Port. + + """ + self.socket_reader = None + self.socket_writer = None + self.command_lock = asyncio.Lock() + + self.hostname = hostname + self.port = port + + async def connect(self) -> None: + """Connects to a gripper on the provided address""" + # print(self.hostname, self.port) + self.socket_reader, self.socket_writer = await asyncio.open_connection(self.hostname, self.port) + + async def disconnect(self) -> None: + """Closes the connection with the gripper.""" + self.socket_writer.close() + await self.socket_writer.wait_closed() + + async def _set_vars(self, var_dict: 'OrderedDict[str, Union[int, float]]') -> bool: + """Sends the appropriate command via socket to set the value of n variables, and waits for its 'ack' response. + + :param var_dict: Dictionary of variables to set (variable_name, value). + :return: True on successful reception of ack, false if no ack was received, indicating the set may not + have been effective. + """ + # construct unique command + cmd = "SET" + for variable, value in var_dict.items(): + cmd += f" {variable} {str(value)}" + cmd += "\n" # new line is required for the command to finish + # atomic commands send/rcv + async with self.command_lock: + self.socket_writer.write(cmd.encode(self.ENCODING)) + await self.socket_writer.drain() + response = await self.socket_reader.read(1024) + return self._is_ack(response) + + async def _set_var(self, variable: str, value: Union[int, float]) -> bool: + """Sends the appropriate command via socket to set the value of a variable, and waits for its 'ack' response. + + :param variable: Variable to set. + :param value: Value to set for the variable. + :return: True on successful reception of ack, false if no ack was received, indicating the set may not + have been effective. + """ + return await self._set_vars(OrderedDict([(variable, value)])) + + async def _get_var(self, variable: str) -> int: + """Sends the appropriate command to retrieve the value of a variable from the gripper, blocking until the + response is received or the socket times out. + + :param variable: Name of the variable to retrieve. + :return: Value of the variable as integer. + """ + # atomic commands send/rcv + async with self.command_lock: + cmd = f"GET {variable}\n" + self.socket_writer.write(cmd.encode(self.ENCODING)) + await self.socket_writer.drain() + data = await self.socket_reader.read(1024) + + # expect data of the form 'VAR x', where VAR is an echo of the variable name, and X the value + # note some special variables (like FLT) may send 2 bytes, instead of an integer. We assume integer here + var_name, value_str = data.decode(self.ENCODING).split() + if var_name != variable: + raise ValueError(f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'") + value = int(value_str) + return value + + @staticmethod + def _is_ack(data: str) -> bool: + return data == b"ack" + + async def activate(self) -> None: + """Resets the activation flag in the gripper, and sets it back to one, clearing previous fault flags. + + :param auto_calibrate: Whether to calibrate the minimum and maximum positions based on actual motion. + """ + # stop the vacuum generator + await self._set_var(self.GTO, 0) + #await self._set_var(self.GTO, 1) + + # to clear fault status + await self._set_var(self.ACT, 0) + await self._set_var(self.ACT, 1) + + # wait for activation to go through + while not await self.is_active(): + await asyncio.sleep(0.01) + + async def is_active(self) -> bool: + """Returns whether the gripper is active.""" + status = await self._get_var(self.STA) + return VacuumGripper.GripperStatus(status) == VacuumGripper.GripperStatus.ACTIVE + + async def get_current_pressure(self) -> int: + """Returns the current pressure as returned by the physical hardware, max pressure if not gripping.""" + return await self._get_var(self.POS) + + async def get_object_status(self) -> ObjectStatus: + a = await self._get_var(self.OBJ) + return VacuumGripper.ObjectStatus(a) + + async def get_fault_status(self) -> int: + value = await self._get_var(self.FLT) + return value + + async def automatic_grip(self) -> bool: + """Sends commands to grip using automatic mode. + In automatic mode, the pressure byte is used to send a grip/release request + + :return: A tuple with a bool indicating whether the action it was successfully sent, and an integer with + the actual position that was requested, after being adjusted to the min/max calibrated range. + """ + + # activate sets GTO to 0 and makes sure that the gripper is activated + await self.activate() + + # in automatic mode, any pressure (POS) value < 100 will lead to the grip command + var_dict = OrderedDict([(self.POS, 50), (self.MOD, 0)]) + + # first set the values, then set GTO + await self._set_vars(var_dict) + await self._set_var(self.GTO, 1) + + async def advanced_grip(self, min_pressure, max_pressure, timeout) -> bool: + """ Sends commands to grip in advanced mode. + min pressure is [0, 99] + max pressure is [10, 78] + timeout is in ms [0, 255] + """ + + # activate sets GTO to 0 and makes sure that the gripper is activated + await self.activate() + + def clip_val(min_val, val, max_val): + return max(min_val, min(val, max_val)) + + clip_min_pressure = 100 - clip_val(0, min_pressure, 99) + clip_max_pressure = 100 - clip_val(10, max_pressure, 78) + clip_timeout = clip_val(0, timeout, 255) + + #val = await self.get_fault_status() + #print(val) + + # moves to the given position with the given speed and force + var_dict = OrderedDict([ + (self.MOD, 1), + (self.POS, clip_max_pressure), + (self.FOR, clip_min_pressure), + (self.SPE, clip_timeout)]) + + await self._set_vars(var_dict) + await self._set_var(self.GTO, 1) + + async def continuous_grip(self, timeout) -> bool: + """ Sends commands to grip in advanced mode. + min pressure is [0, 99] + max pressure is [10, 78] + timeout is in ms [0, 255] + """ + + def clip_val(min_val, val, max_val): + return max(min_val, min(val, max_val)) + + clip_timeout = clip_val(0, timeout, 255) + + # moves to the given position with the given speed and force + var_dict = OrderedDict([ + (self.MOD, 1), + (self.POS, 0), + (self.SPE, clip_timeout), + (self.GTO, 1)]) + + return await self._set_vars(var_dict) + + async def advanced_release(self, min_pressure, max_pressure, timeout) -> bool: + """ Sends commands to do advanced release. This allows to do a more controlled release than the automatic one. + """ + var_dict = OrderedDict([ + (self.POS, 255), + (self.GTO, 1)]) + + return await self._set_vars(var_dict) + + async def automatic_release(self) -> bool: + """ Sends commands to do automatic release. + """ + var_dict = OrderedDict([(self.ACT, 1), (self.ATR, 1)]) + return await self._set_vars(var_dict) From a64c4cb772e198c5d1926dffb852a30b086f512d Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 8 Mar 2024 17:10:50 +0100 Subject: [PATCH 006/338] new robotiq controller that uses ForceMode --- .../robot_controllers/__init__.py | 0 .../robot_controllers/robotiq_controller.py | 216 ++++++++++++++++++ 2 files changed, 216 insertions(+) create mode 100644 serl_robot_infra/robot_controllers/__init__.py create mode 100644 serl_robot_infra/robot_controllers/robotiq_controller.py diff --git a/serl_robot_infra/robot_controllers/__init__.py b/serl_robot_infra/robot_controllers/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py new file mode 100644 index 00000000..5af065e8 --- /dev/null +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -0,0 +1,216 @@ +import time +import threading +import asyncio +import numpy as np +from rtde_control import RTDEControlInterface +from rtde_receive import RTDEReceiveInterface +from robotiq_env.utils.vacuum_gripper import VacuumGripper +from robotiq_env.utils.rotations import rotvec_diff, rotvec_2_quat, quat_2_rotvec +from scipy.spatial.transform import Rotation as R + +np.set_printoptions(precision=4, suppress=True) + + +def pose2quat(rotvec_pose) -> np.ndarray: + return np.concatenate((rotvec_pose[:3], rotvec_2_quat(rotvec_pose[3:]))) + + +def pose2rotvec(quat_pose) -> np.ndarray: + return np.concatenate((quat_pose[:3], quat_2_rotvec(quat_pose[3:]))) + + +class RobotiqImpedanceController(threading.Thread): + def __init__( + self, + robot_ip, + frequency=500, + lookahead_time=0.1, + max_pos_speed=0.25, # 5% of max speed TODO not needed for now + max_rot_speed=0.16, # 5% of max speed + kp=5e4, + kd=1000, + verbose=True, + *args, + **kwargs + ): + super(RobotiqImpedanceController, self).__init__(*args, **kwargs) + self._stop = threading.Event() + """ + frequency: CB2=125, UR3e=500 + max_pos_speed: m/s + max_rot_speed: rad/s + """ + + self.robot_ip = robot_ip + self.frequency = frequency + self.lookahead_time = lookahead_time + self.max_pos_speed = max_pos_speed + self.max_rot_speed = max_rot_speed + self.kp = kp + self.kd = kd + self.lock = threading.Lock() + self.verbose = verbose + + self.target_pos = np.zeros((7,)) # new as quat to avoid +- problems with axis angle repr. + self.target_grip = np.zeros((1,)) + self.curr_pos = np.zeros((7,)) + self.curr_vel = np.zeros((7,)) + self.curr_gripper_state = np.zeros((1,)) # TODO gripper state (sucking or not) + self.curr_Q = np.zeros((6,)) + self.curr_Qd = np.zeros((6,)) + self.curr_force = np.zeros((6,)) # force of tool tip + + self.fm_damping = 0.1 # TODO make customizable + self.fm_task_frame = np.zeros((6,), dtype=np.float32) + self.fm_selection_vector = np.ones((6,), dtype=np.int8) + self.fm_force_type = 2 + self.fm_limits = np.array([2, 2, 2, 1, 1, 1], dtype=np.float32) + + self.robotiq_control: RTDEControlInterface = None + self.robotiq_receive: RTDEReceiveInterface = None + self.robotiq_gripper: VacuumGripper = None + + self._is_ready = False + + def start(self): + super().start() + if self.verbose: + print(f"[RTDEPositionalController] Controller process spawned at {self.native_id}") + + async def start_robotiq_interfaces(self, gripper=True): + self.robotiq_control = RTDEControlInterface(self.robot_ip) + self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) + if gripper: + self.robotiq_gripper = VacuumGripper(self.robot_ip) + await self.robotiq_gripper.connect() + await self.robotiq_gripper.activate() + if self.verbose: + gr_string = "(with gripper) " if gripper else "" + print(f"[RTDEPositionalController] Controller connected to robot {gr_string}at: {self.robot_ip}") + + def init_pose(self): + target_pose = [-0.25, -0.7, 0.25, 0., np.pi, 0.] + self.robotiq_control.moveL(target_pose, speed=0.3, acceleration=0.3) + + def stop(self): + self._stop.set() + + def stopped(self): + return self._stop.is_set() + + def set_target_pos(self, action, gripper_action): # TODO make action scale + action = np.array(action[:6]) * np.array([1.5, 1.5, 1.5, 3, 3, 3]) * 0.01 + with self.lock: + self.target_pos[:3] += action[:3] + self.target_pos[3:] = (R.from_quat(self.target_pos[3:]) * R.from_rotvec(action[3:])).as_quat() + # print("new orientation: ", self.target_pos[3:], "curr: ", self.curr_pos[3:]) + self.target_grip = gripper_action + + def _get_target_pos(self): + with self.lock: + return self.target_pos + + async def _update_robot_state(self): + with self.lock: + self.curr_pos = pose2quat(self.robotiq_receive.getActualTCPPose()) + self.curr_vel = pose2quat(self.robotiq_receive.getActualTCPSpeed()) + self.curr_Q = np.array(self.robotiq_receive.getActualQ()) + self.curr_Qd = np.array(self.robotiq_receive.getActualQd()) + self.curr_force = np.array(self.robotiq_receive.getActualTCPForce()) + self.curr_gripper_state = np.array(await self.robotiq_gripper.get_current_pressure()) + + def get_state(self): + with self.lock: + state = { + "pos": self.curr_pos, + "vel": self.curr_vel, + "Q": self.curr_Q, + "Qd": self.curr_Qd, + "force": self.curr_force[:3], + "torque": self.curr_force[3:], + "pressure": self.curr_gripper_state + } + return state + + def is_ready(self): + with self.lock: + return self._is_ready + + def _calculate_force(self): + target_pos = self._get_target_pos() + + # calc position force + kp, kd = self.kp, self.kd + diff_p = target_pos[:3] - self.curr_pos[:3] + diff_d = - self.curr_vel[:3] + force_pos = kp * diff_p + kd * diff_d + + # calc torque + # rot_diff = rotvec_diff(self.curr_pos[3:], target_pos[3:]) + # rot_diff_vel = rotvec_diff(self.curr_vel[3:], [0, 0, 0]) + # torque = 500 * rot_diff + + # calc torque new + rot_diff = R.from_quat(self.target_pos[3:]) * R.from_quat(self.curr_pos[3:]).inv() + torque = 200 * rot_diff.as_rotvec() + + return np.concatenate((force_pos, torque)) + + def run(self): + asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + + async def run_async(self): + await self.start_robotiq_interfaces(gripper=True) + self.init_pose() + + try: + dt = 1. / self.frequency + await self._update_robot_state() + self.robotiq_control.zeroFtSensor() + self.target_pos = self.curr_pos.copy() + + with self.lock: + self._is_ready = True + + while not self.stopped(): + t_now = time.monotonic() + + # update robot state + last_p = self.curr_pos + await self._update_robot_state() + + t_start = self.robotiq_control.initPeriod() + + # send command to robot + # proportional to pos diff for now (test) + force = self._calculate_force() + # print(force) + # force[3:] = np.clip(force[3:], -3, 3) + + self.robotiq_control.forceModeSetDamping(self.fm_damping) + self.robotiq_control.forceMode( + list(self.fm_task_frame), + list(self.fm_selection_vector), + list(force), + self.fm_force_type, + list(self.fm_limits) + ) + if self.robotiq_gripper: + if self.target_grip > 0.9: + await self.robotiq_gripper.automatic_grip() + elif self.target_grip < -0.9: + await self.robotiq_gripper.automatic_release() + + self.robotiq_control.waitPeriod(t_start) + time.sleep(max(0, (1.0 / self.frequency) - (time.monotonic() - t_now))) + + finally: + # mandatory cleanup + self.robotiq_control.forceModeStop() + + # terminate + self.robotiq_control.disconnect() + self.robotiq_receive.disconnect() + + if self.verbose: + print(f"[RTDEPositionalController] Disconnected from robot: {self.robot_ip}") From 09557332b7d52bef871b5a1406c35648e66aff93 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 12 Mar 2024 15:19:58 +0100 Subject: [PATCH 007/338] Controller Implementation --- .../robot_controllers/robotiq_controller.py | 109 +++++++++++++----- .../robotiq_env/envs/robotiq_env.py | 18 +-- .../robotiq_env/envs/test_env/config.py | 10 +- 3 files changed, 88 insertions(+), 49 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 5af065e8..e1490164 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -2,11 +2,14 @@ import threading import asyncio import numpy as np +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R from rtde_control import RTDEControlInterface from rtde_receive import RTDEReceiveInterface + +from robotiq_env.envs.robotiq_env import DefaultEnvConfig from robotiq_env.utils.vacuum_gripper import VacuumGripper -from robotiq_env.utils.rotations import rotvec_diff, rotvec_2_quat, quat_2_rotvec -from scipy.spatial.transform import Rotation as R +from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec np.set_printoptions(precision=4, suppress=True) @@ -23,12 +26,10 @@ class RobotiqImpedanceController(threading.Thread): def __init__( self, robot_ip, - frequency=500, - lookahead_time=0.1, - max_pos_speed=0.25, # 5% of max speed TODO not needed for now - max_rot_speed=0.16, # 5% of max speed - kp=5e4, - kd=1000, + frequency=100, + kp=4e4, + kd=8e3, + config: DefaultEnvConfig=None, verbose=True, *args, **kwargs @@ -43,9 +44,6 @@ def __init__( self.robot_ip = robot_ip self.frequency = frequency - self.lookahead_time = lookahead_time - self.max_pos_speed = max_pos_speed - self.max_rot_speed = max_rot_speed self.kp = kp self.kd = kd self.lock = threading.Lock() @@ -60,11 +58,12 @@ def __init__( self.curr_Qd = np.zeros((6,)) self.curr_force = np.zeros((6,)) # force of tool tip - self.fm_damping = 0.1 # TODO make customizable - self.fm_task_frame = np.zeros((6,), dtype=np.float32) - self.fm_selection_vector = np.ones((6,), dtype=np.int8) - self.fm_force_type = 2 - self.fm_limits = np.array([2, 2, 2, 1, 1, 1], dtype=np.float32) + self.fm_damping = config.FORCEMODE_DAMPING + self.fm_task_frame = config.FORCEMODE_TASK_FRAME + self.fm_selection_vector = config.FORCEMODE_SELECTION_VECTOR + self.fm_limits = config.FORCEMODE_LIMITS + + self.action_scale = config.ACTION_SCALE self.robotiq_control: RTDEControlInterface = None self.robotiq_receive: RTDEReceiveInterface = None @@ -72,6 +71,12 @@ def __init__( self._is_ready = False + # only temporary to test + self.hist_data = [[], []] + self.horizon = [0, 500] + self.err = 0 + self.noerr = 0 + def start(self): super().start() if self.verbose: @@ -98,8 +103,11 @@ def stop(self): def stopped(self): return self._stop.is_set() - def set_target_pos(self, action, gripper_action): # TODO make action scale - action = np.array(action[:6]) * np.array([1.5, 1.5, 1.5, 3, 3, 3]) * 0.01 + def set_target_pos(self, action, gripper_action): # TODO make action scale + # action = np.array(action[:6]) * np.array([1.5, 1.5, 1.5, 3, 3, 3]) * 0.01 + action = np.array(action[:6], dtype=np.float32) + action[:3] *= self.action_scale[0] + action[3:] *= self.action_scale[1] with self.lock: self.target_pos[:3] += action[:3] self.target_pos[3:] = (R.from_quat(self.target_pos[3:]) * R.from_rotvec(action[3:])).as_quat() @@ -154,15 +162,46 @@ def _calculate_force(self): rot_diff = R.from_quat(self.target_pos[3:]) * R.from_quat(self.curr_pos[3:]).inv() torque = 200 * rot_diff.as_rotvec() + # np.clip(force_pos, a_min=-124., a_max=124.) + # np.clip(torque, a_min=-50., a_max=50.) return np.concatenate((force_pos, torque)) def run(self): asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + def plot(self): + if self.horizon[0] == 0: + self.start_t = time.monotonic() + if self.horizon[0] < self.horizon[1]: + self.horizon[0] += 1 + # print(self.horizon[0], self.horizon[1], end=" ") + return + + print(time.monotonic() - self.start_t) + self.robotiq_control.forceModeStop() + + self.horizon[0] = -1e5 + print("plotting") + real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) + target_pos = np.array([pose2rotvec(q) for q in self.hist_data[1]]) + + plt.figure() + fig, axes = plt.subplots(nrows=3, ncols=2, figsize=(12, 8), dpi=300) + for i in range(6): + ax = axes[i % 3, i // 3] + ax.plot(real_pos[:, i], 'b') + ax.plot(target_pos[:, i], 'g') + + fig.suptitle(f"params_ kp:{self.kp} kd:{self.kd}") + plt.show(block=True) + self.stop() + async def run_async(self): await self.start_robotiq_interfaces(gripper=True) self.init_pose() + self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + try: dt = 1. / self.frequency await self._update_robot_state() @@ -176,25 +215,27 @@ async def run_async(self): t_now = time.monotonic() # update robot state - last_p = self.curr_pos await self._update_robot_state() + # log data + # self.hist_data[0].append(self.curr_pos.copy()) + # self.hist_data[1].append(self.target_pos.copy()) + + # self.plot() + t_start = self.robotiq_control.initPeriod() # send command to robot - # proportional to pos diff for now (test) force = self._calculate_force() - # print(force) - # force[3:] = np.clip(force[3:], -3, 3) - - self.robotiq_control.forceModeSetDamping(self.fm_damping) - self.robotiq_control.forceMode( - list(self.fm_task_frame), - list(self.fm_selection_vector), - list(force), - self.fm_force_type, - list(self.fm_limits) + + assert self.robotiq_control.forceMode( + self.fm_task_frame, + self.fm_selection_vector, + force, + 2, + self.fm_limits ) + if self.robotiq_gripper: if self.target_grip > 0.9: await self.robotiq_gripper.automatic_grip() @@ -202,9 +243,15 @@ async def run_async(self): await self.robotiq_gripper.automatic_release() self.robotiq_control.waitPeriod(t_start) - time.sleep(max(0, (1.0 / self.frequency) - (time.monotonic() - t_now))) + a = (1.0 / self.frequency) - (time.monotonic() - t_now) + time.sleep(max(0., a)) + if a < 0: + self.err += 1 + else: + self.noerr += 1 finally: + print(f"num errs: {self.err} no_err: {self.noerr}") # mandatory cleanup self.robotiq_control.forceModeStop() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index b5b00ea5..5002d502 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -24,14 +24,14 @@ class DefaultEnvConfig: RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.zeros((6,)) ABS_POSE_LIMIT_LOW = np.zeros((6,)) + ACTION_SCALE = np.zeros((3, ), dtype=np.float32) ROBOT_IP: str = "localhost" + ERROR_DELTA: float = 0. FORCEMODE_DAMPING: float = 0.1 FORCEMODE_TASK_FRAME = np.zeros(6, ) FORCEMODE_SELECTION_VECTOR = np.ones(6, ) - FORCEMODE_FORCE_TYPE: int = 2 FORCEMODE_LIMITS = np.zeros(6, ) - FORCEMODE_SCALING = np.ones(6, ) # not used for now REALSENSE_CAMERAS: Dict = { @@ -54,14 +54,13 @@ def __init__( self._TARGET_POSE = config.TARGET_POSE self._REWARD_THRESHOLD = config.REWARD_THRESHOLD self.max_episode_length = max_episode_length + self.action_scale = config.ACTION_SCALE self.robot_ip = config.ROBOT_IP self.FM_DAMPING = config.FORCEMODE_DAMPING self.FM_TASK_FRAME = config.FORCEMODE_TASK_FRAME self.FM_SELECTION_VECTOR = config.FORCEMODE_SELECTION_VECTOR - self.FM_FORCE_TYPE = config.FORCEMODE_FORCE_TYPE self.FM_LIMITS = config.FORCEMODE_LIMITS - self.FM_SCALING = config.FORCEMODE_SCALING self.robotiq_control = None self.robotiq_receive = None @@ -265,15 +264,8 @@ def _recover(self): def _send_force_command(self, action: np.ndarray): """Internal function to send force command to the robot.""" - force = action * self.FM_SCALING - self.robotiq_control.forceModeSetDamping(self.FM_DAMPING) - self.robotiq_control.forceMode( - self.FM_TASK_FRAME, - self.FM_SELECTION_VECTOR, - force, - self.FM_FORCE_TYPE, - self.FM_LIMITS - ) + + # TODO send to controller def _send_gripper_command(self, pos: float): """Internal function to send gripper command to the robot.""" diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/test_env/config.py index fa700c4c..f68fad10 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/test_env/config.py @@ -5,17 +5,17 @@ class TestConfig(DefaultEnvConfig): TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) - RESET_POSE = np.array([-0.2, -0.7, 0.133, 2.58, -1.63, -0.03]) + RESET_POSE = np.array([-0.2, -0.7, 0.25, 0.0, -3.1415, 0.0]) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., 3., 1., 1.]) ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -3., -1., -1.]) + ACTION_SCALE = np.array([0.02, 0.1, 1], dtype=np.float32) ROBOT_IP: str = "172.22.22.3" - FORCEMODE_DAMPING: float = 0.1 + ERROR_DELTA: float = 0.05 # TODO test + FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_FORCE_TYPE: int = 2 - FORCEMODE_LIMITS = np.array([8., 8., 8., 4., 4., 4.]) - FORCEMODE_SCALING = np.array([1e3, 1e3, 1e3, 5, 5, 5]) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) From db67fa9c49f7adcdecec234e7bdb5d93593598e7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:52:36 +0100 Subject: [PATCH 008/338] new config, also reset is now in Q --- serl_robot_infra/robotiq_env/envs/test_env/config.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/test_env/config.py index f68fad10..aee2ae42 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/test_env/config.py @@ -5,16 +5,17 @@ class TestConfig(DefaultEnvConfig): TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) - RESET_POSE = np.array([-0.2, -0.7, 0.25, 0.0, -3.1415, 0.0]) + RESET_Q = np.array([1.0464833974838257, -0.9013996881297608, 1.3149092833148401, -1.9843775234618128, -1.566035572682516, -0.5265157858477991]) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., 3., 1., 1.]) - ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -3., -1., -1.]) - ACTION_SCALE = np.array([0.02, 0.1, 1], dtype=np.float32) + ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., np.inf, np.inf, np.inf]) + ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -np.inf, -np.inf, -np.inf]) + ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.3" - ERROR_DELTA: float = 0.05 # TODO test + CONTROLLER_HZ = 100 + ERROR_DELTA: float = 0.05 FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) From f95a79e88a3691f0a2d9aebc9dbb401665deaeec Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:56:14 +0100 Subject: [PATCH 009/338] fixed the controller --- .../robot_controllers/robotiq_controller.py | 187 +++++++++++------- 1 file changed, 114 insertions(+), 73 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index e1490164..d3cf8aea 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -7,7 +7,6 @@ from rtde_control import RTDEControlInterface from rtde_receive import RTDEReceiveInterface -from robotiq_env.envs.robotiq_env import DefaultEnvConfig from robotiq_env.utils.vacuum_gripper import VacuumGripper from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec @@ -22,6 +21,15 @@ def pose2rotvec(quat_pose) -> np.ndarray: return np.concatenate((quat_pose[:3], quat_2_rotvec(quat_pose[3:]))) +def pos_difference(quat_pose_1: np.ndarray, quat_pose_2: np.ndarray): + assert quat_pose_1.shape == (7,) + assert quat_pose_2.shape == (7,) + p_diff = np.sum(np.abs(quat_pose_1[:3] - quat_pose_2[:3])) + + r_diff = (R.from_quat(quat_pose_1[3:]) * R.from_quat(quat_pose_2[3:]).inv()).magnitude() + return p_diff + r_diff + + class RobotiqImpedanceController(threading.Thread): def __init__( self, @@ -29,13 +37,16 @@ def __init__( frequency=100, kp=4e4, kd=8e3, - config: DefaultEnvConfig=None, + config=None, verbose=True, + plot=False, *args, **kwargs ): super(RobotiqImpedanceController, self).__init__(*args, **kwargs) self._stop = threading.Event() + self._reset = threading.Event() + self._is_ready = threading.Event() """ frequency: CB2=125, UR3e=500 max_pos_speed: m/s @@ -48,29 +59,29 @@ def __init__( self.kd = kd self.lock = threading.Lock() self.verbose = verbose + self.do_plot = plot self.target_pos = np.zeros((7,)) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,)) self.curr_pos = np.zeros((7,)) self.curr_vel = np.zeros((7,)) - self.curr_gripper_state = np.zeros((1,)) # TODO gripper state (sucking or not) + self.curr_pressure = np.zeros((1,)) # TODO gripper state (sucking or not) self.curr_Q = np.zeros((6,)) self.curr_Qd = np.zeros((6,)) self.curr_force = np.zeros((6,)) # force of tool tip + self.reset_Q = np.zeros((6,)) + + self.delta = config.ERROR_DELTA self.fm_damping = config.FORCEMODE_DAMPING self.fm_task_frame = config.FORCEMODE_TASK_FRAME self.fm_selection_vector = config.FORCEMODE_SELECTION_VECTOR self.fm_limits = config.FORCEMODE_LIMITS - self.action_scale = config.ACTION_SCALE - self.robotiq_control: RTDEControlInterface = None self.robotiq_receive: RTDEReceiveInterface = None self.robotiq_gripper: VacuumGripper = None - self._is_ready = False - # only temporary to test self.hist_data = [[], []] self.horizon = [0, 500] @@ -83,19 +94,20 @@ def start(self): print(f"[RTDEPositionalController] Controller process spawned at {self.native_id}") async def start_robotiq_interfaces(self, gripper=True): - self.robotiq_control = RTDEControlInterface(self.robot_ip) - self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) - if gripper: - self.robotiq_gripper = VacuumGripper(self.robot_ip) - await self.robotiq_gripper.connect() - await self.robotiq_gripper.activate() - if self.verbose: - gr_string = "(with gripper) " if gripper else "" - print(f"[RTDEPositionalController] Controller connected to robot {gr_string}at: {self.robot_ip}") - - def init_pose(self): - target_pose = [-0.25, -0.7, 0.25, 0., np.pi, 0.] - self.robotiq_control.moveL(target_pose, speed=0.3, acceleration=0.3) + try: + self.robotiq_control = RTDEControlInterface(self.robot_ip) + self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) + if gripper: + self.robotiq_gripper = VacuumGripper(self.robot_ip) + await self.robotiq_gripper.connect() + await self.robotiq_gripper.activate() + if self.verbose: + gr_string = "(with gripper) " if gripper else "" + print(f"[RTDEPositionalController] Controller connected to robot {gr_string}at: {self.robot_ip}") + except RuntimeError: + print("Failed to start control script, before timeout of 5 seconds, trying again...") + time.sleep(1) + return await self.start_robotiq_interfaces(gripper=gripper) def stop(self): self._stop.set() @@ -103,29 +115,48 @@ def stop(self): def stopped(self): return self._stop.is_set() - def set_target_pos(self, action, gripper_action): # TODO make action scale - # action = np.array(action[:6]) * np.array([1.5, 1.5, 1.5, 3, 3, 3]) * 0.01 - action = np.array(action[:6], dtype=np.float32) - action[:3] *= self.action_scale[0] - action[3:] *= self.action_scale[1] + def set_target_pos(self, target_pos: np.ndarray): + if target_pos.shape == (7,): + target_orientation = target_pos[3:] + elif target_pos.shape == (6,): + target_orientation = R.from_rotvec(target_pos[3:]).as_quat() + else: + raise ValueError(f"target pos has shape {target_pos.shape}") + + with self.lock: + self.target_pos[:3] = target_pos[:3] + self.target_pos[3:] = target_orientation + + # print("target: ", self.target_pos) + + def move_to_reset_Q(self, reset_Q: np.ndarray): + self._reset.set() + with self.lock: + self.reset_Q = reset_Q + + def set_gripper_pos(self, target_grip: np.ndarray): with self.lock: - self.target_pos[:3] += action[:3] - self.target_pos[3:] = (R.from_quat(self.target_pos[3:]) * R.from_rotvec(action[3:])).as_quat() - # print("new orientation: ", self.target_pos[3:], "curr: ", self.curr_pos[3:]) - self.target_grip = gripper_action + self.target_grip = target_grip - def _get_target_pos(self): + def get_target_pos(self): with self.lock: return self.target_pos async def _update_robot_state(self): + pos = self.robotiq_receive.getActualTCPPose() + vel = self.robotiq_receive.getActualTCPSpeed() + Q = self.robotiq_receive.getActualQ() + Qd = self.robotiq_receive.getActualQd() + force = self.robotiq_receive.getActualTCPForce() + pressure = await self.robotiq_gripper.get_current_pressure() + a = self.robotiq_gripper.get_object_status() with self.lock: - self.curr_pos = pose2quat(self.robotiq_receive.getActualTCPPose()) - self.curr_vel = pose2quat(self.robotiq_receive.getActualTCPSpeed()) - self.curr_Q = np.array(self.robotiq_receive.getActualQ()) - self.curr_Qd = np.array(self.robotiq_receive.getActualQd()) - self.curr_force = np.array(self.robotiq_receive.getActualTCPForce()) - self.curr_gripper_state = np.array(await self.robotiq_gripper.get_current_pressure()) + self.curr_pos = pose2quat(pos) + self.curr_vel = pose2quat(vel) + self.curr_Q = np.array(Q) + self.curr_Qd = np.array(Qd) + self.curr_force = np.array(force) + self.curr_pressure = np.array(pressure) def get_state(self): with self.lock: @@ -136,98 +167,107 @@ def get_state(self): "Qd": self.curr_Qd, "force": self.curr_force[:3], "torque": self.curr_force[3:], - "pressure": self.curr_gripper_state + "pressure": self.curr_pressure } return state def is_ready(self): - with self.lock: - return self._is_ready + return self._is_ready.is_set() def _calculate_force(self): - target_pos = self._get_target_pos() + target_pos = self.get_target_pos() + with self.lock: + curr_pos = self.curr_pos + curr_vel = self.curr_vel # calc position force kp, kd = self.kp, self.kd - diff_p = target_pos[:3] - self.curr_pos[:3] - diff_d = - self.curr_vel[:3] + diff_p = np.clip(target_pos[:3] - curr_pos[:3], a_min=-self.delta, a_max=self.delta) + vel_delta = 2 * self.delta * self.frequency + diff_d = np.clip(- curr_vel[:3], a_min=-vel_delta, a_max=vel_delta) force_pos = kp * diff_p + kd * diff_d # calc torque - # rot_diff = rotvec_diff(self.curr_pos[3:], target_pos[3:]) - # rot_diff_vel = rotvec_diff(self.curr_vel[3:], [0, 0, 0]) - # torque = 500 * rot_diff + rot_diff = R.from_quat(target_pos[3:]) * R.from_quat(curr_pos[3:]).inv() + vel_rot_diff = R.from_quat(curr_vel[3:]).inv() + torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable - # calc torque new - rot_diff = R.from_quat(self.target_pos[3:]) * R.from_quat(self.curr_pos[3:]).inv() - torque = 200 * rot_diff.as_rotvec() - - # np.clip(force_pos, a_min=-124., a_max=124.) - # np.clip(torque, a_min=-50., a_max=50.) return np.concatenate((force_pos, torque)) def run(self): asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands def plot(self): - if self.horizon[0] == 0: - self.start_t = time.monotonic() if self.horizon[0] < self.horizon[1]: self.horizon[0] += 1 - # print(self.horizon[0], self.horizon[1], end=" ") + self.hist_data[0].append(self.curr_pos.copy()) + self.hist_data[1].append(self.target_pos.copy()) return print(time.monotonic() - self.start_t) self.robotiq_control.forceModeStop() - self.horizon[0] = -1e5 print("plotting") real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) target_pos = np.array([pose2rotvec(q) for q in self.hist_data[1]]) plt.figure() - fig, axes = plt.subplots(nrows=3, ncols=2, figsize=(12, 8), dpi=300) + fig, axes = plt.subplots(nrows=3, ncols=2, figsize=(12, 8), dpi=200) for i in range(6): ax = axes[i % 3, i // 3] ax.plot(real_pos[:, i], 'b') ax.plot(target_pos[:, i], 'g') - fig.suptitle(f"params_ kp:{self.kp} kd:{self.kd}") + fig.suptitle(f"params--> kp:{self.kp} kd:{self.kd}") plt.show(block=True) self.stop() async def run_async(self): await self.start_robotiq_interfaces(gripper=True) - self.init_pose() - self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.start_t = time.monotonic() try: dt = 1. / self.frequency - await self._update_robot_state() self.robotiq_control.zeroFtSensor() + await self._update_robot_state() self.target_pos = self.curr_pos.copy() - with self.lock: - self._is_ready = True + self._is_ready.set() while not self.stopped(): + if self._reset.is_set(): # move to reset pose with moveL + self._is_ready.clear() + print(f"moving to {self.reset_Q} with moveJ (joint space)") + self.robotiq_control.forceModeStop() + self.robotiq_control.moveJ(self.reset_Q, speed=1.05, acceleration=1.4) + + await self._update_robot_state() + with self.lock: + self.target_pos = self.curr_pos + + self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.robotiq_control.zeroFtSensor() + + self._reset.clear() + self._is_ready.set() # moving complete + t_now = time.monotonic() # update robot state await self._update_robot_state() - # log data - # self.hist_data[0].append(self.curr_pos.copy()) - # self.hist_data[1].append(self.target_pos.copy()) - - # self.plot() - - t_start = self.robotiq_control.initPeriod() + # only used for plotting + if self.do_plot: + self.plot() - # send command to robot + # calculate force force = self._calculate_force() + # print(self.target_pos, self.curr_pos, force) + # send command to robot + t_start = self.robotiq_control.initPeriod() assert self.robotiq_control.forceMode( self.fm_task_frame, self.fm_selection_vector, @@ -243,15 +283,16 @@ async def run_async(self): await self.robotiq_gripper.automatic_release() self.robotiq_control.waitPeriod(t_start) - a = (1.0 / self.frequency) - (time.monotonic() - t_now) + + a = dt - (time.monotonic() - t_now) time.sleep(max(0., a)) - if a < 0: + if a < 0: # log how slow the loop runs self.err += 1 else: self.noerr += 1 finally: - print(f"num errs: {self.err} no_err: {self.noerr}") + print(f"time errs: {self.err} no_err: {self.noerr}") # mandatory cleanup self.robotiq_control.forceModeStop() From 694dfaba2422846496207c870d11c969382e51f1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:58:10 +0100 Subject: [PATCH 010/338] controller usage & reset in J-space --- .../robotiq_env/envs/robotiq_env.py | 184 +++++++++--------- 1 file changed, 89 insertions(+), 95 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 5002d502..fc6551d9 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -5,10 +5,12 @@ import copy import time from typing import Dict -from rtde_control import RTDEControlInterface as RTDEControl -from rtde_receive import RTDEReceiveInterface as RTDEReceive +from scipy.spatial.transform import Rotation as R + from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec +from robot_controllers.robotiq_controller import RobotiqImpedanceController + ############################################################################## @@ -16,17 +18,18 @@ class DefaultEnvConfig: """Default configuration for RobotiqEnv. Fill in the values below.""" - TARGET_POSE: np.ndarray = np.zeros((6,)) # might change as well + TARGET_POSE: np.ndarray = np.zeros((6,)) # might change as well REWARD_THRESHOLD: np.ndarray = np.zeros((6,)) - RESET_POSE = np.zeros((6,)) + RESET_Q = np.zeros((6,)) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.zeros((6,)) ABS_POSE_LIMIT_LOW = np.zeros((6,)) - ACTION_SCALE = np.zeros((3, ), dtype=np.float32) + ACTION_SCALE = np.zeros((3,), dtype=np.float32) ROBOT_IP: str = "localhost" + CONTROLLER_HZ: int = 0 ERROR_DELTA: float = 0. FORCEMODE_DAMPING: float = 0.1 FORCEMODE_TASK_FRAME = np.zeros(6, ) @@ -56,36 +59,24 @@ def __init__( self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE - self.robot_ip = config.ROBOT_IP - self.FM_DAMPING = config.FORCEMODE_DAMPING - self.FM_TASK_FRAME = config.FORCEMODE_TASK_FRAME - self.FM_SELECTION_VECTOR = config.FORCEMODE_SELECTION_VECTOR - self.FM_LIMITS = config.FORCEMODE_LIMITS - - self.robotiq_control = None - self.robotiq_receive = None - self.robotiq_gripper = None - - # convert last 3 elements from axis angle to quat, from size (6,) to (7,) - self.resetpos = np.concatenate( - [config.RESET_POSE[:3], rotvec_2_quat(config.RESET_POSE[3:])] - ).astype(np.float32) - - self.currpos = self.resetpos.copy().astype(np.float32) - self.currvel = np.zeros((6,), dtype=np.float32) - self.q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq - self.dq = np.zeros((6,), dtype=np.float32) + self.config = config + + self.resetQ = config.RESET_Q + + self.currpos = np.zeros((7, ), dtype=np.float32) + self.currvel = np.zeros((7,), dtype=np.float32) + self.Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq + self.Qd = np.zeros((6,), dtype=np.float32) self.currforce = np.zeros((3,), dtype=np.float32) self.currtorque = np.zeros((3,), dtype=np.float32) - self.currjacobian = np.zeros((6, 7), dtype=np.float32) - self.curr_gripper_pos = 0 + self.currpressure = np.zeros((1, ), dtype=np.float32) self.lastsent = time.time() self.randomreset = config.RANDOM_RESET self.random_xy_range = config.RANDOM_XY_RANGE self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz - self.joint_reset_cycle = 200 # reset the robot joint every 200 cycles + self.joint_reset_cycle = 200 # reset the robot joint every 200 cycles # TODO needed? if save_video: print("Saving videos!") @@ -135,15 +126,20 @@ def __init__( ) self.cycle_count = 0 - self.start_robotiq_interfaces() + self.controller = RobotiqImpedanceController( + robot_ip=config.ROBOT_IP, + frequency=config.CONTROLLER_HZ, + kp=10000, + kd=2200, + config=config, + verbose=True, + plot=False + ) - def start_robotiq_interfaces(self): - self.robotiq_control = RTDEControl(self.robot_ip) - self.robotiq_receive = RTDEReceive(self.robot_ip) - # self.robotiq_gripper = VacuumGripper(self.robot_ip) - # TODO gripper - print("UR-RTDE interfaces ready") + self.controller.start() # start Thread + while not self.controller.is_ready(): # wait for contoller + time.sleep(0.1) def pose_r2q(self, pose: np.ndarray) -> np.ndarray: return np.concatenate([pose[:3], rotvec_2_quat(pose[3:])]) @@ -151,35 +147,52 @@ def pose_r2q(self, pose: np.ndarray) -> np.ndarray: def pose_q2r(self, pose: np.ndarray) -> np.ndarray: return np.concatenate([pose[:3], quat_2_rotvec(pose[3:])]) - def clip_safety_box(self, action: np.ndarray) -> np.ndarray: - """Clip the action to not move outside the safety box.""" + def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: + """Clip the pose to be within the safety box.""" + next_pos[:3] = np.clip( + next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high + ) + euler = R.from_quat(next_pos[3:]).as_euler("xyz") + + # Clip first euler angle separately due to discontinuity from pi to -pi + sign = np.sign(euler[0]) + euler[0] = sign * ( + np.clip( + np.abs(euler[0]), + self.rpy_bounding_box.low[0], + self.rpy_bounding_box.high[0], + ) + ) - # check for position limits (prevent, but do not stop) - adverse_move = 0.1 - for i, (low, high) in enumerate(zip(self.xyz_bounding_box.low, self.xyz_bounding_box.high)): - if low and self.currpos[i] < low and action[i] < adverse_move: - action[i] = adverse_move - print(f"lower {i} set new") - elif high and self.currpos[i] > high and action[i] > -adverse_move: - action[i] = -adverse_move - print("upper set new") + euler[1:] = np.clip( + euler[1:], self.rpy_bounding_box.low[1:], self.rpy_bounding_box.high[1:] + ) + next_pos[3:] = R.from_euler("xyz", euler).as_quat() - # TODO apply quaternion limits - # TODO test - return action + return next_pos def step(self, action: np.ndarray) -> tuple: """standard gym step function.""" - t_start_robotiq = self.robotiq_control.initPeriod() start_time = time.time() action = np.clip(action, self.action_space.low, self.action_space.high) - safe_action = self.clip_safety_box(action) - self._send_force_command(safe_action[:6]) - self._send_gripper_command(safe_action[6]) + # position + # next_pos = self.currpos.copy() + next_pos = self.controller.get_target_pos() + next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] + + # orientation (leave for now) + next_pos[3:] = ( + R.from_quat(next_pos[3:]) * R.from_euler("xyz", action[3:6] * self.action_scale[1]) + ).as_quat() + + gripper_action = action[6] * self.action_scale[2] + + safe_pos = self.clip_safety_box(next_pos) + self._send_pos_command(safe_pos) + self._send_gripper_command(gripper_action) self.curr_path_length += 1 - self.robotiq_control.waitPeriod(t_start_robotiq) dt = time.time() - start_time time.sleep(max(0, (1.0 / self.hz) - dt)) @@ -201,14 +214,6 @@ def compute_reward(self, obs) -> bool: # print(f'Goal not reached, the difference is {delta}, the desired threshold is {_REWARD_THRESHOLD}') return False - # TODO adapt get_im(), crop_image(), init_cameras(), close_cameras(), - - def move_to(self, goal: np.ndarray): - """Move the robot to the goal position with moveL (linear in tool-space)""" - goal_ur = self.pose_q2r(goal) - self.robotiq_control.moveL(list(goal_ur), speed=0.05, acceleration=0.3) # command will block until finished - self._update_currpos() - def go_to_rest(self, joint_reset=False): """ The concrete steps to perform reset should be @@ -235,8 +240,13 @@ def go_to_rest(self, joint_reset=False): # self.move_to(reset_pose) pass else: - reset_pose = self.resetpos.copy() - self.move_to(reset_pose) + reset_Q = self.resetQ.copy() + self._send_gripper_command(np.ones((1,))*-1) # disable vacuum gripper + self._send_reset_command(reset_Q) + time.sleep(0.1) + while not self.controller.is_ready(): + time.sleep(0.1) + self._update_currpos() def reset(self, joint_reset=False, **kwargs): if self.save_video: @@ -262,56 +272,40 @@ def _recover(self): # TODO make recover function pass - def _send_force_command(self, action: np.ndarray): + def _send_pos_command(self, target_pos: np.ndarray): """Internal function to send force command to the robot.""" + self.controller.set_target_pos(target_pos=target_pos) - # TODO send to controller + def _send_gripper_command(self, gripper_pos: np.ndarray): + self.controller.set_gripper_pos(gripper_pos) - def _send_gripper_command(self, pos: float): - """Internal function to send gripper command to the robot.""" - if (pos >= -1) and (pos <= -0.9): # close gripper - pass # TODO gripper command - elif (pos >= 0.9) and (pos <= 1): # open gripper - pass - else: # do nothing to the gripper - return + def _send_reset_command(self, reset_Q: np.ndarray): + self.controller.move_to_reset_Q(reset_Q) def _update_currpos(self): """ Internal function to get the latest state of the robot and its gripper. """ - pose = self.robotiq_receive.getActualTCPPose() - vel = self.robotiq_receive.getActualTCPSpeed() - pose_quat = self.pose_r2q(pose) - - force = self.robotiq_receive.getActualTCPForce() - q = self.robotiq_receive.getActualQ() - qd = self.robotiq_receive.getActualQd() - - self.currpos[:] = np.array(pose_quat) - self.currvel[:] = np.array(vel) - - self.currforce[:] = np.array(force[:3]) - self.currtorque[:] = np.array(force[3:]) - # self.currjacobian[:] = np.reshape(np.array(ps["jacobian"]), (6, 7)) # TODO jacobian? - - self.q[:] = np.array(q) - self.dq[:] = np.array(qd) + state = self.controller.get_state() - # TODO get gripper pos - self.curr_gripper_pos = np.zeros(1, dtype=np.float32) + self.currpos[:] = state['pos'] + self.currvel[:] = state['vel'] + self.currforce[:] = state['force'] + self.currtorque[:] = state['torque'] + self.Q[:] = state['Q'] + self.Qd[:] = state['Qd'] + self.currpressure[:] = state['pressure'] def _get_obs(self) -> dict: state_observation = { "tcp_pose": self.currpos, "tcp_vel": self.currvel, - "gripper_pose": self.curr_gripper_pos, + "gripper_pose": self.currpressure, "tcp_force": self.currforce, "tcp_torque": self.currtorque, } return copy.deepcopy(dict(state=state_observation)) def close(self): - self.robotiq_control.forceModeStop() - print("force mode stopped") + self.controller.stop() super().close() From 0f48066263966d3b43bf2eed7a97ae63ac8ce016 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:58:28 +0100 Subject: [PATCH 011/338] remove overwrite example --- serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py b/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py index d35fe58b..5e45cd81 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py +++ b/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py @@ -5,7 +5,3 @@ class RobotiqTest(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=TestConfig) - - def go_to_rest(self, joint_reset=False): - # how to overwrite without blocking the old function - super().go_to_rest(joint_reset) From 8d63a85f0351b7117c3ae1d94a850107531e956e Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:58:49 +0100 Subject: [PATCH 012/338] deadspace and z-rot-invariant implementation --- serl_robot_infra/robotiq_env/envs/wrappers.py | 43 ++++++++++--------- 1 file changed, 23 insertions(+), 20 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 1afa1551..ae4d5c07 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -9,13 +9,14 @@ class SpacemouseIntervention(gym.ActionWrapper): def __init__(self, env): super().__init__(env) - self.gripper_enabled = False + self.gripper_enabled = True self.expert = SpaceMouseExpert() self.last_intervene = 0 self.left, self.right = False, False - self.invert_axes = [1, 1, 1, 1, 1, 1] + self.invert_axes = [-1, -1, 1, 1, -1, 1] + self.deadspace = 0.15 def action(self, action: np.ndarray) -> np.ndarray: """ @@ -24,30 +25,31 @@ def action(self, action: np.ndarray) -> np.ndarray: Output: - action: spacemouse action if nonezero; else, policy action """ - expert_a, buttons = self.expert.get_action() - self.left, self.right = tuple(buttons) + expert_a = self.get_deadspace_action() if np.linalg.norm(expert_a) > 0.001: self.last_intervene = time.time() if self.gripper_enabled: - if self.left: # close gripper - gripper_action = np.random.uniform(-1, -0.9, size=(1,)) - self.last_intervene = time.time() - elif self.right: # open gripper - gripper_action = np.random.uniform(0.9, 1, size=(1,)) - self.last_intervene = time.time() - else: - gripper_action = np.zeros((1,)) + gripper_action = np.zeros((1,)) - int(self.left) + int(self.right) expert_a = np.concatenate((expert_a, gripper_action), axis=0) if time.time() - self.last_intervene < 0.5: expert_a = self.adapt_spacemouse_output(expert_a) - return np.concatenate((expert_a, np.array([0]))) # TODO add gripper + return expert_a return action - def adapt_spacemouse_output(self, expert_a: np.ndarray) -> np.ndarray: + def get_deadspace_action(self) -> np.ndarray: + expert_a, buttons = self.expert.get_action() + + expert_a = np.clip((expert_a - np.sign(expert_a) * self.deadspace) / (1.-self.deadspace), a_min=-1.0, a_max=1.) + + self.left, self.right = tuple(buttons) + + return np.array(expert_a, dtype=np.float32) + + def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: """ Input: - expert_a: spacemouse raw output @@ -55,18 +57,19 @@ def adapt_spacemouse_output(self, expert_a: np.ndarray) -> np.ndarray: - expert_a: spacemouse output adapted to force space (action) """ - position = [1.]*6 # TODO get position + position = super().get_wrapper_attr("currpos") # get position from robotiq_env z_angle = np.arctan2(position[1], position[0]) # get first joint angle z_rot = R.from_rotvec(np.array([0, 0, z_angle])) - expert_a *= self.invert_axes # if some want to be inverted - expert_a[:3] = z_rot.apply(expert_a[:3]) # z rotation invariant translation - expert_a[3:] = z_rot.apply(expert_a[3:]) # z rotation invariant rotation + action[:6] *= self.invert_axes # if some want to be inverted + action[:3] = z_rot.apply(action[:3]) # z rotation invariant translation + action[3:6] = z_rot.inv().apply(action[3:6]) # z rotation invariant rotation - return expert_a + return action - def step(self, action): + def step(self, action): # TODO change here! new_action = self.action(action) + # print(f"new action: {new_action}") obs, rew, done, truncated, info = self.env.step(new_action) info["intervene_action"] = new_action info["left"] = self.left From 99002407d9297c1d8d0dacebbba782a7dbc1bb23 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 15:59:01 +0100 Subject: [PATCH 013/338] demo recording changes, is now ready --- examples/robotiq_first_tests/record_demo.py | 72 ++++++++++++++------- 1 file changed, 50 insertions(+), 22 deletions(-) diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_first_tests/record_demo.py index 923832d7..bee30686 100644 --- a/examples/robotiq_first_tests/record_demo.py +++ b/examples/robotiq_first_tests/record_demo.py @@ -1,38 +1,66 @@ -import gymnasium as gym +import os +import datetime import numpy as np import copy - -from robotiq_env.envs.wrappers import SpacemouseIntervention +import pickle as pkl +from tqdm import tqdm +import gymnasium as gym from pprint import pprint +from robotiq_env.envs.wrappers import SpacemouseIntervention if __name__ == "__main__": env = gym.make("robotiq_test") env = SpacemouseIntervention(env) obs, _ = env.reset() + transitions = [] + success_count = 0 + success_needed = 20 + total_count = 0 + pbar = tqdm(total=success_needed) + + uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + file_name = f"robotiq_test_{success_needed}_demos_{uuid}.pkl" + file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script + file_path = os.path.join(file_dir, file_name) + + if not os.access(file_dir, os.W_OK): + raise PermissionError(f"No permission to write to {file_dir}") - while True: - next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) - actions = info["intervene_action"] - - transition = copy.deepcopy( - dict( - observations=obs, - actions=actions, - next_observations=next_obs, - rewards=rew, - masks=1.0 - done, - dones=done, + try: + while success_count < success_needed: + next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) + actions = info["intervene_action"] + + transition = copy.deepcopy( + dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=rew, + masks=1.0 - done, + dones=done, + ) ) - ) - transitions.append(transition) - pprint(transition) + transitions.append(transition) + # pprint(transition) + + obs = next_obs - obs = next_obs + if done: + success_count += rew + total_count += 1 + print( + f"{rew}\tGot {success_count} successes of {total_count} trials. {success_needed} successes needed." + ) + pbar.update(rew) + obs, _ = env.reset() - if done: - break + with open(file_path, "wb") as f: + pkl.dump(transitions, f) + print(f"saved {success_needed} demos to {file_path}") - env.close() + finally: + env.close() From 58e277248a36cec6d77588143a3025834d1819d3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 16:43:31 +0100 Subject: [PATCH 014/338] code cleanup --- .../robot_controllers/robotiq_controller.py | 77 ++++++++++--------- .../robotiq_env/envs/robotiq_env.py | 25 +++--- 2 files changed, 50 insertions(+), 52 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index d3cf8aea..72a09004 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -35,10 +35,10 @@ def __init__( self, robot_ip, frequency=100, - kp=4e4, - kd=8e3, + kp=10000, + kd=2200, config=None, - verbose=True, + verbose=False, plot=False, *args, **kwargs @@ -47,17 +47,12 @@ def __init__( self._stop = threading.Event() self._reset = threading.Event() self._is_ready = threading.Event() - """ - frequency: CB2=125, UR3e=500 - max_pos_speed: m/s - max_rot_speed: rad/s - """ + self.lock = threading.Lock() self.robot_ip = robot_ip self.frequency = frequency self.kp = kp self.kd = kd - self.lock = threading.Lock() self.verbose = verbose self.do_plot = plot @@ -70,7 +65,7 @@ def __init__( self.curr_Qd = np.zeros((6,)) self.curr_force = np.zeros((6,)) # force of tool tip - self.reset_Q = np.zeros((6,)) + self.reset_Q = np.zeros((6,)) # reset state in Joint Space self.delta = config.ERROR_DELTA self.fm_damping = config.FORCEMODE_DAMPING @@ -91,23 +86,25 @@ def __init__( def start(self): super().start() if self.verbose: - print(f"[RTDEPositionalController] Controller process spawned at {self.native_id}") + print(f"[RobotiqImpedanceController] Controller process spawned at {self.native_id}") async def start_robotiq_interfaces(self, gripper=True): - try: - self.robotiq_control = RTDEControlInterface(self.robot_ip) - self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) - if gripper: - self.robotiq_gripper = VacuumGripper(self.robot_ip) - await self.robotiq_gripper.connect() - await self.robotiq_gripper.activate() - if self.verbose: - gr_string = "(with gripper) " if gripper else "" - print(f"[RTDEPositionalController] Controller connected to robot {gr_string}at: {self.robot_ip}") - except RuntimeError: - print("Failed to start control script, before timeout of 5 seconds, trying again...") - time.sleep(1) - return await self.start_robotiq_interfaces(gripper=gripper) + for _ in range(5): # try it 5 times + try: + self.robotiq_control = RTDEControlInterface(self.robot_ip) + self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) + if gripper: + self.robotiq_gripper = VacuumGripper(self.robot_ip) + await self.robotiq_gripper.connect() + await self.robotiq_gripper.activate() + if self.verbose: + gr_string = "(with gripper) " if gripper else "" + print(f"[RobotiqImpedanceController] Controller connected to robot {gr_string}at: {self.robot_ip}") + except RuntimeError: + print( + "[RobotiqImpedanceController] Failed to start control script, before timeout of 5 seconds, trying again...") + continue + raise RuntimeError(f"[RobotiqImpedanceController] Could not connect to robot [{self.robot_ip}]") def stop(self): self._stop.set() @@ -121,7 +118,7 @@ def set_target_pos(self, target_pos: np.ndarray): elif target_pos.shape == (6,): target_orientation = R.from_rotvec(target_pos[3:]).as_quat() else: - raise ValueError(f"target pos has shape {target_pos.shape}") + raise ValueError(f"[RobotiqImpedanceController] target pos has shape {target_pos.shape}") with self.lock: self.target_pos[:3] = target_pos[:3] @@ -129,7 +126,7 @@ def set_target_pos(self, target_pos: np.ndarray): # print("target: ", self.target_pos) - def move_to_reset_Q(self, reset_Q: np.ndarray): + def set_reset_Q(self, reset_Q: np.ndarray): self._reset.set() with self.lock: self.reset_Q = reset_Q @@ -174,6 +171,9 @@ def get_state(self): def is_ready(self): return self._is_ready.is_set() + def is_reset(self): + return not self._reset.is_set() + def _calculate_force(self): target_pos = self.get_target_pos() with self.lock: @@ -190,12 +190,15 @@ def _calculate_force(self): # calc torque rot_diff = R.from_quat(target_pos[3:]) * R.from_quat(curr_pos[3:]).inv() vel_rot_diff = R.from_quat(curr_vel[3:]).inv() - torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable + torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable return np.concatenate((force_pos, torque)) def run(self): - asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + try: + asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + finally: + self.stop() def plot(self): if self.horizon[0] < self.horizon[1]: @@ -204,19 +207,23 @@ def plot(self): self.hist_data[1].append(self.target_pos.copy()) return - print(time.monotonic() - self.start_t) self.robotiq_control.forceModeStop() - print("plotting") + print("[RobotiqImpedanceController] plotting") real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) target_pos = np.array([pose2rotvec(q) for q in self.hist_data[1]]) plt.figure() fig, axes = plt.subplots(nrows=3, ncols=2, figsize=(12, 8), dpi=200) + ax_label = [{'x': f'time {self.frequency} [Hz]', 'y': ylabel} for ylabel in ["[mm]", "[rad]"]] + plot_label = "X Y Z RX RY RZ".split(' ') + for i in range(6): ax = axes[i % 3, i // 3] - ax.plot(real_pos[:, i], 'b') + ax.plot(real_pos[:, i], 'b', label=plot_label[i]) ax.plot(target_pos[:, i], 'g') + ax.set(xlabel=ax_label[i // 3]['x'], ylabel=ax_label[i // 3]['y']) + ax.legend() fig.suptitle(f"params--> kp:{self.kp} kd:{self.kd}") plt.show(block=True) @@ -237,9 +244,8 @@ async def run_async(self): self._is_ready.set() while not self.stopped(): - if self._reset.is_set(): # move to reset pose with moveL - self._is_ready.clear() - print(f"moving to {self.reset_Q} with moveJ (joint space)") + if self._reset.is_set(): # move to reset joint space pose with moveJ + print(f"[RobotiqImpedanceController] moving to {self.reset_Q} with moveJ (joint space)") self.robotiq_control.forceModeStop() self.robotiq_control.moveJ(self.reset_Q, speed=1.05, acceleration=1.4) @@ -251,7 +257,6 @@ async def run_async(self): self.robotiq_control.zeroFtSensor() self._reset.clear() - self._is_ready.set() # moving complete t_now = time.monotonic() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index fc6551d9..f49c22b1 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -50,7 +50,6 @@ class RobotiqEnv(gym.Env): def __init__( self, hz: int = 10, - save_video: bool = False, config=DefaultEnvConfig, max_episode_length: int = 100 ): @@ -78,11 +77,6 @@ def __init__( self.hz = hz self.joint_reset_cycle = 200 # reset the robot joint every 200 cycles # TODO needed? - if save_video: - print("Saving videos!") - self.save_video = save_video - self.recording_frames = [] - self.xyz_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[:3], config.ABS_POSE_LIMIT_HIGH[:3], @@ -107,7 +101,7 @@ def __init__( -np.inf, np.inf, shape=(7,) ), # xyz + quat "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_pose": gym.spaces.Box(-1, 1, shape=(1,)), + "gripper_pressure": gym.spaces.Box(-1, 1, shape=(1,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } @@ -243,23 +237,22 @@ def go_to_rest(self, joint_reset=False): reset_Q = self.resetQ.copy() self._send_gripper_command(np.ones((1,))*-1) # disable vacuum gripper self._send_reset_command(reset_Q) - time.sleep(0.1) - while not self.controller.is_ready(): + + while True: time.sleep(0.1) + if self.controller.is_reset(): + break # wait for reset + self._update_currpos() def reset(self, joint_reset=False, **kwargs): - if self.save_video: - # TODO adapt save_video_recording() - pass - self.cycle_count += 1 if self.cycle_count % self.joint_reset_cycle == 0: self.cycle_count = 0 joint_reset = True self.go_to_rest(joint_reset=joint_reset) - self._recover() + # self._recover() self.curr_path_length = 0 self._update_currpos() @@ -280,7 +273,7 @@ def _send_gripper_command(self, gripper_pos: np.ndarray): self.controller.set_gripper_pos(gripper_pos) def _send_reset_command(self, reset_Q: np.ndarray): - self.controller.move_to_reset_Q(reset_Q) + self.controller.set_reset_Q(reset_Q) def _update_currpos(self): """ @@ -300,7 +293,7 @@ def _get_obs(self) -> dict: state_observation = { "tcp_pose": self.currpos, "tcp_vel": self.currvel, - "gripper_pose": self.currpressure, + "gripper_pressure": self.currpressure, "tcp_force": self.currforce, "tcp_torque": self.currtorque, } From 5f05492c2a38e2defd86f638b0109fe29beaf99e Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 16:55:30 +0100 Subject: [PATCH 015/338] Wrapper cleanup & additions --- examples/robotiq_first_tests/record_demo.py | 6 +++- serl_robot_infra/robotiq_env/envs/wrappers.py | 30 +++++++++++++++++-- .../robotiq_env/utils/rotations.py | 8 +++++ 3 files changed, 40 insertions(+), 4 deletions(-) diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_first_tests/record_demo.py index bee30686..0294db90 100644 --- a/examples/robotiq_first_tests/record_demo.py +++ b/examples/robotiq_first_tests/record_demo.py @@ -7,11 +7,15 @@ import gymnasium as gym from pprint import pprint -from robotiq_env.envs.wrappers import SpacemouseIntervention +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images + if __name__ == "__main__": env = gym.make("robotiq_test") env = SpacemouseIntervention(env) + env = Quat2EulerWrapper(env) + # env = SERLObsWrapper(env) obs, _ = env.reset() diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index ae4d5c07..c6604461 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -1,9 +1,11 @@ import gymnasium as gym import numpy as np -from franka_env.spacemouse.spacemouse_expert import SpaceMouseExpert +from robotiq_env.spacemouse.spacemouse_expert import SpaceMouseExpert import time from scipy.spatial.transform import Rotation as R +from robotiq_env.utils.rotations import quat_2_euler + class SpacemouseIntervention(gym.ActionWrapper): def __init__(self, env): @@ -43,7 +45,8 @@ def action(self, action: np.ndarray) -> np.ndarray: def get_deadspace_action(self) -> np.ndarray: expert_a, buttons = self.expert.get_action() - expert_a = np.clip((expert_a - np.sign(expert_a) * self.deadspace) / (1.-self.deadspace), a_min=-1.0, a_max=1.) + expert_a = np.clip((expert_a - np.sign(expert_a) * self.deadspace) / (1. - self.deadspace), + a_min=-1.0, a_max=1.) self.left, self.right = tuple(buttons) @@ -67,7 +70,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: return action - def step(self, action): # TODO change here! + def step(self, action): new_action = self.action(action) # print(f"new action: {new_action}") obs, rew, done, truncated, info = self.env.step(new_action) @@ -75,3 +78,24 @@ def step(self, action): # TODO change here! info["left"] = self.left info["right"] = self.right return obs, rew, done, truncated, info + + +class Quat2EulerWrapper(gym.ObservationWrapper): + """ + Convert the quaternion representation of the tcp pose to euler angles + """ + + def __init__(self, env: gym.Env): + super().__init__(env) + # from xyz + quat to xyz + euler + self.observation_space["state"]["tcp_pose"] = gym.spaces.Box( + -np.inf, np.inf, shape=(6,) + ) + + def observation(self, observation): + # convert tcp pose from quat to euler + tcp_pose = observation["state"]["tcp_pose"] + observation["state"]["tcp_pose"] = np.concatenate( + (tcp_pose[:3], quat_2_euler(tcp_pose[3:])) + ) + return observation diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/robotiq_env/utils/rotations.py index 7d10821f..7abc291e 100644 --- a/serl_robot_infra/robotiq_env/utils/rotations.py +++ b/serl_robot_infra/robotiq_env/utils/rotations.py @@ -12,3 +12,11 @@ def rotvec_2_quat(rotvec): def quat_2_rotvec(quat): return R.from_quat(quat).as_rotvec() + + +def quat_2_euler(quat): + return R.from_quat(quat).as_euler() + + +def euler_2_quat(euler): + return R.from_euler(euler).as_quat() From 051b5670bccae3e729a5501b3bd705ef13dbde28 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 15 Mar 2024 17:16:54 +0100 Subject: [PATCH 016/338] more code cleanup --- .../robot_controllers/robotiq_controller.py | 38 +++++++++---------- .../robotiq_env/envs/robotiq_env.py | 38 +++++++++---------- .../robotiq_env/envs/test_env/config.py | 4 +- 3 files changed, 40 insertions(+), 40 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 72a09004..b58635b5 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -56,16 +56,16 @@ def __init__( self.verbose = verbose self.do_plot = plot - self.target_pos = np.zeros((7,)) # new as quat to avoid +- problems with axis angle repr. - self.target_grip = np.zeros((1,)) - self.curr_pos = np.zeros((7,)) - self.curr_vel = np.zeros((7,)) - self.curr_pressure = np.zeros((1,)) # TODO gripper state (sucking or not) - self.curr_Q = np.zeros((6,)) - self.curr_Qd = np.zeros((6,)) - self.curr_force = np.zeros((6,)) # force of tool tip + self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. + self.target_grip = np.zeros((1,), dtype=np.float32) + self.curr_pos = np.zeros((7,), dtype=np.float32) + self.curr_vel = np.zeros((7,), dtype=np.float32) + self.gripper_state = np.zeros((2,), dtype=np.float32) # TODO gripper state (sucking or not) + self.curr_Q = np.zeros((6,), dtype=np.float32) + self.curr_Qd = np.zeros((6,), dtype=np.float32) + self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip - self.reset_Q = np.zeros((6,)) # reset state in Joint Space + self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space self.delta = config.ERROR_DELTA self.fm_damping = config.FORCEMODE_DAMPING @@ -129,11 +129,11 @@ def set_target_pos(self, target_pos: np.ndarray): def set_reset_Q(self, reset_Q: np.ndarray): self._reset.set() with self.lock: - self.reset_Q = reset_Q + self.reset_Q[:] = reset_Q def set_gripper_pos(self, target_grip: np.ndarray): with self.lock: - self.target_grip = target_grip + self.target_grip[:] = target_grip def get_target_pos(self): with self.lock: @@ -146,14 +146,14 @@ async def _update_robot_state(self): Qd = self.robotiq_receive.getActualQd() force = self.robotiq_receive.getActualTCPForce() pressure = await self.robotiq_gripper.get_current_pressure() - a = self.robotiq_gripper.get_object_status() + obj_status = self.robotiq_gripper.get_object_status() with self.lock: - self.curr_pos = pose2quat(pos) - self.curr_vel = pose2quat(vel) - self.curr_Q = np.array(Q) - self.curr_Qd = np.array(Qd) - self.curr_force = np.array(force) - self.curr_pressure = np.array(pressure) + self.curr_pos[:] = pose2quat(pos) + self.curr_vel[:] = pose2quat(vel) + self.curr_Q[:] = Q + self.curr_Qd[:] = Qd + self.curr_force[:] = force + self.gripper_state[:] = [pressure, obj_status] def get_state(self): with self.lock: @@ -164,7 +164,7 @@ def get_state(self): "Qd": self.curr_Qd, "force": self.curr_force[:3], "torque": self.curr_force[3:], - "pressure": self.curr_pressure + "gripper": self.gripper_state } return state diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index f49c22b1..2ba559e2 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -62,16 +62,16 @@ def __init__( self.resetQ = config.RESET_Q - self.currpos = np.zeros((7, ), dtype=np.float32) - self.currvel = np.zeros((7,), dtype=np.float32) + self.curr_pos = np.zeros((7,), dtype=np.float32) + self.curr_vel = np.zeros((7,), dtype=np.float32) self.Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq self.Qd = np.zeros((6,), dtype=np.float32) - self.currforce = np.zeros((3,), dtype=np.float32) - self.currtorque = np.zeros((3,), dtype=np.float32) + self.curr_force = np.zeros((3,), dtype=np.float32) + self.curr_torque = np.zeros((3,), dtype=np.float32) - self.currpressure = np.zeros((1, ), dtype=np.float32) - self.lastsent = time.time() - self.randomreset = config.RANDOM_RESET + self.gripper_state = np.zeros((2,), dtype=np.float32) + self.last_sent = time.time() + self.random_reset = config.RANDOM_RESET self.random_xy_range = config.RANDOM_XY_RANGE self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz @@ -101,7 +101,7 @@ def __init__( -np.inf, np.inf, shape=(7,) ), # xyz + quat "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_pressure": gym.spaces.Box(-1, 1, shape=(1,)), + "gripper_state": gym.spaces.Box(-1, 1, shape=(2,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } @@ -221,7 +221,7 @@ def go_to_rest(self, joint_reset=False): # TODO joint reset # Perform Carteasian reset - if self.randomreset[0]: # randomize reset position in xy plane TODO is most likely bug in codebase, no ...[0] + if self.random_reset: # randomize reset position in xy plane # reset_pose = self.resetpos.copy()ss # reset_pose[:2] += np.random.uniform( # np.negative(self.random_xy_range), self.random_xy_range, (2,) @@ -281,21 +281,21 @@ def _update_currpos(self): """ state = self.controller.get_state() - self.currpos[:] = state['pos'] - self.currvel[:] = state['vel'] - self.currforce[:] = state['force'] - self.currtorque[:] = state['torque'] + self.curr_pos[:] = state['pos'] + self.curr_vel[:] = state['vel'] + self.curr_force[:] = state['force'] + self.curr_torque[:] = state['torque'] self.Q[:] = state['Q'] self.Qd[:] = state['Qd'] - self.currpressure[:] = state['pressure'] + self.gripper_state[:] = state['gripper'] def _get_obs(self) -> dict: state_observation = { - "tcp_pose": self.currpos, - "tcp_vel": self.currvel, - "gripper_pressure": self.currpressure, - "tcp_force": self.currforce, - "tcp_torque": self.currtorque, + "tcp_pose": self.curr_pos, + "tcp_vel": self.curr_vel, + "gripper_state": self.gripper_state, + "tcp_force": self.curr_force, + "tcp_torque": self.curr_torque, } return copy.deepcopy(dict(state=state_observation)) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/test_env/config.py index aee2ae42..eb960867 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/test_env/config.py @@ -6,10 +6,10 @@ class TestConfig(DefaultEnvConfig): TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) RESET_Q = np.array([1.0464833974838257, -0.9013996881297608, 1.3149092833148401, -1.9843775234618128, -1.566035572682516, -0.5265157858477991]) - RANDOM_RESET = (False,) + RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., np.inf, np.inf, np.inf]) + ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., np.inf, np.inf, np.inf]) # TODO define better (box & rot) ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -np.inf, -np.inf, -np.inf]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) From 4a5600c1f48225043a31c2367e444287c24ca178 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 15:07:16 +0100 Subject: [PATCH 017/338] bug fixes --- examples/bc_policy.py | 2 +- .../robot_controllers/robotiq_controller.py | 29 +++++++------------ .../robotiq_env/envs/robotiq_env.py | 14 +++------ serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- .../robotiq_env/utils/rotations.py | 10 ++++++- 5 files changed, 26 insertions(+), 31 deletions(-) diff --git a/examples/bc_policy.py b/examples/bc_policy.py index 007384c3..bbfb755d 100644 --- a/examples/bc_policy.py +++ b/examples/bc_policy.py @@ -9,7 +9,7 @@ import time import gymnasium as gym -from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics +from gymnasium.wrappers import RecordEpisodeStatistics from serl_launcher.utils.timer_utils import Timer from serl_launcher.wrappers.chunking import ChunkingWrapper diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index b58635b5..72a683d9 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -8,18 +8,11 @@ from rtde_receive import RTDEReceiveInterface from robotiq_env.utils.vacuum_gripper import VacuumGripper -from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec +from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2rotvec, pose2quat np.set_printoptions(precision=4, suppress=True) -def pose2quat(rotvec_pose) -> np.ndarray: - return np.concatenate((rotvec_pose[:3], rotvec_2_quat(rotvec_pose[3:]))) - - -def pose2rotvec(quat_pose) -> np.ndarray: - return np.concatenate((quat_pose[:3], quat_2_rotvec(quat_pose[3:]))) - def pos_difference(quat_pose_1: np.ndarray, quat_pose_2: np.ndarray): assert quat_pose_1.shape == (7,) @@ -100,11 +93,11 @@ async def start_robotiq_interfaces(self, gripper=True): if self.verbose: gr_string = "(with gripper) " if gripper else "" print(f"[RobotiqImpedanceController] Controller connected to robot {gr_string}at: {self.robot_ip}") - except RuntimeError: - print( - "[RobotiqImpedanceController] Failed to start control script, before timeout of 5 seconds, trying again...") + break + except RuntimeError as e: + print("[RobotiqImpedanceController] ", e.__str__()) continue - raise RuntimeError(f"[RobotiqImpedanceController] Could not connect to robot [{self.robot_ip}]") + # raise RuntimeError(f"[RobotiqImpedanceController] Could not connect to robot [{self.robot_ip}]") def stop(self): self._stop.set() @@ -116,7 +109,7 @@ def set_target_pos(self, target_pos: np.ndarray): if target_pos.shape == (7,): target_orientation = target_pos[3:] elif target_pos.shape == (6,): - target_orientation = R.from_rotvec(target_pos[3:]).as_quat() + target_orientation = rotvec_2_quat(target_pos[3:]) else: raise ValueError(f"[RobotiqImpedanceController] target pos has shape {target_pos.shape}") @@ -146,14 +139,14 @@ async def _update_robot_state(self): Qd = self.robotiq_receive.getActualQd() force = self.robotiq_receive.getActualTCPForce() pressure = await self.robotiq_gripper.get_current_pressure() - obj_status = self.robotiq_gripper.get_object_status() + obj_status = await self.robotiq_gripper.get_object_status() with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = pose2quat(vel) self.curr_Q[:] = Q self.curr_Qd[:] = Qd self.curr_force[:] = force - self.gripper_state[:] = [pressure, obj_status] + self.gripper_state[:] = [pressure, obj_status.value] def get_state(self): with self.lock: @@ -251,7 +244,7 @@ async def run_async(self): await self._update_robot_state() with self.lock: - self.target_pos = self.curr_pos + self.target_pos = self.curr_pos.copy() self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster self.robotiq_control.zeroFtSensor() @@ -282,9 +275,9 @@ async def run_async(self): ) if self.robotiq_gripper: - if self.target_grip > 0.9: + if self.target_grip[0] > 0.9: await self.robotiq_gripper.automatic_grip() - elif self.target_grip < -0.9: + elif self.target_grip[0] < -0.9: await self.robotiq_gripper.automatic_release() self.robotiq_control.waitPeriod(t_start) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 2ba559e2..363ef763 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -8,7 +8,7 @@ from scipy.spatial.transform import Rotation as R -from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec +from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController @@ -51,7 +51,7 @@ def __init__( self, hz: int = 10, config=DefaultEnvConfig, - max_episode_length: int = 100 + max_episode_length: int = 500 ): self._TARGET_POSE = config.TARGET_POSE self._REWARD_THRESHOLD = config.REWARD_THRESHOLD @@ -135,13 +135,7 @@ def __init__( while not self.controller.is_ready(): # wait for contoller time.sleep(0.1) - def pose_r2q(self, pose: np.ndarray) -> np.ndarray: - return np.concatenate([pose[:3], rotvec_2_quat(pose[3:])]) - - def pose_q2r(self, pose: np.ndarray) -> np.ndarray: - return np.concatenate([pose[:3], quat_2_rotvec(pose[3:])]) - - def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: + def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat """Clip the pose to be within the safety box.""" next_pos[:3] = np.clip( next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high @@ -200,7 +194,7 @@ def step(self, action: np.ndarray) -> tuple: def compute_reward(self, obs) -> bool: current_pose = obs["state"]["tcp_pose"] # convert from quat to axis angle representation first - current_pose = self.pose_q2r(current_pose) + current_pose = pose2rotvec(current_pose) delta = np.abs(current_pose - self._TARGET_POSE) if np.all(delta < self._REWARD_THRESHOLD): return True diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index c6604461..97594e48 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -60,7 +60,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: - expert_a: spacemouse output adapted to force space (action) """ - position = super().get_wrapper_attr("currpos") # get position from robotiq_env + position = super().get_wrapper_attr("curr_pos") # get position from robotiq_env z_angle = np.arctan2(position[1], position[0]) # get first joint angle z_rot = R.from_rotvec(np.array([0, 0, z_angle])) diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/robotiq_env/utils/rotations.py index 7abc291e..6768f94f 100644 --- a/serl_robot_infra/robotiq_env/utils/rotations.py +++ b/serl_robot_infra/robotiq_env/utils/rotations.py @@ -15,8 +15,16 @@ def quat_2_rotvec(quat): def quat_2_euler(quat): - return R.from_quat(quat).as_euler() + return R.from_quat(quat).as_euler('xyz') def euler_2_quat(euler): return R.from_euler(euler).as_quat() + + +def pose2quat(rotvec_pose) -> np.ndarray: + return np.concatenate((rotvec_pose[:3], rotvec_2_quat(rotvec_pose[3:]))) + + +def pose2rotvec(quat_pose) -> np.ndarray: + return np.concatenate((quat_pose[:3], quat_2_rotvec(quat_pose[3:]))) From ec6e27c9c2ee66b8ffcb48dc0ce18f66c042dea0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 16:05:36 +0100 Subject: [PATCH 018/338] more bug fixes --- serl_robot_infra/robot_controllers/robotiq_controller.py | 9 +++++++-- serl_robot_infra/robotiq_env/envs/wrappers.py | 9 +++++---- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 72a683d9..38b6438d 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -275,10 +275,15 @@ async def run_async(self): ) if self.robotiq_gripper: - if self.target_grip[0] > 0.9: + if self.target_grip[0] > 0.9 and self.gripper_state[0] == 100: await self.robotiq_gripper.automatic_grip() - elif self.target_grip[0] < -0.9: + self.target_grip[0] = 0.0 # reset + print("grip") + + elif self.target_grip[0] < -0.9 and self.gripper_state[1] != 3: # only release if obj detected await self.robotiq_gripper.automatic_release() + self.target_grip[0] = 0.0 + print("release") self.robotiq_control.waitPeriod(t_start) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 97594e48..ce8c205f 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -29,7 +29,7 @@ def action(self, action: np.ndarray) -> np.ndarray: """ expert_a = self.get_deadspace_action() - if np.linalg.norm(expert_a) > 0.001: + if np.linalg.norm(expert_a) > 0.001 or self.left or self.right: # also read buttons with no movement self.last_intervene = time.time() if self.gripper_enabled: @@ -45,8 +45,9 @@ def action(self, action: np.ndarray) -> np.ndarray: def get_deadspace_action(self) -> np.ndarray: expert_a, buttons = self.expert.get_action() - expert_a = np.clip((expert_a - np.sign(expert_a) * self.deadspace) / (1. - self.deadspace), - a_min=-1.0, a_max=1.) + positive = np.clip((expert_a - self.deadspace) / (1. - self.deadspace), a_min=0.0, a_max=1.0) + negative = np.clip((expert_a + self.deadspace) / (1. - self.deadspace), a_min=-1.0, a_max=0.0) + expert_a = positive + negative self.left, self.right = tuple(buttons) @@ -72,7 +73,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: def step(self, action): new_action = self.action(action) - # print(f"new action: {new_action}") + print(f"new action: {new_action}") obs, rew, done, truncated, info = self.env.step(new_action) info["intervene_action"] = new_action info["left"] = self.left From 4b5defc7f168309f17834bce88ace138e171ff15 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 16:13:23 +0100 Subject: [PATCH 019/338] do not print --- serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index ce8c205f..7cfeca0a 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -73,7 +73,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: def step(self, action): new_action = self.action(action) - print(f"new action: {new_action}") + # print(f"new action: {new_action}") obs, rew, done, truncated, info = self.env.step(new_action) info["intervene_action"] = new_action info["left"] = self.left From 83fc80b329c1a64de91a08aa9cd8ddddebebf992 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 16:17:48 +0100 Subject: [PATCH 020/338] onkey state output added --- examples/robotiq_first_tests/record_demo.py | 25 ++++++++++++++++++++- 1 file changed, 24 insertions(+), 1 deletion(-) diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_first_tests/record_demo.py index 0294db90..9adce0f8 100644 --- a/examples/robotiq_first_tests/record_demo.py +++ b/examples/robotiq_first_tests/record_demo.py @@ -6,9 +6,20 @@ from tqdm import tqdm import gymnasium as gym from pprint import pprint +from pynput import keyboard from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images + + +def on_space(key, state, gr_state): + if key == keyboard.Key.space: + print(f'state: {state} gripper: {gr_state}') + + +def on_esc(key): + if key == keyboard.Key.esc: + print("ESC pressed (can be used later)") if __name__ == "__main__": @@ -25,6 +36,13 @@ total_count = 0 pbar = tqdm(total=success_needed) + listener_1 = keyboard.Listener(daemon=True, + on_press=lambda event: on_space(event, state=env.unwrapped.curr_pos, gr_state=env.unwrapped.gripper_state)) + listener_1.start() + + listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) + listener_2.start() + uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") file_name = f"robotiq_test_{success_needed}_demos_{uuid}.pkl" file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script @@ -66,5 +84,10 @@ pkl.dump(transitions, f) print(f"saved {success_needed} demos to {file_path}") + except KeyboardInterrupt: + print(f'\nProgram was interrupted, cleaning up...') + finally: env.close() + listener_1.stop() + listener_2.stop() From 87926550c70345f2f4b66f76f321f24aa3f05261 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 16:19:04 +0100 Subject: [PATCH 021/338] better output --- serl_robot_infra/robot_controllers/robotiq_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 38b6438d..a53b3c19 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -295,7 +295,7 @@ async def run_async(self): self.noerr += 1 finally: - print(f"time errs: {self.err} no_err: {self.noerr}") + print(f"[RTDEPositionalController] >dt: {self.err}
Date: Mon, 18 Mar 2024 17:20:58 +0100 Subject: [PATCH 022/338] typo --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 363ef763..d6bc4ffd 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -100,8 +100,8 @@ def __init__( "tcp_pose": gym.spaces.Box( -np.inf, np.inf, shape=(7,) ), # xyz + quat - "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_state": gym.spaces.Box(-1, 1, shape=(2,)), + "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(7,)), + "gripper_state": gym.spaces.Box(-np.inf, np.inf, shape=(2,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } @@ -132,7 +132,7 @@ def __init__( self.controller.start() # start Thread - while not self.controller.is_ready(): # wait for contoller + while not self.controller.is_ready(): # wait for controller time.sleep(0.1) def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat From 4b4c89c8554f49a91e1c9de6f05938634e7badb3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 17:21:22 +0100 Subject: [PATCH 023/338] gripper fix --- serl_robot_infra/robot_controllers/robotiq_controller.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index a53b3c19..6396ee88 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -146,7 +146,7 @@ async def _update_robot_state(self): self.curr_Q[:] = Q self.curr_Qd[:] = Qd self.curr_force[:] = force - self.gripper_state[:] = [pressure, obj_status.value] + self.gripper_state[:] = [pressure, float(obj_status.value)] def get_state(self): with self.lock: @@ -277,13 +277,13 @@ async def run_async(self): if self.robotiq_gripper: if self.target_grip[0] > 0.9 and self.gripper_state[0] == 100: await self.robotiq_gripper.automatic_grip() - self.target_grip[0] = 0.0 # reset - print("grip") + self.target_grip[0] = 0.0 + # print("grip") elif self.target_grip[0] < -0.9 and self.gripper_state[1] != 3: # only release if obj detected await self.robotiq_gripper.automatic_release() self.target_grip[0] = 0.0 - print("release") + # print("release") self.robotiq_control.waitPeriod(t_start) From a858e50c91b6718b9cb3960f71971254c89688cc Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 17:21:40 +0100 Subject: [PATCH 024/338] new conf --- serl_robot_infra/robotiq_env/envs/test_env/config.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/test_env/config.py index eb960867..2808b4dd 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/test_env/config.py @@ -9,8 +9,8 @@ class TestConfig(DefaultEnvConfig): RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., np.inf, np.inf, np.inf]) # TODO define better (box & rot) - ABS_POSE_LIMIT_LOW = np.array([-1., -1., 0.05, -np.inf, -np.inf, -np.inf]) + ABS_POSE_LIMIT_HIGH = np.array([1., -0.41, 1., 3.3, 3.3, 3.3]) # TODO euler rotations suck :/ + ABS_POSE_LIMIT_LOW = np.array([-0.55, -1., 0.05, -3.3, -3.3, -3.3]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.3" From 23cbdb815b55c79c73b04ec322606c52ad249cac Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 18 Mar 2024 17:22:19 +0100 Subject: [PATCH 025/338] some tests --- examples/robotiq_first_tests/record_demo.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_first_tests/record_demo.py index 9adce0f8..3ec9ae01 100644 --- a/examples/robotiq_first_tests/record_demo.py +++ b/examples/robotiq_first_tests/record_demo.py @@ -10,11 +10,13 @@ from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images +from scipy.spatial.transform import Rotation as R def on_space(key, state, gr_state): if key == keyboard.Key.space: - print(f'state: {state} gripper: {gr_state}') + rotvec = R.from_quat(state[3:]).as_rotvec() + print(f'state: {state} gripper: {gr_state} rotvec: {rotvec}') def on_esc(key): @@ -25,7 +27,7 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_test") env = SpacemouseIntervention(env) - env = Quat2EulerWrapper(env) + # env = Quat2EulerWrapper(env) # TODO change pos & vel dimens to 6 if the euler wrapper is used! # env = SERLObsWrapper(env) obs, _ = env.reset() @@ -37,7 +39,8 @@ def on_esc(key): pbar = tqdm(total=success_needed) listener_1 = keyboard.Listener(daemon=True, - on_press=lambda event: on_space(event, state=env.unwrapped.curr_pos, gr_state=env.unwrapped.gripper_state)) + on_press=lambda event: on_space(event, state=env.unwrapped.curr_pos, + gr_state=env.unwrapped.gripper_state)) listener_1.start() listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) From 299325ebb35ff87393d0d4c05b73e77e09168cf6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 15:42:15 +0100 Subject: [PATCH 026/338] name change --- serl_robot_infra/robotiq_env/__init__.py | 4 ++-- .../robotiq_env/envs/robotiq_grip_v1/__init__.py | 1 + .../envs/{test_env => robotiq_grip_v1}/config.py | 12 ++++++------ .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 7 +++++++ .../robotiq_env/envs/test_env/__init__.py | 1 - .../robotiq_env/envs/test_env/robotiq_test.py | 7 ------- .../robotiq_env/spacemouse/spacemouse_test.py | 2 +- 7 files changed, 17 insertions(+), 17 deletions(-) create mode 100644 serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py rename serl_robot_infra/robotiq_env/envs/{test_env => robotiq_grip_v1}/config.py (63%) create mode 100644 serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py delete mode 100644 serl_robot_infra/robotiq_env/envs/test_env/__init__.py delete mode 100644 serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index 9ee39520..89467ba6 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -2,7 +2,7 @@ import numpy as np register( - id="robotiq_test", - entry_point="robotiq_env.envs.test_env:RobotiqTest", + id="robotiq_grip-v1", + entry_point="robotiq_env.envs.robotiq_grip_v1:RobotiqGripV1", max_episode_steps=100, ) \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py new file mode 100644 index 00000000..0e1d56aa --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py @@ -0,0 +1 @@ +from robotiq_env.envs.robotiq_grip_v1.robotiq_grip_v1 import RobotiqGripV1 diff --git a/serl_robot_infra/robotiq_env/envs/test_env/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py similarity index 63% rename from serl_robot_infra/robotiq_env/envs/test_env/config.py rename to serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 2808b4dd..78e8621c 100644 --- a/serl_robot_infra/robotiq_env/envs/test_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -2,19 +2,19 @@ import numpy as np -class TestConfig(DefaultEnvConfig): +class RobotiqCornerConfig(DefaultEnvConfig): TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) - RESET_Q = np.array([1.0464833974838257, -0.9013996881297608, 1.3149092833148401, -1.9843775234618128, -1.566035572682516, -0.5265157858477991]) + RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([1., -0.41, 1., 3.3, 3.3, 3.3]) # TODO euler rotations suck :/ - ABS_POSE_LIMIT_LOW = np.array([-0.55, -1., 0.05, -3.3, -3.3, -3.3]) + ABS_POSE_LIMIT_HIGH = np.array([0.14, 0.07, 1., 3.3, 3.3, 3.3]) # TODO euler rotations suck :/ + ABS_POSE_LIMIT_LOW = np.array([-1., -1., -0.006, -3.3, -3.3, -3.3]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) - ROBOT_IP: str = "172.22.22.3" - CONTROLLER_HZ = 100 + ROBOT_IP: str = "172.22.22.2" + CONTROLLER_HZ = 200 ERROR_DELTA: float = 0.05 FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py new file mode 100644 index 00000000..81aebc4a --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -0,0 +1,7 @@ +from robotiq_env.envs.robotiq_env import RobotiqEnv +from robotiq_env.envs.robotiq_grip_v1.config import RobotiqCornerConfig + + +class RobotiqGripV1(RobotiqEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, config=RobotiqCornerConfig) diff --git a/serl_robot_infra/robotiq_env/envs/test_env/__init__.py b/serl_robot_infra/robotiq_env/envs/test_env/__init__.py deleted file mode 100644 index daa38c69..00000000 --- a/serl_robot_infra/robotiq_env/envs/test_env/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from robotiq_env.envs.test_env.robotiq_test import RobotiqTest \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py b/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py deleted file mode 100644 index 5e45cd81..00000000 --- a/serl_robot_infra/robotiq_env/envs/test_env/robotiq_test.py +++ /dev/null @@ -1,7 +0,0 @@ -from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.test_env.config import TestConfig - - -class RobotiqTest(RobotiqEnv): - def __init__(self, **kwargs): - super().__init__(**kwargs, config=TestConfig) diff --git a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py index 8c9cb638..5127f72a 100644 --- a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py +++ b/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py @@ -1,7 +1,7 @@ """ Test the spacemouse output. """ import time import numpy as np -from serl_robot_infra.franka_env.spacemouse.spacemouse_expert import SpaceMouseExpert +from robotiq_env.spacemouse.spacemouse_expert import SpaceMouseExpert def test_spacemouse(): From 29b80e8238ad08964837dcb8cec7f3f2c6c4595c Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 15:42:27 +0100 Subject: [PATCH 027/338] bug fix --- serl_robot_infra/robotiq_env/envs/wrappers.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 7cfeca0a..d1708ac0 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -17,7 +17,7 @@ def __init__(self, env): self.last_intervene = 0 self.left, self.right = False, False - self.invert_axes = [-1, -1, 1, 1, -1, 1] + self.invert_axes = [-1, -1, 1, 1, -1, -1] self.deadspace = 0.15 def action(self, action: np.ndarray) -> np.ndarray: @@ -61,7 +61,8 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: - expert_a: spacemouse output adapted to force space (action) """ - position = super().get_wrapper_attr("curr_pos") # get position from robotiq_env + # position = super().get_wrapper_attr("curr_pos") # get position from robotiq_env + position = self.unwrapped.curr_pos z_angle = np.arctan2(position[1], position[0]) # get first joint angle z_rot = R.from_rotvec(np.array([0, 0, z_angle])) From fea32bc3fac8ee51d4449e53115960968b3f684f Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 15:42:38 +0100 Subject: [PATCH 028/338] added requirements --- serl_robot_infra/robotiq_env/requirements.txt | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 serl_robot_infra/robotiq_env/requirements.txt diff --git a/serl_robot_infra/robotiq_env/requirements.txt b/serl_robot_infra/robotiq_env/requirements.txt new file mode 100644 index 00000000..9ee4a5bc --- /dev/null +++ b/serl_robot_infra/robotiq_env/requirements.txt @@ -0,0 +1,8 @@ +matplotlib +scipy +pyspacemouse +ur-rtde +pynput +pprint + +# TODO may not be the right place to put the file \ No newline at end of file From 35c2102c1977dbbf51b270f88ffb7660348bc3ce Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 15:42:53 +0100 Subject: [PATCH 029/338] stop program on ESC press --- .../record_demo.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) rename examples/{robotiq_first_tests => robotiq_grip_v1}/record_demo.py (92%) diff --git a/examples/robotiq_first_tests/record_demo.py b/examples/robotiq_grip_v1/record_demo.py similarity index 92% rename from examples/robotiq_first_tests/record_demo.py rename to examples/robotiq_grip_v1/record_demo.py index 3ec9ae01..fc4c60de 100644 --- a/examples/robotiq_first_tests/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -1,5 +1,6 @@ import os import datetime +import threading import numpy as np import copy import pickle as pkl @@ -12,6 +13,8 @@ from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images from scipy.spatial.transform import Rotation as R +exit_program = threading.Event() + def on_space(key, state, gr_state): if key == keyboard.Key.space: @@ -21,11 +24,11 @@ def on_space(key, state, gr_state): def on_esc(key): if key == keyboard.Key.esc: - print("ESC pressed (can be used later)") + exit_program.set() if __name__ == "__main__": - env = gym.make("robotiq_test") + env = gym.make("robotiq_grip-v1") env = SpacemouseIntervention(env) # env = Quat2EulerWrapper(env) # TODO change pos & vel dimens to 6 if the euler wrapper is used! # env = SERLObsWrapper(env) @@ -56,6 +59,9 @@ def on_esc(key): try: while success_count < success_needed: + if exit_program.is_set(): + raise KeyboardInterrupt # stop program, but clean up before + next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) actions = info["intervene_action"] From 95a9c8de7303f2e8dafb764bc4c345dc619531cc Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 16:47:56 +0100 Subject: [PATCH 030/338] reward computation v1 --- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index 81aebc4a..e3349d6e 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -5,3 +5,9 @@ class RobotiqGripV1(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) + + def compute_reward(self, obs) -> bool: + if int(self.gripper_state[1]) == 1 and 10 < self.gripper_state[0] < 30 and self.curr_force[2] < -1.: + return True + else: + return False \ No newline at end of file From 564604dc1a41afe5cf1510a2802b593cad8a2e52 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 16:48:34 +0100 Subject: [PATCH 031/338] added Observation Wrapper with no images --- .../wrappers/serl_obs_wrappers.py | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 6e9a1e46..7f26597a 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -23,3 +23,24 @@ def observation(self, obs): **(obs["images"]), } return obs + + +class SerlObsWrapperNoImages(gym.ObservationWrapper): + """ + This observation wrapper treat the observation space as a dictionary + of a flattened state space, if no images are present. + """ + + def __init__(self, env): + super().__init__(env) + self.observation_space = gym.spaces.Dict( + { + "state": flatten_space(self.env.observation_space["state"]) + } + ) + + def observation(self, obs): + obs = { + "state": flatten(self.env.observation_space["state"], obs["state"]) + } + return obs From 6a97beb13192f66b0b502e6d6222a1722dab1712 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 16:49:09 +0100 Subject: [PATCH 032/338] length back to 100 --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 16 ++++------------ 1 file changed, 4 insertions(+), 12 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index d6bc4ffd..a1dad4af 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -51,9 +51,9 @@ def __init__( self, hz: int = 10, config=DefaultEnvConfig, - max_episode_length: int = 500 + max_episode_length: int = 100 ): - self._TARGET_POSE = config.TARGET_POSE + self._TARGET_POSE = config.TARGET_POSE # TODO not used for now, same for threshold self._REWARD_THRESHOLD = config.REWARD_THRESHOLD self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -165,7 +165,7 @@ def step(self, action: np.ndarray) -> tuple: action = np.clip(action, self.action_space.low, self.action_space.high) # position - # next_pos = self.currpos.copy() + # next_pos = self.curr_pos.copy() next_pos = self.controller.get_target_pos() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] @@ -192,15 +192,7 @@ def step(self, action: np.ndarray) -> tuple: return ob, int(reward), done, False, {} def compute_reward(self, obs) -> bool: - current_pose = obs["state"]["tcp_pose"] - # convert from quat to axis angle representation first - current_pose = pose2rotvec(current_pose) - delta = np.abs(current_pose - self._TARGET_POSE) - if np.all(delta < self._REWARD_THRESHOLD): - return True - else: - # print(f'Goal not reached, the difference is {delta}, the desired threshold is {_REWARD_THRESHOLD}') - return False + return False # overwrite for each task def go_to_rest(self, joint_reset=False): """ From 09b3efa183abc6057b335152ab07519ba6a72c41 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 16:49:51 +0100 Subject: [PATCH 033/338] simplified pose output with spacebar --- examples/robotiq_grip_v1/record_demo.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_grip_v1/record_demo.py index fc4c60de..3fb4b16c 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -10,16 +10,17 @@ from pynput import keyboard from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper # TODO has no images +from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from scipy.spatial.transform import Rotation as R exit_program = threading.Event() -def on_space(key, state, gr_state): +def on_space(key, info_dict): if key == keyboard.Key.space: - rotvec = R.from_quat(state[3:]).as_rotvec() - print(f'state: {state} gripper: {gr_state} rotvec: {rotvec}') + for key, item in info_dict.items(): + print(f'{key}: {item}', end=' ') + print() def on_esc(key): @@ -30,8 +31,8 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_grip-v1") env = SpacemouseIntervention(env) - # env = Quat2EulerWrapper(env) # TODO change pos & vel dimens to 6 if the euler wrapper is used! - # env = SERLObsWrapper(env) + env = Quat2EulerWrapper(env) # TODO change pos & vel dimens to 6 if the euler wrapper is used! + env = SerlObsWrapperNoImages(env) obs, _ = env.reset() @@ -41,9 +42,8 @@ def on_esc(key): total_count = 0 pbar = tqdm(total=success_needed) - listener_1 = keyboard.Listener(daemon=True, - on_press=lambda event: on_space(event, state=env.unwrapped.curr_pos, - gr_state=env.unwrapped.gripper_state)) + info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, 'force': env.unwrapped.curr_force} + listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) listener_1.start() listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) From fd0c13ceed12c5d5cc825ed0bd098c6c722e6815 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:07:40 +0100 Subject: [PATCH 034/338] faster gripper disabling --- .../robot_controllers/robotiq_controller.py | 43 ++++++++++++------- .../robotiq_env/envs/robotiq_env.py | 1 - 2 files changed, 27 insertions(+), 17 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 6396ee88..85d149dd 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -187,12 +187,6 @@ def _calculate_force(self): return np.concatenate((force_pos, torque)) - def run(self): - try: - asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands - finally: - self.stop() - def plot(self): if self.horizon[0] < self.horizon[1]: self.horizon[0] += 1 @@ -222,6 +216,23 @@ def plot(self): plt.show(block=True) self.stop() + async def send_gripper_command(self): + if self.target_grip[0] > 0.9 and self.gripper_state[0] == 100: + await self.robotiq_gripper.automatic_grip() + self.target_grip[0] = 0.0 + # print("grip") + + elif self.target_grip[0] < -0.9 and self.gripper_state[1] != 3: # only release if obj detected + await self.robotiq_gripper.automatic_release() + self.target_grip[0] = 0.0 + # print("release") + + def run(self): + try: + asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + finally: + self.stop() + async def run_async(self): await self.start_robotiq_interfaces(gripper=True) @@ -238,9 +249,16 @@ async def run_async(self): while not self.stopped(): if self._reset.is_set(): # move to reset joint space pose with moveJ + # first disable vaccum gripper + if self.robotiq_gripper: + self.target_grip[0] = -1. + await self.send_gripper_command() + time.sleep(0.1) # TODO not sure if necessary + + # then move to Jointspace position print(f"[RobotiqImpedanceController] moving to {self.reset_Q} with moveJ (joint space)") self.robotiq_control.forceModeStop() - self.robotiq_control.moveJ(self.reset_Q, speed=1.05, acceleration=1.4) + self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.5) await self._update_robot_state() with self.lock: @@ -273,17 +291,10 @@ async def run_async(self): 2, self.fm_limits ) + # TODO try to reset with moveJ if forcemode returns False if self.robotiq_gripper: - if self.target_grip[0] > 0.9 and self.gripper_state[0] == 100: - await self.robotiq_gripper.automatic_grip() - self.target_grip[0] = 0.0 - # print("grip") - - elif self.target_grip[0] < -0.9 and self.gripper_state[1] != 3: # only release if obj detected - await self.robotiq_gripper.automatic_release() - self.target_grip[0] = 0.0 - # print("release") + await self.send_gripper_command() self.robotiq_control.waitPeriod(t_start) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index a1dad4af..cdc08711 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -221,7 +221,6 @@ def go_to_rest(self, joint_reset=False): pass else: reset_Q = self.resetQ.copy() - self._send_gripper_command(np.ones((1,))*-1) # disable vacuum gripper self._send_reset_command(reset_Q) while True: From d3a5c8eea3c7b8cf7bb7b5b3ac9052b11c97ae43 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:28:41 +0100 Subject: [PATCH 035/338] make velocitz 6d (rotvec not quat) --- serl_robot_infra/robot_controllers/robotiq_controller.py | 6 +++--- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 85d149dd..acc825bc 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -52,7 +52,7 @@ def __init__( self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) self.curr_pos = np.zeros((7,), dtype=np.float32) - self.curr_vel = np.zeros((7,), dtype=np.float32) + self.curr_vel = np.zeros((6,), dtype=np.float32) self.gripper_state = np.zeros((2,), dtype=np.float32) # TODO gripper state (sucking or not) self.curr_Q = np.zeros((6,), dtype=np.float32) self.curr_Qd = np.zeros((6,), dtype=np.float32) @@ -142,7 +142,7 @@ async def _update_robot_state(self): obj_status = await self.robotiq_gripper.get_object_status() with self.lock: self.curr_pos[:] = pose2quat(pos) - self.curr_vel[:] = pose2quat(vel) + self.curr_vel[:] = vel self.curr_Q[:] = Q self.curr_Qd[:] = Qd self.curr_force[:] = force @@ -182,7 +182,7 @@ def _calculate_force(self): # calc torque rot_diff = R.from_quat(target_pos[3:]) * R.from_quat(curr_pos[3:]).inv() - vel_rot_diff = R.from_quat(curr_vel[3:]).inv() + vel_rot_diff = R.from_rotvec(curr_vel[3:]).inv() torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable return np.concatenate((force_pos, torque)) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index cdc08711..944d33b5 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -63,7 +63,7 @@ def __init__( self.resetQ = config.RESET_Q self.curr_pos = np.zeros((7,), dtype=np.float32) - self.curr_vel = np.zeros((7,), dtype=np.float32) + self.curr_vel = np.zeros((6,), dtype=np.float32) self.Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq self.Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((3,), dtype=np.float32) From 15e8d5f0c455e8859f75755cffafdbc1c181522d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:29:52 +0100 Subject: [PATCH 036/338] added RelativeFrame and SerlObsWrapperNoImages --- examples/robotiq_grip_v1/record_demo.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_grip_v1/record_demo.py index 3fb4b16c..bcc518f5 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -13,6 +13,9 @@ from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from scipy.spatial.transform import Rotation as R +from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env + + exit_program = threading.Event() @@ -31,7 +34,8 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_grip-v1") env = SpacemouseIntervention(env) - env = Quat2EulerWrapper(env) # TODO change pos & vel dimens to 6 if the euler wrapper is used! + env = RelativeFrame(env) + env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) obs, _ = env.reset() From f1b35fc09cdbdc6091b519ab55483e444ab5d405 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:32:22 +0100 Subject: [PATCH 037/338] button swap (more natural) --- serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index d1708ac0..b09949ab 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -33,7 +33,7 @@ def action(self, action: np.ndarray) -> np.ndarray: self.last_intervene = time.time() if self.gripper_enabled: - gripper_action = np.zeros((1,)) - int(self.left) + int(self.right) + gripper_action = np.zeros((1,)) + int(self.left) - int(self.right) expert_a = np.concatenate((expert_a, gripper_action), axis=0) if time.time() - self.last_intervene < 0.5: From 49673f6438626e567f69230df8f3b384799d489a Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:44:30 +0100 Subject: [PATCH 038/338] added ChungkingWrapper --- examples/robotiq_grip_v1/record_demo.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_grip_v1/record_demo.py index bcc518f5..fd707ab7 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -11,10 +11,9 @@ from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from scipy.spatial.transform import Rotation as R - -from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env +from serl_launcher.wrappers.chunking import ChunkingWrapper +from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env exit_program = threading.Event() @@ -37,6 +36,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) obs, _ = env.reset() @@ -46,7 +46,8 @@ def on_esc(key): total_count = 0 pbar = tqdm(total=success_needed) - info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, 'force': env.unwrapped.curr_force} + info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, + 'force': env.unwrapped.curr_force} listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) listener_1.start() From c46a324e70d5e92bba83502f3c1b8094f112a833 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 19 Mar 2024 17:45:11 +0100 Subject: [PATCH 039/338] copied actor/learner config, not finished yet! --- examples/robotiq_grip_v1/async_drq_v1.py | 395 +++++++++++++++++++++++ 1 file changed, 395 insertions(+) create mode 100644 examples/robotiq_grip_v1/async_drq_v1.py diff --git a/examples/robotiq_grip_v1/async_drq_v1.py b/examples/robotiq_grip_v1/async_drq_v1.py new file mode 100644 index 00000000..6b8f977a --- /dev/null +++ b/examples/robotiq_grip_v1/async_drq_v1.py @@ -0,0 +1,395 @@ +#!/usr/bin/env python3 + +import time +from functools import partial +import jax +import jax.numpy as jnp +import numpy as np +import tqdm +from absl import app, flags +from flax.training import checkpoints + +import gymnasium as gym +from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics + +from serl_launcher.agents.continuous.drq import DrQAgent +from serl_launcher.common.evaluation import evaluate +from serl_launcher.utils.timer_utils import Timer +from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.utils.train_utils import concat_batches + +from agentlace.trainer import TrainerServer, TrainerClient +from agentlace.data.data_store import QueuedDataStore + +from serl_launcher.utils.launcher import ( + make_drq_agent, + make_trainer_config, + make_wandb_logger, +) +from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore +from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper + +import robotiq_env + +FLAGS = flags.FLAGS + +flags.DEFINE_string("env", "robotiq_grip-v1", "Name of environment.") +flags.DEFINE_string("agent", "drq", "Name of agent.") +flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") +flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_integer("seed", 42, "Random seed.") +flags.DEFINE_bool("save_model", False, "Whether to save model.") +flags.DEFINE_integer("batch_size", 256, "Batch size.") +flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") + +flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") +flags.DEFINE_integer("replay_buffer_capacity", 200000, "Replay buffer capacity.") + +flags.DEFINE_integer("random_steps", 300, "Sample random actions for this many steps.") +flags.DEFINE_integer("training_starts", 300, "Training starts after this step.") +flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") + +flags.DEFINE_integer("log_period", 10, "Logging period.") +flags.DEFINE_integer("eval_period", 2000, "Evaluation period.") + +# flag to indicate if this is a leaner or a actor +flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") +flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") +flags.DEFINE_boolean("render", False, "Render the environment.") +flags.DEFINE_string("ip", "localhost", "IP address of the learner.") +# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights +flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") +flags.DEFINE_string("demo_path", "robotiq_test_20_demos_2024-03-19_16-04-24.pkl", "Path to the demo data.") +flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") +flags.DEFINE_string("checkpoint_path", 'checkpoint_test_path', "Path to save checkpoints.") + +flags.DEFINE_integer( + "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" +) +flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") + +flags.DEFINE_boolean( + "debug", True, "Debug mode." +) # debug mode will disable wandb logging + +devices = jax.local_devices() +num_devices = len(devices) +sharding = jax.sharding.PositionalSharding(devices) + + +def print_green(x): + return print("\033[92m {}\033[00m".format(x)) + + +############################################################################## + + +def actor(agent: DrQAgent, data_store, env, sampling_rng): + """ + This is the actor loop, which runs when "--actor" is set to True. + """ + if FLAGS.eval_checkpoint_step: + success_counter = 0 + time_list = [] + + ckpt = checkpoints.restore_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=FLAGS.eval_checkpoint_step, + ) + agent = agent.replace(state=ckpt) + + for episode in range(FLAGS.eval_n_trajs): + obs, _ = env.reset() + done = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=True, + ) + actions = np.asarray(jax.device_get(actions)) + + next_obs, reward, done, truncated, info = env.step(actions) + obs = next_obs + + if done: + if reward: + dt = time.time() - start_time + time_list.append(dt) + print(dt) + + success_counter += reward + print(reward) + print(f"{success_counter}/{episode + 1}") + + print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") + print(f"average time: {np.mean(time_list)}") + return # after done eval, return and exit + + client = TrainerClient( + "actor_env", + FLAGS.ip, + make_trainer_config(), + data_store, + wait_for_server=True, + ) + + # Function to update the agent with new params + def update_params(params): + nonlocal agent + agent = agent.replace(state=agent.state.replace(params=params)) + + client.recv_network_callback(update_params) + + obs, _ = env.reset() + done = False + + # training loop + timer = Timer() + running_return = 0.0 + + for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True): + timer.tick("total") + + with timer.context("sample_actions"): + if step < FLAGS.random_steps: + actions = env.action_space.sample() + else: + sampling_rng, key = jax.random.split(sampling_rng) + actions = agent.sample_actions( + observations=jax.device_put(obs), + seed=key, + deterministic=False, + ) + actions = np.asarray(jax.device_get(actions)) + + # Step environment + with timer.context("step_env"): + + next_obs, reward, done, truncated, info = env.step(actions) + + # override the action with the intervention action + if "intervene_action" in info: + actions = info.pop("intervene_action") + + reward = np.asarray(reward, dtype=np.float32) + info = np.asarray(info) + running_return += reward + transition = dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=reward, + masks=1.0 - done, + dones=done, + ) + data_store.insert(transition) + + obs = next_obs + if done or truncated: + stats = {"train": info} # send stats to the learner to log + client.request("send-stats", stats) + running_return = 0.0 + obs, _ = env.reset() + + if step % FLAGS.steps_per_update == 0: + client.update() + + timer.tock("total") + + if step % FLAGS.log_period == 0: + stats = {"timer": timer.get_average_times()} + client.request("send-stats", stats) + + +############################################################################## + + +def learner(rng, agent: DrQAgent, replay_buffer, demo_buffer, wandb_logger=None): + """ + The learner loop, which runs when "--learner" is set to True. + """ + # To track the step in the training loop + update_steps = 0 + + def stats_callback(type: str, payload: dict) -> dict: + """Callback for when server receives stats request.""" + assert type == "send-stats", f"Invalid request type: {type}" + if wandb_logger is not None: + wandb_logger.log(payload, step=update_steps) + return {} # not expecting a response + + # Create server + server = TrainerServer(make_trainer_config(), request_callback=stats_callback) + server.register_data_store("actor_env", replay_buffer) + server.start(threaded=True) + + # Loop to wait until replay_buffer is filled + pbar = tqdm.tqdm( + total=FLAGS.training_starts, + initial=len(replay_buffer), + desc="Filling up replay buffer", + position=0, + leave=True, + ) + while len(replay_buffer) < FLAGS.training_starts: + pbar.update(len(replay_buffer) - pbar.n) # Update progress bar + time.sleep(1) + pbar.update(len(replay_buffer) - pbar.n) # Update progress bar + pbar.close() + + # send the initial network to the actor + server.publish_network(agent.state.params) + print_green("sent initial network to actor") + + # 50/50 sampling from RLPD, half from demo and half from online experience + replay_iterator = replay_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size // 2, + "pack_obs_and_next_obs": True, + }, + device=sharding.replicate(), + ) + demo_iterator = demo_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size // 2, + "pack_obs_and_next_obs": True, + }, + device=sharding.replicate(), + ) + + # wait till the replay buffer is filled with enough data + timer = Timer() + for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): + # run n-1 critic updates and 1 critic + actor update. + # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU + for critic_step in range(FLAGS.utd_ratio - 1): + with timer.context("sample_replay_buffer"): + batch = next(replay_iterator) + demo_batch = next(demo_iterator) + batch = concat_batches(batch, demo_batch, axis=0) + + with timer.context("train_critics"): + agent, critics_info = agent.update_critics( + batch, + ) + + with timer.context("train"): + batch = next(replay_iterator) + demo_batch = next(demo_iterator) + batch = concat_batches(batch, demo_batch, axis=0) + agent, update_info = agent.update_high_utd(batch, utd_ratio=1) + + # publish the updated network + if step > 0 and step % (FLAGS.steps_per_update) == 0: + agent = jax.block_until_ready(agent) + server.publish_network(agent.state.params) + + if update_steps % FLAGS.log_period == 0 and wandb_logger: + wandb_logger.log(update_info, step=update_steps) + wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) + + if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: + assert FLAGS.checkpoint_path is not None + checkpoints.save_checkpoint( + FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 + ) + + update_steps += 1 + + +############################################################################## + + +def main(_): + assert FLAGS.batch_size % num_devices == 0 + # seed + rng = jax.random.PRNGKey(FLAGS.seed) + + # create env and load dataset + env = gym.make(FLAGS.env) + if FLAGS.actor: + env = SpacemouseIntervention(env) + # env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SerlObsWrapperNoImages(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = RecordEpisodeStatistics(env) + + # TODO adapt to "async_sac_state_sim.py" --> SAC with no images (DRQ needs images) + + image_keys = [key for key in env.observation_space.keys() if key != "state"] + + rng, sampling_rng = jax.random.split(rng) + agent: DrQAgent = make_drq_agent( + seed=FLAGS.seed, + sample_obs=env.observation_space.sample(), + sample_action=env.action_space.sample(), + image_keys=image_keys, + encoder_type=FLAGS.encoder_type, + ) + + # replicate agent across devices + # need the jnp.array to avoid a bug where device_put doesn't recognize primitives + agent: DrQAgent = jax.device_put( + jax.tree_map(jnp.array, agent), sharding.replicate() + ) + + def create_replay_buffer_and_wandb_logger(): + replay_buffer = MemoryEfficientReplayBufferDataStore( + env.observation_space, + env.action_space, + capacity=FLAGS.replay_buffer_capacity, + image_keys=image_keys, + ) + # set up wandb and logging + wandb_logger = make_wandb_logger( + project="serl_dev", + description=FLAGS.exp_name or FLAGS.env, + debug=FLAGS.debug, + ) + return replay_buffer, wandb_logger + + if FLAGS.learner: + sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) + replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() + demo_buffer = MemoryEfficientReplayBufferDataStore( + env.observation_space, + env.action_space, + capacity=10000, + image_keys=image_keys, + ) + import pickle as pkl + + with open(FLAGS.demo_path, "rb") as f: + trajs = pkl.load(f) + for traj in trajs: + demo_buffer.insert(traj) + print(f"demo buffer size: {len(demo_buffer)}") + + # learner loop + print_green("starting learner loop") + learner( + sampling_rng, + agent, + replay_buffer, + demo_buffer=demo_buffer, + wandb_logger=wandb_logger, + ) + + elif FLAGS.actor: + sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) + data_store = QueuedDataStore(50000) # the queue size on the actor + + # actor loop + print_green("starting actor loop") + actor(agent, data_store, env, sampling_rng) + + else: + raise NotImplementedError("Must be either a learner or an actor") + + +if __name__ == "__main__": + app.run(main) From 78df5c8e5a7e074561fbf59f7b296dbbdbbf64e2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 10:42:30 +0100 Subject: [PATCH 040/338] removed unnecessary TODOS --- serl_robot_infra/robot_controllers/robotiq_controller.py | 4 ++-- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 ----- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index acc825bc..7062c92e 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -53,7 +53,7 @@ def __init__( self.target_grip = np.zeros((1,), dtype=np.float32) self.curr_pos = np.zeros((7,), dtype=np.float32) self.curr_vel = np.zeros((6,), dtype=np.float32) - self.gripper_state = np.zeros((2,), dtype=np.float32) # TODO gripper state (sucking or not) + self.gripper_state = np.zeros((2,), dtype=np.float32) self.curr_Q = np.zeros((6,), dtype=np.float32) self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip @@ -253,7 +253,7 @@ async def run_async(self): if self.robotiq_gripper: self.target_grip[0] = -1. await self.send_gripper_command() - time.sleep(0.1) # TODO not sure if necessary + time.sleep(0.1) # then move to Jointspace position print(f"[RobotiqImpedanceController] moving to {self.reset_Q} with moveJ (joint space)") diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 944d33b5..3e900fef 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -201,11 +201,6 @@ def go_to_rest(self, joint_reset=False): Should override this method if custom reset procedure is needed. """ - # Perform joint reset if needed - if joint_reset: - pass - # TODO joint reset - # Perform Carteasian reset if self.random_reset: # randomize reset position in xy plane # reset_pose = self.resetpos.copy()ss From bd71ffe4728f6f96d43c55cb3ae4b4f6ed9acb9f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 12:02:35 +0100 Subject: [PATCH 041/338] bug fix --- serl_robot_infra/robot_controllers/robotiq_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 7062c92e..de32a382 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -93,7 +93,7 @@ async def start_robotiq_interfaces(self, gripper=True): if self.verbose: gr_string = "(with gripper) " if gripper else "" print(f"[RobotiqImpedanceController] Controller connected to robot {gr_string}at: {self.robot_ip}") - break + break except RuntimeError as e: print("[RobotiqImpedanceController] ", e.__str__()) continue From 5b9981e4661f5ad96c3b1a11f9acc25539a5fd75 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 12:02:52 +0100 Subject: [PATCH 042/338] name change --- examples/robotiq_grip_v1/record_demo.py | 2 +- serl_robot_infra/robotiq_env/__init__.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_grip_v1/record_demo.py index fd707ab7..f58f5072 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -31,7 +31,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq_grip-v1") + env = gym.make("robotiq-grip-v1") env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index 89467ba6..d2cbc162 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -2,7 +2,7 @@ import numpy as np register( - id="robotiq_grip-v1", + id="robotiq-grip-v1", entry_point="robotiq_env.envs.robotiq_grip_v1:RobotiqGripV1", max_episode_steps=100, ) \ No newline at end of file From 439c433521da60c756ba5086262252660a807767 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 15:24:44 +0100 Subject: [PATCH 043/338] bug fix, vel is 6D --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 3e900fef..341ff41e 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -100,7 +100,7 @@ def __init__( "tcp_pose": gym.spaces.Box( -np.inf, np.inf, shape=(7,) ), # xyz + quat - "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(7,)), + "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), "gripper_state": gym.spaces.Box(-np.inf, np.inf, shape=(2,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), From b3313e4e44b2e4bc1534c0a028d41a96f07a1a64 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 15:24:59 +0100 Subject: [PATCH 044/338] added BinaryReward wrapper --- serl_robot_infra/robotiq_env/envs/wrappers.py | 26 ++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index b09949ab..95df34a4 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -6,6 +6,8 @@ from robotiq_env.utils.rotations import quat_2_euler +sigmoid = lambda x: 1 / (1 + np.exp(-x)) + class SpacemouseIntervention(gym.ActionWrapper): def __init__(self, env): @@ -29,7 +31,7 @@ def action(self, action: np.ndarray) -> np.ndarray: """ expert_a = self.get_deadspace_action() - if np.linalg.norm(expert_a) > 0.001 or self.left or self.right: # also read buttons with no movement + if np.linalg.norm(expert_a) > 0.001 or self.left or self.right: # also read buttons with no movement self.last_intervene = time.time() if self.gripper_enabled: @@ -101,3 +103,25 @@ def observation(self, observation): (tcp_pose[:3], quat_2_euler(tcp_pose[3:])) ) return observation + + +class BinaryRewardClassifierWrapper(gym.Wrapper): + """ + Compute reward with custom binary reward classifier fn + """ + + def __init__(self, env: gym.Env, reward_classifier_func): + super().__init__(env) + self.reward_classifier_func = reward_classifier_func + + def compute_reward(self, obs): + if self.reward_classifier_func is not None: + logit = self.reward_classifier_func(obs).item() + return (sigmoid(logit) >= 0.5) * 1 + return 0 + + def step(self, action): + obs, rew, done, truncated, info = self.env.step(action) + rew = self.compute_reward(obs) + done = done or rew + return obs, rew, done, truncated, info From 0dc5fbd7bc931d1139153a380771c3b1934446c1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 15:25:13 +0100 Subject: [PATCH 045/338] do not use relative frame for now --- examples/robotiq_grip_v1/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_grip_v1/record_demo.py index f58f5072..fc3d7400 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_grip_v1/record_demo.py @@ -33,7 +33,7 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq-grip-v1") env = SpacemouseIntervention(env) - env = RelativeFrame(env) + # env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) From 633844932561562d7ae69980191bd5b858542fc1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 15:25:42 +0100 Subject: [PATCH 046/338] new limits in x and y --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 78e8621c..c07e42fa 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -10,7 +10,7 @@ class RobotiqCornerConfig(DefaultEnvConfig): RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.14, 0.07, 1., 3.3, 3.3, 3.3]) # TODO euler rotations suck :/ - ABS_POSE_LIMIT_LOW = np.array([-1., -1., -0.006, -3.3, -3.3, -3.3]) + ABS_POSE_LIMIT_LOW = np.array([-0.45, -0.78, -0.006, -3.3, -3.3, -3.3]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" From 95407ade2c621c6ded86e7af1d8cab21ef815779 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 16:13:41 +0100 Subject: [PATCH 047/338] do not ouput "state" dict, but rather raw array as observation --- .../serl_launcher/wrappers/serl_obs_wrappers.py | 14 ++++---------- 1 file changed, 4 insertions(+), 10 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 7f26597a..7ed392b3 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -27,20 +27,14 @@ def observation(self, obs): class SerlObsWrapperNoImages(gym.ObservationWrapper): """ - This observation wrapper treat the observation space as a dictionary - of a flattened state space, if no images are present. + This observation wrapper treat the observation space as a flattened state + space, if no images are present. """ def __init__(self, env): super().__init__(env) - self.observation_space = gym.spaces.Dict( - { - "state": flatten_space(self.env.observation_space["state"]) - } - ) + self.observation_space = flatten_space(self.env.observation_space["state"]) def observation(self, obs): - obs = { - "state": flatten(self.env.observation_space["state"], obs["state"]) - } + obs = flatten(self.env.observation_space["state"], obs["state"]) return obs From e280f239f16dba6f61c1cd3dbf0b136fabbac7c6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:20:21 +0100 Subject: [PATCH 048/338] fake env for sampling --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 341ff41e..6d3e1037 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -50,6 +50,7 @@ class RobotiqEnv(gym.Env): def __init__( self, hz: int = 10, + fake_env = False, config=DefaultEnvConfig, max_episode_length: int = 100 ): @@ -120,6 +121,9 @@ def __init__( ) self.cycle_count = 0 + if fake_env: + return + self.controller = RobotiqImpedanceController( robot_ip=config.ROBOT_IP, frequency=config.CONTROLLER_HZ, From 94748c1e69230c5e95815ac98849f222c7ba4a75 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:23:33 +0100 Subject: [PATCH 049/338] do not use drq, but sac. Not finished yet --- examples/robotiq_grip_v1/async_drq_v1.py | 211 ++++++++--------------- 1 file changed, 69 insertions(+), 142 deletions(-) diff --git a/examples/robotiq_grip_v1/async_drq_v1.py b/examples/robotiq_grip_v1/async_drq_v1.py index 6b8f977a..83e0c7a8 100644 --- a/examples/robotiq_grip_v1/async_drq_v1.py +++ b/examples/robotiq_grip_v1/async_drq_v1.py @@ -12,39 +12,40 @@ import gymnasium as gym from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics -from serl_launcher.agents.continuous.drq import DrQAgent +from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.evaluation import evaluate from serl_launcher.utils.timer_utils import Timer + from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.utils.train_utils import concat_batches from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore from serl_launcher.utils.launcher import ( - make_drq_agent, + make_sac_agent, make_trainer_config, make_wandb_logger, + make_replay_buffer, ) -from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore + from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper, BinaryRewardClassifierWrapper import robotiq_env FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_grip-v1", "Name of environment.") -flags.DEFINE_string("agent", "drq", "Name of agent.") +flags.DEFINE_string("env", "robotiq-grip-v1", "Name of environment.") +flags.DEFINE_string("agent", "sac", "Name of agent.") flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", False, "Whether to save model.") flags.DEFINE_integer("batch_size", 256, "Batch size.") -flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") +flags.DEFINE_integer("utd_ratio", 8, "UTD ratio.") -flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 200000, "Replay buffer capacity.") +flags.DEFINE_integer("max_steps", 100, "Maximum number of training steps.") +flags.DEFINE_integer("replay_buffer_capacity", 1000000, "Replay buffer capacity.") flags.DEFINE_integer("random_steps", 300, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 300, "Training starts after this step.") @@ -52,31 +53,20 @@ flags.DEFINE_integer("log_period", 10, "Logging period.") flags.DEFINE_integer("eval_period", 2000, "Evaluation period.") +flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") # flag to indicate if this is a leaner or a actor flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("render", False, "Render the environment.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights -flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") -flags.DEFINE_string("demo_path", "robotiq_test_20_demos_2024-03-19_16-04-24.pkl", "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") flags.DEFINE_string("checkpoint_path", 'checkpoint_test_path', "Path to save checkpoints.") -flags.DEFINE_integer( - "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" -) -flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") - flags.DEFINE_boolean( "debug", True, "Debug mode." ) # debug mode will disable wandb logging -devices = jax.local_devices() -num_devices = len(devices) -sharding = jax.sharding.PositionalSharding(devices) - def print_green(x): return print("\033[92m {}\033[00m".format(x)) @@ -85,49 +75,10 @@ def print_green(x): ############################################################################## -def actor(agent: DrQAgent, data_store, env, sampling_rng): +def actor(agent: SACAgent, data_store, env, sampling_rng): """ This is the actor loop, which runs when "--actor" is set to True. """ - if FLAGS.eval_checkpoint_step: - success_counter = 0 - time_list = [] - - ckpt = checkpoints.restore_checkpoint( - FLAGS.checkpoint_path, - agent.state, - step=FLAGS.eval_checkpoint_step, - ) - agent = agent.replace(state=ckpt) - - for episode in range(FLAGS.eval_n_trajs): - obs, _ = env.reset() - done = False - start_time = time.time() - while not done: - actions = agent.sample_actions( - observations=jax.device_put(obs), - argmax=True, - ) - actions = np.asarray(jax.device_get(actions)) - - next_obs, reward, done, truncated, info = env.step(actions) - obs = next_obs - - if done: - if reward: - dt = time.time() - start_time - time_list.append(dt) - print(dt) - - success_counter += reward - print(reward) - print(f"{success_counter}/{episode + 1}") - - print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") - print(f"average time: {np.mean(time_list)}") - return # after done eval, return and exit - client = TrainerClient( "actor_env", FLAGS.ip, @@ -143,13 +94,17 @@ def update_params(params): client.recv_network_callback(update_params) + eval_env = gym.make(FLAGS.env) + if FLAGS.env == "PandaPickCube-v0": + eval_env = gym.wrappers.FlattenObservation(eval_env) + eval_env = RecordEpisodeStatistics(eval_env) + obs, _ = env.reset() done = False # training loop timer = Timer() running_return = 0.0 - for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True): timer.tick("total") @@ -169,34 +124,43 @@ def update_params(params): with timer.context("step_env"): next_obs, reward, done, truncated, info = env.step(actions) - - # override the action with the intervention action - if "intervene_action" in info: - actions = info.pop("intervene_action") - + next_obs = np.asarray(next_obs, dtype=np.float32) reward = np.asarray(reward, dtype=np.float32) - info = np.asarray(info) + running_return += reward - transition = dict( - observations=obs, - actions=actions, - next_observations=next_obs, - rewards=reward, - masks=1.0 - done, - dones=done, + + data_store.insert( + dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=reward, + masks=1.0 - done, + dones=done or truncated, + ) ) - data_store.insert(transition) obs = next_obs if done or truncated: - stats = {"train": info} # send stats to the learner to log - client.request("send-stats", stats) running_return = 0.0 obs, _ = env.reset() + if FLAGS.render: + env.render() + if step % FLAGS.steps_per_update == 0: client.update() + if step % FLAGS.eval_period == 0: + with timer.context("eval"): + evaluate_info = evaluate( + policy_fn=partial(agent.sample_actions, argmax=True), + env=eval_env, + num_episodes=FLAGS.eval_n_trajs, + ) + stats = {"eval": evaluate_info} + client.request("send-stats", stats) + timer.tock("total") if step % FLAGS.log_period == 0: @@ -207,7 +171,7 @@ def update_params(params): ############################################################################## -def learner(rng, agent: DrQAgent, replay_buffer, demo_buffer, wandb_logger=None): +def learner(rng, agent: SACAgent, replay_buffer, replay_iterator, wandb_logger=None): """ The learner loop, which runs when "--learner" is set to True. """ @@ -244,47 +208,18 @@ def stats_callback(type: str, payload: dict) -> dict: server.publish_network(agent.state.params) print_green("sent initial network to actor") - # 50/50 sampling from RLPD, half from demo and half from online experience - replay_iterator = replay_buffer.get_iterator( - sample_args={ - "batch_size": FLAGS.batch_size // 2, - "pack_obs_and_next_obs": True, - }, - device=sharding.replicate(), - ) - demo_iterator = demo_buffer.get_iterator( - sample_args={ - "batch_size": FLAGS.batch_size // 2, - "pack_obs_and_next_obs": True, - }, - device=sharding.replicate(), - ) - # wait till the replay buffer is filled with enough data timer = Timer() for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): - # run n-1 critic updates and 1 critic + actor update. - # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU - for critic_step in range(FLAGS.utd_ratio - 1): - with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) - demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) - - with timer.context("train_critics"): - agent, critics_info = agent.update_critics( - batch, - ) - - with timer.context("train"): + # Train the networks + with timer.context("sample_replay_buffer"): batch = next(replay_iterator) - demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) - agent, update_info = agent.update_high_utd(batch, utd_ratio=1) - # publish the updated network - if step > 0 and step % (FLAGS.steps_per_update) == 0: + with timer.context("train"): + agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) agent = jax.block_until_ready(agent) + + # publish the updated network server.publish_network(agent.state.params) if update_steps % FLAGS.log_period == 0 and wandb_logger: @@ -294,7 +229,7 @@ def stats_callback(type: str, payload: dict) -> dict: if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: assert FLAGS.checkpoint_path is not None checkpoints.save_checkpoint( - FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 + FLAGS.checkpoint_path, agent.state, step=update_steps, keep=20 ) update_steps += 1 @@ -304,7 +239,11 @@ def stats_callback(type: str, payload: dict) -> dict: def main(_): + devices = jax.local_devices() + num_devices = len(devices) + sharding = jax.sharding.PositionalSharding(devices) assert FLAGS.batch_size % num_devices == 0 + # seed rng = jax.random.PRNGKey(FLAGS.seed) @@ -318,32 +257,28 @@ def main(_): env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) - # TODO adapt to "async_sac_state_sim.py" --> SAC with no images (DRQ needs images) - - image_keys = [key for key in env.observation_space.keys() if key != "state"] - rng, sampling_rng = jax.random.split(rng) - agent: DrQAgent = make_drq_agent( + agent: SACAgent = make_sac_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), sample_action=env.action_space.sample(), - image_keys=image_keys, - encoder_type=FLAGS.encoder_type, ) # replicate agent across devices # need the jnp.array to avoid a bug where device_put doesn't recognize primitives - agent: DrQAgent = jax.device_put( + agent: SACAgent = jax.device_put( jax.tree_map(jnp.array, agent), sharding.replicate() ) def create_replay_buffer_and_wandb_logger(): - replay_buffer = MemoryEfficientReplayBufferDataStore( - env.observation_space, - env.action_space, + replay_buffer = make_replay_buffer( + env, capacity=FLAGS.replay_buffer_capacity, - image_keys=image_keys, + rlds_logger_path=FLAGS.log_rlds_path, + type="replay_buffer", + preload_rlds_path=FLAGS.preload_rlds_path, ) + # set up wandb and logging wandb_logger = make_wandb_logger( project="serl_dev", @@ -355,27 +290,19 @@ def create_replay_buffer_and_wandb_logger(): if FLAGS.learner: sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() - demo_buffer = MemoryEfficientReplayBufferDataStore( - env.observation_space, - env.action_space, - capacity=10000, - image_keys=image_keys, + replay_iterator = replay_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size * FLAGS.utd_ratio, + }, + device=sharding.replicate(), ) - import pickle as pkl - - with open(FLAGS.demo_path, "rb") as f: - trajs = pkl.load(f) - for traj in trajs: - demo_buffer.insert(traj) - print(f"demo buffer size: {len(demo_buffer)}") - # learner loop print_green("starting learner loop") learner( sampling_rng, agent, replay_buffer, - demo_buffer=demo_buffer, + replay_iterator=replay_iterator, wandb_logger=wandb_logger, ) From 850e6c846063e598164271926e556d9c549f0cac Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:24:12 +0100 Subject: [PATCH 050/338] implemented behavioral cloning agent without image data --- .../agents/continuous/bc_noimg.py | 149 ++++++++++++++++++ 1 file changed, 149 insertions(+) create mode 100644 serl_launcher/serl_launcher/agents/continuous/bc_noimg.py diff --git a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py new file mode 100644 index 00000000..13b56fbe --- /dev/null +++ b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py @@ -0,0 +1,149 @@ +from functools import partial +from typing import Any, Iterable, Optional + +import flax +import jax +import jax.numpy as jnp +import numpy as np +import optax + +from serl_launcher.common.common import JaxRLTrainState, ModuleDict +from serl_launcher.common.typing import Batch, PRNGKey, Data +from serl_launcher.networks.actor_critic_nets import Policy +from serl_launcher.networks.mlp import MLP +from serl_launcher.utils.train_utils import _unpack +from serl_launcher.vision.data_augmentations import batched_random_crop + +""" +Behavioral cloning without using image data as observation, only state data +""" + + +class BCAgentNoImg(flax.struct.PyTreeNode): + state: JaxRLTrainState + + @partial(jax.jit, static_argnames="pmap_axis") + def update(self, batch: Batch, pmap_axis: str = None): + # if self.config["image_keys"][0] not in batch["next_observations"]: + # batch = _unpack(batch) # TODO do include? + + # rng = self.state.rng + # rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) + # obs = self.data_augmentation_fn(obs_rng, batch["observations"]) + # batch = batch.copy(add_or_replace={"observations": obs}) + + def loss_fn(params, rng): + rng, key = jax.random.split(rng) + dist = self.state.apply_fn( + {"params": params}, + batch["observations"], + temperature=1.0, + train=True, + rngs={"dropout": key}, + name="actor", + ) + pi_actions = dist.mode() + log_probs = dist.log_prob(batch["actions"]) + mse = ((pi_actions - batch["actions"]) ** 2).sum(-1) + actor_loss = -(log_probs).mean() + actor_std = dist.stddev().mean(axis=1) + + return actor_loss, { + "actor_loss": actor_loss, + "mse": mse.mean(), + # "log_probs": log_probs, + # "pi_actions": pi_actions, + # "mean_std": actor_std.mean(), + # "max_std": actor_std.max(), + } + + # compute gradients and update params + new_state, info = self.state.apply_loss_fns( + loss_fn, pmap_axis=pmap_axis, has_aux=True + ) + + return self.replace(state=new_state), info + + @partial(jax.jit, static_argnames="argmax") # no img data present + def sample_actions( + self, + observations: np.ndarray, + *, + seed: Optional[PRNGKey] = None, + temperature: float = 1.0, + argmax=False, + ) -> jnp.ndarray: + dist = self.state.apply_fn( + {"params": self.state.params}, + observations, + temperature=temperature, + name="actor", + ) + if argmax: + actions = dist.mode() + else: + actions = dist.sample(seed=seed) + return actions + + @jax.jit + def get_debug_metrics(self, batch, **kwargs): + dist = self.state.apply_fn( + {"params": self.state.params}, + batch["observations"], + temperature=1.0, + name="actor", + ) + pi_actions = dist.mode() + log_probs = dist.log_prob(batch["actions"]) + mse = ((pi_actions - batch["actions"]) ** 2).sum(-1) + + return { + "mse": mse, + "log_probs": log_probs, + "pi_actions": pi_actions, + } + + @classmethod + def create( + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Model architecture + network_kwargs: dict = dict(hidden_dims=[256, 256]), + policy_kwargs: dict = dict(tanh_squash_distribution=False), + # Optimizer + learning_rate: float = 3e-4, + ): + """ + create agent with no encoders + """ + + network_kwargs["activate_final"] = True + networks = { + "actor": Policy( + None, + MLP(**network_kwargs), + action_dim=actions.shape[-1], + **policy_kwargs, + ) + } + + model_def = ModuleDict(networks) + + tx = optax.adam(learning_rate) + + rng, init_rng = jax.random.split(rng) + params = model_def.init(init_rng, actor=[observations])["params"] + + rng, create_rng = jax.random.split(rng) + state = JaxRLTrainState.create( + apply_fn=model_def.apply, + params=params, + txs=tx, + target_params=params, + rng=create_rng, + ) + + agent = cls(state) + return agent From c967291916ac9d1c0ec2fbf5d595eaf9f2dbc998 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:24:29 +0100 Subject: [PATCH 051/338] use new bc agent for the robotiq arm --- examples/bc_policy_robotiq.py | 225 ++++++++++++++++++++++++++++++++++ 1 file changed, 225 insertions(+) create mode 100644 examples/bc_policy_robotiq.py diff --git a/examples/bc_policy_robotiq.py b/examples/bc_policy_robotiq.py new file mode 100644 index 00000000..924076d5 --- /dev/null +++ b/examples/bc_policy_robotiq.py @@ -0,0 +1,225 @@ +from tqdm import tqdm +from absl import app, flags +from flax.training import checkpoints +import jax +from jax import numpy as jnp +import pickle as pkl +import numpy as np +from copy import deepcopy +import time + +import gymnasium as gym +from gymnasium.wrappers import RecordEpisodeStatistics + +from serl_launcher.utils.timer_utils import Timer +from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.agents.continuous.bc_noimg import BCAgentNoImg + +from serl_launcher.utils.launcher import ( + make_bc_agent_no_img, + make_wandb_logger, + make_replay_buffer, +) +from serl_launcher.data.data_store import ( + MemoryEfficientReplayBufferDataStore, + populate_data_store, + populate_data_store_with_z_axis_only, +) +from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages +from serl_launcher.networks.reward_classifier import load_classifier_func +from franka_env.envs.relative_env import RelativeFrame +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper + +import robotiq_env + +FLAGS = flags.FLAGS + +flags.DEFINE_string("env", "robotiq-grip-v1", "Name of environment.") +flags.DEFINE_string("agent", "bc_noimg", "Name of agent.") +flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") +flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_integer("seed", 42, "Random seed.") +flags.DEFINE_bool("save_model", True, "Whether to save model.") +flags.DEFINE_integer("batch_size", 256, "Batch size.") + +flags.DEFINE_integer("max_steps", 10000, "Maximum number of training steps.") +flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") + +flags.DEFINE_multi_string("demo_paths", "robotiq_grip_v1/robotiq_test_20_demos_2024-03-20_15-09-46.pkl", + "paths to demos") +flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/checkpoints", "Path to save checkpoints.") + +flags.DEFINE_integer( + "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" +) +flags.DEFINE_integer("eval_n_trajs", 100, "Number of trajectories for evaluation.") + +flags.DEFINE_boolean( + "debug", True, "Debug mode." +) # debug mode will disable wandb logging +flags.DEFINE_string( + "reward_classifier_ckpt_path", + None, + "Path to reward classifier checkpoint. Default: None", +) + +devices = jax.local_devices() +num_devices = len(devices) +sharding = jax.sharding.PositionalSharding(devices) + + +def main(_): + assert FLAGS.batch_size % num_devices == 0 + rng = jax.random.PRNGKey(FLAGS.seed) + + # create env and load dataset + print(FLAGS.env) + env = gym.make( + FLAGS.env, + fake_env=not FLAGS.eval_checkpoint_step, + ) + env = SpacemouseIntervention(env) + # env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SerlObsWrapperNoImages(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = RecordEpisodeStatistics(env) + + print(1) + + rng, sampling_rng = jax.random.split(rng) + agent: BCAgentNoImg = make_bc_agent_no_img( # replace with no img one + FLAGS.seed, + env.observation_space.sample(), + env.action_space.sample(), + ) + + print(2) + + wandb_logger = make_wandb_logger( + project="serl_dev", + description=FLAGS.exp_name or FLAGS.env, + debug=FLAGS.debug, + ) + print(3) + + + if not FLAGS.eval_checkpoint_step: + """ + Training Mode + """ + sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) + # load demos and populate to current replay buffer + replay_buffer = make_replay_buffer( + env, + capacity=FLAGS.replay_buffer_capacity, + type="replay_buffer", + # rlds_logger_path=FLAGS.log_rlds_path, # can be added to log + # preload_rlds_path=FLAGS.preload_rlds_path, + ) + + print(4) + + replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) + + replay_iterator = replay_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size, + }, + device=sharding.replicate(), + ) + + for step in tqdm(range(FLAGS.max_steps)): + batch = next(replay_iterator) + agent, info = agent.update(batch) + wandb_logger.log(info, step=step) + + if (step + 1) % 1000 == 0 and FLAGS.save_model: # TODO was 10'000 + checkpoints.save_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=step + 1, + keep=100, + overwrite=True, + ) + + else: + """ + Evaluation Mode + """ + from pynput import keyboard + + is_failure = False + is_success = False + + def esc_on_press(key): + nonlocal is_failure + if key == keyboard.Key.esc: + is_failure = True + + def space_on_press(key): + nonlocal is_success + if key == keyboard.Key.space and not is_success: + is_success = True + + esc_listener = keyboard.Listener(on_press=esc_on_press) + esc_listener.start() + space_listener = keyboard.Listener(on_press=space_on_press) + space_listener.start() + + ckpt = checkpoints.restore_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=FLAGS.eval_checkpoint_step, + ) + agent = agent.replace(state=ckpt) + + success_counter = 0 + time_list = [] + + for episode in range(FLAGS.eval_n_trajs): + obs, _ = env.reset() + done = False + is_failure = False + is_success = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=True, + ) + actions = np.asarray(jax.device_get(actions)) + + next_obs, reward, done, truncated, info = env.step(actions) + obs = next_obs + + if is_failure: + done = True + print("terminated by user") + + if is_success: + reward = 1 + done = True + print("success, reset now") + + if done: + if not is_failure: + dt = time.time() - start_time + time_list.append(dt) + print(dt) + + success_counter += reward + print(reward) + print(f"{success_counter}/{episode + 1}") + + wandb_logger.log(info, step=episode) + + print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") + print(f"average time: {np.mean(time_list)}") + + print("done") + env.close() + + +if __name__ == "__main__": + app.run(main) From 926347581032d651f8290543a1cf68c830495471 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:24:52 +0100 Subject: [PATCH 052/338] change back to 100Hz --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index c07e42fa..9fdb56d4 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -14,7 +14,7 @@ class RobotiqCornerConfig(DefaultEnvConfig): ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" - CONTROLLER_HZ = 200 + CONTROLLER_HZ = 100 ERROR_DELTA: float = 0.05 FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) From cd70fdaa9108295de3273a8036ac5e8e3f51530a Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:25:15 +0100 Subject: [PATCH 053/338] added bc agent creation function --- serl_launcher/serl_launcher/utils/launcher.py | 22 +++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 44ed7dec..003b5d7c 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -14,6 +14,7 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.agents.continuous.drq import DrQAgent from serl_launcher.agents.continuous.vice import VICEAgent +from serl_launcher.agents.continuous.bc_noimg import BCAgentNoImg from serl_launcher.data.data_store import ( MemoryEfficientReplayBufferDataStore, @@ -47,6 +48,27 @@ def make_bc_agent( ) +def make_bc_agent_no_img( + seed, sample_obs, sample_action +): + return BCAgentNoImg.create( + jax.random.PRNGKey(seed), + sample_obs, + sample_action, + network_kwargs={ + "activations": nn.tanh, + "use_layer_norm": False, + "hidden_dims": [256, 256], + }, + policy_kwargs={ + "tanh_squash_distribution": False, + "std_parameterization": "exp", + "std_min": 1e-5, + "std_max": 5, + }, + ) + + def make_sac_agent(seed, sample_obs, sample_action): return SACAgent.create_states( jax.random.PRNGKey(seed), From 8e63a5b5a752807e17da45984836fdb82a7e7eed Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 20 Mar 2024 17:25:39 +0100 Subject: [PATCH 054/338] added output in second console (tail -f ...) --- .../robot_controllers/robotiq_controller.py | 27 +++++++++++++------ 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index de32a382..8510c98a 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -1,3 +1,4 @@ +import datetime import time import threading import asyncio @@ -13,7 +14,6 @@ np.set_printoptions(precision=4, suppress=True) - def pos_difference(quat_pose_1: np.ndarray, quat_pose_2: np.ndarray): assert quat_pose_1.shape == (7,) assert quat_pose_2.shape == (7,) @@ -76,10 +76,17 @@ def __init__( self.err = 0 self.noerr = 0 + with open("/tmp/console2.txt", 'w') as f: + f.write("reset\n") + self.second_console = open("/tmp/console2.txt", 'a') + def start(self): super().start() if self.verbose: - print(f"[RobotiqImpedanceController] Controller process spawned at {self.native_id}") + print(f"[RIC] Controller process spawned at {self.native_id}") + + def print(self, msg): + self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') async def start_robotiq_interfaces(self, gripper=True): for _ in range(5): # try it 5 times @@ -92,12 +99,12 @@ async def start_robotiq_interfaces(self, gripper=True): await self.robotiq_gripper.activate() if self.verbose: gr_string = "(with gripper) " if gripper else "" - print(f"[RobotiqImpedanceController] Controller connected to robot {gr_string}at: {self.robot_ip}") + print(f"[RIC] Controller connected to robot {gr_string}at: {self.robot_ip}") break except RuntimeError as e: - print("[RobotiqImpedanceController] ", e.__str__()) + print("[RIC] ", e.__str__()) continue - # raise RuntimeError(f"[RobotiqImpedanceController] Could not connect to robot [{self.robot_ip}]") + # raise RuntimeError(f"[RIC] Could not connect to robot [{self.robot_ip}]") def stop(self): self._stop.set() @@ -111,7 +118,7 @@ def set_target_pos(self, target_pos: np.ndarray): elif target_pos.shape == (6,): target_orientation = rotvec_2_quat(target_pos[3:]) else: - raise ValueError(f"[RobotiqImpedanceController] target pos has shape {target_pos.shape}") + raise ValueError(f"[RIC] target pos has shape {target_pos.shape}") with self.lock: self.target_pos[:3] = target_pos[:3] @@ -196,7 +203,7 @@ def plot(self): self.robotiq_control.forceModeStop() - print("[RobotiqImpedanceController] plotting") + print("[RIC] plotting") real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) target_pos = np.array([pose2rotvec(q) for q in self.hist_data[1]]) @@ -244,6 +251,7 @@ async def run_async(self): self.robotiq_control.zeroFtSensor() await self._update_robot_state() self.target_pos = self.curr_pos.copy() + print(f"[RIC] target position set to curr pos: {self.target_pos}") self._is_ready.set() @@ -256,7 +264,7 @@ async def run_async(self): time.sleep(0.1) # then move to Jointspace position - print(f"[RobotiqImpedanceController] moving to {self.reset_Q} with moveJ (joint space)") + print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)") self.robotiq_control.forceModeStop() self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.5) @@ -281,6 +289,7 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) + self.print(f"{self.target_pos}, {self.curr_pos}, {force}") # output to file # send command to robot t_start = self.robotiq_control.initPeriod() @@ -291,6 +300,8 @@ async def run_async(self): 2, self.fm_limits ) + # if np.sum(np.abs(force)) > 50: + # print("high force: ", force) # TODO try to reset with moveJ if forcemode returns False if self.robotiq_gripper: From 20afb53becb97db6f2dcf0b92c24a6f1e12fd89a Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 15:56:59 +0100 Subject: [PATCH 055/338] shell script for actor / learner --- examples/run_rbc_actor.sh | 10 ++++++++++ examples/run_rbc_learner.sh | 10 ++++++++++ 2 files changed, 20 insertions(+) create mode 100644 examples/run_rbc_actor.sh create mode 100644 examples/run_rbc_learner.sh diff --git a/examples/run_rbc_actor.sh b/examples/run_rbc_actor.sh new file mode 100644 index 00000000..2a3e3a8e --- /dev/null +++ b/examples/run_rbc_actor.sh @@ -0,0 +1,10 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +which python && \ +python bc_policy_robotiq.py "$@" \ + --env robotiq-grip-v1 \ + --exp_name=bc_robotiq_policy \ + --seed 42 \ + --batch_size 256 \ + --eval_checkpoint_step 100000 \ + --debug # wandb is disabled when debug diff --git a/examples/run_rbc_learner.sh b/examples/run_rbc_learner.sh new file mode 100644 index 00000000..adb9a958 --- /dev/null +++ b/examples/run_rbc_learner.sh @@ -0,0 +1,10 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python bc_policy_robotiq.py "$@" \ + --env robotiq-grip-v1 \ + --exp_name=bc_robotiq_policy \ + --seed 42 \ + --batch_size 256 \ + --demo_paths robotiq_grip_v1/robotiq_test_20_demos_2024-03-20_15-09-46.pkl \ + --eval_checkpoint_step 0 \ + --debug # wandb is disabled when debug From 880dfc514490a93675754be8c12754665d924720 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 15:57:29 +0100 Subject: [PATCH 056/338] target pose removal & bug fix --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 6d3e1037..031fcbfc 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -18,8 +18,6 @@ class DefaultEnvConfig: """Default configuration for RobotiqEnv. Fill in the values below.""" - TARGET_POSE: np.ndarray = np.zeros((6,)) # might change as well - REWARD_THRESHOLD: np.ndarray = np.zeros((6,)) RESET_Q = np.zeros((6,)) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) @@ -54,8 +52,6 @@ def __init__( config=DefaultEnvConfig, max_episode_length: int = 100 ): - self._TARGET_POSE = config.TARGET_POSE # TODO not used for now, same for threshold - self._REWARD_THRESHOLD = config.REWARD_THRESHOLD self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -120,6 +116,7 @@ def __init__( } ) self.cycle_count = 0 + self.controller = None if fake_env: return @@ -284,5 +281,6 @@ def _get_obs(self) -> dict: return copy.deepcopy(dict(state=state_observation)) def close(self): - self.controller.stop() + if self.controller: + self.controller.stop() super().close() From 10cc060168bc0354cfd077b977e7f68ba47e4197 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 15:57:45 +0100 Subject: [PATCH 057/338] restrict pose orientation --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 9fdb56d4..dc327672 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -3,14 +3,12 @@ class RobotiqCornerConfig(DefaultEnvConfig): - TARGET_POSE: np.ndarray = np.array([-0.23454916629572226, -0.6939331362168063, 0.1548973281273407, 2.9025739504570782, 1.1983948447880342, -0.08076374785512226]) - REWARD_THRESHOLD: np.ndarray = np.array([0.01, 0.01, 0.01, 0.2, 0.2, 0.2]) RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.14, 0.07, 1., 3.3, 3.3, 3.3]) # TODO euler rotations suck :/ - ABS_POSE_LIMIT_LOW = np.array([-0.45, -0.78, -0.006, -3.3, -3.3, -3.3]) + ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ + ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" From f943967087d33631ed69237b8337e6c287cc3a82 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 17:26:54 +0100 Subject: [PATCH 058/338] no debug for wandb --- examples/run_rbc_actor.sh | 4 ++-- examples/run_rbc_learner.sh | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/run_rbc_actor.sh b/examples/run_rbc_actor.sh index 2a3e3a8e..6d4f1d35 100644 --- a/examples/run_rbc_actor.sh +++ b/examples/run_rbc_actor.sh @@ -6,5 +6,5 @@ python bc_policy_robotiq.py "$@" \ --exp_name=bc_robotiq_policy \ --seed 42 \ --batch_size 256 \ - --eval_checkpoint_step 100000 \ - --debug # wandb is disabled when debug + --eval_checkpoint_step 40000 \ +# --debug # wandb is disabled when debug diff --git a/examples/run_rbc_learner.sh b/examples/run_rbc_learner.sh index adb9a958..41e02136 100644 --- a/examples/run_rbc_learner.sh +++ b/examples/run_rbc_learner.sh @@ -6,5 +6,5 @@ python bc_policy_robotiq.py "$@" \ --seed 42 \ --batch_size 256 \ --demo_paths robotiq_grip_v1/robotiq_test_20_demos_2024-03-20_15-09-46.pkl \ - --eval_checkpoint_step 0 \ - --debug # wandb is disabled when debug + --eval_checkpoint_step 0 +# --debug # wandb is disabled when debug From b2aa67613f7eef7aad63d91aa8d67b7b6d851259 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 17:27:12 +0100 Subject: [PATCH 059/338] new reward (might not be smart...) --- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index e3349d6e..e000b6f6 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -6,8 +6,10 @@ class RobotiqGripV1(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) - def compute_reward(self, obs) -> bool: + def compute_reward(self, obs) -> float: if int(self.gripper_state[1]) == 1 and 10 < self.gripper_state[0] < 30 and self.curr_force[2] < -1.: - return True + return 1. + elif self.curr_force[2] > 3.: # neg reward if the downward force is too big + return -0.5 else: - return False \ No newline at end of file + return 0.0 From cc76f481060c65e66ef98ff6e47cff17ee0e4145 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 25 Mar 2024 17:27:47 +0100 Subject: [PATCH 060/338] wandb setup --- examples/bc_policy_robotiq.py | 32 ++++++++++++++------------------ 1 file changed, 14 insertions(+), 18 deletions(-) diff --git a/examples/bc_policy_robotiq.py b/examples/bc_policy_robotiq.py index 924076d5..c7e95231 100644 --- a/examples/bc_policy_robotiq.py +++ b/examples/bc_policy_robotiq.py @@ -27,7 +27,7 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.networks.reward_classifier import load_classifier_func -from franka_env.envs.relative_env import RelativeFrame +# from franka_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper import robotiq_env @@ -40,14 +40,15 @@ flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", True, "Whether to save model.") -flags.DEFINE_integer("batch_size", 256, "Batch size.") +flags.DEFINE_integer("batch_size", 512, "Batch size.") -flags.DEFINE_integer("max_steps", 10000, "Maximum number of training steps.") +flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") -flags.DEFINE_multi_string("demo_paths", "robotiq_grip_v1/robotiq_test_20_demos_2024-03-20_15-09-46.pkl", +flags.DEFINE_multi_string("demo_paths", "robotiq_grip_v1/robotiq_test_20_demos_2024-03-25_16-39-22.pkl", "paths to demos") -flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/checkpoints", "Path to save checkpoints.") +flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/checkpoints", + "Path to save checkpoints.") flags.DEFINE_integer( "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" @@ -55,7 +56,7 @@ flags.DEFINE_integer("eval_n_trajs", 100, "Number of trajectories for evaluation.") flags.DEFINE_boolean( - "debug", True, "Debug mode." + "debug", False, "Debug mode." ) # debug mode will disable wandb logging flags.DEFINE_string( "reward_classifier_ckpt_path", @@ -82,27 +83,21 @@ def main(_): # env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) - env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) - print(1) - rng, sampling_rng = jax.random.split(rng) - agent: BCAgentNoImg = make_bc_agent_no_img( # replace with no img one + agent: BCAgentNoImg = make_bc_agent_no_img( # replace with no img one FLAGS.seed, env.observation_space.sample(), env.action_space.sample(), ) - print(2) - wandb_logger = make_wandb_logger( - project="serl_dev", + project="real-world-rl", description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) - print(3) - if not FLAGS.eval_checkpoint_step: """ @@ -118,8 +113,6 @@ def main(_): # preload_rlds_path=FLAGS.preload_rlds_path, ) - print(4) - replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) replay_iterator = replay_buffer.get_iterator( @@ -134,7 +127,7 @@ def main(_): agent, info = agent.update(batch) wandb_logger.log(info, step=step) - if (step + 1) % 1000 == 0 and FLAGS.save_model: # TODO was 10'000 + if (step + 1) % 10000 == 0 and FLAGS.save_model: checkpoints.save_checkpoint( FLAGS.checkpoint_path, agent.state, @@ -143,6 +136,8 @@ def main(_): overwrite=True, ) + wandb_logger.join() + else: """ Evaluation Mode @@ -189,6 +184,7 @@ def space_on_press(key): argmax=True, ) actions = np.asarray(jax.device_get(actions)) + print(f"sampled actions: {actions}") next_obs, reward, done, truncated, info = env.step(actions) obs = next_obs From fc3cc22021654b22db0dadb3caa40f3220747805 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 11:36:45 +0100 Subject: [PATCH 061/338] check demo repeatibility --- examples/robotiq_grip_v1/test_demo.py | 72 +++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 examples/robotiq_grip_v1/test_demo.py diff --git a/examples/robotiq_grip_v1/test_demo.py b/examples/robotiq_grip_v1/test_demo.py new file mode 100644 index 00000000..e73dcb74 --- /dev/null +++ b/examples/robotiq_grip_v1/test_demo.py @@ -0,0 +1,72 @@ +import numpy as np +import threading +import pickle as pkl +import gymnasium as gym +from pynput import keyboard + +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages + +exit_program = threading.Event() + +""" +Script to test the demos recorded --> they can be repeated easily (if the box is in the same position) +""" + + +def on_space(key, info_dict): + if key == keyboard.Key.space: + for key, item in info_dict.items(): + print(f'{key}: {item}', end=' ') + print() + + +def on_esc(key): + if key == keyboard.Key.esc: + exit_program.set() + + +if __name__ == "__main__": + env = gym.make("robotiq-grip-v1") + env = SpacemouseIntervention(env) + # env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SerlObsWrapperNoImages(env) + # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + + obs, _ = env.reset() + + info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, + 'force': env.unwrapped.curr_force} + listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) + listener_1.start() + + listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) + listener_2.start() + + file_path = "robotiq_test_20_demos_2024-03-25_16-39-22.pkl" + + with open(file_path, "rb") as f: + transitions = pkl.load(f) + + try: + for transition in transitions: + if exit_program.is_set(): + raise KeyboardInterrupt # stop program, but clean up before + + action = transition["actions"] + next_obs, rew, done, truncated, info = env.step(action=action) + + print(next_obs - transition["next_observations"]) + + if transition["dones"] or done: + print(f"done with {transition['dones']} {done}") + env.reset() + + except KeyboardInterrupt: + print(f'\nProgram was interrupted, cleaning up...') + + finally: + env.close() + listener_1.stop() + listener_2.stop() From d768038a63462cde4f4b90e4107d3ee847348546 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 11:36:59 +0100 Subject: [PATCH 062/338] add more wandb logging --- serl_launcher/serl_launcher/agents/continuous/bc_noimg.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py index 13b56fbe..26f28849 100644 --- a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py +++ b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py @@ -51,10 +51,10 @@ def loss_fn(params, rng): return actor_loss, { "actor_loss": actor_loss, "mse": mse.mean(), - # "log_probs": log_probs, - # "pi_actions": pi_actions, - # "mean_std": actor_std.mean(), - # "max_std": actor_std.max(), + "log_probs": log_probs, + "pi_actions": pi_actions, + "mean_std": actor_std.mean(), + "max_std": actor_std.max(), } # compute gradients and update params From c27f22ca7badad2a58ff2f9989fd991011c45eee Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 11:37:07 +0100 Subject: [PATCH 063/338] bugfix --- examples/bc_policy_robotiq.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/examples/bc_policy_robotiq.py b/examples/bc_policy_robotiq.py index c7e95231..47d01452 100644 --- a/examples/bc_policy_robotiq.py +++ b/examples/bc_policy_robotiq.py @@ -136,8 +136,6 @@ def main(_): overwrite=True, ) - wandb_logger.join() - else: """ Evaluation Mode From bbb0b41d90ed7f5295aa9e67933d827aa030c03d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 14:17:02 +0100 Subject: [PATCH 064/338] truncate if force is too big --- examples/bc_policy_robotiq.py | 9 ++++++++- .../robot_controllers/robotiq_controller.py | 17 +++++++++++++---- .../robotiq_env/envs/robotiq_env.py | 19 +++++++++++-------- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 2 -- 4 files changed, 32 insertions(+), 15 deletions(-) diff --git a/examples/bc_policy_robotiq.py b/examples/bc_policy_robotiq.py index 47d01452..de8751e8 100644 --- a/examples/bc_policy_robotiq.py +++ b/examples/bc_policy_robotiq.py @@ -113,6 +113,7 @@ def main(_): # preload_rlds_path=FLAGS.preload_rlds_path, ) + print(f"loaded demos from {FLAGS.demo_paths}") replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) replay_iterator = replay_buffer.get_iterator( @@ -179,7 +180,8 @@ def space_on_press(key): while not done: actions = agent.sample_actions( observations=jax.device_put(obs), - argmax=True, + argmax=False, + seed=rng, ) actions = np.asarray(jax.device_get(actions)) print(f"sampled actions: {actions}") @@ -196,6 +198,11 @@ def space_on_press(key): done = True print("success, reset now") + if truncated: + reward = 0 + done = True + print("truncated, reset now") + if done: if not is_failure: dt = time.time() - start_time diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 8510c98a..1fadba0b 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -59,6 +59,7 @@ def __init__( self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space + self._is_truncated = False self.delta = config.ERROR_DELTA self.fm_damping = config.FORCEMODE_DAMPING @@ -224,16 +225,25 @@ def plot(self): self.stop() async def send_gripper_command(self): - if self.target_grip[0] > 0.9 and self.gripper_state[0] == 100: + if self.target_grip[0] > 0.5 and self.gripper_state[0] == 100: await self.robotiq_gripper.automatic_grip() self.target_grip[0] = 0.0 # print("grip") - elif self.target_grip[0] < -0.9 and self.gripper_state[1] != 3: # only release if obj detected + elif self.target_grip[0] < -0.5 and self.gripper_state[1] != 3: # only release if obj detected await self.robotiq_gripper.automatic_release() self.target_grip[0] = 0.0 # print("release") + def _truncate_check(self): + if self.curr_force[2] > 8.: # TODO add better criteria + self._is_truncated = True + else: + self._is_truncated = False + + def is_truncated(self): + return self._is_truncated + def run(self): try: asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands @@ -281,6 +291,7 @@ async def run_async(self): # update robot state await self._update_robot_state() + self._truncate_check() # only used for plotting if self.do_plot: @@ -300,8 +311,6 @@ async def run_async(self): 2, self.fm_limits ) - # if np.sum(np.abs(force)) > 50: - # print("high force: ", force) # TODO try to reset with moveJ if forcemode returns False if self.robotiq_gripper: diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 031fcbfc..3d8acceb 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -7,7 +7,6 @@ from typing import Dict from scipy.spatial.transform import Rotation as R - from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController @@ -48,7 +47,7 @@ class RobotiqEnv(gym.Env): def __init__( self, hz: int = 10, - fake_env = False, + fake_env=False, config=DefaultEnvConfig, max_episode_length: int = 100 ): @@ -133,7 +132,7 @@ def __init__( self.controller.start() # start Thread - while not self.controller.is_ready(): # wait for controller + while not self.controller.is_ready(): # wait for controller time.sleep(0.1) def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat @@ -170,7 +169,7 @@ def step(self, action: np.ndarray) -> tuple: next_pos = self.controller.get_target_pos() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] - # orientation (leave for now) + # orientation next_pos[3:] = ( R.from_quat(next_pos[3:]) * R.from_euler("xyz", action[3:6] * self.action_scale[1]) ).as_quat() @@ -189,11 +188,12 @@ def step(self, action: np.ndarray) -> tuple: self._update_currpos() ob = self._get_obs() reward = self.compute_reward(ob) - done = self.curr_path_length >= self.max_episode_length or reward - return ob, int(reward), done, False, {} + truncated = self._is_truncated() + done = self.curr_path_length >= self.max_episode_length or (reward > 0.99) + return ob, int(reward), done, truncated, {} def compute_reward(self, obs) -> bool: - return False # overwrite for each task + return False # overwrite for each task def go_to_rest(self, joint_reset=False): """ @@ -222,7 +222,7 @@ def go_to_rest(self, joint_reset=False): while True: time.sleep(0.1) if self.controller.is_reset(): - break # wait for reset + break # wait for reset self._update_currpos() @@ -270,6 +270,9 @@ def _update_currpos(self): self.Qd[:] = state['Qd'] self.gripper_state[:] = state['gripper'] + def _is_truncated(self): + return self.controller.is_truncated() + def _get_obs(self) -> dict: state_observation = { "tcp_pose": self.curr_pos, diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index e000b6f6..c991c93d 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -9,7 +9,5 @@ def __init__(self, **kwargs): def compute_reward(self, obs) -> float: if int(self.gripper_state[1]) == 1 and 10 < self.gripper_state[0] < 30 and self.curr_force[2] < -1.: return 1. - elif self.curr_force[2] > 3.: # neg reward if the downward force is too big - return -0.5 else: return 0.0 From 0cd727da87c29eabb5a22c7e640b05cd5b307048 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 14:49:29 +0100 Subject: [PATCH 065/338] prevent gripping too much (with added timer) --- serl_robot_infra/robot_controllers/robotiq_controller.py | 7 +++++-- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 9 ++------- .../robotiq_env/envs/robotiq_grip_v1/config.py | 1 + 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 1fadba0b..a7876fb6 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -46,6 +46,7 @@ def __init__( self.frequency = frequency self.kp = kp self.kd = kd + self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic()-1e6} self.verbose = verbose self.do_plot = plot @@ -225,9 +226,11 @@ def plot(self): self.stop() async def send_gripper_command(self): - if self.target_grip[0] > 0.5 and self.gripper_state[0] == 100: + timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout["timeout"] + if self.target_grip[0] > 0.5 and timeout_exceeded: await self.robotiq_gripper.automatic_grip() self.target_grip[0] = 0.0 + self.gripper_timeout["last_grip"] = time.monotonic() # print("grip") elif self.target_grip[0] < -0.5 and self.gripper_state[1] != 3: # only release if obj detected @@ -300,7 +303,7 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f"{self.target_pos}, {self.curr_pos}, {force}") # output to file + self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # output to file # send command to robot t_start = self.robotiq_control.initPeriod() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 3d8acceb..22e15494 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -27,18 +27,13 @@ class DefaultEnvConfig: ROBOT_IP: str = "localhost" CONTROLLER_HZ: int = 0 + GRIPPER_TIMEOUT: int = 0 # in milliseconds ERROR_DELTA: float = 0. - FORCEMODE_DAMPING: float = 0.1 + FORCEMODE_DAMPING: float = 0. FORCEMODE_TASK_FRAME = np.zeros(6, ) FORCEMODE_SELECTION_VECTOR = np.ones(6, ) FORCEMODE_LIMITS = np.zeros(6, ) - # not used for now - REALSENSE_CAMERAS: Dict = { - "wrist_1": "130322274175", - "wrist_2": "127122270572", - } - ############################################################################## diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index dc327672..41765118 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -13,6 +13,7 @@ class RobotiqCornerConfig(DefaultEnvConfig): ROBOT_IP: str = "172.22.22.2" CONTROLLER_HZ = 100 + GRIPPER_TIMEOUT = 2000 # in milliseconds ERROR_DELTA: float = 0.05 FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) From 99fc86146e7e4758fd665418b246d1cb7859634e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 14:52:23 +0100 Subject: [PATCH 066/338] joint reset is not needed --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 22e15494..e67a4639 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -66,7 +66,6 @@ def __init__( self.random_xy_range = config.RANDOM_XY_RANGE self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz - self.joint_reset_cycle = 200 # reset the robot joint every 200 cycles # TODO needed? self.xyz_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[:3], @@ -223,12 +222,8 @@ def go_to_rest(self, joint_reset=False): def reset(self, joint_reset=False, **kwargs): self.cycle_count += 1 - if self.cycle_count % self.joint_reset_cycle == 0: - self.cycle_count = 0 - joint_reset = True self.go_to_rest(joint_reset=joint_reset) - # self._recover() self.curr_path_length = 0 self._update_currpos() From 4725edfdb686f14de9b79bb746c772c1fa28f22e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 14:59:01 +0100 Subject: [PATCH 067/338] unecessary TODO removals --- .../serl_launcher/agents/continuous/bc_noimg.py | 3 --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 10 +++------- 2 files changed, 3 insertions(+), 10 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py index 26f28849..a5a2f6b4 100644 --- a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py +++ b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py @@ -24,9 +24,6 @@ class BCAgentNoImg(flax.struct.PyTreeNode): @partial(jax.jit, static_argnames="pmap_axis") def update(self, batch: Batch, pmap_axis: str = None): - # if self.config["image_keys"][0] not in batch["next_observations"]: - # batch = _unpack(batch) # TODO do include? - # rng = self.state.rng # rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) # obs = self.data_augmentation_fn(obs_rng, batch["observations"]) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index e67a4639..954b0061 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -27,7 +27,7 @@ class DefaultEnvConfig: ROBOT_IP: str = "localhost" CONTROLLER_HZ: int = 0 - GRIPPER_TIMEOUT: int = 0 # in milliseconds + GRIPPER_TIMEOUT: int = 0 # in milliseconds ERROR_DELTA: float = 0. FORCEMODE_DAMPING: float = 0. FORCEMODE_TASK_FRAME = np.zeros(6, ) @@ -129,7 +129,8 @@ def __init__( while not self.controller.is_ready(): # wait for controller time.sleep(0.1) - def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat + def clip_safety_box(self, + next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat """Clip the pose to be within the safety box.""" next_pos[:3] = np.clip( next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high @@ -231,11 +232,6 @@ def reset(self, joint_reset=False, **kwargs): return obs, {} - def _recover(self): - """Internal function to recover the robot from error state.""" - # TODO make recover function - pass - def _send_pos_command(self, target_pos: np.ndarray): """Internal function to send force command to the robot.""" self.controller.set_target_pos(target_pos=target_pos) From 284754776557dc99ba9f766aeb27f18a512f87a6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 15:11:58 +0100 Subject: [PATCH 068/338] catch KeyBoardInterrupt --- examples/bc_policy_robotiq.py | 121 ++++++++++++++++++---------------- 1 file changed, 63 insertions(+), 58 deletions(-) diff --git a/examples/bc_policy_robotiq.py b/examples/bc_policy_robotiq.py index de8751e8..f3be194d 100644 --- a/examples/bc_policy_robotiq.py +++ b/examples/bc_policy_robotiq.py @@ -122,20 +122,22 @@ def main(_): }, device=sharding.replicate(), ) - - for step in tqdm(range(FLAGS.max_steps)): - batch = next(replay_iterator) - agent, info = agent.update(batch) - wandb_logger.log(info, step=step) - - if (step + 1) % 10000 == 0 and FLAGS.save_model: - checkpoints.save_checkpoint( - FLAGS.checkpoint_path, - agent.state, - step=step + 1, - keep=100, - overwrite=True, - ) + try: + for step in tqdm(range(FLAGS.max_steps)): + batch = next(replay_iterator) + agent, info = agent.update(batch) + wandb_logger.log(info, step=step) + + if (step + 1) % 10000 == 0 and FLAGS.save_model: + checkpoints.save_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=step + 1, + keep=100, + overwrite=True, + ) + except KeyboardInterrupt: + print("interrupted by user") else: """ @@ -171,54 +173,57 @@ def space_on_press(key): success_counter = 0 time_list = [] - for episode in range(FLAGS.eval_n_trajs): - obs, _ = env.reset() - done = False - is_failure = False - is_success = False - start_time = time.time() - while not done: - actions = agent.sample_actions( - observations=jax.device_put(obs), - argmax=False, - seed=rng, - ) - actions = np.asarray(jax.device_get(actions)) - print(f"sampled actions: {actions}") - - next_obs, reward, done, truncated, info = env.step(actions) - obs = next_obs - - if is_failure: - done = True - print("terminated by user") - - if is_success: - reward = 1 - done = True - print("success, reset now") - - if truncated: - reward = 0 - done = True - print("truncated, reset now") - - if done: - if not is_failure: - dt = time.time() - start_time - time_list.append(dt) - print(dt) - - success_counter += reward - print(reward) - print(f"{success_counter}/{episode + 1}") - - wandb_logger.log(info, step=episode) + try: + for episode in range(FLAGS.eval_n_trajs): + obs, _ = env.reset() + done = False + is_failure = False + is_success = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=False, + seed=rng, + ) + actions = np.asarray(jax.device_get(actions)) + print(f"sampled actions: {actions}") + + next_obs, reward, done, truncated, info = env.step(actions) + obs = next_obs + + if is_failure: + done = True + print("terminated by user") + + if is_success: + reward = 1 + done = True + print("success, reset now") + + if truncated: + reward = 0 + done = True + print("truncated, reset now") + + if done: + if not is_failure: + dt = time.time() - start_time + time_list.append(dt) + print(dt) + + success_counter += reward + print(reward) + print(f"{success_counter}/{episode + 1}") + + wandb_logger.log(info, step=episode) + + except KeyboardInterrupt: + print("interrupted by user, exiting...") print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") print(f"average time: {np.mean(time_list)}") - print("done") env.close() From dd83be6184262a9c80023b91016340676c3c69e7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 15:26:39 +0100 Subject: [PATCH 069/338] name change --- examples/{ => robotiq_bc}/bc_policy_robotiq.py | 4 ++-- examples/{ => robotiq_bc}/run_rbc_actor.sh | 2 +- examples/{ => robotiq_bc}/run_rbc_learner.sh | 2 +- examples/{robotiq_grip_v1 => robotiq_bc}/test_demo.py | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename examples/{ => robotiq_bc}/bc_policy_robotiq.py (97%) rename examples/{ => robotiq_bc}/run_rbc_actor.sh (89%) rename examples/{ => robotiq_bc}/run_rbc_learner.sh (95%) rename examples/{robotiq_grip_v1 => robotiq_bc}/test_demo.py (97%) diff --git a/examples/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py similarity index 97% rename from examples/bc_policy_robotiq.py rename to examples/robotiq_bc/bc_policy_robotiq.py index f3be194d..bc2a8bfd 100644 --- a/examples/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -40,12 +40,12 @@ flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", True, "Whether to save model.") -flags.DEFINE_integer("batch_size", 512, "Batch size.") +flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") -flags.DEFINE_multi_string("demo_paths", "robotiq_grip_v1/robotiq_test_20_demos_2024-03-25_16-39-22.pkl", +flags.DEFINE_multi_string("demo_paths", "robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl", "paths to demos") flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/checkpoints", "Path to save checkpoints.") diff --git a/examples/run_rbc_actor.sh b/examples/robotiq_bc/run_rbc_actor.sh similarity index 89% rename from examples/run_rbc_actor.sh rename to examples/robotiq_bc/run_rbc_actor.sh index 6d4f1d35..24aeeca6 100644 --- a/examples/run_rbc_actor.sh +++ b/examples/robotiq_bc/run_rbc_actor.sh @@ -6,5 +6,5 @@ python bc_policy_robotiq.py "$@" \ --exp_name=bc_robotiq_policy \ --seed 42 \ --batch_size 256 \ - --eval_checkpoint_step 40000 \ + --eval_checkpoint_step 50000 \ # --debug # wandb is disabled when debug diff --git a/examples/run_rbc_learner.sh b/examples/robotiq_bc/run_rbc_learner.sh similarity index 95% rename from examples/run_rbc_learner.sh rename to examples/robotiq_bc/run_rbc_learner.sh index 41e02136..8142b0d8 100644 --- a/examples/run_rbc_learner.sh +++ b/examples/robotiq_bc/run_rbc_learner.sh @@ -5,6 +5,6 @@ python bc_policy_robotiq.py "$@" \ --exp_name=bc_robotiq_policy \ --seed 42 \ --batch_size 256 \ - --demo_paths robotiq_grip_v1/robotiq_test_20_demos_2024-03-20_15-09-46.pkl \ + --demo_paths robotiq_grip_v1/robotiq_test_20_demos_2024-03-26_12-23-50.pkl \ --eval_checkpoint_step 0 # --debug # wandb is disabled when debug diff --git a/examples/robotiq_grip_v1/test_demo.py b/examples/robotiq_bc/test_demo.py similarity index 97% rename from examples/robotiq_grip_v1/test_demo.py rename to examples/robotiq_bc/test_demo.py index e73dcb74..6aafe13a 100644 --- a/examples/robotiq_grip_v1/test_demo.py +++ b/examples/robotiq_bc/test_demo.py @@ -44,7 +44,7 @@ def on_esc(key): listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) listener_2.start() - file_path = "robotiq_test_20_demos_2024-03-25_16-39-22.pkl" + file_path = "robotiq_test_20_demos_2024-03-26_12-23-50.pkl" with open(file_path, "rb") as f: transitions = pkl.load(f) From 4c319c50234f5a19c90447516e21e5ba7d2b6d92 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 15:27:02 +0100 Subject: [PATCH 070/338] SAC implementation (does not work yet) --- examples/robotiq_sac/run_actor.sh | 13 +++++++++++++ examples/robotiq_sac/run_learner.sh | 13 +++++++++++++ .../sac_policy_robotiq.py} | 10 +++------- 3 files changed, 29 insertions(+), 7 deletions(-) create mode 100644 examples/robotiq_sac/run_actor.sh create mode 100644 examples/robotiq_sac/run_learner.sh rename examples/{robotiq_grip_v1/async_drq_v1.py => robotiq_sac/sac_policy_robotiq.py} (97%) diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh new file mode 100644 index 00000000..ff551b91 --- /dev/null +++ b/examples/robotiq_sac/run_actor.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +python sac_policy_robotiq.py "$@" \ + --actor \ + --env robotiq-grip-v1 \ + --exp_name=sac_robotiq_policy \ + --seed 0 \ + --random_steps 1000 \ + --training_starts 1000 \ + --utd_ratio 8 \ + --batch_size 256 \ + --eval_period 2000 +# --debug diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh new file mode 100644 index 00000000..d5813011 --- /dev/null +++ b/examples/robotiq_sac/run_learner.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +python sac_policy_robotiq.py "$@" \ + --learner \ + --env robotiq-grip-v1 \ + --exp_name=sac_robotiq_policy \ + --seed 0 \ + --random_steps 1000 \ + --training_starts 1000 \ + --utd_ratio 8 \ + --batch_size 256 \ + --eval_period 2000 +# --debug diff --git a/examples/robotiq_grip_v1/async_drq_v1.py b/examples/robotiq_sac/sac_policy_robotiq.py similarity index 97% rename from examples/robotiq_grip_v1/async_drq_v1.py rename to examples/robotiq_sac/sac_policy_robotiq.py index 83e0c7a8..56f08084 100644 --- a/examples/robotiq_grip_v1/async_drq_v1.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -40,11 +40,11 @@ flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") -flags.DEFINE_bool("save_model", False, "Whether to save model.") +flags.DEFINE_bool("save_model", True, "Whether to save model.") flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 8, "UTD ratio.") -flags.DEFINE_integer("max_steps", 100, "Maximum number of training steps.") +flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 1000000, "Replay buffer capacity.") flags.DEFINE_integer("random_steps", 300, "Sample random actions for this many steps.") @@ -58,13 +58,12 @@ # flag to indicate if this is a leaner or a actor flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") -flags.DEFINE_boolean("render", False, "Render the environment.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") flags.DEFINE_string("checkpoint_path", 'checkpoint_test_path', "Path to save checkpoints.") flags.DEFINE_boolean( - "debug", True, "Debug mode." + "debug", False, "Debug mode." ) # debug mode will disable wandb logging @@ -145,9 +144,6 @@ def update_params(params): running_return = 0.0 obs, _ = env.reset() - if FLAGS.render: - env.render() - if step % FLAGS.steps_per_update == 0: client.update() From e7d064a61e797c88c18dbfd386cc7bc37642de4f Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 26 Mar 2024 15:27:18 +0100 Subject: [PATCH 071/338] Chungking Wrapper does not function yet --- examples/{robotiq_grip_v1 => robotiq_bc}/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename examples/{robotiq_grip_v1 => robotiq_bc}/record_demo.py (97%) diff --git a/examples/robotiq_grip_v1/record_demo.py b/examples/robotiq_bc/record_demo.py similarity index 97% rename from examples/robotiq_grip_v1/record_demo.py rename to examples/robotiq_bc/record_demo.py index fc3d7400..f6e3bf71 100644 --- a/examples/robotiq_grip_v1/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -36,7 +36,7 @@ def on_esc(key): # env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) - env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) obs, _ = env.reset() From 7a155aca5624aed756fd8be73c39bf0ac734ba7a Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 14:44:23 +0100 Subject: [PATCH 072/338] no random steps for now --- examples/async_sac_state_sim/async_sac_state_sim.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/async_sac_state_sim/async_sac_state_sim.py b/examples/async_sac_state_sim/async_sac_state_sim.py index 90b96d63..af8b4b0f 100644 --- a/examples/async_sac_state_sim/async_sac_state_sim.py +++ b/examples/async_sac_state_sim/async_sac_state_sim.py @@ -107,7 +107,8 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: - actions = env.action_space.sample() + # actions = env.action_space.sample() + actions = np.zeros((7,)) else: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( @@ -119,7 +120,6 @@ def update_params(params): # Step environment with timer.context("step_env"): - next_obs, reward, done, truncated, info = env.step(actions) next_obs = np.asarray(next_obs, dtype=np.float32) reward = np.asarray(reward, dtype=np.float32) From 56e5e9fc7aa0899b8d1b8ac1477880241ac90925 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 14:44:45 +0100 Subject: [PATCH 073/338] added more conservative limits (to test) --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 41765118..5791a2fe 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -9,6 +9,8 @@ class RobotiqCornerConfig(DefaultEnvConfig): RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) + # ABS_POSE_LIMIT_HIGH = np.array([0.0, -0.5, 0.15, 3.2, 0.1, 3.2]) # more conservative for tests + # ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.6, 0.1, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" From d4cb995f59d5b1ad228b452f62ba090c5727d15f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 14:44:55 +0100 Subject: [PATCH 074/338] bugfix --- .../robot_controllers/robotiq_controller.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index a7876fb6..a7901777 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -87,8 +87,9 @@ def start(self): if self.verbose: print(f"[RIC] Controller process spawned at {self.native_id}") - def print(self, msg): - self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') + def print(self, msg, probability=1.): + if np.random.random() < probability: + self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') async def start_robotiq_interfaces(self, gripper=True): for _ in range(5): # try it 5 times @@ -102,11 +103,11 @@ async def start_robotiq_interfaces(self, gripper=True): if self.verbose: gr_string = "(with gripper) " if gripper else "" print(f"[RIC] Controller connected to robot {gr_string}at: {self.robot_ip}") - break + return except RuntimeError as e: print("[RIC] ", e.__str__()) continue - # raise RuntimeError(f"[RIC] Could not connect to robot [{self.robot_ip}]") + raise RuntimeError(f"[RIC] Could not connect to robot [{self.robot_ip}]") def stop(self): self._stop.set() @@ -280,6 +281,7 @@ async def run_async(self): print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)") self.robotiq_control.forceModeStop() self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.5) + self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)") await self._update_robot_state() with self.lock: @@ -303,7 +305,7 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # output to file + self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}", probability=1.) # output to file # send command to robot t_start = self.robotiq_control.initPeriod() From 6e041ecae41ef327ed8b446ac0025d07a2c1727e Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 14:45:17 +0100 Subject: [PATCH 075/338] print controller infos --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 954b0061..4b6afbfe 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -112,6 +112,7 @@ def __init__( self.controller = None if fake_env: + print("[RobotiqEnv] is fake!") return self.controller = RobotiqImpedanceController( @@ -123,7 +124,7 @@ def __init__( verbose=True, plot=False ) - + print("controller started: ", self.controller._started.is_set()) self.controller.start() # start Thread while not self.controller.is_ready(): # wait for controller From eaada941c05aa79e08f1433d99825c33b05594d7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 14:45:42 +0100 Subject: [PATCH 076/338] used to run actor with saved weights --- examples/robotiq_sac/run_rsac_actor.sh | 10 ++++++++++ 1 file changed, 10 insertions(+) create mode 100644 examples/robotiq_sac/run_rsac_actor.sh diff --git a/examples/robotiq_sac/run_rsac_actor.sh b/examples/robotiq_sac/run_rsac_actor.sh new file mode 100644 index 00000000..690c205f --- /dev/null +++ b/examples/robotiq_sac/run_rsac_actor.sh @@ -0,0 +1,10 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +which python && \ +python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ + --env robotiq-grip-v1 \ + --exp_name=sav_robotiq_actor \ + --seed 42 \ + --batch_size 256 \ + --eval_checkpoint_step 100000 \ +# --debug # wandb is disabled when debug From fa3f8b6918042a3d4e346774e6ab899792d36c46 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 17:56:25 +0100 Subject: [PATCH 077/338] path change --- examples/robotiq_bc/bc_policy_robotiq.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index bc2a8bfd..6e5d8aad 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -47,7 +47,7 @@ flags.DEFINE_multi_string("demo_paths", "robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl", "paths to demos") -flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/checkpoints", +flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/robotiq_bc/checkpoints", "Path to save checkpoints.") flags.DEFINE_integer( From cf7287d2255d107a4594324a140b4ed20f6b6fe6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 17:56:49 +0100 Subject: [PATCH 078/338] fixed a few bugs --- examples/robotiq_sac/sac_policy_robotiq.py | 100 ++++++++++++--------- 1 file changed, 59 insertions(+), 41 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 56f08084..a03d5c30 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -15,6 +15,7 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.evaluation import evaluate from serl_launcher.utils.timer_utils import Timer +from serl_launcher.data.data_store import populate_data_store from serl_launcher.wrappers.chunking import ChunkingWrapper @@ -37,7 +38,7 @@ flags.DEFINE_string("env", "robotiq-grip-v1", "Name of environment.") flags.DEFINE_string("agent", "sac", "Name of agent.") -flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") +flags.DEFINE_string("exp_name", "sac_robotiq_policy", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", True, "Whether to save model.") @@ -46,9 +47,11 @@ flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 1000000, "Replay buffer capacity.") +flags.DEFINE_multi_string("demo_paths", None, + "paths to demos") -flags.DEFINE_integer("random_steps", 300, "Sample random actions for this many steps.") -flags.DEFINE_integer("training_starts", 300, "Training starts after this step.") +flags.DEFINE_integer("random_steps", 1000, "Sample random actions for this many steps.") +flags.DEFINE_integer("training_starts", 1000, "Training starts after this step.") flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") flags.DEFINE_integer("log_period", 10, "Logging period.") @@ -56,11 +59,15 @@ flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") # flag to indicate if this is a leaner or a actor -flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") +flags.DEFINE_boolean("learner", True, "Is this a learner or a trainer.") # TODO change back! flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", 'checkpoint_test_path', "Path to save checkpoints.") +flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints', "Path to save checkpoints.") + +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', "Path to save RLDS logs.") +flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") # TODO does not work yet + flags.DEFINE_boolean( "debug", False, "Debug mode." @@ -91,14 +98,10 @@ def update_params(params): nonlocal agent agent = agent.replace(state=agent.state.replace(params=params)) - client.recv_network_callback(update_params) - - eval_env = gym.make(FLAGS.env) - if FLAGS.env == "PandaPickCube-v0": - eval_env = gym.wrappers.FlattenObservation(eval_env) - eval_env = RecordEpisodeStatistics(eval_env) + client.recv_network_callback(update_params) # TODO RLDS does not load obs, _ = env.reset() + print(f"obs: {obs}") done = False # training loop @@ -115,13 +118,13 @@ def update_params(params): actions = agent.sample_actions( observations=jax.device_put(obs), seed=key, - deterministic=False, + # deterministic=False, + argmax=False, ) actions = np.asarray(jax.device_get(actions)) # Step environment with timer.context("step_env"): - next_obs, reward, done, truncated, info = env.step(actions) next_obs = np.asarray(next_obs, dtype=np.float32) reward = np.asarray(reward, dtype=np.float32) @@ -151,7 +154,7 @@ def update_params(params): with timer.context("eval"): evaluate_info = evaluate( policy_fn=partial(agent.sample_actions, argmax=True), - env=eval_env, + env=env, num_episodes=FLAGS.eval_n_trajs, ) stats = {"eval": evaluate_info} @@ -206,30 +209,34 @@ def stats_callback(type: str, payload: dict) -> dict: # wait till the replay buffer is filled with enough data timer = Timer() - for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): - # Train the networks - with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) - - with timer.context("train"): - agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) - agent = jax.block_until_ready(agent) - - # publish the updated network - server.publish_network(agent.state.params) - - if update_steps % FLAGS.log_period == 0 and wandb_logger: - wandb_logger.log(update_info, step=update_steps) - wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) - - if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: - assert FLAGS.checkpoint_path is not None - checkpoints.save_checkpoint( - FLAGS.checkpoint_path, agent.state, step=update_steps, keep=20 - ) - - update_steps += 1 + try: + for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): + # Train the networks + with timer.context("sample_replay_buffer"): + batch = next(replay_iterator) + + with timer.context("train"): + agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) + agent = jax.block_until_ready(agent) + + # publish the updated network + server.publish_network(agent.state.params) + + if update_steps % FLAGS.log_period == 0 and wandb_logger: + wandb_logger.log(update_info, step=update_steps) + wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) + wandb_logger.log({"replay_buffer_size": len(replay_buffer)}) + + if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0 and update_steps: + assert FLAGS.checkpoint_path is not None + checkpoints.save_checkpoint( + FLAGS.checkpoint_path, agent.state, step=update_steps, keep=20 + ) + update_steps += 1 + finally: + print("closing learner, clearning up...") + del replay_buffer ############################################################################## @@ -244,16 +251,21 @@ def main(_): rng = jax.random.PRNGKey(FLAGS.seed) # create env and load dataset - env = gym.make(FLAGS.env) + env = gym.make( + FLAGS.env, + fake_env=FLAGS.learner, + max_episode_length=FLAGS.max_traj_length, + ) if FLAGS.actor: env = SpacemouseIntervention(env) # env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) - env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) rng, sampling_rng = jax.random.split(rng) + print(f"obs shape: {env.observation_space.sample().shape}") agent: SACAgent = make_sac_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), @@ -270,8 +282,8 @@ def create_replay_buffer_and_wandb_logger(): replay_buffer = make_replay_buffer( env, capacity=FLAGS.replay_buffer_capacity, - rlds_logger_path=FLAGS.log_rlds_path, type="replay_buffer", + rlds_logger_path=FLAGS.log_rlds_path, preload_rlds_path=FLAGS.preload_rlds_path, ) @@ -286,6 +298,11 @@ def create_replay_buffer_and_wandb_logger(): if FLAGS.learner: sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() + + if FLAGS.preload_rlds_path == None: + print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way + replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) + replay_iterator = replay_buffer.get_iterator( sample_args={ "batch_size": FLAGS.batch_size * FLAGS.utd_ratio, @@ -302,6 +319,7 @@ def create_replay_buffer_and_wandb_logger(): wandb_logger=wandb_logger, ) + elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) data_store = QueuedDataStore(50000) # the queue size on the actor From 92d2c729cdb2627111102c5da8b105f8ccdbe36d Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 17:57:05 +0100 Subject: [PATCH 079/338] new actor and learner parameters for now --- examples/robotiq_sac/run_actor.sh | 10 ++++++---- examples/robotiq_sac/run_learner.sh | 13 ++++++++----- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh index ff551b91..c88e2a6d 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/robotiq_sac/run_actor.sh @@ -1,13 +1,15 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python sac_policy_robotiq.py "$@" \ --actor \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ --seed 0 \ - --random_steps 1000 \ - --training_starts 1000 \ + --max_steps 10000 \ + --random_steps 600 \ + --training_starts 600 \ --utd_ratio 8 \ --batch_size 256 \ - --eval_period 2000 + --eval_period 2000 \ + --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl" \ # --debug diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh index d5813011..77c1b239 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/robotiq_sac/run_learner.sh @@ -1,13 +1,16 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python sac_policy_robotiq.py "$@" \ --learner \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ --seed 0 \ - --random_steps 1000 \ - --training_starts 1000 \ + --random_steps 600 \ + --training_starts 600 \ --utd_ratio 8 \ - --batch_size 256 \ - --eval_period 2000 + --batch_size 1024 \ + --eval_period 2000 \ + --max_steps 10000 \ + --preload_rlds_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds" \ +# --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl" \ # --debug From 0d45f0c44c455ee92e000c902bb76f626b1e6bc2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 28 Mar 2024 17:57:19 +0100 Subject: [PATCH 080/338] add as security that it cleaned up --- serl_launcher/serl_launcher/data/data_store.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/serl_launcher/serl_launcher/data/data_store.py b/serl_launcher/serl_launcher/data/data_store.py index e9f99969..5acb89e3 100644 --- a/serl_launcher/serl_launcher/data/data_store.py +++ b/serl_launcher/serl_launcher/data/data_store.py @@ -79,6 +79,11 @@ def latest_data_id(self): def get_latest_data(self, from_id: int): raise NotImplementedError # TODO + def __del__(self): + if self._logger: + self._logger.close() + print("[ReplayBufferDataStore] RLDS logger closed successfully") + class MemoryEfficientReplayBufferDataStore(MemoryEfficientReplayBuffer, DataStoreBase): def __init__( From 5cf197a7f1b2c66dffd7442aac7dbd6c40e7ad8f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 14:30:12 +0200 Subject: [PATCH 081/338] consiervative z rotation --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 5791a2fe..4496ee74 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -7,8 +7,8 @@ class RobotiqCornerConfig(DefaultEnvConfig): RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ - ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) + ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 1.5]) # TODO euler rotations suck :/ + ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -1.5]) # ABS_POSE_LIMIT_HIGH = np.array([0.0, -0.5, 0.15, 3.2, 0.1, 3.2]) # more conservative for tests # ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.6, 0.1, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) From 5e19dd79555b4be5e79af464fdc2bed56a43839d Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 14:30:31 +0200 Subject: [PATCH 082/338] lower NN complexity --- serl_launcher/serl_launcher/utils/launcher.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 003b5d7c..42ebb55a 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -58,7 +58,8 @@ def make_bc_agent_no_img( network_kwargs={ "activations": nn.tanh, "use_layer_norm": False, - "hidden_dims": [256, 256], + # "hidden_dims": [256, 256], + "hidden_dims": [128, 64], }, policy_kwargs={ "tanh_squash_distribution": False, @@ -83,18 +84,20 @@ def make_sac_agent(seed, sample_obs, sample_action): critic_network_kwargs={ "activations": nn.tanh, "use_layer_norm": True, - "hidden_dims": [256, 256], + # "hidden_dims": [256, 256], # TODO trying it with simpler network + "hidden_dims": [128, 64], }, policy_network_kwargs={ "activations": nn.tanh, "use_layer_norm": True, - "hidden_dims": [256, 256], + # "hidden_dims": [256, 256], + "hidden_dims": [128, 64], }, temperature_init=1e-2, - discount=0.99, + discount=0.95, # TODO maybe try 0.98 or lower (only 100 steps!) backup_entropy=False, - critic_ensemble_size=10, - critic_subsample_size=2, + # critic_ensemble_size=10, # isREDQ with these + # critic_subsample_size=2, ) From 9adc92584c748df933ea8874ad4667584e0bbbe6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 14:31:16 +0200 Subject: [PATCH 083/338] small improvements --- examples/robotiq_sac/sac_policy_robotiq.py | 28 ++++++++++++---------- 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index a03d5c30..e5af6c86 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -8,6 +8,7 @@ import tqdm from absl import app, flags from flax.training import checkpoints +from datetime import datetime import gymnasium as gym from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics @@ -59,15 +60,16 @@ flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") # flag to indicate if this is a leaner or a actor -flags.DEFINE_boolean("learner", True, "Is this a learner or a trainer.") # TODO change back! +flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") # TODO change back! flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints', "Path to save checkpoints.") - -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', "Path to save RLDS logs.") -flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") # TODO does not work yet +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints', + "Path to save checkpoints.") +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', + "Path to save RLDS logs.") +flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") # TODO does not work yet flags.DEFINE_boolean( "debug", False, "Debug mode." @@ -98,7 +100,7 @@ def update_params(params): nonlocal agent agent = agent.replace(state=agent.state.replace(params=params)) - client.recv_network_callback(update_params) # TODO RLDS does not load + client.recv_network_callback(update_params) # TODO RLDS does not load obs, _ = env.reset() print(f"obs: {obs}") @@ -112,14 +114,15 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: + print("sampling randomly!") actions = env.action_space.sample() else: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( observations=jax.device_put(obs), - seed=key, + # seed=key, # deterministic=False, - argmax=False, + argmax=True, # TODO which one to use? ) actions = np.asarray(jax.device_get(actions)) @@ -227,10 +230,10 @@ def stats_callback(type: str, payload: dict) -> dict: wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) wandb_logger.log({"replay_buffer_size": len(replay_buffer)}) - if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0 and update_steps: + if FLAGS.checkpoint_period and (update_steps + 1) % FLAGS.checkpoint_period == 0: assert FLAGS.checkpoint_path is not None checkpoints.save_checkpoint( - FLAGS.checkpoint_path, agent.state, step=update_steps, keep=20 + FLAGS.checkpoint_path, agent.state, step=update_steps + 1, keep=20 ) update_steps += 1 @@ -238,6 +241,7 @@ def stats_callback(type: str, payload: dict) -> dict: print("closing learner, clearning up...") del replay_buffer + ############################################################################## @@ -246,6 +250,7 @@ def main(_): num_devices = len(devices) sharding = jax.sharding.PositionalSharding(devices) assert FLAGS.batch_size % num_devices == 0 + FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") # seed rng = jax.random.PRNGKey(FLAGS.seed) @@ -300,7 +305,7 @@ def create_replay_buffer_and_wandb_logger(): replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() if FLAGS.preload_rlds_path == None: - print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way + print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) replay_iterator = replay_buffer.get_iterator( @@ -319,7 +324,6 @@ def create_replay_buffer_and_wandb_logger(): wandb_logger=wandb_logger, ) - elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) data_store = QueuedDataStore(50000) # the queue size on the actor From da664f487c57118091a674a0fcf60b570036e28f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 16:12:24 +0200 Subject: [PATCH 084/338] implemented random xy reset poses --- .../robotiq_env/envs/robotiq_env.py | 35 ++++++++++--------- .../envs/robotiq_grip_v1/config.py | 8 ++--- 2 files changed, 23 insertions(+), 20 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 4b6afbfe..b14ebba2 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -199,28 +199,31 @@ def go_to_rest(self, joint_reset=False): """ # Perform Carteasian reset + reset_Q = self.resetQ.copy() + + self._send_reset_command(reset_Q) + + while True: + time.sleep(0.1) + if self.controller.is_reset(): + break # wait for reset + + self._update_currpos() if self.random_reset: # randomize reset position in xy plane - # reset_pose = self.resetpos.copy()ss - # reset_pose[:2] += np.random.uniform( - # np.negative(self.random_xy_range), self.random_xy_range, (2,) - # ) - # euler_random = self._TARGET_POSE[3:].copy() + # reset_pose = self.resetpos.copy() + reset_pose = self.controller.get_target_pos() + reset_pose[:2] += np.random.uniform( + np.negative(self.random_xy_range), self.random_xy_range, (2,) + ) + # euler_random = reset_pose[3:] # euler_random[-1] += np.random.uniform( # np.negative(self.random_rz_range), self.random_rz_range # ) - # reset_pose[3:] = euler_2_quat(euler_random) - # self.move_to(reset_pose) - pass - else: - reset_Q = self.resetQ.copy() - self._send_reset_command(reset_Q) - + self.controller.set_target_pos(reset_pose) # random movement after resetting while True: time.sleep(0.1) - if self.controller.is_reset(): - break # wait for reset - - self._update_currpos() + if not self.controller.is_moving(): + break def reset(self, joint_reset=False, **kwargs): self.cycle_count += 1 diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 4496ee74..8b4cc630 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -4,11 +4,11 @@ class RobotiqCornerConfig(DefaultEnvConfig): RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.0,) + RANDOM_RESET = True + RANDOM_XY_RANGE = (0.05,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 1.5]) # TODO euler rotations suck :/ - ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -1.5]) + ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ + ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) # ABS_POSE_LIMIT_HIGH = np.array([0.0, -0.5, 0.15, 3.2, 0.1, 3.2]) # more conservative for tests # ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.6, 0.1, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) From d85b9610c7a5d340e0444992d770483f16519542 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 16:12:36 +0200 Subject: [PATCH 085/338] new reward function --- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index c991c93d..537fa609 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -7,7 +7,13 @@ def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) def compute_reward(self, obs) -> float: - if int(self.gripper_state[1]) == 1 and 10 < self.gripper_state[0] < 30 and self.curr_force[2] < -1.: - return 1. + if int(self.gripper_state[1]) == 1: + if 10 < self.gripper_state[0] < 30: + if self.curr_force[2] < -1.: + return 10. + return 5. + return 2.5 + if self.curr_force[2] > 5.: + return (5. - self.curr_force[2]) * 0.2 # return 0 if force=5, -1 if force=10 (max)) else: return 0.0 From dfb381e8ca75fae4fe714c164da0adb067a3e264 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 16:12:42 +0200 Subject: [PATCH 086/338] bugfix --- examples/robotiq_bc/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index f6e3bf71..b551991e 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -86,7 +86,7 @@ def on_esc(key): obs = next_obs if done: - success_count += rew + success_count += int(rew > 0.99) total_count += 1 print( f"{rew}\tGot {success_count} successes of {total_count} trials. {success_needed} successes needed." From bb8ca0d06e0e5019ec3182d4024ba59ec4e8dc0b Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 3 Apr 2024 16:13:16 +0200 Subject: [PATCH 087/338] added upward movement while resetting --- .../robot_controllers/robotiq_controller.py | 21 ++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index a7901777..f9843444 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -60,6 +60,7 @@ def __init__( self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space + self.reset_height = np.array([0.06], dtype=np.float32) # TODO make customizable self._is_truncated = False self.delta = config.ERROR_DELTA @@ -115,6 +116,9 @@ def stop(self): def stopped(self): return self._stop.is_set() + def is_moving(self): + return np.linalg.norm(self.get_state()["vel"], 2) > 0.01 + def set_target_pos(self, target_pos: np.ndarray): if target_pos.shape == (7,): target_orientation = target_pos[3:] @@ -138,9 +142,12 @@ def set_gripper_pos(self, target_grip: np.ndarray): with self.lock: self.target_grip[:] = target_grip - def get_target_pos(self): + def get_target_pos(self, copy=True): with self.lock: - return self.target_pos + if copy: + return self.target_pos.copy() + else: + return self.target_pos async def _update_robot_state(self): pos = self.robotiq_receive.getActualTCPPose() @@ -178,7 +185,7 @@ def is_reset(self): return not self._reset.is_set() def _calculate_force(self): - target_pos = self.get_target_pos() + target_pos = self.get_target_pos(copy=False) with self.lock: curr_pos = self.curr_pos curr_vel = self.curr_vel @@ -240,7 +247,7 @@ async def send_gripper_command(self): # print("release") def _truncate_check(self): - if self.curr_force[2] > 8.: # TODO add better criteria + if self.curr_force[2] > 10.: # TODO add better criteria self._is_truncated = True else: self._is_truncated = False @@ -270,7 +277,11 @@ async def run_async(self): self._is_ready.set() while not self.stopped(): - if self._reset.is_set(): # move to reset joint space pose with moveJ + if self._reset.is_set() and self.curr_pos[2] < self.reset_height: + # move up first, then in joint-space + self.target_pos[2] = self.reset_height + + elif self._reset.is_set() and not self.is_moving(): # move to reset joint space pose with moveJ # first disable vaccum gripper if self.robotiq_gripper: self.target_grip[0] = -1. From 4b93d2f238527dfc101378af6207bf05e28e54c6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 14:34:36 +0200 Subject: [PATCH 088/338] added reward scale and no utd update --- examples/robotiq_sac/sac_policy_robotiq.py | 10 ++++-- .../serl_launcher/data/data_store.py | 32 ++++++++++--------- 2 files changed, 25 insertions(+), 17 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index e5af6c86..00d6779b 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -12,6 +12,7 @@ import gymnasium as gym from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics +from gymnasium.wrappers import TransformReward from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.evaluation import evaluate @@ -45,6 +46,7 @@ flags.DEFINE_bool("save_model", True, "Whether to save model.") flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 8, "UTD ratio.") +flags.DEFINE_integer("reward_scale", 1, "Reward Scale to help out SAC algorithm") flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 1000000, "Replay buffer capacity.") @@ -219,7 +221,10 @@ def stats_callback(type: str, payload: dict) -> dict: batch = next(replay_iterator) with timer.context("train"): - agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) + if FLAGS.utd_ratio == 1: + agent, update_info = agent.update(batch=batch) # try it without utd + else: + agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) agent = jax.block_until_ready(agent) # publish the updated network @@ -268,6 +273,7 @@ def main(_): env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) + env = TransformReward(env, lambda r: FLAGS.reward_scale * r) rng, sampling_rng = jax.random.split(rng) print(f"obs shape: {env.observation_space.sample().shape}") @@ -306,7 +312,7 @@ def create_replay_buffer_and_wandb_logger(): if FLAGS.preload_rlds_path == None: print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way - replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) + replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths, reward_scaling=FLAGS.reward_scale) replay_iterator = replay_buffer.get_iterator( sample_args={ diff --git a/serl_launcher/serl_launcher/data/data_store.py b/serl_launcher/serl_launcher/data/data_store.py index 5acb89e3..a45f996d 100644 --- a/serl_launcher/serl_launcher/data/data_store.py +++ b/serl_launcher/serl_launcher/data/data_store.py @@ -25,11 +25,11 @@ class ReplayBufferDataStore(ReplayBuffer, DataStoreBase): def __init__( - self, - observation_space: gym.Space, - action_space: gym.Space, - capacity: int, - rlds_logger: Optional[RLDSLogger] = None, + self, + observation_space: gym.Space, + action_space: gym.Space, + capacity: int, + rlds_logger: Optional[RLDSLogger] = None, ): ReplayBuffer.__init__(self, observation_space, action_space, capacity) DataStoreBase.__init__(self, capacity) @@ -87,12 +87,12 @@ def __del__(self): class MemoryEfficientReplayBufferDataStore(MemoryEfficientReplayBuffer, DataStoreBase): def __init__( - self, - observation_space: gym.Space, - action_space: gym.Space, - capacity: int, - image_keys: Iterable[str] = ("image",), - rlds_logger: Optional[RLDSLogger] = None, + self, + observation_space: gym.Space, + action_space: gym.Space, + capacity: int, + image_keys: Iterable[str] = ("image",), + rlds_logger: Optional[RLDSLogger] = None, ): MemoryEfficientReplayBuffer.__init__( self, observation_space, action_space, capacity, pixel_keys=image_keys @@ -150,8 +150,9 @@ def get_latest_data(self, from_id: int): def populate_data_store( - data_store: DataStoreBase, - demos_path: str, + data_store: DataStoreBase, + demos_path: str, + reward_scaling: int = 1, ): """ Utility function to populate demonstrations data into data_store. @@ -163,14 +164,15 @@ def populate_data_store( with open(demo_path, "rb") as f: demo = pkl.load(f) for transition in demo: + transition["rewards"] *= reward_scaling # apply reward scaling data_store.insert(transition) print(f"Loaded {len(data_store)} transitions.") return data_store def populate_data_store_with_z_axis_only( - data_store: DataStoreBase, - demos_path: str, + data_store: DataStoreBase, + demos_path: str, ): """ Utility function to populate demonstrations data into data_store. From d231af9700f0434293ad730d50093bf2594a020b Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 14:36:15 +0200 Subject: [PATCH 089/338] print error --- examples/robotiq_bc/record_demo.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index b551991e..a8df726c 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -98,8 +98,8 @@ def on_esc(key): pkl.dump(transitions, f) print(f"saved {success_needed} demos to {file_path}") - except KeyboardInterrupt: - print(f'\nProgram was interrupted, cleaning up...') + except KeyboardInterrupt as e: + print(f'\nProgram was interrupted, cleaning up... ', e.__str__()) finally: env.close() From 70d3ba0aea342103270785f9b4a076fdd4d5b793 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 14:36:54 +0200 Subject: [PATCH 090/338] bugfix --- serl_robot_infra/robot_controllers/robotiq_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index f9843444..85a43eee 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -277,7 +277,7 @@ async def run_async(self): self._is_ready.set() while not self.stopped(): - if self._reset.is_set() and self.curr_pos[2] < self.reset_height: + if self._reset.is_set() and self.curr_pos[2] < self.reset_height - 0.01: # move up first, then in joint-space self.target_pos[2] = self.reset_height From 8a4fe9b7373e23e8bc436cdd7d416a4959a4c9b3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 14:37:27 +0200 Subject: [PATCH 091/338] streamlined reward function --- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index 537fa609..a801e673 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -7,13 +7,9 @@ def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) def compute_reward(self, obs) -> float: - if int(self.gripper_state[1]) == 1: - if 10 < self.gripper_state[0] < 30: - if self.curr_force[2] < -1.: - return 10. - return 5. - return 2.5 + if 10. < self.gripper_state[0] < 30. and self.curr_force[2] < -3.: + return 1. if self.curr_force[2] > 5.: - return (5. - self.curr_force[2]) * 0.2 # return 0 if force=5, -1 if force=10 (max)) + return (5. - self.curr_force[2]) * 0.1 # return 0 if force=5, -0.5 if force=10 (max)) else: return 0.0 From e66ca6847e2e2d01c69761d833680d8a6af7991e Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:29:25 +0200 Subject: [PATCH 092/338] better reset Q --- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index 8b4cc630..f708e1c2 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -3,8 +3,9 @@ class RobotiqCornerConfig(DefaultEnvConfig): - RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) - RANDOM_RESET = True + # RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) # old one + RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) + RANDOM_RESET = False RANDOM_XY_RANGE = (0.05,) RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ From d9dac42a9ec00f554eb9f5980cbb374d17e76151 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:29:45 +0200 Subject: [PATCH 093/338] added relative frame --- examples/robotiq_bc/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index a8df726c..bc28b073 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -33,7 +33,7 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq-grip-v1") env = SpacemouseIntervention(env) - # env = RelativeFrame(env) + env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) From 9e074308814e10407a3e3d95777b4220913a7842 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:30:28 +0200 Subject: [PATCH 094/338] changed pressure to be within [0, 1] --- serl_robot_infra/robot_controllers/robotiq_controller.py | 7 ++++--- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 85a43eee..1da583aa 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -131,7 +131,7 @@ def set_target_pos(self, target_pos: np.ndarray): self.target_pos[:3] = target_pos[:3] self.target_pos[3:] = target_orientation - # print("target: ", self.target_pos) + self.print(f"target: {self.target_pos}") def set_reset_Q(self, reset_Q: np.ndarray): self._reset.set() @@ -163,7 +163,7 @@ async def _update_robot_state(self): self.curr_Q[:] = Q self.curr_Qd[:] = Qd self.curr_force[:] = force - self.gripper_state[:] = [pressure, float(obj_status.value)] + self.gripper_state[:] = [pressure / 100., float(obj_status.value)] # pressure between [0, 1] def get_state(self): with self.lock: @@ -316,7 +316,7 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}", probability=1.) # output to file + self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # output to file # send command to robot t_start = self.robotiq_control.initPeriod() @@ -338,6 +338,7 @@ async def run_async(self): time.sleep(max(0., a)) if a < 0: # log how slow the loop runs self.err += 1 + self.print(f"over dt: {-a:.5f} s") else: self.noerr += 1 diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index a801e673..c58a6922 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -7,7 +7,7 @@ def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) def compute_reward(self, obs) -> float: - if 10. < self.gripper_state[0] < 30. and self.curr_force[2] < -3.: + if 0.1 < self.gripper_state[0] < 0.3 and self.curr_force[2] < -3.: return 1. if self.curr_force[2] > 5.: return (5. - self.curr_force[2]) * 0.1 # return 0 if force=5, -0.5 if force=10 (max)) From 2b3796ca2780f78156d16d414aff51b6ccdfda53 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:30:39 +0200 Subject: [PATCH 095/338] addd gripper action span --- serl_robot_infra/robotiq_env/envs/wrappers.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 95df34a4..6271661f 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -10,14 +10,15 @@ class SpacemouseIntervention(gym.ActionWrapper): - def __init__(self, env): + def __init__(self, env, gripper_action_span=3): super().__init__(env) self.gripper_enabled = True self.expert = SpaceMouseExpert() self.last_intervene = 0 - self.left, self.right = False, False + self.left = np.array([False] * gripper_action_span, dtype=np.bool_) + self.right = self.left.copy() self.invert_axes = [-1, -1, 1, 1, -1, -1] self.deadspace = 0.15 @@ -31,11 +32,11 @@ def action(self, action: np.ndarray) -> np.ndarray: """ expert_a = self.get_deadspace_action() - if np.linalg.norm(expert_a) > 0.001 or self.left or self.right: # also read buttons with no movement + if np.linalg.norm(expert_a) > 0.001 or self.left.any() or self.right.any(): # also read buttons with no movement self.last_intervene = time.time() if self.gripper_enabled: - gripper_action = np.zeros((1,)) + int(self.left) - int(self.right) + gripper_action = np.zeros((1,)) + int(self.left.any()) - int(self.right.any()) expert_a = np.concatenate((expert_a, gripper_action), axis=0) if time.time() - self.last_intervene < 0.5: @@ -51,7 +52,8 @@ def get_deadspace_action(self) -> np.ndarray: negative = np.clip((expert_a + self.deadspace) / (1. - self.deadspace), a_min=-1.0, a_max=0.0) expert_a = positive + negative - self.left, self.right = tuple(buttons) + self.left, self.right = np.roll(self.left, -1), np.roll(self.right, -1) # shift them one to the left + self.left[-1], self.right[-1] = tuple(buttons) return np.array(expert_a, dtype=np.float32) @@ -79,8 +81,8 @@ def step(self, action): # print(f"new action: {new_action}") obs, rew, done, truncated, info = self.env.step(new_action) info["intervene_action"] = new_action - info["left"] = self.left - info["right"] = self.right + info["left"] = self.left.any() + info["right"] = self.right.any() return obs, rew, done, truncated, info From 800668abb1007d91c3d6171b2eda4fab0cf2f69b Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:30:54 +0200 Subject: [PATCH 096/338] minor imporvements --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index b14ebba2..d5abdea2 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -124,11 +124,11 @@ def __init__( verbose=True, plot=False ) - print("controller started: ", self.controller._started.is_set()) self.controller.start() # start Thread while not self.controller.is_ready(): # wait for controller time.sleep(0.1) + print("[RIC] Controller has started and is ready!") def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat @@ -161,7 +161,7 @@ def step(self, action: np.ndarray) -> tuple: action = np.clip(action, self.action_space.low, self.action_space.high) # position - # next_pos = self.curr_pos.copy() + # next_pos = self.curr_pos.copy() # TODO might be better with actual pos! next_pos = self.controller.get_target_pos() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] @@ -233,7 +233,6 @@ def reset(self, joint_reset=False, **kwargs): self._update_currpos() obs = self._get_obs() - return obs, {} def _send_pos_command(self, target_pos: np.ndarray): From ef252ef2ecf10cec720617e0b671d34541dd3e57 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 16:31:09 +0200 Subject: [PATCH 097/338] added RelativeFrame --- examples/robotiq_sac/sac_policy_robotiq.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 00d6779b..eaed3d40 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -20,6 +20,7 @@ from serl_launcher.data.data_store import populate_data_store from serl_launcher.wrappers.chunking import ChunkingWrapper +from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore @@ -32,7 +33,7 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper, BinaryRewardClassifierWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper import robotiq_env @@ -268,7 +269,7 @@ def main(_): ) if FLAGS.actor: env = SpacemouseIntervention(env) - # env = RelativeFrame(env) + env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) From 9511f76bb4f14061a4e14ef93a01c6b5ed831582 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 18:41:31 +0200 Subject: [PATCH 098/338] added Reward Transformer --- examples/robotiq_bc/record_demo.py | 4 +++- examples/robotiq_sac/sac_policy_robotiq.py | 2 +- serl_launcher/serl_launcher/data/data_store.py | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index bc28b073..d663c8a7 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -13,6 +13,7 @@ from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.wrappers.chunking import ChunkingWrapper +from gymnasium.wrappers import TransformReward from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env exit_program = threading.Event() @@ -36,6 +37,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) + env = TransformReward(env, lambda r: 10. * r) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) obs, _ = env.reset() @@ -91,7 +93,7 @@ def on_esc(key): print( f"{rew}\tGot {success_count} successes of {total_count} trials. {success_needed} successes needed." ) - pbar.update(rew) + pbar.update(int(rew > 0.99)) obs, _ = env.reset() with open(file_path, "wb") as f: diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index eaed3d40..38e3c110 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -273,8 +273,8 @@ def main(_): env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - env = RecordEpisodeStatistics(env) env = TransformReward(env, lambda r: FLAGS.reward_scale * r) + env = RecordEpisodeStatistics(env) rng, sampling_rng = jax.random.split(rng) print(f"obs shape: {env.observation_space.sample().shape}") diff --git a/serl_launcher/serl_launcher/data/data_store.py b/serl_launcher/serl_launcher/data/data_store.py index a45f996d..b03a81e6 100644 --- a/serl_launcher/serl_launcher/data/data_store.py +++ b/serl_launcher/serl_launcher/data/data_store.py @@ -164,7 +164,7 @@ def populate_data_store( with open(demo_path, "rb") as f: demo = pkl.load(f) for transition in demo: - transition["rewards"] *= reward_scaling # apply reward scaling + transition["rewards"] *= reward_scaling # apply reward scaling data_store.insert(transition) print(f"Loaded {len(data_store)} transitions.") return data_store From 5a9a71a90a0c0784b545e81711d2105d5d991588 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 4 Apr 2024 18:41:47 +0200 Subject: [PATCH 099/338] more streamlined reward --- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index c58a6922..0f9275da 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -7,9 +7,9 @@ def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) def compute_reward(self, obs) -> float: - if 0.1 < self.gripper_state[0] < 0.3 and self.curr_force[2] < -3.: + if 0.1 < self.gripper_state[0] < 0.4 and self.curr_force[2] < -3.: return 1. - if self.curr_force[2] > 5.: - return (5. - self.curr_force[2]) * 0.1 # return 0 if force=5, -0.5 if force=10 (max)) + # if self.curr_force[2] > 5.: + # return (5. - self.curr_force[2]) * 0.1 # return 0 if force=5, -0.5 if force=10 (max)) else: return 0.0 From 7620cbddc372f7f78bbf6f9814c0df06f7774317 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 14:50:39 +0200 Subject: [PATCH 100/338] soft actor critic worked with this, so I commit :) --- examples/robotiq_bc/record_demo.py | 2 +- examples/robotiq_sac/run_actor.sh | 12 +++++------ examples/robotiq_sac/run_learner.sh | 13 ++++++------ examples/robotiq_sac/sac_policy_robotiq.py | 14 ++++++++----- .../serl_launcher/agents/continuous/sac.py | 9 +++++++- serl_launcher/serl_launcher/utils/launcher.py | 16 +++++++------- .../robotiq_env/envs/robotiq_env.py | 17 ++++++++------- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 21 +++++++++++++------ 8 files changed, 64 insertions(+), 40 deletions(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index d663c8a7..3d0fa150 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -37,7 +37,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) - env = TransformReward(env, lambda r: 10. * r) + # env = TransformReward(env, lambda r: 10. * r) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) obs, _ = env.reset() diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh index c88e2a6d..2ce75e43 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/robotiq_sac/run_actor.sh @@ -6,10 +6,10 @@ python sac_policy_robotiq.py "$@" \ --exp_name=sac_robotiq_policy \ --seed 0 \ --max_steps 10000 \ - --random_steps 600 \ - --training_starts 600 \ + --random_steps 0 \ + --training_starts 0 \ --utd_ratio 8 \ - --batch_size 256 \ - --eval_period 2000 \ - --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl" \ -# --debug + --batch_size 1024 \ + --eval_period 1000 \ + --reward_scale 1 \ +# --debug \ No newline at end of file diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh index 77c1b239..8fb8f79c 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/robotiq_sac/run_learner.sh @@ -5,12 +5,13 @@ python sac_policy_robotiq.py "$@" \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ --seed 0 \ - --random_steps 600 \ - --training_starts 600 \ + --random_steps 400 \ + --training_starts 400 \ --utd_ratio 8 \ --batch_size 1024 \ - --eval_period 2000 \ - --max_steps 10000 \ - --preload_rlds_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds" \ -# --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl" \ + --eval_period 1000 \ + --max_steps 100000 \ + --reward_scale 1 \ + --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_apr9_action_cost.pkl" \ +# --preload_rlds_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds" \ # --debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 38e3c110..a4d4fa8c 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -117,15 +117,15 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: - print("sampling randomly!") + # print("sampling randomly!") actions = env.action_space.sample() else: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( observations=jax.device_put(obs), - # seed=key, + seed=key, # deterministic=False, - argmax=True, # TODO which one to use? + argmax=False, # TODO which one to use? ) actions = np.asarray(jax.device_get(actions)) @@ -150,6 +150,7 @@ def update_params(params): obs = next_obs if done or truncated: + print(f"running return: {running_return} done:{done} truncated:{truncated}") running_return = 0.0 obs, _ = env.reset() @@ -223,7 +224,7 @@ def stats_callback(type: str, payload: dict) -> dict: with timer.context("train"): if FLAGS.utd_ratio == 1: - agent, update_info = agent.update(batch=batch) # try it without utd + agent, update_info = agent.update(batch=batch) # try it without utd else: agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) agent = jax.block_until_ready(agent) @@ -275,6 +276,9 @@ def main(_): # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = TransformReward(env, lambda r: FLAGS.reward_scale * r) env = RecordEpisodeStatistics(env) + """ + env = gym.make(FLAGS.env) + """ rng, sampling_rng = jax.random.split(rng) print(f"obs shape: {env.observation_space.sample().shape}") @@ -311,7 +315,7 @@ def create_replay_buffer_and_wandb_logger(): sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() - if FLAGS.preload_rlds_path == None: + if FLAGS.preload_rlds_path is None and FLAGS.demo_paths is not None: print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths, reward_scaling=FLAGS.reward_scale) diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index ca933db4..4024b7a9 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -385,7 +385,14 @@ def create( # Config assert not entropy_per_dim, "Not implemented" if target_entropy is None: - target_entropy = -actions.shape[-1] / 2 + # target_entropy = -actions.shape[-1] / 2 + print(f"actions shape: {actions.shape}") + + # from https://github.com/NickKaparinos/OpenAI-Gym-Projects/blob/master/Classic%20Control/MountainCarContinuous/main.py: + # target_entropy = -np.prod(env.action_space.shape) + from numpy import prod + target_entropy = -prod(actions.shape) + print(f"target_entropy: {target_entropy}") return cls( state=state, diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 42ebb55a..c93eeaab 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -84,20 +84,20 @@ def make_sac_agent(seed, sample_obs, sample_action): critic_network_kwargs={ "activations": nn.tanh, "use_layer_norm": True, - # "hidden_dims": [256, 256], # TODO trying it with simpler network - "hidden_dims": [128, 64], + "hidden_dims": [256, 256], # TODO trying it with simpler network + # "hidden_dims": [128, 64], }, policy_network_kwargs={ "activations": nn.tanh, "use_layer_norm": True, - # "hidden_dims": [256, 256], - "hidden_dims": [128, 64], + "hidden_dims": [256, 256], + # "hidden_dims": [128, 64], }, - temperature_init=1e-2, - discount=0.95, # TODO maybe try 0.98 or lower (only 100 steps!) + temperature_init=1e-2, # 1e-2 + discount=0.99, # TODO maybe try 0.98 or lower (only 100 steps!) backup_entropy=False, - # critic_ensemble_size=10, # isREDQ with these - # critic_subsample_size=2, + critic_ensemble_size=10, # isREDQ with these + critic_subsample_size=2, ) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index d5abdea2..7efec1f6 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -161,8 +161,8 @@ def step(self, action: np.ndarray) -> tuple: action = np.clip(action, self.action_space.low, self.action_space.high) # position - # next_pos = self.curr_pos.copy() # TODO might be better with actual pos! - next_pos = self.controller.get_target_pos() + next_pos = self.curr_pos.copy() # TODO might be better with actual pos (but will be delayed to target) + # next_pos = self.controller.get_target_pos() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] # orientation @@ -182,13 +182,16 @@ def step(self, action: np.ndarray) -> tuple: time.sleep(max(0, (1.0 / self.hz) - dt)) self._update_currpos() - ob = self._get_obs() - reward = self.compute_reward(ob) + obs = self._get_obs() + reward = self.compute_reward(obs, action) truncated = self._is_truncated() - done = self.curr_path_length >= self.max_episode_length or (reward > 0.99) - return ob, int(reward), done, truncated, {} + done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) + return obs, reward, done, truncated, {} + + def compute_reward(self, obs, action) -> float: + return 0. # overwrite for each task - def compute_reward(self, obs) -> bool: + def reached_goal_state(self, obs) -> bool: return False # overwrite for each task def go_to_rest(self, joint_reset=False): diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index 0f9275da..d2d85870 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -1,3 +1,5 @@ +import numpy as np + from robotiq_env.envs.robotiq_env import RobotiqEnv from robotiq_env.envs.robotiq_grip_v1.config import RobotiqCornerConfig @@ -6,10 +8,17 @@ class RobotiqGripV1(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) - def compute_reward(self, obs) -> float: - if 0.1 < self.gripper_state[0] < 0.4 and self.curr_force[2] < -3.: - return 1. - # if self.curr_force[2] > 5.: - # return (5. - self.curr_force[2]) * 0.1 # return 0 if force=5, -0.5 if force=10 (max)) + def compute_reward(self, obs, action) -> float: + # huge action gives negative reward (like in mountain car) + neg_rew = -0.1 * np.sum(np.power(action, 2)) + # neg_rew = 0. + + if self.reached_goal_state(obs): + return 10. + neg_rew else: - return 0.0 + return 0.0 + neg_rew + + def reached_goal_state(self, obs) -> bool: + # obs[0] == gripper pressure, obs[4] == force in Z-axis + state = obs["state"] + return 0.1 < state['gripper_state'][0] < 0.4 and state['tcp_force'][2] < -3. From fafa19ba5b26c52386290b05cba1aeeefbdfa668 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:18:07 +0200 Subject: [PATCH 101/338] added evaluation to SAC actor --- examples/robotiq_bc/bc_policy_robotiq.py | 14 ++--- examples/robotiq_sac/run_evaluation.sh | 9 ++++ examples/robotiq_sac/run_rsac_actor.sh | 10 ---- examples/robotiq_sac/sac_policy_robotiq.py | 51 ++++++++++++++++--- serl_launcher/serl_launcher/utils/launcher.py | 4 +- 5 files changed, 63 insertions(+), 25 deletions(-) create mode 100644 examples/robotiq_sac/run_evaluation.sh delete mode 100644 examples/robotiq_sac/run_rsac_actor.sh diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index 6e5d8aad..e5033e0e 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -30,6 +30,8 @@ # from franka_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env + import robotiq_env FLAGS = flags.FLAGS @@ -45,10 +47,8 @@ flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") -flags.DEFINE_multi_string("demo_paths", "robotiq_bc/robotiq_test_20_demos_2024-03-26_12-23-50.pkl", - "paths to demos") -flags.DEFINE_string("checkpoint_path", "/home/nico/real-world-rl/serl/examples/robotiq_bc/checkpoints", - "Path to save checkpoints.") +flags.DEFINE_multi_string("demo_paths", None, "paths to demos") +flags.DEFINE_string("checkpoint_path", None, "Path to save checkpoints.") flags.DEFINE_integer( "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" @@ -80,7 +80,7 @@ def main(_): fake_env=not FLAGS.eval_checkpoint_step, ) env = SpacemouseIntervention(env) - # env = RelativeFrame(env) + env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) @@ -183,8 +183,8 @@ def space_on_press(key): while not done: actions = agent.sample_actions( observations=jax.device_put(obs), - argmax=False, - seed=rng, + argmax=True, + # seed=rng, ) actions = np.asarray(jax.device_get(actions)) print(f"sampled actions: {actions}") diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/robotiq_sac/run_evaluation.sh new file mode 100644 index 00000000..86b707c7 --- /dev/null +++ b/examples/robotiq_sac/run_evaluation.sh @@ -0,0 +1,9 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python sac_policy_robotiq.py "$@" \ + --actor \ + --env robotiq-grip-v1 \ + --exp_name=sac_robotiq_policy_evaluation \ + --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0409-15:15"\ + --eval_checkpoint_step 100000 \ + --debug \ No newline at end of file diff --git a/examples/robotiq_sac/run_rsac_actor.sh b/examples/robotiq_sac/run_rsac_actor.sh deleted file mode 100644 index 690c205f..00000000 --- a/examples/robotiq_sac/run_rsac_actor.sh +++ /dev/null @@ -1,10 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -which python && \ -python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ - --env robotiq-grip-v1 \ - --exp_name=sav_robotiq_actor \ - --seed 42 \ - --batch_size 256 \ - --eval_checkpoint_step 100000 \ -# --debug # wandb is disabled when debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index a4d4fa8c..7c0607a0 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -60,16 +60,19 @@ flags.DEFINE_integer("log_period", 10, "Logging period.") flags.DEFINE_integer("eval_period", 2000, "Evaluation period.") -flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") +flags.DEFINE_integer("eval_n_trajs", 3, "Number of trajectories for evaluation.") # flag to indicate if this is a leaner or a actor -flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") # TODO change back! +flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints', "Path to save checkpoints.") +flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") +flags.DEFINE_integer("eval_checkpoint_path", 0, "evaluate the policy from ckpt from this path") + flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") # TODO does not work yet @@ -90,6 +93,45 @@ def actor(agent: SACAgent, data_store, env, sampling_rng): """ This is the actor loop, which runs when "--actor" is set to True. """ + if FLAGS.eval_checkpoint_step: + success_counter = 0 + time_list = [] + + ckpt = checkpoints.restore_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=FLAGS.eval_checkpoint_step, + ) + agent = agent.replace(state=ckpt) + + for episode in range(FLAGS.eval_n_trajs): + obs, _ = env.reset() + done = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=True, + ) + actions = np.asarray(jax.device_get(actions)) + + next_obs, reward, done, truncated, info = env.step(actions) + obs = next_obs + + if done: + if reward: + dt = time.time() - start_time + time_list.append(dt) + print(dt) + + success_counter += int(reward > 0.99) + print(reward) + print(f"{success_counter}/{episode + 1}") + + print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") + print(f"average time: {np.mean(time_list)}") + return # after done eval, return and exit + client = TrainerClient( "actor_env", FLAGS.ip, @@ -150,7 +192,7 @@ def update_params(params): obs = next_obs if done or truncated: - print(f"running return: {running_return} done:{done} truncated:{truncated}") + # print(f"running return: {running_return} done:{done} truncated:{truncated}") running_return = 0.0 obs, _ = env.reset() @@ -276,9 +318,6 @@ def main(_): # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = TransformReward(env, lambda r: FLAGS.reward_scale * r) env = RecordEpisodeStatistics(env) - """ - env = gym.make(FLAGS.env) - """ rng, sampling_rng = jax.random.split(rng) print(f"obs shape: {env.observation_space.sample().shape}") diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index c93eeaab..81df1465 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -58,8 +58,8 @@ def make_bc_agent_no_img( network_kwargs={ "activations": nn.tanh, "use_layer_norm": False, - # "hidden_dims": [256, 256], - "hidden_dims": [128, 64], + "hidden_dims": [256, 256], + # "hidden_dims": [128, 64], }, policy_kwargs={ "tanh_squash_distribution": False, From ace462463279d76fa9812f07a5c54c6dee64574c Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:23:27 +0200 Subject: [PATCH 102/338] bugfix --- examples/robotiq_sac/run_evaluation.sh | 3 ++- examples/robotiq_sac/sac_policy_robotiq.py | 6 ++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/robotiq_sac/run_evaluation.sh index 86b707c7..23b97925 100644 --- a/examples/robotiq_sac/run_evaluation.sh +++ b/examples/robotiq_sac/run_evaluation.sh @@ -6,4 +6,5 @@ python sac_policy_robotiq.py "$@" \ --exp_name=sac_robotiq_policy_evaluation \ --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0409-15:15"\ --eval_checkpoint_step 100000 \ - --debug \ No newline at end of file + --eval_n_trajs 20 \ + --debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 7c0607a0..ed370acf 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -71,7 +71,7 @@ "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_integer("eval_checkpoint_path", 0, "evaluate the policy from ckpt from this path") +flags.DEFINE_string("eval_checkpoint_path", None, "evaluate the policy from ckpt from this path") flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', "Path to save RLDS logs.") @@ -98,7 +98,7 @@ def actor(agent: SACAgent, data_store, env, sampling_rng): time_list = [] ckpt = checkpoints.restore_checkpoint( - FLAGS.checkpoint_path, + FLAGS.eval_checkpoint_path, agent.state, step=FLAGS.eval_checkpoint_step, ) @@ -381,6 +381,8 @@ def create_replay_buffer_and_wandb_logger(): # actor loop print_green("starting actor loop") actor(agent, data_store, env, sampling_rng) + print_green("actor loop finished") + env.close() else: raise NotImplementedError("Must be either a learner or an actor") From 840d74f3488fba4d2d65abcab6cb477ee9faff4a Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:38:19 +0200 Subject: [PATCH 103/338] namechange --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 7efec1f6..15c7e979 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -55,8 +55,8 @@ def __init__( self.curr_pos = np.zeros((7,), dtype=np.float32) self.curr_vel = np.zeros((6,), dtype=np.float32) - self.Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq - self.Qd = np.zeros((6,), dtype=np.float32) + self.curr_Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq + self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((3,), dtype=np.float32) self.curr_torque = np.zeros((3,), dtype=np.float32) @@ -258,8 +258,8 @@ def _update_currpos(self): self.curr_vel[:] = state['vel'] self.curr_force[:] = state['force'] self.curr_torque[:] = state['torque'] - self.Q[:] = state['Q'] - self.Qd[:] = state['Qd'] + self.curr_Q[:] = state['Q'] + self.curr_Qd[:] = state['Qd'] self.gripper_state[:] = state['gripper'] def _is_truncated(self): From 071374f3bd2df7a7464d3fea02e59bfd1fd72d8c Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:39:33 +0200 Subject: [PATCH 104/338] namechange --- examples/robotiq_bc/test_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_bc/test_demo.py b/examples/robotiq_bc/test_demo.py index 6aafe13a..b4349fdd 100644 --- a/examples/robotiq_bc/test_demo.py +++ b/examples/robotiq_bc/test_demo.py @@ -44,7 +44,7 @@ def on_esc(key): listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) listener_2.start() - file_path = "robotiq_test_20_demos_2024-03-26_12-23-50.pkl" + file_path = "robotiq_test_20_demos_mar26_rew1.pkl.old" with open(file_path, "rb") as f: transitions = pkl.load(f) From 17d1fabc042b53327549624ea9e9529f93f182ec Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:40:32 +0200 Subject: [PATCH 105/338] new actor and learner config --- examples/robotiq_sac/run_actor.sh | 4 ++-- examples/robotiq_sac/run_learner.sh | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh index 2ce75e43..cfd9295c 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/robotiq_sac/run_actor.sh @@ -4,12 +4,12 @@ python sac_policy_robotiq.py "$@" \ --actor \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ - --seed 0 \ + --seed 42 \ --max_steps 10000 \ --random_steps 0 \ --training_starts 0 \ --utd_ratio 8 \ --batch_size 1024 \ - --eval_period 1000 \ + --eval_period 500 \ --reward_scale 1 \ # --debug \ No newline at end of file diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh index 8fb8f79c..5cdfaeee 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/robotiq_sac/run_learner.sh @@ -4,12 +4,12 @@ python sac_policy_robotiq.py "$@" \ --learner \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ - --seed 0 \ + --seed 42 \ --random_steps 400 \ --training_starts 400 \ --utd_ratio 8 \ --batch_size 1024 \ - --eval_period 1000 \ + --eval_period 500 \ --max_steps 100000 \ --reward_scale 1 \ --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_apr9_action_cost.pkl" \ From 059cc05beaf12398248373eeac048102cb68adf7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:57:10 +0200 Subject: [PATCH 106/338] more cleanup when terminated --- .../robot_controllers/robotiq_controller.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 1da583aa..fd414e0a 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -347,6 +347,17 @@ async def run_async(self): # mandatory cleanup self.robotiq_control.forceModeStop() + # release gripper + if self.robotiq_gripper: + self.target_grip[0] = -1. + await self.send_gripper_command() + time.sleep(0.1) + + # move to real home + pi = 3.1415 + reset_Q = [pi / 2., -pi / 2., pi / 2., -pi / 2., -pi / 2., 0.] + self.robotiq_control.moveJ(reset_Q, speed=1., acceleration=0.5) + # terminate self.robotiq_control.disconnect() self.robotiq_receive.disconnect() From 4ac40e1cfd6b4f9eaec6b2ecb1b5165414910e2e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 16:57:38 +0200 Subject: [PATCH 107/338] params for boxes with rough surfaces --- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index d2d85870..ec99ead8 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -21,4 +21,4 @@ def compute_reward(self, obs, action) -> float: def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.4 and state['tcp_force'][2] < -3. + return 0.1 < state['gripper_state'][0] < 0.8 and state['tcp_force'][2] < -3. From 9be84dbcd67132c606cb6aac3f20cc67f23eb41e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 9 Apr 2024 17:18:28 +0200 Subject: [PATCH 108/338] boxes tried out --- .../robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index ec99ead8..8c96ae4b 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -11,7 +11,7 @@ def __init__(self, **kwargs): def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) neg_rew = -0.1 * np.sum(np.power(action, 2)) - # neg_rew = 0. + # TODO maybe add neg reward for sucking too early if self.reached_goal_state(obs): return 10. + neg_rew From 6ea821a97016e3644ef2e83e52cd7c9f29d86c58 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Apr 2024 17:57:40 +0200 Subject: [PATCH 109/338] higher reset height --- serl_robot_infra/robot_controllers/robotiq_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index fd414e0a..26ee34d4 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -60,7 +60,7 @@ def __init__( self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space - self.reset_height = np.array([0.06], dtype=np.float32) # TODO make customizable + self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable self._is_truncated = False self.delta = config.ERROR_DELTA From 8ed035f678cd68c697972834e24e2c055a824360 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Apr 2024 17:58:12 +0200 Subject: [PATCH 110/338] added step cost and ignore xy cost --- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index 8c96ae4b..8f720c5c 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -10,15 +10,22 @@ def __init__(self, **kwargs): def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) - neg_rew = -0.1 * np.sum(np.power(action, 2)) + action_cost = 0.1 * np.sum(np.power(action, 2)) # TODO maybe add neg reward for sucking too early + step_cost = 0.01 + pose = obs["state"]["tcp_pose"] + # box_xy = np.array([0.009, -0.5437]) # TODO replace with camera / pointcloud info of box + # xy_cost = 5 * np.sum(np.power(pose[:2] - box_xy, 2)) # TODO can be ignored + + # print(f"action_cost: {action_cost}, xy_cost: {xy_cost}") if self.reached_goal_state(obs): - return 10. + neg_rew + return 10. - action_cost - step_cost else: - return 0.0 + neg_rew + return 0.0 - action_cost - step_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.8 and state['tcp_force'][2] < -3. + # return 0.1 < state['gripper_state'][0] < 0.8 and state['tcp_force'][2] < -3. + return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.15 # new min height with box From 77f9244535a44bc3e3ae9c24b28388218936fdd8 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Apr 2024 17:58:37 +0200 Subject: [PATCH 111/338] catch if actor is terminated early --- examples/robotiq_sac/sac_policy_robotiq.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index ed370acf..70faff31 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -199,7 +199,7 @@ def update_params(params): if step % FLAGS.steps_per_update == 0: client.update() - if step % FLAGS.eval_period == 0: + if step % FLAGS.eval_period == 0 and step: with timer.context("eval"): evaluate_info = evaluate( policy_fn=partial(agent.sample_actions, argmax=True), @@ -380,9 +380,13 @@ def create_replay_buffer_and_wandb_logger(): # actor loop print_green("starting actor loop") - actor(agent, data_store, env, sampling_rng) - print_green("actor loop finished") - env.close() + try: + actor(agent, data_store, env, sampling_rng) + print_green("actor loop finished") + except KeyboardInterrupt: + print_green("actor loop interrupted") + finally: + env.close() else: raise NotImplementedError("Must be either a learner or an actor") From 6e914a1004944e65995b8dcd33606bf255febc79 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Apr 2024 17:59:20 +0200 Subject: [PATCH 112/338] set original pose (without shift) as the relative pose --- serl_robot_infra/franka_env/envs/relative_env.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/serl_robot_infra/franka_env/envs/relative_env.py b/serl_robot_infra/franka_env/envs/relative_env.py index 75b15bf6..81639cd7 100644 --- a/serl_robot_infra/franka_env/envs/relative_env.py +++ b/serl_robot_infra/franka_env/envs/relative_env.py @@ -56,6 +56,9 @@ def step(self, action: np.ndarray): def reset(self, **kwargs): obs, info = self.env.reset(**kwargs) + # TODO remove after image / pointcloud data + obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) + # Update adjoint matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) if self.include_relative_pose: From ca58a2009a1e574c64e3d2b4f34902c83b343f73 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Apr 2024 17:59:40 +0200 Subject: [PATCH 113/338] pose shift and multiple reset poses implementation --- .../robotiq_env/envs/robotiq_env.py | 24 +++++++--- .../envs/robotiq_grip_v1/config.py | 47 +++++++++++++++---- 2 files changed, 56 insertions(+), 15 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 15c7e979..945b228f 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -17,7 +17,7 @@ class DefaultEnvConfig: """Default configuration for RobotiqEnv. Fill in the values below.""" - RESET_Q = np.zeros((6,)) + RESET_Q = np.zeros((6, )) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) @@ -202,7 +202,14 @@ def go_to_rest(self, joint_reset=False): """ # Perform Carteasian reset - reset_Q = self.resetQ.copy() + reset_Q = np.zeros((6)) + if self.resetQ.shape == (6, ): + reset_Q[:] = self.resetQ.copy() + elif self.resetQ.shape[1] == 6 and len(self.resetQ.shape) == 2: + choice = np.random.randint(self.resetQ.shape[0]) + reset_Q[:] = self.resetQ[choice, :].copy() # make random guess + else: + raise ValueError(f"invalid resetQ dimension: {self.resetQ.shape}") self._send_reset_command(reset_Q) @@ -215,9 +222,9 @@ def go_to_rest(self, joint_reset=False): if self.random_reset: # randomize reset position in xy plane # reset_pose = self.resetpos.copy() reset_pose = self.controller.get_target_pos() - reset_pose[:2] += np.random.uniform( - np.negative(self.random_xy_range), self.random_xy_range, (2,) - ) + reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) + reset_pose[:2] += reset_shift + # euler_random = reset_pose[3:] # euler_random[-1] += np.random.uniform( # np.negative(self.random_rz_range), self.random_rz_range @@ -227,16 +234,19 @@ def go_to_rest(self, joint_reset=False): time.sleep(0.1) if not self.controller.is_moving(): break + return reset_shift + else: + return np.zeros((2,)) def reset(self, joint_reset=False, **kwargs): self.cycle_count += 1 - self.go_to_rest(joint_reset=joint_reset) + shift = self.go_to_rest(joint_reset=joint_reset) self.curr_path_length = 0 self._update_currpos() obs = self._get_obs() - return obs, {} + return obs, {"reset_shift": shift} def _send_pos_command(self, target_pos: np.ndarray): """Internal function to send force command to the robot.""" diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py index f708e1c2..016e087e 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py @@ -3,22 +3,53 @@ class RobotiqCornerConfig(DefaultEnvConfig): - # RESET_Q = np.array([[1.38228, -1.24648, 1.9504, -2.2732, -1.5645, -0.18799]]) # old one - RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) + # RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) # original one + # RESET_Q = np.array([[1.3463, -1.3584, 1.9014, -2.1243, -1.5758, -0.2312]]) + RESET_Q = np.array([ + [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], + [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], + [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], + [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], + [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] + ]) RANDOM_RESET = False - RANDOM_XY_RANGE = (0.05,) + RANDOM_XY_RANGE = (0.06,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ + # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ + # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) + ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.1, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 3.0, -0.1, -3.2]) + ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + + ROBOT_IP: str = "172.22.22.2" + CONTROLLER_HZ = 100 + GRIPPER_TIMEOUT = 2000 # in milliseconds + ERROR_DELTA: float = 0.05 + FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_TASK_FRAME = np.zeros(6) + FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) + + +class RobotiqCornerConfigV1(DefaultEnvConfig): + """ + Configuration for the first set of SAC training's (only 1 box) + """ + # RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) # original one + RESET_Q = np.array([[1.3463, -1.3584, 1.9014, -2.1243, -1.5758, -0.2312]]) + # TODO make multiple reset Q positions, one for each box to train on (randomize it) + RANDOM_RESET = False + RANDOM_XY_RANGE = (0.06,) + RANDOM_RZ_RANGE = (0.0,) + ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) - # ABS_POSE_LIMIT_HIGH = np.array([0.0, -0.5, 0.15, 3.2, 0.1, 3.2]) # more conservative for tests - # ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.6, 0.1, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" CONTROLLER_HZ = 100 - GRIPPER_TIMEOUT = 2000 # in milliseconds + GRIPPER_TIMEOUT = 2000 # in milliseconds ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) From 6c95ca38254ea44aa09b6cd63b3cf1353317673b Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 12 Apr 2024 15:58:16 +0200 Subject: [PATCH 114/338] some controller cleanup --- .../robot_controllers/robotiq_controller.py | 107 ++++++++++-------- .../robotiq_env/envs/robotiq_env.py | 10 +- 2 files changed, 63 insertions(+), 54 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 26ee34d4..eb81adc2 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -40,13 +40,14 @@ def __init__( self._stop = threading.Event() self._reset = threading.Event() self._is_ready = threading.Event() + self._is_truncated = threading.Event() self.lock = threading.Lock() self.robot_ip = robot_ip self.frequency = frequency self.kp = kp self.kd = kd - self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic()-1e6} + self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} self.verbose = verbose self.do_plot = plot @@ -60,8 +61,7 @@ def __init__( self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space - self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable - self._is_truncated = False + self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable self.delta = config.ERROR_DELTA self.fm_damping = config.FORCEMODE_DAMPING @@ -88,9 +88,11 @@ def start(self): if self.verbose: print(f"[RIC] Controller process spawned at {self.native_id}") - def print(self, msg, probability=1.): + def print(self, msg, probability=1., both=False): if np.random.random() < probability: self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') + if both: + print(msg) async def start_robotiq_interfaces(self, gripper=True): for _ in range(5): # try it 5 times @@ -134,9 +136,9 @@ def set_target_pos(self, target_pos: np.ndarray): self.print(f"target: {self.target_pos}") def set_reset_Q(self, reset_Q: np.ndarray): - self._reset.set() with self.lock: self.reset_Q[:] = reset_Q + self._reset.set() def set_gripper_pos(self, target_grip: np.ndarray): with self.lock: @@ -163,7 +165,7 @@ async def _update_robot_state(self): self.curr_Q[:] = Q self.curr_Qd[:] = Qd self.curr_force[:] = force - self.gripper_state[:] = [pressure / 100., float(obj_status.value)] # pressure between [0, 1] + self.gripper_state[:] = [pressure / 100., float(obj_status.value)] # pressure between [0, 1] def get_state(self): with self.lock: @@ -234,7 +236,8 @@ def plot(self): self.stop() async def send_gripper_command(self): - timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout["timeout"] + timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout[ + "timeout"] if self.target_grip[0] > 0.5 and timeout_exceeded: await self.robotiq_gripper.automatic_grip() self.target_grip[0] = 0.0 @@ -247,13 +250,14 @@ async def send_gripper_command(self): # print("release") def _truncate_check(self): - if self.curr_force[2] > 10.: # TODO add better criteria - self._is_truncated = True + downward_force = self.curr_force[2] > 10 + if downward_force: # TODO add better criteria + self._is_truncated.set() else: - self._is_truncated = False + self._is_truncated.clear() def is_truncated(self): - return self._is_truncated + return self._is_truncated.is_set() def run(self): try: @@ -261,6 +265,35 @@ def run(self): finally: self.stop() + async def _go_to_reset_pose(self): + self.robotiq_control.forceModeStop() + + # first disable vaccum gripper + if self.robotiq_gripper: + self.target_grip[0] = -1. + await self.send_gripper_command() + time.sleep(0.1) + + # then move up (so no boxes are moved) + while self.curr_pos[2] < self.reset_height: + assert self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) + await self._update_robot_state() + time.sleep(0.01) + self.robotiq_control.speedStop(a=1.) + + # then move to desired Jointspace position + assert self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) + self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) + + await self._update_robot_state() + with self.lock: + self.target_pos = self.curr_pos.copy() + + self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.robotiq_control.zeroFtSensor() + + self._reset.clear() + async def run_async(self): await self.start_robotiq_interfaces(gripper=True) @@ -277,35 +310,12 @@ async def run_async(self): self._is_ready.set() while not self.stopped(): - if self._reset.is_set() and self.curr_pos[2] < self.reset_height - 0.01: - # move up first, then in joint-space - self.target_pos[2] = self.reset_height - - elif self._reset.is_set() and not self.is_moving(): # move to reset joint space pose with moveJ - # first disable vaccum gripper - if self.robotiq_gripper: - self.target_grip[0] = -1. - await self.send_gripper_command() - time.sleep(0.1) - - # then move to Jointspace position - print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)") - self.robotiq_control.forceModeStop() - self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.5) - self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)") - - await self._update_robot_state() - with self.lock: - self.target_pos = self.curr_pos.copy() - - self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster - self.robotiq_control.zeroFtSensor() - - self._reset.clear() + if self._reset.is_set(): + await self._go_to_reset_pose() t_now = time.monotonic() - # update robot state + # update robot state and check for truncation await self._update_robot_state() self._truncate_check() @@ -316,18 +326,24 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # output to file + self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # log to file # send command to robot t_start = self.robotiq_control.initPeriod() - assert self.robotiq_control.forceMode( + fm_successful = self.robotiq_control.forceMode( self.fm_task_frame, self.fm_selection_vector, force, 2, self.fm_limits ) - # TODO try to reset with moveJ if forcemode returns False + if not fm_successful: # truncate if the robot ends up in a singularity + self._is_truncated.set() + + # disconnect and reconnect, otherwise the controller won't take any commands + self.robotiq_control.disconnect() + time.sleep(0.5) + self.robotiq_control.reconnect() if self.robotiq_gripper: await self.send_gripper_command() @@ -336,14 +352,11 @@ async def run_async(self): a = dt - (time.monotonic() - t_now) time.sleep(max(0., a)) - if a < 0: # log how slow the loop runs - self.err += 1 - self.print(f"over dt: {-a:.5f} s") - else: - self.noerr += 1 + self.err, self.noerr = self.err + int(a < 0.), self.noerr + int(a >= 0.) # some logging finally: - print(f"[RTDEPositionalController] >dt: {self.err}
dt: {self.err}
Date: Fri, 12 Apr 2024 15:59:37 +0200 Subject: [PATCH 115/338] bugfix --- serl_robot_infra/robot_controllers/robotiq_controller.py | 1 - 1 file changed, 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index eb81adc2..440a3a76 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -298,7 +298,6 @@ async def run_async(self): await self.start_robotiq_interfaces(gripper=True) self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster - self.start_t = time.monotonic() try: dt = 1. / self.frequency From aec9b32d31a9d693f3443ece85c760cfeaadd8c1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 12 Apr 2024 17:14:07 +0200 Subject: [PATCH 116/338] RelativeFrame Wrapper has been customized for Robotiq Env --- examples/robotiq_bc/bc_policy_robotiq.py | 2 +- examples/robotiq_bc/record_demo.py | 2 +- .../franka_env/envs/relative_env.py | 3 - .../robotiq_env/envs/relative_env.py | 99 +++++++++++++++++++ 4 files changed, 101 insertions(+), 5 deletions(-) create mode 100644 serl_robot_infra/robotiq_env/envs/relative_env.py diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index e5033e0e..f6c14a9e 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -30,7 +30,7 @@ # from franka_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env +from robotiq_env.envs.relative_env import RelativeFrame import robotiq_env diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index 3d0fa150..5fad694d 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -14,7 +14,7 @@ from serl_launcher.wrappers.chunking import ChunkingWrapper from gymnasium.wrappers import TransformReward -from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env +from robotiq_env.envs.relative_env import RelativeFrame exit_program = threading.Event() diff --git a/serl_robot_infra/franka_env/envs/relative_env.py b/serl_robot_infra/franka_env/envs/relative_env.py index 81639cd7..75b15bf6 100644 --- a/serl_robot_infra/franka_env/envs/relative_env.py +++ b/serl_robot_infra/franka_env/envs/relative_env.py @@ -56,9 +56,6 @@ def step(self, action: np.ndarray): def reset(self, **kwargs): obs, info = self.env.reset(**kwargs) - # TODO remove after image / pointcloud data - obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) - # Update adjoint matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) if self.include_relative_pose: diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py new file mode 100644 index 00000000..81639cd7 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -0,0 +1,99 @@ +from scipy.spatial.transform import Rotation as R +import gymnasium as gym +import numpy as np +from gym import Env +from franka_env.utils.transformations import ( + construct_adjoint_matrix, + construct_homogeneous_matrix, +) + + +class RelativeFrame(gym.Wrapper): + """ + This wrapper transforms the observation and action to be expressed in the end-effector frame. + Optionally, it can transform the tcp_pose into a relative frame defined as the reset pose. + + This wrapper is expected to be used on top of the base Franka environment, which has the following + observation space: + { + "state": spaces.Dict( + { + "tcp_pose": spaces.Box(-np.inf, np.inf, shape=(7,)), # xyz + quat + ...... + } + ), + ...... + }, and at least 6 DoF action space with (x, y, z, rx, ry, rz, ...) + """ + + def __init__(self, env: Env, include_relative_pose=True): + super().__init__(env) + self.adjoint_matrix = np.zeros((6, 6)) + + self.include_relative_pose = include_relative_pose + if self.include_relative_pose: + # Homogeneous transformation matrix from reset pose's relative frame to base frame + self.T_r_o_inv = np.zeros((4, 4)) + + def step(self, action: np.ndarray): + # action is assumed to be (x, y, z, rx, ry, rz, gripper) + # Transform action from end-effector frame to base frame + transformed_action = self.transform_action(action) + + obs, reward, done, truncated, info = self.env.step(transformed_action) + + # this is to convert the spacemouse intervention action + if "intervene_action" in info: + info["intervene_action"] = self.transform_action(info["intervene_action"]) + + # Update adjoint matrix + self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) + + # Transform observation to spatial frame + transformed_obs = self.transform_observation(obs) + return transformed_obs, reward, done, truncated, info + + def reset(self, **kwargs): + obs, info = self.env.reset(**kwargs) + + # TODO remove after image / pointcloud data + obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) + + # Update adjoint matrix + self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) + if self.include_relative_pose: + # Update transformation matrix from the reset pose's relative frame to base frame + self.T_r_o_inv = np.linalg.inv( + construct_homogeneous_matrix(obs["state"]["tcp_pose"]) + ) + + # Transform observation to spatial frame + return self.transform_observation(obs), info + + def transform_observation(self, obs): + """ + Transform observations from spatial(base) frame into body(end-effector) frame + using the adjoint matrix + """ + adjoint_inv = np.linalg.inv(self.adjoint_matrix) + obs["state"]["tcp_vel"] = adjoint_inv @ obs["state"]["tcp_vel"] + + if self.include_relative_pose: + T_b_o = construct_homogeneous_matrix(obs["state"]["tcp_pose"]) + T_b_r = self.T_r_o_inv @ T_b_o + + # Reconstruct transformed tcp_pose vector + p_b_r = T_b_r[:3, 3] + theta_b_r = R.from_matrix(T_b_r[:3, :3]).as_quat() + obs["state"]["tcp_pose"] = np.concatenate((p_b_r, theta_b_r)) + + return obs + + def transform_action(self, action: np.ndarray): + """ + Transform action from body(end-effector) frame into into spatial(base) frame + using the adjoint matrix + """ + action = np.array(action) # in case action is a jax read-only array + action[:6] = self.adjoint_matrix @ action[:6] + return action From f4e9e2c6ac47c4b631e239d1344cd84dba8b85aa Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 12 Apr 2024 17:15:21 +0200 Subject: [PATCH 117/338] clean a few TODO's --- examples/robotiq_sac/sac_policy_robotiq.py | 10 +++++----- serl_launcher/serl_launcher/utils/launcher.py | 10 +++++----- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 70faff31..97ded4d8 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -20,7 +20,7 @@ from serl_launcher.data.data_store import populate_data_store from serl_launcher.wrappers.chunking import ChunkingWrapper -from franka_env.envs.relative_env import RelativeFrame # TODO make robotiq_env +from robotiq_env.envs.relative_env import RelativeFrame from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore @@ -145,7 +145,7 @@ def update_params(params): nonlocal agent agent = agent.replace(state=agent.state.replace(params=params)) - client.recv_network_callback(update_params) # TODO RLDS does not load + client.recv_network_callback(update_params) obs, _ = env.reset() print(f"obs: {obs}") @@ -166,8 +166,8 @@ def update_params(params): actions = agent.sample_actions( observations=jax.device_put(obs), seed=key, - # deterministic=False, - argmax=False, # TODO which one to use? + argmax=False, + # deterministic=False, # sample without argmax for more diverse actions ) actions = np.asarray(jax.device_get(actions)) @@ -311,7 +311,7 @@ def main(_): max_episode_length=FLAGS.max_traj_length, ) if FLAGS.actor: - env = SpacemouseIntervention(env) + env = SpacemouseIntervention(env) # TODO really needed? env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 81df1465..ba284421 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -84,8 +84,8 @@ def make_sac_agent(seed, sample_obs, sample_action): critic_network_kwargs={ "activations": nn.tanh, "use_layer_norm": True, - "hidden_dims": [256, 256], # TODO trying it with simpler network - # "hidden_dims": [128, 64], + "hidden_dims": [256, 256], + # "hidden_dims": [128, 64], # simpler network }, policy_network_kwargs={ "activations": nn.tanh, @@ -93,10 +93,10 @@ def make_sac_agent(seed, sample_obs, sample_action): "hidden_dims": [256, 256], # "hidden_dims": [128, 64], }, - temperature_init=1e-2, # 1e-2 - discount=0.99, # TODO maybe try 0.98 or lower (only 100 steps!) + temperature_init=1e-2, # 1e-2 + discount=0.99, # or try values lower, not lower than 0.95 backup_entropy=False, - critic_ensemble_size=10, # isREDQ with these + critic_ensemble_size=10, # isREDQ with these critic_subsample_size=2, ) From 30e3a6ab286a23037635598867b706d25d510801 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Apr 2024 16:30:12 +0200 Subject: [PATCH 118/338] added suction cost --- .../envs/robotiq_grip_v1/robotiq_grip_v1.py | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py index 8f720c5c..c3c9fa13 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py @@ -4,6 +4,11 @@ from robotiq_env.envs.robotiq_grip_v1.config import RobotiqCornerConfig +# used for float value comparisons (pressure of vacuum-gripper) +def is_close(value, target): + return abs(value - target) < 1e-4 + + class RobotiqGripV1(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) @@ -11,18 +16,20 @@ def __init__(self, **kwargs): def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) - # TODO maybe add neg reward for sucking too early step_cost = 0.01 + gripper_state = obs["state"]['gripper_state'] + suck_cost = 0.1 * float(is_close(gripper_state[0], 0.99)) + pose = obs["state"]["tcp_pose"] # box_xy = np.array([0.009, -0.5437]) # TODO replace with camera / pointcloud info of box # xy_cost = 5 * np.sum(np.power(pose[:2] - box_xy, 2)) # TODO can be ignored # print(f"action_cost: {action_cost}, xy_cost: {xy_cost}") if self.reached_goal_state(obs): - return 10. - action_cost - step_cost + return 10. - action_cost - step_cost - suck_cost else: - return 0.0 - action_cost - step_cost + return 0.0 - action_cost - step_cost - suck_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From 7e7f984de240bd5063730362007d27283943e815 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Apr 2024 16:30:36 +0200 Subject: [PATCH 119/338] new actor and learner params --- examples/robotiq_sac/run_actor.sh | 6 +++--- examples/robotiq_sac/run_learner.sh | 11 +++++------ 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh index cfd9295c..0d758dfa 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/robotiq_sac/run_actor.sh @@ -4,12 +4,12 @@ python sac_policy_robotiq.py "$@" \ --actor \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ + --max_traj_length 300 \ --seed 42 \ --max_steps 10000 \ --random_steps 0 \ - --training_starts 0 \ --utd_ratio 8 \ - --batch_size 1024 \ - --eval_period 500 \ + --batch_size 2048 \ + --eval_period 1000 \ --reward_scale 1 \ # --debug \ No newline at end of file diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh index 5cdfaeee..e1c851cd 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/robotiq_sac/run_learner.sh @@ -4,14 +4,13 @@ python sac_policy_robotiq.py "$@" \ --learner \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy \ + --max_traj_length 300 \ --seed 42 \ - --random_steps 400 \ - --training_starts 400 \ + --training_starts 900 \ --utd_ratio 8 \ - --batch_size 1024 \ - --eval_period 500 \ - --max_steps 100000 \ + --batch_size 2048 \ + --max_steps 50000 \ --reward_scale 1 \ - --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_bc/robotiq_test_20_demos_apr9_action_cost.pkl" \ + --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_sac/robotiq_test_20_demos_apr11_random_boxes.pkl" \ # --preload_rlds_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds" \ # --debug From e9c0739951dd6425c6389e1c6a561a41ba30ab1d Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Apr 2024 16:31:33 +0200 Subject: [PATCH 120/338] added camera support (not tested yet) --- .../robotiq_env/envs/robotiq_env.py | 157 +++++++++++++++--- 1 file changed, 138 insertions(+), 19 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 6085f688..110c4562 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -1,23 +1,51 @@ """Gym Interface for Robotiq""" +import time +import threading +import copy import numpy as np import gymnasium as gym -import copy -import time +import cv2 +import queue from typing import Dict +from datetime import datetime +from collections import OrderedDict from scipy.spatial.transform import Rotation as R +from franka_env.camera.video_capture import VideoCapture +from franka_env.camera.rs_capture import RSCapture # TODO make robotiq (both) + from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController +class ImageDisplayer(threading.Thread): + def __init__(self, queue): + threading.Thread.__init__(self) + self.queue = queue + self.daemon = True # make this a daemon thread + + def run(self): + while True: + img_array = self.queue.get() # retrieve an image from the queue + if img_array is None: # None is our signal to exit + break + + frame = np.concatenate( + [v for k, v in img_array.items() if "full" not in k], axis=0 + ) + + cv2.imshow("RealSense Cameras", frame) + cv2.waitKey(1) + + ############################################################################## class DefaultEnvConfig: """Default configuration for RobotiqEnv. Fill in the values below.""" - RESET_Q = np.zeros((6, )) + RESET_Q = np.zeros((6,)) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) @@ -34,6 +62,11 @@ class DefaultEnvConfig: FORCEMODE_SELECTION_VECTOR = np.ones(6, ) FORCEMODE_LIMITS = np.zeros(6, ) + REALSENSE_CAMERAS: Dict = { + "shoulder": "", + "wrist": "", + } + ############################################################################## @@ -44,7 +77,8 @@ def __init__( hz: int = 10, fake_env=False, config=DefaultEnvConfig, - max_episode_length: int = 100 + max_episode_length: int = 100, + save_video=False, ): self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -67,6 +101,11 @@ def __init__( self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz + if save_video: + print("Saving videos!") + self.save_video = save_video + self.recording_frames = [] + self.xyz_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[:3], config.ABS_POSE_LIMIT_HIGH[:3], @@ -95,17 +134,17 @@ def __init__( "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } - ) - # "images": gym.spaces.Dict( # Images are ignored for now - # { - # "wrist_1": gym.spaces.Box( - # 0, 255, shape=(128, 128, 3), dtype=np.uint8 - # ), - # "wrist_2": gym.spaces.Box( - # 0, 255, shape=(128, 128, 3), dtype=np.uint8 - # ), - # } - # ), + ), + "images": gym.spaces.Dict( # TODO add depth info + { + "shoulder": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + "wrist": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + } + ), } ) self.cycle_count = 0 @@ -126,6 +165,12 @@ def __init__( ) self.controller.start() # start Thread + self.cap = None + self.init_cameras(config.REALSENSE_CAMERAS) + self.img_queue = queue.Queue() + self.displayer = ImageDisplayer(self.img_queue) + self.displayer.start() + while not self.controller.is_ready(): # wait for controller time.sleep(0.1) print("[RIC] Controller has started and is ready!") @@ -161,7 +206,7 @@ def step(self, action: np.ndarray) -> tuple: action = np.clip(action, self.action_space.low, self.action_space.high) # position - next_pos = self.curr_pos.copy() # TODO might be better with actual pos (but will be delayed to target) + next_pos = self.curr_pos.copy() # TODO might be better with actual pos (but will be delayed to target) # next_pos = self.controller.get_target_pos() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] @@ -203,18 +248,18 @@ def go_to_rest(self, joint_reset=False): # Perform Carteasian reset reset_Q = np.zeros((6)) - if self.resetQ.shape == (6, ): + if self.resetQ.shape == (6,): reset_Q[:] = self.resetQ.copy() elif self.resetQ.shape[1] == 6 and len(self.resetQ.shape) == 2: choice = np.random.randint(self.resetQ.shape[0]) - reset_Q[:] = self.resetQ[choice, :].copy() # make random guess + reset_Q[:] = self.resetQ[choice, :].copy() # make random guess else: raise ValueError(f"invalid resetQ dimension: {self.resetQ.shape}") self._send_reset_command(reset_Q) while not self.controller.is_reset(): - time.sleep(0.1) # wait for the reset operation + time.sleep(0.1) # wait for the reset operation self._update_currpos() if self.random_reset: # randomize reset position in xy plane @@ -244,6 +289,80 @@ def reset(self, joint_reset=False, **kwargs): obs = self._get_obs() return obs, {"reset_shift": shift} + def save_video_recording(self): + try: + if len(self.recording_frames): + video_writer = cv2.VideoWriter( + f'./videos/{datetime.now().strftime("%Y-%m-%d_%H-%M-%S")}.mp4', + cv2.VideoWriter_fourcc(*"mp4v"), + 10, + self.recording_frames[0].shape[:2][::-1], + ) + for frame in self.recording_frames: + video_writer.write(frame) + video_writer.release() + self.recording_frames.clear() + except Exception as e: + print(f"Failed to save video: {e}") + + def init_cameras(self, name_serial_dict=None): + """Init both cameras.""" + if self.cap is not None: # close cameras if they are already open + self.close_cameras() + + self.cap = OrderedDict() + for cam_name, cam_serial in name_serial_dict.items(): + cap = VideoCapture( + RSCapture(name=cam_name, serial_number=cam_serial, depth=False) + ) + self.cap[cam_name] = cap + + def crop_image(self, name, image) -> np.ndarray: + """Crop realsense images to be a square.""" + if name == "wrist_1": + return image[:, 80:560, :] + elif name == "wrist_2": + return image[:, 80:560, :] + else: + raise ValueError(f"Camera {name} not recognized in cropping") + + def get_im(self) -> Dict[str, np.ndarray]: + """Get images from the realsense cameras.""" + images = {} + display_images = {} + for key, cap in self.cap.items(): + try: + rgb = cap.read() + cropped_rgb = self.crop_image(key, rgb) + resized = cv2.resize( + cropped_rgb, self.observation_space["images"][key].shape[:2][::-1] + ) + images[key] = resized[..., ::-1] + display_images[key] = resized + display_images[key + "_full"] = cropped_rgb + except queue.Empty: + input( + f"{key} camera frozen. Check connect, then press enter to relaunch..." + ) + cap.close() + self.init_cameras(self.config.REALSENSE_CAMERAS) + return self.get_im() + + self.recording_frames.append( + np.concatenate([display_images[f"{k}_full"] for k in self.cap], axis=0) + ) + self.img_queue.put(display_images) + return images + + def close_cameras(self): + """Close both wrist cameras.""" + try: + for cap in self.cap.values(): + cap.close() + except Exception as e: + print(f"Failed to close cameras: {e}") + + def _send_pos_command(self, target_pos: np.ndarray): """Internal function to send force command to the robot.""" self.controller.set_target_pos(target_pos=target_pos) From 8b974999a44a6c85cce8e236f96eed7eee81cc18 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:04:56 +0200 Subject: [PATCH 121/338] name change --- serl_robot_infra/robotiq_env/envs/basic_env/__init__.py | 1 + .../robotiq_env/envs/{robotiq_grip_v1 => basic_env}/config.py | 0 .../robotiq_grip_v1.py => basic_env/robotiq_basic_env.py} | 4 ++-- serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py | 1 - 4 files changed, 3 insertions(+), 3 deletions(-) create mode 100644 serl_robot_infra/robotiq_env/envs/basic_env/__init__.py rename serl_robot_infra/robotiq_env/envs/{robotiq_grip_v1 => basic_env}/config.py (100%) rename serl_robot_infra/robotiq_env/envs/{robotiq_grip_v1/robotiq_grip_v1.py => basic_env/robotiq_basic_env.py} (93%) delete mode 100644 serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/__init__.py b/serl_robot_infra/robotiq_env/envs/basic_env/__init__.py new file mode 100644 index 00000000..84803837 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/basic_env/__init__.py @@ -0,0 +1 @@ +from robotiq_env.envs.basic_env.robotiq_basic_env import RobotiqBasicEnv diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py b/serl_robot_infra/robotiq_env/envs/basic_env/config.py similarity index 100% rename from serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/config.py rename to serl_robot_infra/robotiq_env/envs/basic_env/config.py diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py similarity index 93% rename from serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py rename to serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py index c3c9fa13..73f88934 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/robotiq_grip_v1.py +++ b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py @@ -1,7 +1,7 @@ import numpy as np from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.robotiq_grip_v1.config import RobotiqCornerConfig +from robotiq_env.envs.basic_env.config import RobotiqCornerConfig # used for float value comparisons (pressure of vacuum-gripper) @@ -9,7 +9,7 @@ def is_close(value, target): return abs(value - target) < 1e-4 -class RobotiqGripV1(RobotiqEnv): +class RobotiqBasicEnv(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py b/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py deleted file mode 100644 index 0e1d56aa..00000000 --- a/serl_robot_infra/robotiq_env/envs/robotiq_grip_v1/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from robotiq_env.envs.robotiq_grip_v1.robotiq_grip_v1 import RobotiqGripV1 From 8856153f1b27b88f71c6e0ccf92fe19598eae09c Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:05:42 +0200 Subject: [PATCH 122/338] added camera to environment --- serl_robot_infra/robotiq_env/__init__.py | 10 ++++- .../robotiq_env/envs/camera_env/__init__.py | 1 + .../robotiq_env/envs/camera_env/config.py | 28 ++++++++++++ .../envs/camera_env/robotiq_camera_env.py | 37 ++++++++++++++++ .../robotiq_env/envs/robotiq_env.py | 43 +++++++++++++------ 5 files changed, 105 insertions(+), 14 deletions(-) create mode 100644 serl_robot_infra/robotiq_env/envs/camera_env/__init__.py create mode 100644 serl_robot_infra/robotiq_env/envs/camera_env/config.py create mode 100644 serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index d2cbc162..ae79e8b8 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -3,6 +3,12 @@ register( id="robotiq-grip-v1", - entry_point="robotiq_env.envs.robotiq_grip_v1:RobotiqGripV1", - max_episode_steps=100, + entry_point="robotiq_env.envs.basic_env:RobotiqBasicEnv", + max_episode_steps=200, +) + +register( + id="robotiq_camera_env", + entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnv", + max_episode_steps=300, ) \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py new file mode 100644 index 00000000..7117d00e --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py @@ -0,0 +1 @@ +from robotiq_env.envs.camera_env.robotiq_camera_env import RobotiqCameraEnv \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py new file mode 100644 index 00000000..00cd1c98 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -0,0 +1,28 @@ +from robotiq_env.envs.robotiq_env import DefaultEnvConfig +import numpy as np + + +class RobotiqCameraConfig(DefaultEnvConfig): + RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) + RANDOM_RESET = True + RANDOM_XY_RANGE = (0.05,) + RANDOM_RZ_RANGE = (0.0,) + # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ + # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) + ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.1, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 3.0, -0.1, -3.2]) + ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + + ROBOT_IP: str = "172.22.22.2" + CONTROLLER_HZ = 100 + GRIPPER_TIMEOUT = 2000 # in milliseconds + ERROR_DELTA: float = 0.05 + FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_TASK_FRAME = np.zeros(6) + FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) + + REALSENSE_CAMERAS = { + "wrist": "218622271597", + "shoulder": "218622270808" + } \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py new file mode 100644 index 00000000..118d86b9 --- /dev/null +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -0,0 +1,37 @@ +import numpy as np + +from robotiq_env.envs.robotiq_env import RobotiqEnv +from robotiq_env.envs.camera_env.config import RobotiqCameraConfig + + +# used for float value comparisons (pressure of vacuum-gripper) +def is_close(value, target): + return abs(value - target) < 1e-4 + + +class RobotiqCameraEnv(RobotiqEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, config=RobotiqCameraConfig) + + def compute_reward(self, obs, action) -> float: + # huge action gives negative reward (like in mountain car) + action_cost = 0.1 * np.sum(np.power(action, 2)) + step_cost = 0.01 + + gripper_state = obs["state"]['gripper_state'] + suction_cost = 0.1 * float(is_close(gripper_state[0], 0.99)) + + torque = obs["state"]['tcp_torque'] + non_central_cost = 0.5 * max(np.linalg.norm(torque[:2]) - 0.07, 0.) + + # print(f"action_cost: {action_cost}, suction_cost: {suction_cost} non_central_cost: {non_central_cost}") + if self.reached_goal_state(obs): + box_is_central = np.sum(np.power(torque[:2], 2)) - 0.01 < 0. + return (10. if box_is_central else 5.) - action_cost - step_cost - suction_cost + else: + return 0.0 - action_cost - step_cost - suction_cost - non_central_cost + + def reached_goal_state(self, obs) -> bool: + # obs[0] == gripper pressure, obs[4] == force in Z-axis + state = obs["state"] + return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.15 # new min height with box diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 110c4562..9811172c 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -13,8 +13,9 @@ from scipy.spatial.transform import Rotation as R from franka_env.camera.video_capture import VideoCapture -from franka_env.camera.rs_capture import RSCapture # TODO make robotiq (both) +from franka_env.camera.rs_capture import RSCapture # TODO make robotiq (both) +from robotiq_env.utils.real_time_plotter import DataClient from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController @@ -34,7 +35,8 @@ def run(self): frame = np.concatenate( [v for k, v in img_array.items() if "full" not in k], axis=0 ) - + cv2.namedWindow("RealSense Cameras", cv2.WINDOW_NORMAL) + cv2.resizeWindow("RealSense Cameras", 300, 700) cv2.imshow("RealSense Cameras", frame) cv2.waitKey(1) @@ -79,6 +81,7 @@ def __init__( config=DefaultEnvConfig, max_episode_length: int = 100, save_video=False, + realtime_plot=False, ): self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -106,6 +109,8 @@ def __init__( self.save_video = save_video self.recording_frames = [] + self.realtime_plot = realtime_plot + self.xyz_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[:3], config.ABS_POSE_LIMIT_HIGH[:3], @@ -135,7 +140,7 @@ def __init__( "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } ), - "images": gym.spaces.Dict( # TODO add depth info + "images": gym.spaces.Dict( # TODO add depth info, or make bigger (only 128x128x3) { "shoulder": gym.spaces.Box( 0, 255, shape=(128, 128, 3), dtype=np.uint8 @@ -170,6 +175,14 @@ def __init__( self.img_queue = queue.Queue() self.displayer = ImageDisplayer(self.img_queue) self.displayer.start() + print("[CAM] Cameras are ready!") + + if self.realtime_plot: + try: + self.plotting_client = DataClient() + except ConnectionRefusedError: + print("Plotting Client could not be opened, continuing without plotting") + self.realtime_plot = False while not self.controller.is_ready(): # wait for controller time.sleep(0.1) @@ -248,9 +261,9 @@ def go_to_rest(self, joint_reset=False): # Perform Carteasian reset reset_Q = np.zeros((6)) - if self.resetQ.shape == (6,): + if self.resetQ.shape == (1, 6): reset_Q[:] = self.resetQ.copy() - elif self.resetQ.shape[1] == 6 and len(self.resetQ.shape) == 2: + elif self.resetQ.shape[1] == 6 and self.resetQ.shape[0] > 1: choice = np.random.randint(self.resetQ.shape[0]) reset_Q[:] = self.resetQ[choice, :].copy() # make random guess else: @@ -281,6 +294,8 @@ def go_to_rest(self, joint_reset=False): def reset(self, joint_reset=False, **kwargs): self.cycle_count += 1 + if self.save_video: + self.save_video_recording() shift = self.go_to_rest(joint_reset=joint_reset) self.curr_path_length = 0 @@ -293,7 +308,7 @@ def save_video_recording(self): try: if len(self.recording_frames): video_writer = cv2.VideoWriter( - f'./videos/{datetime.now().strftime("%Y-%m-%d_%H-%M-%S")}.mp4', + f'/home/nico/real-world-rl/spacemouse_tests/videos/{datetime.now().strftime("%Y-%m-%d_%H-%M-%S")}.mp4', cv2.VideoWriter_fourcc(*"mp4v"), 10, self.recording_frames[0].shape[:2][::-1], @@ -312,6 +327,7 @@ def init_cameras(self, name_serial_dict=None): self.cap = OrderedDict() for cam_name, cam_serial in name_serial_dict.items(): + print(f"cam serial: {cam_serial}") cap = VideoCapture( RSCapture(name=cam_name, serial_number=cam_serial, depth=False) ) @@ -319,10 +335,10 @@ def init_cameras(self, name_serial_dict=None): def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" - if name == "wrist_1": - return image[:, 80:560, :] - elif name == "wrist_2": - return image[:, 80:560, :] + if name == "wrist": + return image[:, 184:664, :] + elif name == "shoulder": + return image[:, 184:664, :] else: raise ValueError(f"Camera {name} not recognized in cropping") @@ -362,7 +378,6 @@ def close_cameras(self): except Exception as e: print(f"Failed to close cameras: {e}") - def _send_pos_command(self, target_pos: np.ndarray): """Internal function to send force command to the robot.""" self.controller.set_target_pos(target_pos=target_pos) @@ -391,6 +406,7 @@ def _is_truncated(self): return self.controller.is_truncated() def _get_obs(self) -> dict: + images = self.get_im() state_observation = { "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, @@ -398,7 +414,10 @@ def _get_obs(self) -> dict: "tcp_force": self.curr_force, "tcp_torque": self.curr_torque, } - return copy.deepcopy(dict(state=state_observation)) + if self.realtime_plot: + self.plotting_client.send(np.concatenate([self.curr_force, self.curr_torque])) + + return copy.deepcopy(dict(images=images, state=state_observation)) def close(self): if self.controller: From fe8bedccbc987bd968df94c689fdc6db6817e9ba Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:06:19 +0200 Subject: [PATCH 123/338] added camera to environment --- serl_robot_infra/franka_env/camera/rs_capture.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/serl_robot_infra/franka_env/camera/rs_capture.py b/serl_robot_infra/franka_env/camera/rs_capture.py index 249135f8..24f00806 100644 --- a/serl_robot_infra/franka_env/camera/rs_capture.py +++ b/serl_robot_infra/franka_env/camera/rs_capture.py @@ -9,17 +9,22 @@ def get_device_serial_numbers(self): def __init__(self, name, serial_number, dim=(640, 480), fps=15, depth=False): self.name = name + print(self.get_device_serial_numbers()) assert serial_number in self.get_device_serial_numbers() self.serial_number = serial_number self.depth = depth self.pipe = rs.pipeline() self.cfg = rs.config() self.cfg.enable_device(self.serial_number) + self.cfg.enable_stream(rs.stream.color, dim[0], dim[1], rs.format.bgr8, fps) if self.depth: self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) self.profile = self.pipe.start(self.cfg) + depth_sensor = self.profile.get_device().query_sensors()[0] + depth_sensor.set_option(rs.option.enable_auto_white_balance, True) # TODO needed? + # Create an align object # rs.align allows us to perform alignment of depth frames to others frames # The "align_to" is the stream type to which we plan to align depth frames. From dadf75890dd6d0858fb9c8c704f12b4d002ce318 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:06:54 +0200 Subject: [PATCH 124/338] cleanup --- examples/robotiq_bc/record_demo.py | 1 + examples/robotiq_sac/run_evaluation.sh | 6 +++--- examples/robotiq_sac/sac_policy_robotiq.py | 2 +- serl_launcher/serl_launcher/vision/resnet_v1.py | 4 ++-- serl_robot_infra/robotiq_env/envs/relative_env.py | 3 +-- serl_robot_infra/robotiq_env/envs/wrappers.py | 4 ++++ 6 files changed, 12 insertions(+), 8 deletions(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index 5fad694d..58e1811a 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -104,6 +104,7 @@ def on_esc(key): print(f'\nProgram was interrupted, cleaning up... ', e.__str__()) finally: + pbar.close() env.close() listener_1.stop() listener_2.stop() diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/robotiq_sac/run_evaluation.sh index 23b97925..04313a92 100644 --- a/examples/robotiq_sac/run_evaluation.sh +++ b/examples/robotiq_sac/run_evaluation.sh @@ -4,7 +4,7 @@ python sac_policy_robotiq.py "$@" \ --actor \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy_evaluation \ - --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0409-15:15"\ - --eval_checkpoint_step 100000 \ - --eval_n_trajs 20 \ + --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0412-16:22"\ + --eval_checkpoint_step 50000 \ + --eval_n_trajs 10 \ --debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 97ded4d8..4fd22894 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -75,7 +75,7 @@ flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', "Path to save RLDS logs.") -flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") # TODO does not work yet +flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") flags.DEFINE_boolean( "debug", False, "Debug mode." diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index e18769b3..ee42ba62 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -198,7 +198,7 @@ class ResNetEncoder(nn.Module): norm: str = "group" add_spatial_coordinates: bool = False pooling_method: str = "avg" - use_spatial_softmax: bool = False + # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 use_multiplicative_cond: bool = False num_spatial_blocks: int = 8 @@ -323,7 +323,7 @@ def __call__( class PreTrainedResNetEncoder(nn.Module): pooling_method: str = "avg" - use_spatial_softmax: bool = False + # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 num_spatial_blocks: int = 8 bottleneck_dim: Optional[int] = None diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index 81639cd7..cf8779f6 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -56,8 +56,7 @@ def step(self, action: np.ndarray): def reset(self, **kwargs): obs, info = self.env.reset(**kwargs) - # TODO remove after image / pointcloud data - obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) + # obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) # Update adjoint matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 6271661f..1cf01ee9 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -1,5 +1,7 @@ import gymnasium as gym import numpy as np +from agentlace import action + from robotiq_env.spacemouse.spacemouse_expert import SpaceMouseExpert import time from scipy.spatial.transform import Rotation as R @@ -72,6 +74,8 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: z_rot = R.from_rotvec(np.array([0, 0, z_angle])) action[:6] *= self.invert_axes # if some want to be inverted action[:3] = z_rot.apply(action[:3]) # z rotation invariant translation + + # TODO add tcp orientation to the equation (extract z rotation from tcp pose) action[3:6] = z_rot.inv().apply(action[3:6]) # z rotation invariant rotation return action From 361ae1df7f31a4fa44bef5d25663d23e305c0cd0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:07:26 +0200 Subject: [PATCH 125/338] force as moving average in the controller (too much fluctuations otherwise) --- serl_robot_infra/robot_controllers/robotiq_controller.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 440a3a76..a0fb8c3c 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -164,7 +164,8 @@ async def _update_robot_state(self): self.curr_vel[:] = vel self.curr_Q[:] = Q self.curr_Qd[:] = Qd - self.curr_force[:] = force + # use moving average (5), since the force fluctuates heavily + self.curr_force[:] = 0.2 * np.array(force) + 0.8 * self.curr_force[:] self.gripper_state[:] = [pressure / 100., float(obj_status.value)] # pressure between [0, 1] def get_state(self): From 63799ebc68703bcb952665464bbd5556d4bd1f8d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:07:42 +0200 Subject: [PATCH 126/338] added realtime plotter to env --- .../robotiq_env/utils/real_time_plotter.py | 113 ++++++++++++++++++ 1 file changed, 113 insertions(+) create mode 100644 serl_robot_infra/robotiq_env/utils/real_time_plotter.py diff --git a/serl_robot_infra/robotiq_env/utils/real_time_plotter.py b/serl_robot_infra/robotiq_env/utils/real_time_plotter.py new file mode 100644 index 00000000..6e9e4d25 --- /dev/null +++ b/serl_robot_infra/robotiq_env/utils/real_time_plotter.py @@ -0,0 +1,113 @@ +from multiprocessing.connection import Listener, Client +import numpy as np +from threading import Thread, Lock +import matplotlib.pyplot as plt +import matplotlib.animation as animation +from matplotlib import use +from time import time_ns + +use("TkAgg") + + +class DataClient: + def __init__(self): + self.conn = None + print("Opening Client to Realtime Plotter") + self.conn = Client(('localhost', 6000)) + + def send(self, msg): + self.conn.send(msg) + + def __del__(self): + if self.conn: + self.conn.send("close") + self.conn.close() + + +class DataListener: + def __init__(self, shape, verbose=True): + self.listener = Listener(('localhost', 6000)) + self.data = np.zeros(shape) + self.all_data = [] + self.lock = Lock() + self.verbose = verbose + self.last_time = time_ns() * 1e-6 + print("listener opened on localhost:6000, not connected yet") + + # get connection + self.listener_thread = Thread(target=self._listen, daemon=True).start() # listen here + + def _listen(self): + self.conn = self.listener.accept() + print('connection accepted from', self.listener.last_accepted) + + while True: + try: + msg = self.conn.recv() + if isinstance(msg, str) and msg == "close": + print("connection closed, terminating...") + return + with self.lock: + self.data = np.roll(self.data, -1, axis=1) + self.data[:, -1] = msg + self.all_data.append(msg) + if self.verbose: + now = time_ns() * 1e-6 + print(f"{now - self.last_time} ms {msg}") + self.last_time = now + except EOFError: + print("listener Thread terminated!") + return + + def get_data(self): + with self.lock: + return self.data + + def save_history(self): + with open('plotting_data.npy', 'wb') as f: # save run + np.save(f, np.array(self.all_data)) + + +class RealTimePlotter: + def __init__(self, plots=3, horizon=50, limit=3, figsize=(12, 8)): + self.data_listener = None + self.fig, self.axes = plt.subplots(plots, 1, figsize=figsize) + self.lines, self.text, colors = [], [], plt.rcParams["axes.prop_cycle"]() + for ax in self.axes: + ax.set_ylim(-limit, limit) + color = next(colors)["color"] + line, = ax.plot(np.arange(horizon), np.zeros(horizon), color, animated=True) + text = ax.text(0.91, 0.76, "0.0000", fontsize=14, color=color, transform=ax.transAxes) + self.lines.append(line) + self.text.append(text) + + plt.tight_layout() + plt.show(block=False) + plt.pause(2) + + def animate(self, j): + data = self.data_listener.get_data() + for i, line in enumerate(self.lines): + line.set_ydata(data[i]) + for i, text in enumerate(self.text): + text.set_text(str(round(data[i, -1], 4))) + return *self.lines, *self.text + + def set_listener(self, data_listener): + self.data_listener = data_listener + + def start_animation(self): + ani = animation.FuncAnimation(self.fig, self.animate, interval=50, blit=True, save_count=5) + plt.show() + + def close(self): + plt.close("all") + + +if __name__ == '__main__': + # only a test + plotter = RealTimePlotter(plots=6, horizon=30, figsize=(12, 8)) + fetcher = DataListener((6, 30)) + plotter.set_listener(fetcher) + plotter.start_animation() + # fetcher.save_history() From 9a034822376d28f6a8b7acdb888bd54be5aea1bd Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:08:07 +0200 Subject: [PATCH 127/338] drq tools for the box lifting task --- examples/robotiq_drq/drq_policy_robotiq.py | 496 +++++++++++++++++++++ examples/robotiq_drq/record_demo.py | 108 +++++ examples/robotiq_drq/run_actor.sh | 15 + examples/robotiq_drq/run_learner.sh | 15 + 4 files changed, 634 insertions(+) create mode 100644 examples/robotiq_drq/drq_policy_robotiq.py create mode 100644 examples/robotiq_drq/record_demo.py create mode 100644 examples/robotiq_drq/run_actor.sh create mode 100644 examples/robotiq_drq/run_learner.sh diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py new file mode 100644 index 00000000..2cdc3ddc --- /dev/null +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -0,0 +1,496 @@ +#!/usr/bin/env python3 + +import time +from functools import partial +import jax +import jax.numpy as jnp +import numpy as np +import pynput +import threading +import tqdm +from absl import app, flags +from flax.training import checkpoints +from datetime import datetime + + +import gymnasium as gym +from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics + +from serl_launcher.agents.continuous.drq import DrQAgent +from serl_launcher.common.evaluation import evaluate +from serl_launcher.utils.timer_utils import Timer +from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.utils.train_utils import concat_batches + +from agentlace.trainer import TrainerServer, TrainerClient +from agentlace.data.data_store import QueuedDataStore + +from serl_launcher.utils.launcher import ( + make_drq_agent, + make_trainer_config, + make_wandb_logger, +) +from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper +from franka_env.envs.relative_env import RelativeFrame +from franka_env.envs.wrappers import ( + GripperCloseEnv, + SpacemouseIntervention, + Quat2EulerWrapper, +) + +import franka_env + +devices = jax.local_devices() +num_devices = len(devices) +sharding = jax.sharding.PositionalSharding(devices) + +FLAGS = flags.FLAGS + +flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("agent", "drq", "Name of agent.") +flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") +flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_integer("seed", 42, "Random seed.") +flags.DEFINE_bool("save_model", False, "Whether to save model.") +flags.DEFINE_integer("batch_size", 512, "Batch size.") +flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") + +flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") +flags.DEFINE_integer("replay_buffer_capacity", 200000, "Replay buffer capacity.") + +flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") +flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") +flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") + +flags.DEFINE_integer("log_period", 10, "Logging period.") +flags.DEFINE_integer("eval_period", 1000, "Evaluation period.") + +# flag to indicate if this is a leaner or a actor +flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") +flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") +flags.DEFINE_string("ip", "localhost", "IP address of the learner.") +# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights +flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") +flags.DEFINE_string("demo_path", None, "Path to the demo data.") +flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', "Path to save checkpoints.") + +flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") +flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") + +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', + "Path to save RLDS logs.") +flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") + +flags.DEFINE_boolean( + "debug", False, "Debug mode." +) # debug mode will disable wandb logging + +def print_green(x): + return print("\033[92m {}\033[00m".format(x)) + + +PAUSE_EVENT_FLAG = threading.Event() +PAUSE_EVENT_FLAG.clear() # clear() to continue the actor/learner loop, set() to pause + + +def pause_callback(key): + """Callback for when a key is pressed""" + global PAUSE_EVENT_FLAG + try: + # chosen a rarely used key to avoid conflicts. this listener is always on, even when the program is not in focus + if key == pynput.keyboard.Key.pause: + print("Requested pause training") + # set the PAUSE FLAG to pause the actor/learner loop + PAUSE_EVENT_FLAG.set() + except AttributeError: + # print(f'{key} pressed') + pass + + +listener = pynput.keyboard.Listener( + on_press=pause_callback +) # to enable keyboard based pause +listener.start() + +############################################################################## + + +def actor(agent: DrQAgent, data_store, env, sampling_rng): + """ + This is the actor loop, which runs when "--actor" is set to True. + """ + global PAUSE_EVENT_FLAG + + if FLAGS.eval_checkpoint_step: + success_counter = 0 + time_list = [] + + ckpt = checkpoints.restore_checkpoint( + FLAGS.checkpoint_path, + agent.state, + step=FLAGS.eval_checkpoint_step, + ) + agent = agent.replace(state=ckpt) + + for episode in range(FLAGS.eval_n_trajs): + obs, _ = env.reset() + done = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=True, + ) + actions = np.asarray(jax.device_get(actions)) + + next_obs, reward, done, truncated, info = env.step(actions) + obs = next_obs + + if done: + if reward: + dt = time.time() - start_time + time_list.append(dt) + print(dt) + + success_counter += reward + print(reward) + print(f"{success_counter}/{episode + 1}") + + # if pause event is requested, pause the actor + if PAUSE_EVENT_FLAG.is_set(): + print("Actor eval loop interrupted") + response = input("Do you want to continue (c), or exit (e)? ") + if response == "c": + # update PAUSE FLAG to continue training + PAUSE_EVENT_FLAG.clear() + print("Continuing") + else: + print("Stopping actor eval") + break + + print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") + print(f"average time: {np.mean(time_list)}") + return # after done eval, return and exit + + client = TrainerClient( + "actor_env", + FLAGS.ip, + make_trainer_config(), + data_store, + wait_for_server=True, + ) + + # Function to update the agent with new params + def update_params(params): + nonlocal agent + agent = agent.replace(state=agent.state.replace(params=params)) + + client.recv_network_callback(update_params) + + obs, _ = env.reset() + done = False + + # training loop + timer = Timer() + running_return = 0.0 + + for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True): + timer.tick("total") + + with timer.context("sample_actions"): + if step < FLAGS.random_steps: + actions = env.action_space.sample() + else: + sampling_rng, key = jax.random.split(sampling_rng) + actions = agent.sample_actions( + observations=jax.device_put(obs), + seed=key, + deterministic=False, + ) + actions = np.asarray(jax.device_get(actions)) + + # Step environment + with timer.context("step_env"): + + next_obs, reward, done, truncated, info = env.step(actions) + + # override the action with the intervention action + if "intervene_action" in info: + actions = info.pop("intervene_action") + + reward = np.asarray(reward, dtype=np.float32) + info = np.asarray(info) + running_return += reward + transition = dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=reward, + masks=1.0 - done, + dones=done, + ) + data_store.insert(transition) + + obs = next_obs + if done or truncated: + stats = {"train": info} # send stats to the learner to log + client.request("send-stats", stats) + running_return = 0.0 + obs, _ = env.reset() + + if step % FLAGS.steps_per_update == 0: + client.update() + + timer.tock("total") + + if step % FLAGS.log_period == 0: + stats = {"timer": timer.get_average_times()} + client.request("send-stats", stats) + + if PAUSE_EVENT_FLAG.is_set(): + print_green("Actor loop interrupted") + response = input( + "Do you want to continue (c), save replay buffer and exit (s) or simply exit (e)? " + ) + if response == "c": + print("Continuing") + PAUSE_EVENT_FLAG.clear() + else: + if response == "s": + print("Saving replay buffer") + data_store.save( + "replay_buffer_actor.npz" + ) # not yet supported for QueuedDataStore + else: + print("Replay buffer not saved") + print("Stopping actor client") + client.stop() + break + + print("Actor loop finished") + + +############################################################################## + + +def learner(rng, agent: DrQAgent, replay_buffer, demo_buffer, wandb_logger=None): + """ + The learner loop, which runs when "--learner" is set to True. + """ + # To track the step in the training loop + update_steps = 0 + global PAUSE_EVENT_FLAG + + def stats_callback(type: str, payload: dict) -> dict: + """Callback for when server receives stats request.""" + assert type == "send-stats", f"Invalid request type: {type}" + if wandb_logger is not None: + wandb_logger.log(payload, step=update_steps) + return {} # not expecting a response + + # Create server + server = TrainerServer(make_trainer_config(), request_callback=stats_callback) + server.register_data_store("actor_env", replay_buffer) + server.start(threaded=True) + + # Loop to wait until replay_buffer is filled + pbar = tqdm.tqdm( + total=FLAGS.training_starts, + initial=len(replay_buffer), + desc="Filling up replay buffer", + position=0, + leave=True, + ) + while len(replay_buffer) < FLAGS.training_starts: + pbar.update(len(replay_buffer) - pbar.n) # Update progress bar + time.sleep(1) + pbar.update(len(replay_buffer) - pbar.n) # Update progress bar + pbar.close() + + # send the initial network to the actor + server.publish_network(agent.state.params) + print_green("sent initial network to actor") + + # 50/50 sampling from RLPD, half from demo and half from online experience + replay_iterator = replay_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size // 2, + "pack_obs_and_next_obs": True, + }, + device=sharding.replicate(), + ) + demo_iterator = demo_buffer.get_iterator( + sample_args={ + "batch_size": FLAGS.batch_size // 2, + "pack_obs_and_next_obs": True, + }, + device=sharding.replicate(), + ) + + # wait till the replay buffer is filled with enough data + timer = Timer() + for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): + # run n-1 critic updates and 1 critic + actor update. + # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU + for critic_step in range(FLAGS.utd_ratio - 1): + with timer.context("sample_replay_buffer"): + batch = next(replay_iterator) + demo_batch = next(demo_iterator) + batch = concat_batches(batch, demo_batch, axis=0) + + with timer.context("train_critics"): + agent, critics_info = agent.update_critics( + batch, + ) + + with timer.context("train"): + batch = next(replay_iterator) + demo_batch = next(demo_iterator) + batch = concat_batches(batch, demo_batch, axis=0) + agent, update_info = agent.update_high_utd(batch, utd_ratio=1) + + # publish the updated network + if step > 0 and step % (FLAGS.steps_per_update) == 0: + agent = jax.block_until_ready(agent) + server.publish_network(agent.state.params) + + if update_steps % FLAGS.log_period == 0 and wandb_logger: + wandb_logger.log(update_info, step=update_steps) + wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) + + if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: + assert FLAGS.checkpoint_path is not None + checkpoints.save_checkpoint( + FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 + ) + + update_steps += 1 + + if PAUSE_EVENT_FLAG.is_set(): + print("Learner loop interrupted") + response = input( + "Do you want to continue (c), save training state and exit (s) or simply exit (e)? " + ) + if response == "c": + print("Continuing") + PAUSE_EVENT_FLAG.clear() + else: + if response == "s": + print("Saving learner state") + agent_ckpt = checkpoints.save_checkpoint( + FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 + ) + replay_buffer.save( + "replay_buffer_learner.npz" + ) # not yet supported for QueuedDataStore + # TODO: save other parts of training state + else: + print("Training state not saved") + print("Stopping learner client") + break + + # Wrap up the learner loop + server.stop() + print("Learner loop finished") + + +############################################################################## + + +def main(_): + assert FLAGS.batch_size % num_devices == 0 + FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") + + # seed + rng = jax.random.PRNGKey(FLAGS.seed) + + # create env and load dataset + env = gym.make( + FLAGS.env, + fake_env=FLAGS.learner, + max_episode_length=FLAGS.max_traj_length, + ) + if FLAGS.actor: + env = SpacemouseIntervention(env) + env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SERLObsWrapper(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = RecordEpisodeStatistics(env) + + image_keys = [key for key in env.observation_space.keys() if key != "state"] + + rng, sampling_rng = jax.random.split(rng) + print(f"obs shape: {env.observation_space.sample().shape}") + agent: DrQAgent = make_drq_agent( + seed=FLAGS.seed, + sample_obs=env.observation_space.sample(), + sample_action=env.action_space.sample(), + image_keys=image_keys, + encoder_type=FLAGS.encoder_type, + ) + + # replicate agent across devices + # need the jnp.array to avoid a bug where device_put doesn't recognize primitives + agent: DrQAgent = jax.device_put( + jax.tree_map(jnp.array, agent), sharding.replicate() + ) + + def create_replay_buffer_and_wandb_logger(): + replay_buffer = MemoryEfficientReplayBufferDataStore( + env.observation_space, + env.action_space, + capacity=FLAGS.replay_buffer_capacity, + image_keys=image_keys, + ) + # set up wandb and logging + wandb_logger = make_wandb_logger( + project="serl_dev", + description=FLAGS.exp_name or FLAGS.env, + debug=FLAGS.debug, + ) + return replay_buffer, wandb_logger + + if FLAGS.learner: + sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) + replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() + demo_buffer = MemoryEfficientReplayBufferDataStore( + env.observation_space, + env.action_space, + capacity=10000, + image_keys=image_keys, + ) + import pickle as pkl + + with open(FLAGS.demo_path, "rb") as f: + trajs = pkl.load(f) + for traj in trajs: + demo_buffer.insert(traj) + print(f"demo buffer size: {len(demo_buffer)}") + + # learner loop + print_green("starting learner loop") + learner( + sampling_rng, + agent, + replay_buffer, + demo_buffer=demo_buffer, + wandb_logger=wandb_logger, + ) + + elif FLAGS.actor: + sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) + data_store = QueuedDataStore(50000) # the queue size on the actor + + # actor loop + print_green("starting actor loop") + actor(agent, data_store, env, sampling_rng) + + else: + raise NotImplementedError("Must be either a learner or an actor") + + +if __name__ == "__main__": + app.run(main) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py new file mode 100644 index 00000000..d33a625e --- /dev/null +++ b/examples/robotiq_drq/record_demo.py @@ -0,0 +1,108 @@ +import gymnasium as gym +from tqdm import tqdm +import numpy as np +import copy +import pickle as pkl +import datetime +import os +import threading +from pynput import keyboard + +from robotiq_env.envs.relative_env import RelativeFrame +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper + +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper +from serl_launcher.wrappers.chunking import ChunkingWrapper + +import robotiq_env + +exit_program = threading.Event() + + +def on_space(key, info_dict): + if key == keyboard.Key.space: + for key, item in info_dict.items(): + print(f'{key}: {item}', end=' ') + print() + + +def on_esc(key): + if key == keyboard.Key.esc: + exit_program.set() + + +if __name__ == "__main__": + env = gym.make("robotiq_camera_env") + env = SpacemouseIntervention(env) + env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SERLObsWrapper(env) + # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + + obs, _ = env.reset() + + transitions = [] + success_count = 0 + success_needed = 3 + total_count = 0 + pbar = tqdm(total=success_needed) + + info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, + 'force': env.unwrapped.curr_force} + listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) + listener_1.start() + + listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) + listener_2.start() + + uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + file_name = f"pcb_insert_{success_needed}_demos_{uuid}.pkl" + file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script + file_path = os.path.join(file_dir, file_name) + + if not os.access(file_dir, os.W_OK): + raise PermissionError(f"No permission to write to {file_dir}") + + try: + while success_count < success_needed: + if exit_program.is_set(): + raise KeyboardInterrupt # stop program, but clean up before + + next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) + actions = info["intervene_action"] + + transition = copy.deepcopy( + dict( + observations=obs, + actions=actions, + next_observations=next_obs, + rewards=rew, + masks=1.0 - done, + dones=done, + ) + ) + transitions.append(transition) + + obs = next_obs + + if done: + success_count += int(rew > 0.99) + total_count += 1 + print( + f"{rew}\tGot {success_count} successes of {total_count} trials. {success_needed} successes needed." + ) + pbar.update(int(rew > 0.99)) + obs, _ = env.reset() + + with open(file_path, "wb") as f: + pkl.dump(transitions, f) + print(f"saved {success_needed} demos to {file_path}") + + except KeyboardInterrupt as e: + print(f'\nProgram was interrupted, cleaning up... ', e.__str__()) + + finally: + pbar.close() + env.close() + listener_1.stop() + listener_2.stop() diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh new file mode 100644 index 00000000..fc9d67ec --- /dev/null +++ b/examples/robotiq_drq/run_actor.sh @@ -0,0 +1,15 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name=drq_robotiq_policy \ + --max_traj_length 300 \ + --seed 0 \ + --max_steps 10000 \ + --random_steps 100 \ + --training_starts 100 \ + --utd_ratio 4 \ + --batch_size 512 \ + --eval_period 1000 \ + --encoder_type resnet-pretrained \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh new file mode 100644 index 00000000..ab00bdb0 --- /dev/null +++ b/examples/robotiq_drq/run_learner.sh @@ -0,0 +1,15 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name=drq_robotiq_policy \ + --seed 0 \ + --random_steps 100 \ + --training_starts 100 \ + --utd_ratio 4 \ + --batch_size 512 \ + --eval_period 1000 \ + --encoder_type resnet-pretrained \ + --checkpoint_period 10000 \ + --demo_path TODO \ From 6f9ceb8f277bbb4d85a78914bec9265df8b7865d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 15:45:26 +0200 Subject: [PATCH 128/338] new reset pose --- examples/robotiq_drq/drq_policy_robotiq.py | 18 ++++++++---------- examples/robotiq_drq/record_demo.py | 2 +- examples/robotiq_drq/run_actor.sh | 1 + examples/robotiq_drq/run_learner.sh | 3 ++- .../robotiq_env/envs/robotiq_env.py | 2 ++ 5 files changed, 14 insertions(+), 12 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 2cdc3ddc..b211065e 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -12,7 +12,6 @@ from flax.training import checkpoints from datetime import datetime - import gymnasium as gym from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics @@ -32,14 +31,10 @@ ) from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper -from franka_env.envs.relative_env import RelativeFrame -from franka_env.envs.wrappers import ( - GripperCloseEnv, - SpacemouseIntervention, - Quat2EulerWrapper, -) +from robotiq_env.envs.relative_env import RelativeFrame +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -import franka_env +import robotiq_env devices = jax.local_devices() num_devices = len(devices) @@ -74,7 +69,8 @@ flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', "Path to save checkpoints.") +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', + "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") @@ -87,6 +83,7 @@ "debug", False, "Debug mode." ) # debug mode will disable wandb logging + def print_green(x): return print("\033[92m {}\033[00m".format(x)) @@ -114,6 +111,7 @@ def pause_callback(key): ) # to enable keyboard based pause listener.start() + ############################################################################## @@ -423,7 +421,7 @@ def main(_): image_keys = [key for key in env.observation_space.keys() if key != "state"] rng, sampling_rng = jax.random.split(rng) - print(f"obs shape: {env.observation_space.sample().shape}") + # print(f"obs shape: {env.observation_space.sample().shape}") agent: DrQAgent = make_drq_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index d33a625e..5ff34b7f 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -43,7 +43,7 @@ def on_esc(key): transitions = [] success_count = 0 - success_needed = 3 + success_needed = 20 total_count = 0 pbar = tqdm(total=success_needed) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index fc9d67ec..38b56d8a 100644 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -13,3 +13,4 @@ python drq_policy_robotiq.py "$@" \ --batch_size 512 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ + --debug \ No newline at end of file diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index ab00bdb0..85fcef03 100644 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -12,4 +12,5 @@ python drq_policy_robotiq.py "$@" \ --eval_period 1000 \ --encoder_type resnet-pretrained \ --checkpoint_period 10000 \ - --demo_path TODO \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_apr23_firstwithcam.pkl \ + --debug \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 9811172c..7e02940d 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -286,8 +286,10 @@ def go_to_rest(self, joint_reset=False): # np.negative(self.random_rz_range), self.random_rz_range # ) self.controller.set_target_pos(reset_pose) # random movement after resetting + time.sleep(0.1) while self.controller.is_moving(): time.sleep(0.1) + print(reset_shift, reset_pose) return reset_shift else: return np.zeros((2,)) From 323cfc91209218d852778641331c3588bfbb1f0c Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Apr 2024 16:47:40 +0200 Subject: [PATCH 129/338] readme update --- examples/robotiq_drq/drq_policy_robotiq.py | 2 +- examples/robotiq_drq/run_actor.sh | 4 ++-- examples/robotiq_drq/run_learner.sh | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index b211065e..f07b6572 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -52,7 +52,7 @@ flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 200000, "Replay buffer capacity.") +flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index 38b56d8a..74f414c3 100644 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -1,5 +1,5 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ @@ -10,7 +10,7 @@ python drq_policy_robotiq.py "$@" \ --random_steps 100 \ --training_starts 100 \ --utd_ratio 4 \ - --batch_size 512 \ + --batch_size 256 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ --debug \ No newline at end of file diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index 85fcef03..31547c90 100644 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -1,5 +1,5 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ @@ -8,7 +8,7 @@ python drq_policy_robotiq.py "$@" \ --random_steps 100 \ --training_starts 100 \ --utd_ratio 4 \ - --batch_size 512 \ + --batch_size 256 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ --checkpoint_period 10000 \ From 93ee00a5818c347cc55901aa2d77dd85d0e397e0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Apr 2024 18:30:11 +0200 Subject: [PATCH 130/338] bugfix of RuntimeWarning --- serl_launcher/serl_launcher/networks/actor_critic_nets.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index 189eef82..d0d568d9 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -62,7 +62,9 @@ def __call__( obs_enc = self.encoder(observations) inputs = jnp.concatenate([obs_enc, actions], -1) - outputs = self.network(inputs, train=train) + outputs = self.network(inputs, train) + # train=train throws: "RuntimeWarning: kwargs are not supported in vmap, so "train" is(are) ignored" + if self.init_final is not None: value = nn.Dense( 1, @@ -179,6 +181,8 @@ class Policy(nn.Module): def __call__( self, observations: jnp.ndarray, temperature: float = 1.0, train: bool = False ) -> distrax.Distribution: + info_dict = {key:value.shape for key, value in observations.items()} + # print(f"policy observations shape: {info_dict}") # TODO remove if self.encoder is None: obs_enc = observations else: From 412fe44a469ab826389dc65964ae629503f2f72c Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Apr 2024 18:30:22 +0200 Subject: [PATCH 131/338] output encoder definition --- serl_launcher/serl_launcher/agents/continuous/drq.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 9b2b690b..568d0d5e 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -192,6 +192,8 @@ def create_drq( image_keys=image_keys, ) + print(f"encoder def: {encoder_def}") + encoders = { "critic": encoder_def, "actor": encoder_def, From c9361d1c2a67afab913466848640a61f92b2b406 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Apr 2024 18:30:56 +0200 Subject: [PATCH 132/338] misc --- examples/robotiq_drq/run_actor.sh | 0 examples/robotiq_drq/run_learner.sh | 10 +++++----- serl_launcher/serl_launcher/common/encoding.py | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) mode change 100644 => 100755 examples/robotiq_drq/run_actor.sh mode change 100644 => 100755 examples/robotiq_drq/run_learner.sh diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh old mode 100644 new mode 100755 diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh old mode 100644 new mode 100755 index 31547c90..177ce98a --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -1,16 +1,16 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ --exp_name=drq_robotiq_policy \ --seed 0 \ - --random_steps 100 \ - --training_starts 100 \ + --random_steps 0 \ + --training_starts 0 \ --utd_ratio 4 \ - --batch_size 256 \ + --batch_size 128 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ --checkpoint_period 10000 \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_apr23_firstwithcam.pkl \ - --debug \ No newline at end of file + --debug diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index 823782d5..0c006885 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -72,7 +72,7 @@ def __call__( return encoded -class GCEncodingWrapper(nn.Module): +class GCEncodingWrapper(nn.Module): # never used """ Encodes observations and goals into a single flat encoding. Handles all the logic about when/how to combine observations and goals. From 836d8e09d5e75a5d2bd66224af24f829b74f55b7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 25 Apr 2024 15:44:08 +0200 Subject: [PATCH 133/338] Added depth only for realsense cameras --- .../franka_env/camera/rs_capture.py | 3 - .../robotiq_env/camera/__init__.py | 0 .../robotiq_env/camera/rs_capture.py | 63 +++++++++++++++++++ .../robotiq_env/camera/video_capture.py | 39 ++++++++++++ .../robotiq_env/envs/robotiq_env.py | 4 +- 5 files changed, 104 insertions(+), 5 deletions(-) create mode 100644 serl_robot_infra/robotiq_env/camera/__init__.py create mode 100644 serl_robot_infra/robotiq_env/camera/rs_capture.py create mode 100644 serl_robot_infra/robotiq_env/camera/video_capture.py diff --git a/serl_robot_infra/franka_env/camera/rs_capture.py b/serl_robot_infra/franka_env/camera/rs_capture.py index 24f00806..8d3ee534 100644 --- a/serl_robot_infra/franka_env/camera/rs_capture.py +++ b/serl_robot_infra/franka_env/camera/rs_capture.py @@ -22,9 +22,6 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, depth=False): self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) self.profile = self.pipe.start(self.cfg) - depth_sensor = self.profile.get_device().query_sensors()[0] - depth_sensor.set_option(rs.option.enable_auto_white_balance, True) # TODO needed? - # Create an align object # rs.align allows us to perform alignment of depth frames to others frames # The "align_to" is the stream type to which we plan to align depth frames. diff --git a/serl_robot_infra/robotiq_env/camera/__init__.py b/serl_robot_infra/robotiq_env/camera/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py new file mode 100644 index 00000000..845d9d44 --- /dev/null +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -0,0 +1,63 @@ +import numpy as np +import pyrealsense2 as rs # Intel RealSense cross-platform open-source API + + +class RSCapture: + def get_device_serial_numbers(self): + devices = rs.context().devices + return [d.get_info(rs.camera_info.serial_number) for d in devices] + + def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth=False): + self.name = name + print(self.get_device_serial_numbers()) + assert serial_number in self.get_device_serial_numbers() + self.serial_number = serial_number + self.rgb = rgb + self.depth = depth + self.pipe = rs.pipeline() + self.cfg = rs.config() + self.cfg.enable_device(self.serial_number) + + assert self.rgb or self.depth + if self.rgb: + self.cfg.enable_stream(rs.stream.color, dim[0], dim[1], rs.format.bgr8, fps) + if self.depth: + self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) + self.profile = self.pipe.start(self.cfg) + + # depth_sensor = self.profile.get_device().query_sensors()[0] + # depth_sensor.set_option(rs.option.enable_auto_white_balance, True) # TODO needed? + + # Create an align object + # rs.align allows us to perform alignment of depth frames to others frames + # The "align_to" is the stream type to which we plan to align depth frames. + align_to = rs.stream.color + self.align = rs.align(align_to) + + def read(self): + frames = self.pipe.wait_for_frames() + aligned_frames = self.align.process(frames) + if self.rgb: + color_frame = aligned_frames.get_color_frame() + if self.depth: + depth_frame = aligned_frames.get_depth_frame() + + image, depth = None, None + if self.rgb and color_frame.is_video_frame(): + image = np.asarray(color_frame.get_data()) + + if self.depth and depth_frame.is_depth_frame(): + depth = np.expand_dims(np.asarray(depth_frame.get_data()), axis=2) + + if isinstance(image, np.ndarray) and isinstance(depth, np.ndarray): + return True, np.concatenate((image, depth), axis=-1) + elif isinstance(image, np.ndarray): + return True, image + elif isinstance(depth, np.ndarray): + return True, depth # maybe invert depth and convert it to uint8 (maybe also filter for far away objects) + else: + return False, None + + def close(self): + self.pipe.stop() + self.cfg.disable_all_streams() diff --git a/serl_robot_infra/robotiq_env/camera/video_capture.py b/serl_robot_infra/robotiq_env/camera/video_capture.py new file mode 100644 index 00000000..842010ff --- /dev/null +++ b/serl_robot_infra/robotiq_env/camera/video_capture.py @@ -0,0 +1,39 @@ +import queue +import threading +import time + + +class VideoCapture: + def __init__(self, cap, name=None): + if name is None: + name = cap.name + self.name = name + self.q = queue.Queue() + self.cap = cap + self.t = threading.Thread(target=self._reader) + self.t.daemon = True + self.enable = True + self.t.start() + + # read frames as soon as they are available, keeping only most recent one + + def _reader(self): + while self.enable: + time.sleep(0.01) + ret, frame = self.cap.read() + if not ret: + break + if not self.q.empty(): + try: + self.q.get_nowait() # discard previous (unprocessed) frame + except queue.Empty: + pass + self.q.put(frame) + + def read(self): + return self.q.get(timeout=5) + + def close(self): + self.enable = False + self.t.join() + self.cap.close() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 7e02940d..29fd9dda 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -12,8 +12,8 @@ from collections import OrderedDict from scipy.spatial.transform import Rotation as R -from franka_env.camera.video_capture import VideoCapture -from franka_env.camera.rs_capture import RSCapture # TODO make robotiq (both) +from robotiq_env.camera.video_capture import VideoCapture +from robotiq_env.camera.rs_capture import RSCapture from robotiq_env.utils.real_time_plotter import DataClient from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec From ee1760a084a09aeb204833c62bd647409ad0fc7a Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 29 Apr 2024 16:07:28 +0200 Subject: [PATCH 134/338] faulty spacemouse action fix --- serl_robot_infra/robotiq_env/envs/relative_env.py | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index cf8779f6..0f08da0d 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -44,7 +44,7 @@ def step(self, action: np.ndarray): # this is to convert the spacemouse intervention action if "intervene_action" in info: - info["intervene_action"] = self.transform_action(info["intervene_action"]) + info["intervene_action"] = self.transform_action_inv(info["intervene_action"]) # Update adjoint matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) @@ -96,3 +96,12 @@ def transform_action(self, action: np.ndarray): action = np.array(action) # in case action is a jax read-only array action[:6] = self.adjoint_matrix @ action[:6] return action + + def transform_action_inv(self, action: np.ndarray): + """ + Transform action from spatial(base) frame into body(end-effector) frame + using the adjoint matrix. + """ + action = np.array(action) + action[:6] = np.linalg.inv(self.adjoint_matrix) @ action[:6] + return action From b736ff292d0e2730e987f0488a61b01a1299703b Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:55:54 +0200 Subject: [PATCH 135/338] added depth images as option --- examples/robotiq_drq/drq_policy_robotiq.py | 37 ++++++--- .../serl_launcher/agents/continuous/drq.py | 18 ++++- .../serl_launcher/vision/resnet_v1.py | 7 ++ .../robotiq_env/camera/rs_capture.py | 2 +- .../robotiq_env/envs/robotiq_env.py | 79 ++++++++++++++----- 5 files changed, 104 insertions(+), 39 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index f07b6572..c9b85c83 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -30,7 +30,7 @@ make_wandb_logger, ) from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from robotiq_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper @@ -46,6 +46,8 @@ flags.DEFINE_string("agent", "drq", "Name of agent.") flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both)") + flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", False, "Whether to save model.") flags.DEFINE_integer("batch_size", 512, "Batch size.") @@ -97,7 +99,7 @@ def pause_callback(key): global PAUSE_EVENT_FLAG try: # chosen a rarely used key to avoid conflicts. this listener is always on, even when the program is not in focus - if key == pynput.keyboard.Key.pause: + if not PAUSE_EVENT_FLAG.is_set() and key == pynput.keyboard.Key.pause: print("Requested pause training") # set the PAUSE FLAG to pause the actor/learner loop PAUSE_EVENT_FLAG.set() @@ -208,10 +210,10 @@ def update_params(params): deterministic=False, ) actions = np.asarray(jax.device_get(actions)) + print(actions) # Step environment with timer.context("step_env"): - next_obs, reward, done, truncated, info = env.step(actions) # override the action with the intervention action @@ -330,23 +332,30 @@ def stats_callback(type: str, payload: dict) -> dict: # wait till the replay buffer is filled with enough data timer = Timer() for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): + # Train the networks + """with timer.context("sample_replay_buffer"): + batch = next(replay_iterator) if len(replay_buffer) > 0 else None + demo_batch = next(demo_iterator) + batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch + + with timer.context("train"): + agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio)""" + # run n-1 critic updates and 1 critic + actor update. # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU for critic_step in range(FLAGS.utd_ratio - 1): with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) + batch = next(replay_iterator) if len(replay_buffer) > 0 else None demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) + batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch with timer.context("train_critics"): - agent, critics_info = agent.update_critics( - batch, - ) + agent, critics_info = agent.update_critics(batch,) with timer.context("train"): - batch = next(replay_iterator) + batch = next(replay_iterator) if len(replay_buffer) > 0 else None demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) + batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch agent, update_info = agent.update_high_utd(batch, utd_ratio=1) # publish the updated network @@ -358,7 +367,7 @@ def stats_callback(type: str, payload: dict) -> dict: wandb_logger.log(update_info, step=update_steps) wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) - if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: + if FLAGS.checkpoint_period and update_steps and update_steps % FLAGS.checkpoint_period == 0: assert FLAGS.checkpoint_path is not None checkpoints.save_checkpoint( FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 @@ -371,7 +380,7 @@ def stats_callback(type: str, payload: dict) -> dict: response = input( "Do you want to continue (c), save training state and exit (s) or simply exit (e)? " ) - if response == "c": + if "c" in response: print("Continuing") PAUSE_EVENT_FLAG.clear() else: @@ -407,6 +416,7 @@ def main(_): # create env and load dataset env = gym.make( FLAGS.env, + camera_mode=FLAGS.camera_mode, fake_env=FLAGS.learner, max_episode_length=FLAGS.max_traj_length, ) @@ -414,6 +424,7 @@ def main(_): env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) + env = ScaleObservationWrapper(env) # scale obs space env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -421,7 +432,6 @@ def main(_): image_keys = [key for key in env.observation_space.keys() if key != "state"] rng, sampling_rng = jax.random.split(rng) - # print(f"obs shape: {env.observation_space.sample().shape}") agent: DrQAgent = make_drq_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), @@ -462,6 +472,7 @@ def create_replay_buffer_and_wandb_logger(): ) import pickle as pkl + # TOOD check for depth or rgb with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) for traj in trajs: diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 568d0d5e..811cdfc0 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -33,10 +33,10 @@ def create( temperature_def: nn.Module, # Optimizer actor_optimizer_kwargs={ - "learning_rate": 3e-4, + "learning_rate": 3e-4, # 3e-4 }, critic_optimizer_kwargs={ - "learning_rate": 3e-4, + "learning_rate": 3e-4, # 3e-4 }, temperature_optimizer_kwargs={ "learning_rate": 3e-4, @@ -86,7 +86,12 @@ def create( # Config assert not entropy_per_dim, "Not implemented" if target_entropy is None: - target_entropy = -actions.shape[-1] / 2 + # target_entropy = -actions.shape[-1] / 2 + from numpy import prod + target_entropy = -prod(actions.shape) + + print(f"config: discount: {discount}, target_entropy: {target_entropy}") + print(f"actor_optimizer {actor_optimizer_kwargs} critic_optimizer {critic_optimizer_kwargs} temperature {temperature_optimizer_kwargs}") return cls( state=state, @@ -172,6 +177,10 @@ def create_drq( pre_pooling=True, name="pretrained_encoder", ) + + use_depth_only = list(observations.values())[0].shape[-3:] == (128, 128, 1) # only one channel means depth + print(f"use depth only: {use_depth_only}") + encoders = { image_key: PreTrainedResNetEncoder( pooling_method="spatial_learned_embeddings", @@ -179,6 +188,7 @@ def create_drq( bottleneck_dim=256, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", + use_depth_only=use_depth_only, ) for image_key in image_keys } @@ -192,7 +202,7 @@ def create_drq( image_keys=image_keys, ) - print(f"encoder def: {encoder_def}") + # print(f"encoder def: {encoder_def}") encoders = { "critic": encoder_def, diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index ee42ba62..c519ddde 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -328,6 +328,7 @@ class PreTrainedResNetEncoder(nn.Module): num_spatial_blocks: int = 8 bottleneck_dim: Optional[int] = None pretrained_encoder: nn.module = None + use_depth_only: bool = False @nn.compact def __call__( @@ -337,6 +338,12 @@ def __call__( train: bool = True, ): x = observations + + # use DDD instead of RGB and pass it through resnet + if self.use_depth_only: + assert x.shape == (128, 128, 1) + x = jnp.repeat(x, 3, axis=-1) + if encode: x = self.pretrained_encoder(x, train=train) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 845d9d44..ab4c2ff4 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -9,7 +9,7 @@ def get_device_serial_numbers(self): def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth=False): self.name = name - print(self.get_device_serial_numbers()) + # print(self.get_device_serial_numbers()) assert serial_number in self.get_device_serial_numbers() self.serial_number = serial_number self.rgb = rgb diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 29fd9dda..aafcc4fd 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -82,6 +82,7 @@ def __init__( max_episode_length: int = 100, save_video=False, realtime_plot=False, + camera_mode="rgb", # one of (rgb, depth, both) ): self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -108,6 +109,7 @@ def __init__( print("Saving videos!") self.save_video = save_video self.recording_frames = [] + self.camera_mode = camera_mode self.realtime_plot = realtime_plot @@ -127,6 +129,32 @@ def __init__( np.ones((7,), dtype=np.float32), ) + if camera_mode=="rgb": + image_space = gym.spaces.Dict( # TODO add depth info, or make bigger (only 128x128x3) + { + "shoulder": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + "wrist": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + }) + elif camera_mode=="depth": + image_space = gym.spaces.Dict( + { + "shoulder": gym.spaces.Box( + 0, 65535, shape=(128, 128, 1), dtype=np.uint16 + ), + "wrist": gym.spaces.Box( + 0, 65535, shape=(128, 128, 1), dtype=np.uint16 + ) + } + ) + elif camera_mode=="both": + raise NotImplementedError("not yet implemented") + else: + raise NotImplementedError(f"camera mode {camera_mode} not implemented") + self.observation_space = gym.spaces.Dict( { "state": gym.spaces.Dict( @@ -140,20 +168,12 @@ def __init__( "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } ), - "images": gym.spaces.Dict( # TODO add depth info, or make bigger (only 128x128x3) - { - "shoulder": gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - "wrist": gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - } - ), + "images": image_space, } ) self.cycle_count = 0 self.controller = None + self.cap = None if fake_env: print("[RobotiqEnv] is fake!") @@ -170,7 +190,6 @@ def __init__( ) self.controller.start() # start Thread - self.cap = None self.init_cameras(config.REALSENSE_CAMERAS) self.img_queue = queue.Queue() self.displayer = ImageDisplayer(self.img_queue) @@ -219,8 +238,7 @@ def step(self, action: np.ndarray) -> tuple: action = np.clip(action, self.action_space.low, self.action_space.high) # position - next_pos = self.curr_pos.copy() # TODO might be better with actual pos (but will be delayed to target) - # next_pos = self.controller.get_target_pos() + next_pos = self.curr_pos.copy() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] # orientation @@ -338,13 +356,13 @@ def init_cameras(self, name_serial_dict=None): def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" if name == "wrist": - return image[:, 184:664, :] + return image[:, 80:560, :] elif name == "shoulder": - return image[:, 184:664, :] + return image[:, 80:560, :] else: raise ValueError(f"Camera {name} not recognized in cropping") - def get_im(self) -> Dict[str, np.ndarray]: + def get_image(self) -> Dict[str, np.ndarray]: """Get images from the realsense cameras.""" images = {} display_images = {} @@ -359,12 +377,10 @@ def get_im(self) -> Dict[str, np.ndarray]: display_images[key] = resized display_images[key + "_full"] = cropped_rgb except queue.Empty: - input( - f"{key} camera frozen. Check connect, then press enter to relaunch..." - ) + input(f"{key} camera frozen. Check connect, then press enter to relaunch...") cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) - return self.get_im() + return self.get_image() self.recording_frames.append( np.concatenate([display_images[f"{k}_full"] for k in self.cap], axis=0) @@ -372,6 +388,27 @@ def get_im(self) -> Dict[str, np.ndarray]: self.img_queue.put(display_images) return images + def get_depth(self) -> Dict[str, np.ndarray]: + depth = {} + display_depth = {} + for key, cap in self.cap.items(): + try: + depth = cap.read() + cropped_depth = self.crop_image(key, depth) + resized = cv2.resize( + cropped_depth, self.observation_space["images"][key].shape[:2][::-1] + ) + except queue.Empty: + input(f"{key} camera frozen. Check connect, then press enter to relaunch...") + cap.close() + self.init_cameras(self.config.REALSENSE_CAMERAS) + return self.get_depth() + self.recording_frames.append( + np.concatenate([display_depth[f"{k}_full"] for k in self.cap], axis=0) + ) + self.img_queue.put(display_depth) + return depth + def close_cameras(self): """Close both wrist cameras.""" try: @@ -408,7 +445,7 @@ def _is_truncated(self): return self.controller.is_truncated() def _get_obs(self) -> dict: - images = self.get_im() + images = self.get_image() state_observation = { "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, From b654ecb6e8cf213e0cdff274a500423c429e1c44 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:56:32 +0200 Subject: [PATCH 136/338] new configs --- examples/robotiq_drq/run_actor.sh | 13 +++++++------ examples/robotiq_drq/run_learner.sh | 7 +++++-- serl_launcher/serl_launcher/utils/launcher.py | 8 +++++++- 3 files changed, 19 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index 74f414c3..337fb91a 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -1,16 +1,17 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.05 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ --exp_name=drq_robotiq_policy \ - --max_traj_length 300 \ + --max_traj_length 100 \ + --camera_mode rgb \ --seed 0 \ --max_steps 10000 \ - --random_steps 100 \ - --training_starts 100 \ + --random_steps 0 \ + --training_starts 0 \ --utd_ratio 4 \ - --batch_size 256 \ + --batch_size 128 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ - --debug \ No newline at end of file +# --debug \ No newline at end of file diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index 177ce98a..e209854d 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -1,10 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ --exp_name=drq_robotiq_policy \ + --camera_mode rgb \ + --max_traj_length 100 \ --seed 0 \ + --max_steps 20000 \ --random_steps 0 \ --training_starts 0 \ --utd_ratio 4 \ @@ -12,5 +15,5 @@ python drq_policy_robotiq.py "$@" \ --eval_period 1000 \ --encoder_type resnet-pretrained \ --checkpoint_period 10000 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_apr23_firstwithcam.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_apr30_newrew.pkl \ --debug diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index ba284421..68e4a569 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -128,10 +128,16 @@ def make_drq_agent( "hidden_dims": [256, 256], }, temperature_init=1e-2, - discount=0.96, # 0.99 + discount=0.99, # 0.99 backup_entropy=False, critic_ensemble_size=10, critic_subsample_size=2, + actor_optimizer_kwargs={ + "learning_rate": 3e-3, # 3e-4 + }, + critic_optimizer_kwargs={ + "learning_rate": 3e-3, # 3e-4 + }, ) return agent From 6d8de7200a311d48ce92ed0f99672cdd660f8491 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:56:44 +0200 Subject: [PATCH 137/338] added running reward info --- examples/robotiq_drq/record_demo.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index 5ff34b7f..4b3907bb 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -64,6 +64,7 @@ def on_esc(key): raise PermissionError(f"No permission to write to {file_dir}") try: + running_reward = 0. while success_count < success_needed: if exit_program.is_set(): raise KeyboardInterrupt # stop program, but clean up before @@ -84,8 +85,9 @@ def on_esc(key): transitions.append(transition) obs = next_obs + running_reward += rew - if done: + if done or truncated: success_count += int(rew > 0.99) total_count += 1 print( @@ -93,6 +95,9 @@ def on_esc(key): ) pbar.update(int(rew > 0.99)) obs, _ = env.reset() + print("Reward total:", running_reward) + running_reward = 0. + with open(file_path, "wb") as f: pkl.dump(transitions, f) From 7a8b49bccac9f1d440976ed96e84ea7c5bf1c8be Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:56:56 +0200 Subject: [PATCH 138/338] added cost plotter --- .../envs/camera_env/robotiq_camera_env.py | 57 ++++++++++++++++--- 1 file changed, 49 insertions(+), 8 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 118d86b9..932890f6 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -6,32 +6,73 @@ # used for float value comparisons (pressure of vacuum-gripper) def is_close(value, target): - return abs(value - target) < 1e-4 + return abs(value - target) < 1e-3 class RobotiqCameraEnv(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCameraConfig) + self.plot_costs_yes = False + if self.plot_costs_yes: + self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], downward_force_cost=[]) - def compute_reward(self, obs, action) -> float: + def compute_reward(self, obs, action) -> float: # TODO streamline reward # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 gripper_state = obs["state"]['gripper_state'] - suction_cost = 0.1 * float(is_close(gripper_state[0], 0.99)) + suction_cost = 0.2 * float(is_close(gripper_state[0], 0.99)) + suction_reward = 0.1 * float(0.1 < gripper_state[0] < 0.85) + downward_force_cost = 0.4 * max(obs["state"]["tcp_force"][2] - 5, 0.) torque = obs["state"]['tcp_torque'] non_central_cost = 0.5 * max(np.linalg.norm(torque[:2]) - 0.07, 0.) - # print(f"action_cost: {action_cost}, suction_cost: {suction_cost} non_central_cost: {non_central_cost}") + if self.plot_costs_yes: + self.reward_hist['action_cost'].append(-action_cost) + self.reward_hist['suction_cost'].append(-suction_cost) + self.reward_hist['non_central_cost'].append(-non_central_cost) + self.reward_hist['suction_reward'].append(suction_reward) + self.reward_hist['downward_force_cost'].append(-downward_force_cost) + + total_cost = action_cost + step_cost + suction_cost + non_central_cost + downward_force_cost if self.reached_goal_state(obs): - box_is_central = np.sum(np.power(torque[:2], 2)) - 0.01 < 0. - return (10. if box_is_central else 5.) - action_cost - step_cost - suction_cost + box_is_central = np.sum(np.power(torque[:2], 2)) - 0.1 < 0. + # return (100. if box_is_central else 50.) - action_cost - step_cost - suction_cost + return 100. - total_cost else: - return 0.0 - action_cost - step_cost - suction_cost - non_central_cost + return 0.0 - total_cost + suction_reward def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.15 # new min height with box + return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.10 # new min height with box + + def close(self): + if self.plot_costs_yes: + self.plot_costs() + super().close() + + def plot_costs(self): + import matplotlib.pyplot as plt + fig, ax = plt.subplots(6, 1, figsize=(12, 10), sharey=True, sharex=True) + y = np.arange(len(self.reward_hist["action_cost"])) + + ax1, ax2, ax3, ax4, ax5, ax6 = ax + ax1.plot(y, self.reward_hist["action_cost"], label="action_cost") + ax1.legend() + ax2.plot(y, self.reward_hist["suction_cost"], label="suction_cost") + ax2.legend() + ax3.plot(y, self.reward_hist["non_central_cost"], label="non_central_cost") + ax3.legend() + ax4.plot(y, self.reward_hist["suction_reward"], label="suction_reward") + ax4.legend() + ax5.plot(y, self.reward_hist["downward_force_cost"], label="downward_force_cost") + ax5.legend() + + total = [sum(i) for i in zip(*self.reward_hist.values())] + ax6.plot(y, total, label="total") + ax6.legend() + + plt.show() \ No newline at end of file From 116c573fcd620c18a2befa82eeabfd47e4c0dfc4 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:57:14 +0200 Subject: [PATCH 139/338] changed grip status representation --- serl_robot_infra/robot_controllers/robotiq_controller.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index a0fb8c3c..cebeb966 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -159,6 +159,9 @@ async def _update_robot_state(self): force = self.robotiq_receive.getActualTCPForce() pressure = await self.robotiq_gripper.get_current_pressure() obj_status = await self.robotiq_gripper.get_object_status() + + pressure /= 100. # pressure between [0, 1] + grip_status = 0. if obj_status.value == 3 else 1. # 3-> no object detected, [0, 1, 2]-> obj detected with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = vel @@ -166,7 +169,7 @@ async def _update_robot_state(self): self.curr_Qd[:] = Qd # use moving average (5), since the force fluctuates heavily self.curr_force[:] = 0.2 * np.array(force) + 0.8 * self.curr_force[:] - self.gripper_state[:] = [pressure / 100., float(obj_status.value)] # pressure between [0, 1] + self.gripper_state[:] = [pressure, grip_status] def get_state(self): with self.lock: From 089199bfd4a66ec00501e85aa7452908577556fd Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 3 May 2024 11:57:41 +0200 Subject: [PATCH 140/338] added wrapper to scale the obs space --- .../wrappers/serl_obs_wrappers.py | 41 +++++++++++++++++-- 1 file changed, 38 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 7ed392b3..bd93ca6a 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -1,10 +1,12 @@ import gymnasium as gym +from gymnasium import spaces +from gymnasium.core import ObsType, WrapperObsType from gymnasium.spaces import flatten_space, flatten class SERLObsWrapper(gym.ObservationWrapper): """ - This observation wrapper treat the observation space as a dictionary + This observation wrapper treats the observation space as a dictionary of a flattened state space and the images. """ @@ -27,8 +29,8 @@ def observation(self, obs): class SerlObsWrapperNoImages(gym.ObservationWrapper): """ - This observation wrapper treat the observation space as a flattened state - space, if no images are present. + This observation wrapper treats the observation space as a flattened state + space, if no images are present. """ def __init__(self, env): @@ -38,3 +40,36 @@ def __init__(self, env): def observation(self, obs): obs = flatten(self.env.observation_space["state"], obs["state"]) return obs + + +class ScaleObservationWrapper(gym.ObservationWrapper): + + """ + This observation wrapper scales the observations with the provided hyperparams + (to somewhat normalize the observations space) + """ + def __init__(self, + env, + translation_scale=10., + rotation_scale=10., + velocity_scale=10., + rotational_velocity_scale=10., + force_scale=1., + torque_scale=10. + ): + super().__init__(env) + self.translation_scale = translation_scale + self.rotation_scale = rotation_scale + self.velocity_scale = velocity_scale + self.rotational_velocity_scale = rotational_velocity_scale + self.force_scale = force_scale + self.torque_scale = torque_scale + + def observation(self, obs) -> WrapperObsType: + obs["state"]["tcp_pose"][:3] *= self.translation_scale + obs["state"]["tcp_pose"][3:] *= self.rotation_scale + obs["state"]["tcp_vel"][:3] *= self.velocity_scale + obs["state"]["tcp_vel"][3:] *= self.rotational_velocity_scale + obs["state"]["tcp_force"] *= self.force_scale + obs["state"]["tcp_torque"] *= self.torque_scale + return obs From a1a457d2a78f49f8e5e257d9ce62026af9d11ce9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 6 May 2024 14:48:45 +0200 Subject: [PATCH 141/338] small optimizations and modified env for SAC backwards compatibility --- examples/robotiq_drq/record_demo.py | 11 ++- examples/robotiq_sac/run_evaluation.sh | 4 +- examples/robotiq_sac/sac_policy_robotiq.py | 4 +- .../networks/actor_critic_nets.py | 2 +- .../wrappers/serl_obs_wrappers.py | 2 +- .../robot_controllers/robotiq_controller.py | 25 ++++-- serl_robot_infra/robotiq_env/__init__.py | 2 +- .../robotiq_env/envs/camera_env/config.py | 6 +- .../robotiq_env/envs/robotiq_env.py | 87 ++++++++++--------- 9 files changed, 85 insertions(+), 58 deletions(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index 4b3907bb..b747455e 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -11,7 +11,7 @@ from robotiq_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.chunking import ChunkingWrapper import robotiq_env @@ -32,12 +32,16 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq_camera_env") + env = gym.make("robotiq_camera_env", + camera_mode="rgb", + max_episode_length=100 + ) env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) + env = ScaleObservationWrapper(env) env = SERLObsWrapper(env) - # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) obs, _ = env.reset() @@ -98,7 +102,6 @@ def on_esc(key): print("Reward total:", running_reward) running_reward = 0. - with open(file_path, "wb") as f: pkl.dump(transitions, f) print(f"saved {success_needed} demos to {file_path}") diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/robotiq_sac/run_evaluation.sh index 04313a92..27bac681 100644 --- a/examples/robotiq_sac/run_evaluation.sh +++ b/examples/robotiq_sac/run_evaluation.sh @@ -4,7 +4,7 @@ python sac_policy_robotiq.py "$@" \ --actor \ --env robotiq-grip-v1 \ --exp_name=sac_robotiq_policy_evaluation \ - --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0412-16:22"\ - --eval_checkpoint_step 50000 \ + --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0411-16:46"\ + --eval_checkpoint_step 100000 \ --eval_n_trajs 10 \ --debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 4fd22894..e4bd4dbe 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -114,6 +114,7 @@ def actor(agent: SACAgent, data_store, env, sampling_rng): argmax=True, ) actions = np.asarray(jax.device_get(actions)) + # print(actions) next_obs, reward, done, truncated, info = env.step(actions) obs = next_obs @@ -309,6 +310,7 @@ def main(_): FLAGS.env, fake_env=FLAGS.learner, max_episode_length=FLAGS.max_traj_length, + camera_mode=None, ) if FLAGS.actor: env = SpacemouseIntervention(env) # TODO really needed? @@ -316,7 +318,7 @@ def main(_): env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - env = TransformReward(env, lambda r: FLAGS.reward_scale * r) + # env = TransformReward(env, lambda r: FLAGS.reward_scale * r) env = RecordEpisodeStatistics(env) rng, sampling_rng = jax.random.split(rng) diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index d0d568d9..c65fff4b 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -181,7 +181,7 @@ class Policy(nn.Module): def __call__( self, observations: jnp.ndarray, temperature: float = 1.0, train: bool = False ) -> distrax.Distribution: - info_dict = {key:value.shape for key, value in observations.items()} + # info_dict = {key:value.shape for key, value in observations.items()} # print(f"policy observations shape: {info_dict}") # TODO remove if self.encoder is None: obs_enc = observations diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index bd93ca6a..317919a6 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -65,7 +65,7 @@ def __init__(self, self.force_scale = force_scale self.torque_scale = torque_scale - def observation(self, obs) -> WrapperObsType: + def observation(self, obs): obs["state"]["tcp_pose"][:3] *= self.translation_scale obs["state"]["tcp_pose"][3:] *= self.rotation_scale obs["state"]["tcp_vel"][:3] *= self.velocity_scale diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index cebeb966..35703dba 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -33,6 +33,7 @@ def __init__( config=None, verbose=False, plot=False, + old_obs=False, *args, **kwargs ): @@ -50,6 +51,7 @@ def __init__( self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} self.verbose = verbose self.do_plot = plot + self.old_obs = old_obs # use the old observation layout self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) @@ -167,9 +169,13 @@ async def _update_robot_state(self): self.curr_vel[:] = vel self.curr_Q[:] = Q self.curr_Qd[:] = Qd - # use moving average (5), since the force fluctuates heavily - self.curr_force[:] = 0.2 * np.array(force) + 0.8 * self.curr_force[:] - self.gripper_state[:] = [pressure, grip_status] + if self.old_obs: + self.curr_force[:] = np.asarray(force) # old representation for SAC policy + self.gripper_state[:] = [pressure, float(obj_status.value)] + else: + # use moving average (5), since the force fluctuates heavily + self.curr_force[:] = 0.2 * np.array(force) + 0.8 * self.curr_force[:] + self.gripper_state[:] = [pressure, grip_status] def get_state(self): with self.lock: @@ -208,6 +214,13 @@ def _calculate_force(self): vel_rot_diff = R.from_rotvec(curr_vel[3:]).inv() torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable + # TODO make better and more general (tcp force check) + # check for big downward tcp force and adapt accordingly + # if self.curr_force[2] > 0.5 and force_pos[2] < 0.: + # print(force_pos[2], end=" ") + # force_pos[2] = max((1.5 - self.curr_force[2]), 0.) * force_pos[2] + min(self.curr_force[2] - 0.5, 1.) * 20. + # print(force_pos[2]) + return np.concatenate((force_pos, torque)) def plot(self): @@ -248,13 +261,13 @@ async def send_gripper_command(self): self.gripper_timeout["last_grip"] = time.monotonic() # print("grip") - elif self.target_grip[0] < -0.5 and self.gripper_state[1] != 3: # only release if obj detected + elif self.target_grip[0] < -0.5: await self.robotiq_gripper.automatic_release() self.target_grip[0] = 0.0 # print("release") def _truncate_check(self): - downward_force = self.curr_force[2] > 10 + downward_force = self.curr_force[2] > 10. if downward_force: # TODO add better criteria self._is_truncated.set() else: @@ -276,7 +289,7 @@ async def _go_to_reset_pose(self): if self.robotiq_gripper: self.target_grip[0] = -1. await self.send_gripper_command() - time.sleep(0.1) + time.sleep(0.2) # then move up (so no boxes are moved) while self.curr_pos[2] < self.reset_height: diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index ae79e8b8..ce5844db 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -10,5 +10,5 @@ register( id="robotiq_camera_env", entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnv", - max_episode_steps=300, + max_episode_steps=100, ) \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 00cd1c98..42f54dc3 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -9,8 +9,8 @@ class RobotiqCameraConfig(DefaultEnvConfig): RANDOM_RZ_RANGE = (0.0,) # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) - ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.1, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 3.0, -0.1, -3.2]) + ABS_POSE_LIMIT_HIGH = np.array([0.2, -0.4, 0.22, 3.2, 0.18, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.7, - 0.006, 2.8, -0.18, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" @@ -20,7 +20,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): FORCEMODE_DAMPING: float = 0.0 # faster FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) REALSENSE_CAMERAS = { "wrist": "218622271597", diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index aafcc4fd..88011506 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -80,9 +80,9 @@ def __init__( fake_env=False, config=DefaultEnvConfig, max_episode_length: int = 100, - save_video=False, - realtime_plot=False, - camera_mode="rgb", # one of (rgb, depth, both) + save_video: bool = False, + realtime_plot: bool = False, + camera_mode: str = "rgb", # one of (rgb, depth, both, None) ): self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -105,7 +105,7 @@ def __init__( self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz - if save_video: + if camera_mode is not None and save_video: print("Saving videos!") self.save_video = save_video self.recording_frames = [] @@ -129,17 +129,17 @@ def __init__( np.ones((7,), dtype=np.float32), ) - if camera_mode=="rgb": + if camera_mode == "rgb": image_space = gym.spaces.Dict( # TODO add depth info, or make bigger (only 128x128x3) - { - "shoulder": gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - "wrist": gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - }) - elif camera_mode=="depth": + { + "shoulder": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + "wrist": gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ), + }) + elif camera_mode == "depth": image_space = gym.spaces.Dict( { "shoulder": gym.spaces.Box( @@ -150,27 +150,31 @@ def __init__( ) } ) - elif camera_mode=="both": + elif camera_mode == "both": raise NotImplementedError("not yet implemented") - else: + elif camera_mode is not None: raise NotImplementedError(f"camera mode {camera_mode} not implemented") - self.observation_space = gym.spaces.Dict( + state_space = gym.spaces.Dict( { - "state": gym.spaces.Dict( - { - "tcp_pose": gym.spaces.Box( - -np.inf, np.inf, shape=(7,) - ), # xyz + quat - "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_state": gym.spaces.Box(-np.inf, np.inf, shape=(2,)), - "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - } - ), - "images": image_space, + "tcp_pose": gym.spaces.Box( + -np.inf, np.inf, shape=(7,) + ), # xyz + quat + "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), + "gripper_state": gym.spaces.Box(-np.inf, np.inf, shape=(2,)), + "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } ) + + if self.camera_mode is None: + self.observation_space = gym.spaces.Dict({"state": state_space}) + else: + self.observation_space = gym.spaces.Dict({ + "state": state_space, + "images": image_space, + }) + self.cycle_count = 0 self.controller = None self.cap = None @@ -185,16 +189,18 @@ def __init__( kp=10000, kd=2200, config=config, - verbose=True, - plot=False + verbose=False, + plot=False, + old_obs=camera_mode is None ) self.controller.start() # start Thread - self.init_cameras(config.REALSENSE_CAMERAS) - self.img_queue = queue.Queue() - self.displayer = ImageDisplayer(self.img_queue) - self.displayer.start() - print("[CAM] Cameras are ready!") + if self.camera_mode is not None: + self.init_cameras(config.REALSENSE_CAMERAS) + self.img_queue = queue.Queue() + self.displayer = ImageDisplayer(self.img_queue) + self.displayer.start() + print("[CAM] Cameras are ready!") if self.realtime_plot: try: @@ -307,7 +313,7 @@ def go_to_rest(self, joint_reset=False): time.sleep(0.1) while self.controller.is_moving(): time.sleep(0.1) - print(reset_shift, reset_pose) + # print(reset_shift, reset_pose) return reset_shift else: return np.zeros((2,)) @@ -445,7 +451,6 @@ def _is_truncated(self): return self.controller.is_truncated() def _get_obs(self) -> dict: - images = self.get_image() state_observation = { "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, @@ -456,7 +461,11 @@ def _get_obs(self) -> dict: if self.realtime_plot: self.plotting_client.send(np.concatenate([self.curr_force, self.curr_torque])) - return copy.deepcopy(dict(images=images, state=state_observation)) + if self.camera_mode is not None: + images = self.get_image() + return copy.deepcopy(dict(images=images, state=state_observation)) + else: + return copy.deepcopy(dict(state=state_observation)) def close(self): if self.controller: From 92f0a93fb5b7a5a1d724e621506eff3eb2228213 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 7 May 2024 16:56:46 +0200 Subject: [PATCH 142/338] controller optimization (force check) --- .../robot_controllers/robotiq_controller.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 35703dba..d0a61dd0 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -216,10 +216,10 @@ def _calculate_force(self): # TODO make better and more general (tcp force check) # check for big downward tcp force and adapt accordingly - # if self.curr_force[2] > 0.5 and force_pos[2] < 0.: - # print(force_pos[2], end=" ") - # force_pos[2] = max((1.5 - self.curr_force[2]), 0.) * force_pos[2] + min(self.curr_force[2] - 0.5, 1.) * 20. - # print(force_pos[2]) + if self.curr_force[2] > 0.5 and force_pos[2] < 0.: + print(force_pos[2], end=" ") + force_pos[2] = max((1.5 - self.curr_force[2]), 0.) * force_pos[2] + min(self.curr_force[2] - 0.5, 1.) * 20. + print(force_pos[2]) return np.concatenate((force_pos, torque)) @@ -261,7 +261,7 @@ async def send_gripper_command(self): self.gripper_timeout["last_grip"] = time.monotonic() # print("grip") - elif self.target_grip[0] < -0.5: + elif self.target_grip[0] < -0.5 and not np.isclose(self.gripper_state[0], 1., atol=1e-4): await self.robotiq_gripper.automatic_release() self.target_grip[0] = 0.0 # print("release") From 6f4d3eadbc0f9faf6a529e36b0ad4264dd173ad8 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 7 May 2024 16:57:54 +0200 Subject: [PATCH 143/338] added encoded observation output (through print and parse) --- examples/robotiq_drq/encoder_feature_plot.py | 191 ++++++++++++++++++ .../data/memory_efficient_replay_buffer.py | 4 +- .../networks/actor_critic_nets.py | 4 + 3 files changed, 198 insertions(+), 1 deletion(-) create mode 100644 examples/robotiq_drq/encoder_feature_plot.py diff --git a/examples/robotiq_drq/encoder_feature_plot.py b/examples/robotiq_drq/encoder_feature_plot.py new file mode 100644 index 00000000..1f4357f3 --- /dev/null +++ b/examples/robotiq_drq/encoder_feature_plot.py @@ -0,0 +1,191 @@ +#!/usr/bin/env python3 + +import time +from functools import partial +import jax +import jax.numpy as jnp +import numpy as np +import pynput +import threading +import tqdm +from absl import app, flags +from flax.training import checkpoints +from datetime import datetime + +import gymnasium as gym +from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics + +from serl_launcher.agents.continuous.drq import DrQAgent +from serl_launcher.common.evaluation import evaluate +from serl_launcher.utils.timer_utils import Timer +from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.utils.train_utils import concat_batches + +from agentlace.trainer import TrainerServer, TrainerClient +from agentlace.data.data_store import QueuedDataStore + +from serl_launcher.utils.launcher import ( + make_drq_agent, + make_trainer_config, + make_wandb_logger, +) +from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper +from robotiq_env.envs.relative_env import RelativeFrame +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper + +import robotiq_env + +devices = jax.local_devices() +num_devices = len(devices) +sharding = jax.sharding.PositionalSharding(devices) + +FLAGS = flags.FLAGS + +flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("agent", "drq", "Name of agent.") +flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") +flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both)") + +flags.DEFINE_integer("seed", 42, "Random seed.") +flags.DEFINE_bool("save_model", False, "Whether to save model.") +flags.DEFINE_integer("batch_size", 512, "Batch size.") +flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") + +flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") +flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") + +flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") +flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") +flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") + +flags.DEFINE_integer("log_period", 10, "Logging period.") +flags.DEFINE_integer("eval_period", 1000, "Evaluation period.") + +# flag to indicate if this is a leaner or a actor +flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") +flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") +flags.DEFINE_string("ip", "localhost", "IP address of the learner.") +# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights +flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") +flags.DEFINE_string("demo_path", None, "Path to the demo data.") +flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', + "Path to save checkpoints.") + +flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") +flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") + +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', + "Path to save RLDS logs.") +flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") + +flags.DEFINE_boolean( + "debug", False, "Debug mode." +) # debug mode will disable wandb logging + + +def main(_): + assert FLAGS.batch_size % num_devices == 0 + FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") + + # seed + rng = jax.random.PRNGKey(FLAGS.seed) + + # create env and load dataset + env = gym.make( + FLAGS.env, + camera_mode="rgb", + fake_env=True, + max_episode_length=100, + ) + env = RelativeFrame(env) + env = Quat2EulerWrapper(env) + env = SERLObsWrapper(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = RecordEpisodeStatistics(env) + + image_keys = [key for key in env.observation_space.keys() if key != "state"] + + rng, sampling_rng = jax.random.split(rng) + agent: DrQAgent = make_drq_agent( + seed=FLAGS.seed, + sample_obs=env.observation_space.sample(), + sample_action=env.action_space.sample(), + image_keys=image_keys, + encoder_type=FLAGS.encoder_type, + ) + + # replicate agent across devices + # need the jnp.array to avoid a bug where device_put doesn't recognize primitives + agent: DrQAgent = jax.device_put( + jax.tree_map(jnp.array, agent), sharding.replicate() + ) + + demo_buffer = MemoryEfficientReplayBufferDataStore( + env.observation_space, + env.action_space, + capacity=2000, + image_keys=image_keys, + ) + + sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) + + import pickle as pkl + + with open("/home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai3_streamlined.pkl", "rb") as f: + trajs = pkl.load(f) + for traj in trajs: + demo_buffer.insert(traj) + print(f"demo buffer size: {len(demo_buffer)}") + + # encode here + # encode(demo_buffer, agent) + + # plot here + plot(demo_buffer) + + +def encode(demo_buffer, agent): + for i in range(len(demo_buffer) // 10): + index = np.arange(10) + i * 10 + obs = demo_buffer.sample(batch_size=10, indx=index) + + actions = agent.sample_actions( + observations=jax.device_put(obs["observations"]), + argmax=True + ) + + +def plot(demo_buffer): + import sys + sys.path.append("/home/nico/real-world-rl/spacemouse_tests") + from spacemouse_tests.jax_feature_plotter import generate_and_save_images + feature_file = "/home/nico/real-world-rl/serl/examples/robotiq_drq/features_meanstd.npy" + + with open(feature_file, 'rb') as f: + features = np.load(f) + + print("features shape ", features.shape) + shoulder_f = features[:, :256].reshape((800, 16, 16)) # shoulder comes first + wrist_f = features[:, 256:512].reshape((800, 16, 16)) + + # get images here + shoulder, wrist = [], [] + for i in range(len(demo_buffer) // 10): + index = np.arange(10) + i * 10 + obs = demo_buffer.sample(batch_size=10, indx=index) + + wrist.append(obs["observations"]["wrist"]) + shoulder.append(obs["observations"]["shoulder"]) + + wrist = np.array(wrist).reshape((800, 128, 128, 3)) + shoulder = np.array(shoulder).reshape((800, 128, 128, 3)) + + output_folder = '/home/nico/real-world-rl/spacemouse_tests/feature_plots_meanstd' + generate_and_save_images(output_folder, [shoulder, wrist, shoulder_f, wrist_f]) + + +if __name__ == "__main__": + app.run(main) diff --git a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py index 80f8d461..3d71164c 100644 --- a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py +++ b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py @@ -121,7 +121,9 @@ def sample( else: indx[i] = self.np_random.randint(len(self)) else: - raise NotImplementedError() + # raise NotImplementedError() + # print(f"indx is {indx}") + assert type(indx) == np.ndarray if keys is None: keys = self.dataset_dict.keys() diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index c65fff4b..0c48307a 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -188,6 +188,10 @@ def __call__( else: obs_enc = self.encoder(observations, train=train, stop_gradient=True) + # output the encoded obs, returning is not possible due to jax (on gpu) + # for i in range(obs_enc.shape[0]): + # jax.debug.print("{}\n\n", obs_enc[i, ...]) + outputs = self.network(obs_enc, train=train) means = nn.Dense(self.action_dim, kernel_init=default_init())(outputs) From b7e4fa4433dbd8e3962435d5e805bd3e9ff7f770 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 7 May 2024 16:58:10 +0200 Subject: [PATCH 144/338] try to use mean and std from demo images --- serl_launcher/serl_launcher/vision/mobilenet.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/serl_launcher/serl_launcher/vision/mobilenet.py b/serl_launcher/serl_launcher/vision/mobilenet.py index 33d5ab02..1e0875a1 100644 --- a/serl_launcher/serl_launcher/vision/mobilenet.py +++ b/serl_launcher/serl_launcher/vision/mobilenet.py @@ -38,6 +38,11 @@ def __call__(self, x: jnp.ndarray, train=False) -> jnp.ndarray: # normalize inputs using imagenet mean and std mean = jnp.array((0.485, 0.456, 0.406))[None, ...] std = jnp.array((0.229, 0.224, 0.225))[None, ...] + + # normalization constants calculated from the demo trajectories ...demos_mai3_streamlined.pkl + mean = jnp.array((0.68992649, 0.66665285, 0.57000176))[None, ...] + std = jnp.array((0.35203312, 0.29289631, 0.29029032))[None, ...] + x = x.astype(jnp.float32) / 255.0 x = (x - mean) / std From cb222d5e13a4a0bb82092924bcfdf77e09946a76 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 7 May 2024 16:58:22 +0200 Subject: [PATCH 145/338] DRQ TODO's --- serl_launcher/serl_launcher/agents/continuous/drq.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 811cdfc0..3a69db31 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -11,7 +11,7 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.common import JaxRLTrainState, ModuleDict, nonpytree_field from serl_launcher.common.encoding import EncodingWrapper -from serl_launcher.common.optimizers import make_optimizer +from serl_launcher.common.optimizers import make_optimizer, make_adam_optimizer from serl_launcher.common.typing import Batch, Data, Params, PRNGKey from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize from serl_launcher.networks.lagrange import GeqLagrangeMultiplier @@ -298,6 +298,8 @@ def update_high_utd( } ) + # TODO implement K=2 and M=2 + new_state = self.state.replace(rng=rng) new_agent = self.replace(state=new_state) @@ -316,6 +318,8 @@ def update_critics( if self.config["image_keys"][0] not in batch["next_observations"]: batch = _unpack(batch) + # TODO implement K=2 and M=2 + rng = new_agent.state.rng rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) obs = self.data_augmentation_fn(obs_rng, batch["observations"]) From 6f2d62836db2c4a86da2def7e4e64fef6cd4040e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 7 May 2024 16:58:52 +0200 Subject: [PATCH 146/338] streamlined reward --- .../envs/camera_env/robotiq_camera_env.py | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 932890f6..e6223940 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -16,7 +16,7 @@ def __init__(self, **kwargs): if self.plot_costs_yes: self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], downward_force_cost=[]) - def compute_reward(self, obs, action) -> float: # TODO streamline reward + """def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 @@ -42,7 +42,18 @@ def compute_reward(self, obs, action) -> float: # TODO streamline reward # return (100. if box_is_central else 50.) - action_cost - step_cost - suction_cost return 100. - total_cost else: - return 0.0 - total_cost + suction_reward + return 0.0 - total_cost + suction_reward""" + + def compute_reward(self, obs, action) -> float: + action_cost = 0.2 * np.sum(np.power(action, 2)) + step_cost = 0.02 + + downward_force_cost = 0.4 * max(obs["state"]["tcp_force"][2] - 5, 0.) + if self.reached_goal_state(obs): + return 100. - action_cost - step_cost - downward_force_cost + else: + return 0. - action_cost - step_cost - downward_force_cost + def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From a2f11bc9f42462ddd6e49976a1a7b7ab239ab0ad Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:53:56 +0200 Subject: [PATCH 147/338] controller corrections --- .../robot_controllers/robotiq_controller.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index d0a61dd0..124408e5 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -163,7 +163,7 @@ async def _update_robot_state(self): obj_status = await self.robotiq_gripper.get_object_status() pressure /= 100. # pressure between [0, 1] - grip_status = 0. if obj_status.value == 3 else 1. # 3-> no object detected, [0, 1, 2]-> obj detected + grip_status = [0., 1., 1., 0.][obj_status.value] # 3-> no object detected, [0, 1, 2]-> obj detected with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = vel @@ -174,7 +174,7 @@ async def _update_robot_state(self): self.gripper_state[:] = [pressure, float(obj_status.value)] else: # use moving average (5), since the force fluctuates heavily - self.curr_force[:] = 0.2 * np.array(force) + 0.8 * self.curr_force[:] + self.curr_force[:] = 0.1 * np.array(force) + 0.9 * self.curr_force[:] self.gripper_state[:] = [pressure, grip_status] def get_state(self): @@ -202,7 +202,7 @@ def _calculate_force(self): curr_pos = self.curr_pos curr_vel = self.curr_vel - # calc position force + # calc position for kp, kd = self.kp, self.kd diff_p = np.clip(target_pos[:3] - curr_pos[:3], a_min=-self.delta, a_max=self.delta) vel_delta = 2 * self.delta * self.frequency @@ -217,9 +217,9 @@ def _calculate_force(self): # TODO make better and more general (tcp force check) # check for big downward tcp force and adapt accordingly if self.curr_force[2] > 0.5 and force_pos[2] < 0.: - print(force_pos[2], end=" ") + # print(force_pos[2], end=" ") force_pos[2] = max((1.5 - self.curr_force[2]), 0.) * force_pos[2] + min(self.curr_force[2] - 0.5, 1.) * 20. - print(force_pos[2]) + # print(force_pos[2]) return np.concatenate((force_pos, torque)) @@ -267,7 +267,7 @@ async def send_gripper_command(self): # print("release") def _truncate_check(self): - downward_force = self.curr_force[2] > 10. + downward_force = self.curr_force[2] > 20. if downward_force: # TODO add better criteria self._is_truncated.set() else: From 4441f1a98eb4c851690aecc1bb933fb5c9b37cee Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:54:31 +0200 Subject: [PATCH 148/338] backup entropy as in original SAC paper and slight loss change --- serl_launcher/serl_launcher/agents/continuous/sac.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index 4024b7a9..4f18536f 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -167,9 +167,10 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): ) chex.assert_shape(target_q, (batch_size,)) - if self.config["backup_entropy"]: + if self.config["backup_entropy"]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py temperature = self.forward_temperature() - target_q = target_q - temperature * next_actions_log_probs + # target_q = target_q - temperature * next_actions_log_probs # serl original + target_q = target_q - self.config["discount"] * batch["masks"] * next_actions_log_probs * temperature # as in jaxrl_m predicted_qs = self.forward_critic( batch["observations"], batch["actions"], rng=rng, grad_params=params @@ -180,7 +181,7 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): ) target_qs = target_q[None].repeat(self.config["critic_ensemble_size"], axis=0) chex.assert_equal_shape([predicted_qs, target_qs]) - critic_loss = jnp.mean((predicted_qs - target_qs) ** 2) + critic_loss = jnp.mean(jnp.sum((predicted_qs - target_qs) ** 2, axis=0)) info = { "critic_loss": critic_loss, From bf60dd48c80cfa05f888e0ad503ce793b9d0f66f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:54:43 +0200 Subject: [PATCH 149/338] translation scale change --- serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 317919a6..62814a6a 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -50,7 +50,7 @@ class ScaleObservationWrapper(gym.ObservationWrapper): """ def __init__(self, env, - translation_scale=10., + translation_scale=100., rotation_scale=10., velocity_scale=10., rotational_velocity_scale=10., From 9781215af6748ce1ab96aebfe85f3a9a061c9c5c Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:55:27 +0200 Subject: [PATCH 150/338] small changes to drq policy --- examples/robotiq_drq/drq_policy_robotiq.py | 28 ++++++++++--------- serl_launcher/serl_launcher/utils/launcher.py | 6 ++-- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index c9b85c83..a3201c1e 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -44,17 +44,17 @@ flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") flags.DEFINE_string("agent", "drq", "Name of agent.") -flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") +flags.DEFINE_string("exp_name", "DRQ agent", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both)") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", False, "Whether to save model.") -flags.DEFINE_integer("batch_size", 512, "Batch size.") +flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") +flags.DEFINE_integer("replay_buffer_capacity", 20000, "Replay buffer capacity.") flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") @@ -222,7 +222,7 @@ def update_params(params): reward = np.asarray(reward, dtype=np.float32) info = np.asarray(info) - running_return += reward + running_return = running_return * 0.99 + reward transition = dict( observations=obs, actions=actions, @@ -237,6 +237,7 @@ def update_params(params): if done or truncated: stats = {"train": info} # send stats to the learner to log client.request("send-stats", stats) + print(f"running return: {running_return}") running_return = 0.0 obs, _ = env.reset() @@ -345,17 +346,17 @@ def stats_callback(type: str, payload: dict) -> dict: # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU for critic_step in range(FLAGS.utd_ratio - 1): with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) if len(replay_buffer) > 0 else None + batch = next(replay_iterator) demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch + batch = concat_batches(batch, demo_batch, axis=0) with timer.context("train_critics"): agent, critics_info = agent.update_critics(batch,) with timer.context("train"): - batch = next(replay_iterator) if len(replay_buffer) > 0 else None + batch = next(replay_iterator) demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch + batch = concat_batches(batch, demo_batch, axis=0) agent, update_info = agent.update_high_utd(batch, utd_ratio=1) # publish the updated network @@ -366,6 +367,7 @@ def stats_callback(type: str, payload: dict) -> dict: if update_steps % FLAGS.log_period == 0 and wandb_logger: wandb_logger.log(update_info, step=update_steps) wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) + wandb_logger.log({"replay_buffer_size": len(replay_buffer)}) if FLAGS.checkpoint_period and update_steps and update_steps % FLAGS.checkpoint_period == 0: assert FLAGS.checkpoint_path is not None @@ -420,11 +422,11 @@ def main(_): fake_env=FLAGS.learner, max_episode_length=FLAGS.max_traj_length, ) - if FLAGS.actor: - env = SpacemouseIntervention(env) + # if FLAGS.actor: + # env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) - env = ScaleObservationWrapper(env) # scale obs space + env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -467,12 +469,12 @@ def create_replay_buffer_and_wandb_logger(): demo_buffer = MemoryEfficientReplayBufferDataStore( env.observation_space, env.action_space, - capacity=10000, + capacity=2000, image_keys=image_keys, ) import pickle as pkl - # TOOD check for depth or rgb + # TODO check for depth or rgb with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) for traj in trajs: diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 68e4a569..dab7de31 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -129,14 +129,14 @@ def make_drq_agent( }, temperature_init=1e-2, discount=0.99, # 0.99 - backup_entropy=False, + backup_entropy=True, # default: False critic_ensemble_size=10, critic_subsample_size=2, actor_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 + "learning_rate": 3e-4, # 3e-4 }, critic_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 + "learning_rate": 3e-4, # 3e-4 }, ) return agent From 6483203cc684dfd061a0bd08955879434df674f1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:55:33 +0200 Subject: [PATCH 151/338] reward change --- .../envs/camera_env/robotiq_camera_env.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index e6223940..85117d61 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -14,7 +14,8 @@ def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCameraConfig) self.plot_costs_yes = False if self.plot_costs_yes: - self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], downward_force_cost=[]) + self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], + downward_force_cost=[]) """def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) @@ -45,16 +46,16 @@ def __init__(self, **kwargs): return 0.0 - total_cost + suction_reward""" def compute_reward(self, obs, action) -> float: - action_cost = 0.2 * np.sum(np.power(action, 2)) - step_cost = 0.02 + action_cost = 0.1 * np.sum(np.power(action, 2)) + step_cost = 0.01 + + downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 5., 0.) - downward_force_cost = 0.4 * max(obs["state"]["tcp_force"][2] - 5, 0.) if self.reached_goal_state(obs): return 100. - action_cost - step_cost - downward_force_cost else: return 0. - action_cost - step_cost - downward_force_cost - def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] @@ -86,4 +87,4 @@ def plot_costs(self): ax6.plot(y, total, label="total") ax6.legend() - plt.show() \ No newline at end of file + plt.show() From 5cc477972c764d5f8142073486c24a0e04431f37 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 16 May 2024 13:55:40 +0200 Subject: [PATCH 152/338] reward change --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 88011506..767a0429 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -267,7 +267,10 @@ def step(self, action: np.ndarray) -> tuple: obs = self._get_obs() reward = self.compute_reward(obs, action) truncated = self._is_truncated() - done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) + + reward = reward if not truncated else reward - 100. # truncation penalty + + done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated return obs, reward, done, truncated, {} def compute_reward(self, obs, action) -> float: From 66e09725242db0f074d20041e5bbaf267f494d8a Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 12:15:06 +0200 Subject: [PATCH 153/338] better lightning conditions for the camera sensor --- serl_robot_infra/robotiq_env/camera/rs_capture.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index ab4c2ff4..f02f847c 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -25,8 +25,10 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) self.profile = self.pipe.start(self.cfg) - # depth_sensor = self.profile.get_device().query_sensors()[0] - # depth_sensor.set_option(rs.option.enable_auto_white_balance, True) # TODO needed? + # for some weird reason, these values have to be set in order for the image to appear with good lightning + for sensor in self.profile.get_device().query_sensors(): + sensor.set_option(rs.option.enable_auto_exposure, False) + sensor.set_option(rs.option.enable_auto_white_balance, True) # Create an align object # rs.align allows us to perform alignment of depth frames to others frames From e5012db1eda8b6db665f4d85c5eb6f21dee18fa7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 13:52:39 +0200 Subject: [PATCH 154/338] new cameras --- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 42f54dc3..d62f985e 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -4,7 +4,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) - RANDOM_RESET = True + RANDOM_RESET = False RANDOM_XY_RANGE = (0.05,) RANDOM_RZ_RANGE = (0.0,) # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ @@ -23,6 +23,6 @@ class RobotiqCameraConfig(DefaultEnvConfig): FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) REALSENSE_CAMERAS = { - "wrist": "218622271597", - "shoulder": "218622270808" - } \ No newline at end of file + "wrist": "218622279756", + # "shoulder": "218622277164" + } From be846e0e2af7de5a26b7bb3d4e15f98cf719e808 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 13:54:39 +0200 Subject: [PATCH 155/338] run that got drq working --- examples/robotiq_drq/drq_policy_robotiq.py | 54 +++++++++++-------- serl_launcher/serl_launcher/utils/launcher.py | 43 ++++++++++++++- .../serl_launcher/vision/mobilenet.py | 4 +- .../envs/camera_env/robotiq_camera_env.py | 7 ++- 4 files changed, 82 insertions(+), 26 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index a3201c1e..a78e40c1 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -54,7 +54,7 @@ flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 20000, "Replay buffer capacity.") +flags.DEFINE_integer("replay_buffer_capacity", 5000, "Replay buffer capacity.") # quite low to forget old ones flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") @@ -210,7 +210,7 @@ def update_params(params): deterministic=False, ) actions = np.asarray(jax.device_get(actions)) - print(actions) + # print(actions) # Step environment with timer.context("step_env"): @@ -270,8 +270,6 @@ def update_params(params): client.stop() break - print("Actor loop finished") - ############################################################################## @@ -317,18 +315,21 @@ def stats_callback(type: str, payload: dict) -> dict: # 50/50 sampling from RLPD, half from demo and half from online experience replay_iterator = replay_buffer.get_iterator( sample_args={ - "batch_size": FLAGS.batch_size // 2, - "pack_obs_and_next_obs": True, - }, - device=sharding.replicate(), - ) - demo_iterator = demo_buffer.get_iterator( - sample_args={ - "batch_size": FLAGS.batch_size // 2, + "batch_size": FLAGS.batch_size, "pack_obs_and_next_obs": True, }, device=sharding.replicate(), ) + # demo_iterator = demo_buffer.get_iterator( + # sample_args={ + # "batch_size": FLAGS.batch_size // 2, + # "pack_obs_and_next_obs": True, + # }, + # device=sharding.replicate(), + # ) + + # if FLAGS.debug: # debug without replay buffer + # replay_iterator = demo_iterator # wait till the replay buffer is filled with enough data timer = Timer() @@ -347,16 +348,16 @@ def stats_callback(type: str, payload: dict) -> dict: for critic_step in range(FLAGS.utd_ratio - 1): with timer.context("sample_replay_buffer"): batch = next(replay_iterator) - demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) + # demo_batch = next(demo_iterator) if len(replay_buffer) < 5000 else next(replay_iterator) + # batch = concat_batches(batch, demo_batch, axis=0) with timer.context("train_critics"): agent, critics_info = agent.update_critics(batch,) with timer.context("train"): batch = next(replay_iterator) - demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) + # demo_batch = next(demo_iterator) if len(replay_buffer) < 5000 else next(replay_iterator) + # batch = concat_batches(batch, demo_batch, axis=0) agent, update_info = agent.update_high_utd(batch, utd_ratio=1) # publish the updated network @@ -369,13 +370,14 @@ def stats_callback(type: str, payload: dict) -> dict: wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) wandb_logger.log({"replay_buffer_size": len(replay_buffer)}) - if FLAGS.checkpoint_period and update_steps and update_steps % FLAGS.checkpoint_period == 0: + update_steps += 1 + + if FLAGS.checkpoint_period and update_steps % FLAGS.checkpoint_period == 0: assert FLAGS.checkpoint_path is not None checkpoints.save_checkpoint( FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 ) - update_steps += 1 if PAUSE_EVENT_FLAG.is_set(): print("Learner loop interrupted") @@ -478,8 +480,12 @@ def create_replay_buffer_and_wandb_logger(): with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) for traj in trajs: - demo_buffer.insert(traj) - print(f"demo buffer size: {len(demo_buffer)}") + # TODO only temporary to test one image only + traj["observations"].pop("shoulder") + traj["next_observations"].pop("shoulder") + + replay_buffer.insert(traj) # TODO only temporary, to test demos in replaybuffer + print(f"demo buffer size: {len(replay_buffer)}") # learner loop print_green("starting learner loop") @@ -497,7 +503,13 @@ def create_replay_buffer_and_wandb_logger(): # actor loop print_green("starting actor loop") - actor(agent, data_store, env, sampling_rng) + try: + actor(agent, data_store, env, sampling_rng) + print_green("actor loop finished") + except KeyboardInterrupt: + print_green("actor loop interrupted") + finally: + env.close() else: raise NotImplementedError("Must be either a learner or an actor") diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index dab7de31..0144b17d 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -133,10 +133,49 @@ def make_drq_agent( critic_ensemble_size=10, critic_subsample_size=2, actor_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 + "learning_rate": 3e-3, # 3e-4 }, critic_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 + "learning_rate": 3e-3, # 3e-4 + }, + ) + return agent + + +def make_drq_agent_no_images( + seed, sample_obs, sample_action, image_keys=(), encoder_type="small" +): + agent = DrQAgent.create_drq_no_images( + jax.random.PRNGKey(seed), + sample_obs, + sample_action, + image_keys=image_keys, + policy_kwargs={ + "tanh_squash_distribution": True, + "std_parameterization": "exp", + "std_min": 1e-5, + "std_max": 5, + }, + critic_network_kwargs={ + "activations": nn.tanh, + "use_layer_norm": True, + "hidden_dims": [256, 256], + }, + policy_network_kwargs={ + "activations": nn.tanh, + "use_layer_norm": True, + "hidden_dims": [256, 256], + }, + temperature_init=1e-2, + discount=0.99, # 0.99 + backup_entropy=True, # default: False + critic_ensemble_size=10, + critic_subsample_size=2, + actor_optimizer_kwargs={ + "learning_rate": 3e-3, # 3e-4 + }, + critic_optimizer_kwargs={ + "learning_rate": 3e-3, # 3e-4 }, ) return agent diff --git a/serl_launcher/serl_launcher/vision/mobilenet.py b/serl_launcher/serl_launcher/vision/mobilenet.py index 1e0875a1..b9b54e83 100644 --- a/serl_launcher/serl_launcher/vision/mobilenet.py +++ b/serl_launcher/serl_launcher/vision/mobilenet.py @@ -40,8 +40,8 @@ def __call__(self, x: jnp.ndarray, train=False) -> jnp.ndarray: std = jnp.array((0.229, 0.224, 0.225))[None, ...] # normalization constants calculated from the demo trajectories ...demos_mai3_streamlined.pkl - mean = jnp.array((0.68992649, 0.66665285, 0.57000176))[None, ...] - std = jnp.array((0.35203312, 0.29289631, 0.29029032))[None, ...] + # mean = jnp.array((0.68992649, 0.66665285, 0.57000176))[None, ...] + # std = jnp.array((0.35203312, 0.29289631, 0.29029032))[None, ...] x = x.astype(jnp.float32) / 255.0 x = (x - mean) / std diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 85117d61..819ce56e 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -50,11 +50,16 @@ def compute_reward(self, obs, action) -> float: step_cost = 0.01 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 5., 0.) + suction_reward = 0.5 * float(obs["state"]["gripper_state"][1] > 0.9) + + # TODO make cost for being at orientation limit + # TODO make cost for being too far away from starting position if self.reached_goal_state(obs): + # TODO make offset end position cost with self.curr_reset_pose return 100. - action_cost - step_cost - downward_force_cost else: - return 0. - action_cost - step_cost - downward_force_cost + return 0. + suction_reward - action_cost - step_cost - downward_force_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From 9bd136ec993cb0be4dde4e47f93c88bf465d9b8e Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 13:54:54 +0200 Subject: [PATCH 156/338] new observation space definition (rgb, depth, both) --- .../robotiq_env/envs/robotiq_env.py | 62 +++++++++---------- 1 file changed, 30 insertions(+), 32 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 767a0429..b3a8fc9d 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -90,6 +90,7 @@ def __init__( self.config = config self.resetQ = config.RESET_Q + self.curr_reset_pose = np.zeros((7,), dtype=np.float32) self.curr_pos = np.zeros((7,), dtype=np.float32) self.curr_vel = np.zeros((6,), dtype=np.float32) @@ -129,32 +130,29 @@ def __init__( np.ones((7,), dtype=np.float32), ) - if camera_mode == "rgb": - image_space = gym.spaces.Dict( # TODO add depth info, or make bigger (only 128x128x3) - { - "shoulder": gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - "wrist": gym.spaces.Box( + image_space_definition = {} + if camera_mode in ["rgb", "both"]: + # image_space_definition["shoulder"] = gym.spaces.Box( # TODO only temporary with one image + # 0, 255, shape=(128, 128, 3), dtype=np.uint8 + # ) + image_space_definition["wrist"] = gym.spaces.Box( 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ), - }) - elif camera_mode == "depth": - image_space = gym.spaces.Dict( - { - "shoulder": gym.spaces.Box( + ) + + elif camera_mode in ["depth", "both"]: + image_space_definition["shoulder_depth"] = gym.spaces.Box( 0, 65535, shape=(128, 128, 1), dtype=np.uint16 - ), - "wrist": gym.spaces.Box( + ) + image_space_definition["wrist_depth"] = gym.spaces.Box( 0, 65535, shape=(128, 128, 1), dtype=np.uint16 - ) - } ) - elif camera_mode == "both": - raise NotImplementedError("not yet implemented") elif camera_mode is not None: raise NotImplementedError(f"camera mode {camera_mode} not implemented") + image_space = gym.spaces.Dict( + image_space_definition + ) + state_space = gym.spaces.Dict( { "tcp_pose": gym.spaces.Box( @@ -167,13 +165,11 @@ def __init__( } ) - if self.camera_mode is None: - self.observation_space = gym.spaces.Dict({"state": state_space}) - else: - self.observation_space = gym.spaces.Dict({ - "state": state_space, - "images": image_space, - }) + obs_space_definition = {"state": state_space} + if self.camera_mode in ["rgb", "both", "depth"]: + obs_space_definition["images"] = image_space + + self.observation_space = gym.spaces.Dict(obs_space_definition) self.cycle_count = 0 self.controller = None @@ -302,11 +298,13 @@ def go_to_rest(self, joint_reset=False): time.sleep(0.1) # wait for the reset operation self._update_currpos() + reset_pose = self.controller.get_target_pos() + if self.random_reset: # randomize reset position in xy plane # reset_pose = self.resetpos.copy() - reset_pose = self.controller.get_target_pos() reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) reset_pose[:2] += reset_shift + self.curr_reset_pose[:] = reset_pose # euler_random = reset_pose[3:] # euler_random[-1] += np.random.uniform( @@ -319,6 +317,7 @@ def go_to_rest(self, joint_reset=False): # print(reset_shift, reset_pose) return reset_shift else: + self.curr_reset_pose[:] = reset_pose return np.zeros((2,)) def reset(self, joint_reset=False, **kwargs): @@ -361,6 +360,7 @@ def init_cameras(self, name_serial_dict=None): RSCapture(name=cam_name, serial_number=cam_serial, depth=False) ) self.cap[cam_name] = cap + # TODO make simultaneous depth capture def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" @@ -399,7 +399,6 @@ def get_image(self) -> Dict[str, np.ndarray]: def get_depth(self) -> Dict[str, np.ndarray]: depth = {} - display_depth = {} for key, cap in self.cap.items(): try: depth = cap.read() @@ -407,15 +406,12 @@ def get_depth(self) -> Dict[str, np.ndarray]: resized = cv2.resize( cropped_depth, self.observation_space["images"][key].shape[:2][::-1] ) + depth[key] = resized[..., ::-1] except queue.Empty: input(f"{key} camera frozen. Check connect, then press enter to relaunch...") cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_depth() - self.recording_frames.append( - np.concatenate([display_depth[f"{k}_full"] for k in self.cap], axis=0) - ) - self.img_queue.put(display_depth) return depth def close_cameras(self): @@ -466,6 +462,8 @@ def _get_obs(self) -> dict: if self.camera_mode is not None: images = self.get_image() + # TODO remove, temporarly set every image to black + # images = np.ones_like(images) * 255 return copy.deepcopy(dict(images=images, state=state_observation)) else: return copy.deepcopy(dict(state=state_observation)) From 4175d83f5fedf7e614700ed69b1929476018fae7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 13:55:03 +0200 Subject: [PATCH 157/338] new observation space definition (rgb, depth, both) --- examples/robotiq_drq/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index b747455e..b1e39b32 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -33,7 +33,7 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_camera_env", - camera_mode="rgb", + camera_mode="rgb", # TODO save both modalities! max_episode_length=100 ) env = SpacemouseIntervention(env) From 62661a89908da2fe405e7fc44e6e6cfb02e6c7ca Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 13:55:54 +0200 Subject: [PATCH 158/338] run that got drq working (new loggers) --- serl_launcher/serl_launcher/agents/continuous/sac.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index 4f18536f..c777c77a 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -162,13 +162,13 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): chex.assert_shape(target_next_min_q, (batch_size,)) target_q = ( - batch["rewards"] - + self.config["discount"] * batch["masks"] * target_next_min_q + batch["rewards"] + + self.config["discount"] * batch["masks"] * target_next_min_q ) chex.assert_shape(target_q, (batch_size,)) + temperature = self.forward_temperature() if self.config["backup_entropy"]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py - temperature = self.forward_temperature() # target_q = target_q - temperature * next_actions_log_probs # serl original target_q = target_q - self.config["discount"] * batch["masks"] * next_actions_log_probs * temperature # as in jaxrl_m @@ -187,6 +187,8 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): "critic_loss": critic_loss, "predicted_qs": jnp.mean(predicted_qs), "target_qs": jnp.mean(target_qs), + "log_probs": jnp.mean(next_actions_log_probs), + "temp_log_probs": jnp.mean(next_actions_log_probs * temperature * batch["masks"] * self.config["discount"]), } return critic_loss, info From 78feccad9c6b7bcb9f0f4e9d947b0b9b926b280b Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 14:03:08 +0200 Subject: [PATCH 159/338] run that make drq work --- examples/robotiq_drq/run_actor.sh | 12 ++++++------ examples/robotiq_drq/run_learner.sh | 14 +++++++------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index 337fb91a..f8dc178f 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -1,16 +1,16 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ --exp_name=drq_robotiq_policy \ --max_traj_length 100 \ --camera_mode rgb \ - --seed 0 \ - --max_steps 10000 \ - --random_steps 0 \ - --training_starts 0 \ - --utd_ratio 4 \ + --seed 2 \ + --max_steps 20000 \ + --random_steps 100 \ + --training_starts 100 \ + --utd_ratio 8 \ --batch_size 128 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index e209854d..a2ca3754 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -6,14 +6,14 @@ python drq_policy_robotiq.py "$@" \ --exp_name=drq_robotiq_policy \ --camera_mode rgb \ --max_traj_length 100 \ - --seed 0 \ + --seed 2 \ --max_steps 20000 \ - --random_steps 0 \ - --training_starts 0 \ - --utd_ratio 4 \ + --random_steps 100 \ + --training_starts 100 \ + --utd_ratio 8 \ --batch_size 128 \ --eval_period 1000 \ --encoder_type resnet-pretrained \ - --checkpoint_period 10000 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_apr30_newrew.pkl \ - --debug + --checkpoint_period 5000 \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai16_100transition.pkl \ +# --debug From 613c208d081ead3c41d9692bc0983511c1f11529 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 14:14:38 +0200 Subject: [PATCH 160/338] cleanup --- examples/robotiq_drq/drq_policy_robotiq.py | 41 ++++++---------------- 1 file changed, 11 insertions(+), 30 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index a78e40c1..f7befbc0 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -274,7 +274,7 @@ def update_params(params): ############################################################################## -def learner(rng, agent: DrQAgent, replay_buffer, demo_buffer, wandb_logger=None): +def learner(rng, agent: DrQAgent, replay_buffer, wandb_logger=None): """ The learner loop, which runs when "--learner" is set to True. """ @@ -320,16 +320,6 @@ def stats_callback(type: str, payload: dict) -> dict: }, device=sharding.replicate(), ) - # demo_iterator = demo_buffer.get_iterator( - # sample_args={ - # "batch_size": FLAGS.batch_size // 2, - # "pack_obs_and_next_obs": True, - # }, - # device=sharding.replicate(), - # ) - - # if FLAGS.debug: # debug without replay buffer - # replay_iterator = demo_iterator # wait till the replay buffer is filled with enough data timer = Timer() @@ -348,16 +338,12 @@ def stats_callback(type: str, payload: dict) -> dict: for critic_step in range(FLAGS.utd_ratio - 1): with timer.context("sample_replay_buffer"): batch = next(replay_iterator) - # demo_batch = next(demo_iterator) if len(replay_buffer) < 5000 else next(replay_iterator) - # batch = concat_batches(batch, demo_batch, axis=0) with timer.context("train_critics"): agent, critics_info = agent.update_critics(batch,) with timer.context("train"): batch = next(replay_iterator) - # demo_batch = next(demo_iterator) if len(replay_buffer) < 5000 else next(replay_iterator) - # batch = concat_batches(batch, demo_batch, axis=0) agent, update_info = agent.update_high_utd(batch, utd_ratio=1) # publish the updated network @@ -468,32 +454,27 @@ def create_replay_buffer_and_wandb_logger(): if FLAGS.learner: sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() - demo_buffer = MemoryEfficientReplayBufferDataStore( - env.observation_space, - env.action_space, - capacity=2000, - image_keys=image_keys, - ) - import pickle as pkl - # TODO check for depth or rgb + import pickle as pkl with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) for traj in trajs: - # TODO only temporary to test one image only - traj["observations"].pop("shoulder") - traj["next_observations"].pop("shoulder") + # check which observations can be ignored for this run + for obs_name in traj["observations"].keys(): + if obs_name not in env.observation_space.spaces: + traj["observations"].pop(obs_name) + traj["next_observations"].pop(obs_name) + print(f"ignored {obs_name} in demo trajectories") - replay_buffer.insert(traj) # TODO only temporary, to test demos in replaybuffer - print(f"demo buffer size: {len(replay_buffer)}") + replay_buffer.insert(traj) + print(f"replay buffer size: {len(replay_buffer)}") # learner loop print_green("starting learner loop") learner( sampling_rng, agent, - replay_buffer, - demo_buffer=demo_buffer, + replay_buffer=replay_buffer, wandb_logger=wandb_logger, ) From 5f46b810351b2219cef49b1f169c16909b993333 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 17 May 2024 14:20:33 +0200 Subject: [PATCH 161/338] bugfix --- examples/robotiq_drq/drq_policy_robotiq.py | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index f7befbc0..a0893523 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -458,14 +458,18 @@ def create_replay_buffer_and_wandb_logger(): import pickle as pkl with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) - for traj in trajs: - # check which observations can be ignored for this run - for obs_name in traj["observations"].keys(): - if obs_name not in env.observation_space.spaces: - traj["observations"].pop(obs_name) - traj["next_observations"].pop(obs_name) - print(f"ignored {obs_name} in demo trajectories") + # check which observations can be ignored for this run + to_pop = [] + for obs_name in [i for i in trajs[0]["observations"].keys()]: + if obs_name not in env.observation_space.spaces: + to_pop.append(obs_name) + print(f"ignored {to_pop} observation in the demo trajectories") + + for traj in trajs: + for obs_name in to_pop: + traj["observations"].pop(obs_name) + traj["next_observations"].pop(obs_name) replay_buffer.insert(traj) print(f"replay buffer size: {len(replay_buffer)}") From a7004b99c6e04323a9c44939ac793682318eae14 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 21 May 2024 15:16:51 +0200 Subject: [PATCH 162/338] depth images implemented in gym environment --- examples/robotiq_drq/record_demo.py | 2 +- .../robotiq_env/camera/rs_capture.py | 28 +++++-- .../robotiq_env/envs/robotiq_env.py | 79 ++++++++++--------- 3 files changed, 65 insertions(+), 44 deletions(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index b1e39b32..58385e66 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -33,7 +33,7 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_camera_env", - camera_mode="rgb", # TODO save both modalities! + camera_mode="both", max_episode_length=100 ) env = SpacemouseIntervention(env) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index f02f847c..d63cb19f 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -17,14 +17,22 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.pipe = rs.pipeline() self.cfg = rs.config() self.cfg.enable_device(self.serial_number) + self.colorizer = None assert self.rgb or self.depth if self.rgb: self.cfg.enable_stream(rs.stream.color, dim[0], dim[1], rs.format.bgr8, fps) if self.depth: self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) + self.profile = self.pipe.start(self.cfg) + if self.depth: + depth_sensor = self.profile.get_device().first_depth_sensor() + depth_scale = depth_sensor.get_depth_scale() + self.max_clipping_distance = 1. / depth_scale # 1m max clipping distance + self.min_clipping_distance = 0.0 / depth_scale # might mess things up + # for some weird reason, these values have to be set in order for the image to appear with good lightning for sensor in self.profile.get_device().query_sensors(): sensor.set_option(rs.option.enable_auto_exposure, False) @@ -39,17 +47,27 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= def read(self): frames = self.pipe.wait_for_frames() aligned_frames = self.align.process(frames) + image, depth = None, None + if self.rgb: color_frame = aligned_frames.get_color_frame() + + if color_frame.is_video_frame(): + image = np.asarray(color_frame.get_data()) + if self.depth: depth_frame = aligned_frames.get_depth_frame() - image, depth = None, None - if self.rgb and color_frame.is_video_frame(): - image = np.asarray(color_frame.get_data()) + if depth_frame.is_depth_frame(): + depth = np.asanyarray(depth_frame.get_data()) + # clip max + depth = np.where((depth > self.max_clipping_distance) | (depth < self.min_clipping_distance), 0., self.max_clipping_distance - depth) + # clip min + # scale = self.max_clipping_distance / (self.max_clipping_distance - self.min_clipping_distance) + # depth *= scale - if self.depth and depth_frame.is_depth_frame(): - depth = np.expand_dims(np.asarray(depth_frame.get_data()), axis=2) + depth = (depth * (256. / self.max_clipping_distance)).astype(np.uint8) + depth = depth[..., None] if isinstance(image, np.ndarray) and isinstance(depth, np.ndarray): return True, np.concatenate((image, depth), axis=-1) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index b3a8fc9d..91b55eaf 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -136,17 +136,18 @@ def __init__( # 0, 255, shape=(128, 128, 3), dtype=np.uint8 # ) image_space_definition["wrist"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 + 0, 255, shape=(128, 128, 3), dtype=np.uint8 ) - elif camera_mode in ["depth", "both"]: - image_space_definition["shoulder_depth"] = gym.spaces.Box( - 0, 65535, shape=(128, 128, 1), dtype=np.uint16 - ) + if camera_mode in ["depth", "both"]: + # image_space_definition["shoulder_depth"] = gym.spaces.Box( + # 0, 255, shape=(128, 128, 1), dtype=np.uint8 + # ) image_space_definition["wrist_depth"] = gym.spaces.Box( - 0, 65535, shape=(128, 128, 1), dtype=np.uint16 + 0, 255, shape=(128, 128, 1), dtype=np.uint8 ) - elif camera_mode is not None: + + if camera_mode is not None and camera_mode not in ["rgb", "both", "depth"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") image_space = gym.spaces.Dict( @@ -261,10 +262,11 @@ def step(self, action: np.ndarray) -> tuple: self._update_currpos() obs = self._get_obs() + reward = self.compute_reward(obs, action) truncated = self._is_truncated() - reward = reward if not truncated else reward - 100. # truncation penalty + reward = reward if not truncated else reward - 100. # truncation penalty done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated return obs, reward, done, truncated, {} @@ -356,11 +358,12 @@ def init_cameras(self, name_serial_dict=None): self.cap = OrderedDict() for cam_name, cam_serial in name_serial_dict.items(): print(f"cam serial: {cam_serial}") + rgb = self.camera_mode in ["rgb", "both"] + depth = self.camera_mode in ["depth", "both"] cap = VideoCapture( - RSCapture(name=cam_name, serial_number=cam_serial, depth=False) + RSCapture(name=cam_name, serial_number=cam_serial, rgb=rgb, depth=depth) ) self.cap[cam_name] = cap - # TODO make simultaneous depth capture def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" @@ -377,43 +380,43 @@ def get_image(self) -> Dict[str, np.ndarray]: display_images = {} for key, cap in self.cap.items(): try: - rgb = cap.read() - cropped_rgb = self.crop_image(key, rgb) - resized = cv2.resize( - cropped_rgb, self.observation_space["images"][key].shape[:2][::-1] - ) - images[key] = resized[..., ::-1] - display_images[key] = resized - display_images[key + "_full"] = cropped_rgb + image = cap.read() + if self.camera_mode in ["rgb", "both"]: + rgb = image[..., :3].astype(np.uint8) + cropped_rgb = self.crop_image(key, rgb) + resized = cv2.resize( + cropped_rgb, self.observation_space["images"][key].shape[:2][::-1] + ) + images[key] = resized[..., ::-1] + display_images[key] = resized + display_images[key + "_full"] = cropped_rgb + + if self.camera_mode in ["depth", "both"]: + depth_key = key + "_depth" + depth = image[..., -1:] + cropped_depth = self.crop_image(key, depth) + + resized = cv2.resize( + cropped_depth, self.observation_space["images"][depth_key].shape[:2] + )[..., None] + + images[depth_key] = resized + display_images[depth_key] = cv2.applyColorMap(resized, cv2.COLORMAP_JET) + display_images[depth_key + "_full"] = cv2.applyColorMap(cropped_depth, cv2.COLORMAP_JET) + except queue.Empty: input(f"{key} camera frozen. Check connect, then press enter to relaunch...") cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() + self.recording_frames.append( - np.concatenate([display_images[f"{k}_full"] for k in self.cap], axis=0) + np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) ) self.img_queue.put(display_images) return images - def get_depth(self) -> Dict[str, np.ndarray]: - depth = {} - for key, cap in self.cap.items(): - try: - depth = cap.read() - cropped_depth = self.crop_image(key, depth) - resized = cv2.resize( - cropped_depth, self.observation_space["images"][key].shape[:2][::-1] - ) - depth[key] = resized[..., ::-1] - except queue.Empty: - input(f"{key} camera frozen. Check connect, then press enter to relaunch...") - cap.close() - self.init_cameras(self.config.REALSENSE_CAMERAS) - return self.get_depth() - return depth - def close_cameras(self): """Close both wrist cameras.""" try: @@ -462,8 +465,8 @@ def _get_obs(self) -> dict: if self.camera_mode is not None: images = self.get_image() - # TODO remove, temporarly set every image to black - # images = np.ones_like(images) * 255 + # TODO remove, temporarily set every image to black + # images = np.ones_like(image) * 255 return copy.deepcopy(dict(images=images, state=state_observation)) else: return copy.deepcopy(dict(state=state_observation)) From 958602263b43928b4897913c868169cbcdd5a869 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 21 May 2024 18:26:43 +0200 Subject: [PATCH 163/338] bugfixes --- examples/robotiq_drq/encoder_feature_plot.py | 9 +++++++-- .../serl_launcher/agents/continuous/drq.py | 16 +++++++++------- serl_launcher/serl_launcher/vision/resnet_v1.py | 2 +- .../serl_launcher/wrappers/serl_obs_wrappers.py | 4 ++-- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 11 +++++------ 5 files changed, 24 insertions(+), 18 deletions(-) diff --git a/examples/robotiq_drq/encoder_feature_plot.py b/examples/robotiq_drq/encoder_feature_plot.py index 1f4357f3..9c352cd3 100644 --- a/examples/robotiq_drq/encoder_feature_plot.py +++ b/examples/robotiq_drq/encoder_feature_plot.py @@ -162,7 +162,7 @@ def plot(demo_buffer): import sys sys.path.append("/home/nico/real-world-rl/spacemouse_tests") from spacemouse_tests.jax_feature_plotter import generate_and_save_images - feature_file = "/home/nico/real-world-rl/serl/examples/robotiq_drq/features_meanstd.npy" + feature_file = "/spacemouse_tests/feature_plots_meanstd/features_meanstd.npy" with open(feature_file, 'rb') as f: features = np.load(f) @@ -173,13 +173,18 @@ def plot(demo_buffer): # get images here shoulder, wrist = [], [] + s_next, w_next = [], [] for i in range(len(demo_buffer) // 10): index = np.arange(10) + i * 10 obs = demo_buffer.sample(batch_size=10, indx=index) - wrist.append(obs["observations"]["wrist"]) shoulder.append(obs["observations"]["shoulder"]) + w_next.append(obs["next_observations"]["wrist"]) + s_next.append(obs["next_observations"]["shoulder"]) + + w_next = np.array(w_next).reshape((800, 128, 128, 3)) + s_next = np.array(s_next).reshape((800, 128, 128, 3)) wrist = np.array(wrist).reshape((800, 128, 128, 3)) shoulder = np.array(shoulder).reshape((800, 128, 128, 3)) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 3a69db31..900ff3d3 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -11,7 +11,7 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.common import JaxRLTrainState, ModuleDict, nonpytree_field from serl_launcher.common.encoding import EncodingWrapper -from serl_launcher.common.optimizers import make_optimizer, make_adam_optimizer +from serl_launcher.common.optimizers import make_optimizer from serl_launcher.common.typing import Batch, Data, Params, PRNGKey from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize from serl_launcher.networks.lagrange import GeqLagrangeMultiplier @@ -133,7 +133,7 @@ def create_drq( **kwargs, ): """ - Create a new pixel-based agent, with no encoders. + Create a new pixel-based agent. """ policy_network_kwargs["activate_final"] = True @@ -178,7 +178,7 @@ def create_drq( name="pretrained_encoder", ) - use_depth_only = list(observations.values())[0].shape[-3:] == (128, 128, 1) # only one channel means depth + use_depth_only = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) print(f"use depth only: {use_depth_only}") encoders = { @@ -192,6 +192,8 @@ def create_drq( ) for image_key in image_keys } + elif encoder_type == "None": + encoders = None else: raise NotImplementedError(f"Unknown encoder type: {encoder_type}") @@ -205,8 +207,8 @@ def create_drq( # print(f"encoder def: {encoder_def}") encoders = { - "critic": encoder_def, - "actor": encoder_def, + "critic": encoder_def, + "actor": encoder_def, } # Define networks @@ -284,7 +286,7 @@ def update_high_utd( before updating the network. """ new_agent = self - if self.config["image_keys"][0] not in batch["next_observations"]: + if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: batch = _unpack(batch) rng = new_agent.state.rng @@ -315,7 +317,7 @@ def update_critics( pmap_axis: Optional[str] = None, ) -> Tuple["DrQAgent", dict]: new_agent = self - if self.config["image_keys"][0] not in batch["next_observations"]: + if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: batch = _unpack(batch) # TODO implement K=2 and M=2 diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index c519ddde..b70dffff 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -341,7 +341,7 @@ def __call__( # use DDD instead of RGB and pass it through resnet if self.use_depth_only: - assert x.shape == (128, 128, 1) + assert x.shape[-3:] == (128, 128, 1) # check shape x = jnp.repeat(x, 3, axis=-1) if encode: diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 62814a6a..676fba4b 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -15,14 +15,14 @@ def __init__(self, env): self.observation_space = gym.spaces.Dict( { "state": flatten_space(self.env.observation_space["state"]), - **(self.env.observation_space["images"]), + **(self.env.observation_space["images"] if "images" in self.env.observation_space else {}), } ) def observation(self, obs): obs = { "state": flatten(self.env.observation_space["state"], obs["state"]), - **(obs["images"]), + **(obs["images"] if "images" in self.env.observation_space else {}), } return obs diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 91b55eaf..190f58cf 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -106,6 +106,7 @@ def __init__( self.random_rz_range = config.RANDOM_RZ_RANGE self.hz = hz + camera_mode = None if camera_mode.lower() == "none" else camera_mode if camera_mode is not None and save_video: print("Saving videos!") self.save_video = save_video @@ -150,10 +151,6 @@ def __init__( if camera_mode is not None and camera_mode not in ["rgb", "both", "depth"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") - image_space = gym.spaces.Dict( - image_space_definition - ) - state_space = gym.spaces.Dict( { "tcp_pose": gym.spaces.Box( @@ -168,7 +165,9 @@ def __init__( obs_space_definition = {"state": state_space} if self.camera_mode in ["rgb", "both", "depth"]: - obs_space_definition["images"] = image_space + obs_space_definition["images"] = gym.spaces.Dict( + image_space_definition + ) self.observation_space = gym.spaces.Dict(obs_space_definition) @@ -188,7 +187,7 @@ def __init__( config=config, verbose=False, plot=False, - old_obs=camera_mode is None + # old_obs=camera_mode is None # do not use anymore ) self.controller.start() # start Thread From c881102b9327266d1a424ade3da7f3e7f9218ede Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 21 May 2024 18:30:03 +0200 Subject: [PATCH 164/338] bugfixes --- serl_launcher/serl_launcher/utils/launcher.py | 76 +++++-------------- 1 file changed, 19 insertions(+), 57 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 0144b17d..f873f249 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -21,11 +21,12 @@ ReplayBufferDataStore, ) + ############################################################################## def make_bc_agent( - seed, sample_obs, sample_action, image_keys=("image",), encoder_type="small" + seed, sample_obs, sample_action, image_keys=("image",), encoder_type="small" ): return BCAgent.create( jax.random.PRNGKey(seed), @@ -102,7 +103,7 @@ def make_sac_agent(seed, sample_obs, sample_action): def make_drq_agent( - seed, sample_obs, sample_action, image_keys=("image",), encoder_type="small" + seed, sample_obs, sample_action, image_keys=("image",), encoder_type="small" ): agent = DrQAgent.create_drq( jax.random.PRNGKey(seed), @@ -129,7 +130,7 @@ def make_drq_agent( }, temperature_init=1e-2, discount=0.99, # 0.99 - backup_entropy=True, # default: False + backup_entropy=True, # default: False critic_ensemble_size=10, critic_subsample_size=2, actor_optimizer_kwargs={ @@ -142,53 +143,14 @@ def make_drq_agent( return agent -def make_drq_agent_no_images( - seed, sample_obs, sample_action, image_keys=(), encoder_type="small" -): - agent = DrQAgent.create_drq_no_images( - jax.random.PRNGKey(seed), +def make_vice_agent( + seed, sample_obs, sample_action, - image_keys=image_keys, - policy_kwargs={ - "tanh_squash_distribution": True, - "std_parameterization": "exp", - "std_min": 1e-5, - "std_max": 5, - }, - critic_network_kwargs={ - "activations": nn.tanh, - "use_layer_norm": True, - "hidden_dims": [256, 256], - }, - policy_network_kwargs={ - "activations": nn.tanh, - "use_layer_norm": True, - "hidden_dims": [256, 256], - }, - temperature_init=1e-2, - discount=0.99, # 0.99 - backup_entropy=True, # default: False - critic_ensemble_size=10, - critic_subsample_size=2, - actor_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 - }, - critic_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 - }, - ) - return agent - - -def make_vice_agent( - seed, - sample_obs, - sample_action, - sample_vice_obs, - image_keys=("image",), - vice_image_keys=("image",), - encoder_type="small", + sample_vice_obs, + image_keys=("image",), + vice_image_keys=("image",), + encoder_type="small", ): agent = VICEAgent.create_vice( jax.random.PRNGKey(seed), @@ -241,9 +203,9 @@ def make_trainer_config(port_number: int = 5488, broadcast_port: int = 5489): def make_wandb_logger( - project: str = "agentlace", - description: str = "serl_launcher", - debug: bool = False, + project: str = "agentlace", + description: str = "serl_launcher", + debug: bool = False, ): wandb_config = WandBLogger.get_default_config() wandb_config.update( @@ -262,12 +224,12 @@ def make_wandb_logger( def make_replay_buffer( - env, - capacity: int = 1000000, - rlds_logger_path: Optional[str] = None, - type: str = "replay_buffer", - image_keys: list = [], # used only type=="memory_efficient_replay_buffer" - preload_rlds_path: Optional[str] = None, + env, + capacity: int = 1000000, + rlds_logger_path: Optional[str] = None, + type: str = "replay_buffer", + image_keys: list = [], # used only type=="memory_efficient_replay_buffer" + preload_rlds_path: Optional[str] = None, ): """ This is the high-level helper function to From 0a68a2e68ce47a178835be4f35e6c7277afce783 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 21 May 2024 18:41:17 +0200 Subject: [PATCH 165/338] obs space bugfix --- serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 676fba4b..a7dee819 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -15,14 +15,14 @@ def __init__(self, env): self.observation_space = gym.spaces.Dict( { "state": flatten_space(self.env.observation_space["state"]), - **(self.env.observation_space["images"] if "images" in self.env.observation_space else {}), + **(self.env.observation_space["images"] if "images" in self.env.observation_space.spaces else {}), } ) def observation(self, obs): obs = { "state": flatten(self.env.observation_space["state"], obs["state"]), - **(obs["images"] if "images" in self.env.observation_space else {}), + **(obs["images"] if "images" in obs else {}), } return obs From b2678848d451b00feba47846d96eacc6b06a8526 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 22 May 2024 16:01:42 +0200 Subject: [PATCH 166/338] added function to print params & small changes --- examples/robotiq_drq/drq_policy_robotiq.py | 23 ++++++++++----- .../serl_launcher/utils/train_utils.py | 29 +++++++++++++++++-- 2 files changed, 43 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index a0893523..b9f2ad0b 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -19,7 +19,7 @@ from serl_launcher.common.evaluation import evaluate from serl_launcher.utils.timer_utils import Timer from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.utils.train_utils import concat_batches +from serl_launcher.utils.train_utils import concat_batches, print_agent_params from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore @@ -420,6 +420,7 @@ def main(_): env = RecordEpisodeStatistics(env) image_keys = [key for key in env.observation_space.keys() if key != "state"] + print(f"image keys: {image_keys}") rng, sampling_rng = jax.random.split(rng) agent: DrQAgent = make_drq_agent( @@ -436,6 +437,9 @@ def main(_): jax.tree_map(jnp.array, agent), sharding.replicate() ) + # print useful info + print_agent_params(agent, image_keys) + def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( env.observation_space, @@ -475,12 +479,17 @@ def create_replay_buffer_and_wandb_logger(): # learner loop print_green("starting learner loop") - learner( - sampling_rng, - agent, - replay_buffer=replay_buffer, - wandb_logger=wandb_logger, - ) + try: + learner( + sampling_rng, + agent, + replay_buffer=replay_buffer, + wandb_logger=wandb_logger, + ) + except KeyboardInterrupt: + print_green("leraner loop interrupted") + finally: + env.close() elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 31037317..c33db274 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -32,7 +32,7 @@ def concat_batches(offline_batch, online_batch, axis=1): def load_recorded_video( - video_path: str, + video_path: str, ): with tf.io.gfile.GFile(video_path, "rb") as f: video = np.array(imageio.mimread(f, "MP4")).transpose((0, 3, 1, 2)) @@ -110,7 +110,7 @@ def load_resnet10_params(agent, image_keys=("image",), public=True): param_count = sum(x.size for x in jax.tree_leaves(encoder_params)) print( - f"Loaded {param_count/1e6}M parameters from ResNet-10 pretrained on ImageNet-1K" + f"Loaded {param_count / 1e6}M parameters from ResNet-10 pretrained on ImageNet-1K" ) new_params = agent.state.params @@ -128,3 +128,28 @@ def load_resnet10_params(agent, image_keys=("image",), public=True): agent = agent.replace(state=agent.state.replace(params=new_params)) return agent + + +def print_agent_params(agent, image_keys=("image",)): + """ + helper function to print the parameter count of the actor and critic networks + """ + def get_size(params): + return sum(x.size for x in jax.tree.leaves(params)) + + total_param_count = get_size(agent.state.params) + actor, critic = agent.state.params["modules_actor"], agent.state.params["modules_critic"] + + # calculate encoder params + pretrained_encoder_count = get_size(actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"]) + encoder_count = get_size(actor["encoder"]) + + actor_count = get_size(actor) + critic_count = get_size(critic) + + print(f"\ntotal params: {total_param_count / 1e6:.3f}M") + print( + f"encoder params: {(encoder_count - pretrained_encoder_count) / 1e6:.3f}M pretrained encoder params: {pretrained_encoder_count / 1e6:.3f}M") + print(f"actor params: {(actor_count - encoder_count)/ 1e6:.3f}M critic_params: {critic_count / 1e6:.3f}M") + print(f"total parameters to train: {(total_param_count - pretrained_encoder_count) / 1e6:.3f}M\n") + From 6af4d135b984ad1b4da749178256aabfccb207ad Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 22 May 2024 16:02:11 +0200 Subject: [PATCH 167/338] added return for encoder == None --- serl_launcher/serl_launcher/common/encoding.py | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index 0c006885..b6bbaad7 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -32,6 +32,22 @@ def __call__( is_encoded=False, ) -> jnp.ndarray: # encode images with encoder + if self.encoder is None: + # project state to embeddings as well + state = observations["state"] + if self.enable_stacking: + # Combine stacking and channels into a single dimension + if len(state.shape) == 2: + state = rearrange(state, "T C -> (T C)") + if len(state.shape) == 3: + state = rearrange(state, "B T C -> B (T C)") + state = nn.Dense( + self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() + )(state) + state = nn.LayerNorm()(state) + state = nn.tanh(state) + return state + encoded = [] for image_key in self.image_keys: image = observations[image_key] From 6c0f712ae9dd8ae4b8d621eaef7634403d69a295 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 22 May 2024 16:02:31 +0200 Subject: [PATCH 168/338] shape check in ResNet --- serl_launcher/serl_launcher/vision/resnet_v1.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index b70dffff..f3e3048f 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -217,6 +217,8 @@ def __call__( # put inputs in [-1, 1] # x = observations.astype(jnp.float32) / 127.5 - 1.0 + assert observations.shape[-3:] == (128, 128, 3) # check for shape + # imagenet mean and std mean = jnp.array([0.485, 0.456, 0.406]) std = jnp.array([0.229, 0.224, 0.225]) From 87db0f6a25cbf54b274c095d66051d108e49fe1d Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:13:44 +0200 Subject: [PATCH 169/338] added some model examination tools --- .../serl_launcher/utils/train_utils.py | 27 ++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index c33db274..d681e062 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -134,6 +134,7 @@ def print_agent_params(agent, image_keys=("image",)): """ helper function to print the parameter count of the actor and critic networks """ + def get_size(params): return sum(x.size for x in jax.tree.leaves(params)) @@ -150,6 +151,30 @@ def get_size(params): print(f"\ntotal params: {total_param_count / 1e6:.3f}M") print( f"encoder params: {(encoder_count - pretrained_encoder_count) / 1e6:.3f}M pretrained encoder params: {pretrained_encoder_count / 1e6:.3f}M") - print(f"actor params: {(actor_count - encoder_count)/ 1e6:.3f}M critic_params: {critic_count / 1e6:.3f}M") + print(f"actor params: {(actor_count - encoder_count) / 1e6:.3f}M critic_params: {critic_count / 1e6:.3f}M") print(f"total parameters to train: {(total_param_count - pretrained_encoder_count) / 1e6:.3f}M\n") + +def parameter_overview(agent): + from clu import parameter_overview + print(parameter_overview.get_parameter_overview(agent.state.params)) + + +def plot_feature_kernel_histogram(agent): + import matplotlib.pyplot as plt + + feature_kernel = agent.state.params["modules_actor"]["network"]["Dense_0"]["kernel"] + feature_bias = agent.state.params["modules_actor"]["network"]["Dense_0"]["bias"] + print(f"kernel has shape: {feature_kernel.shape}") + + plots = feature_kernel.shape[0] // 256 + 1 + fig, axes = plt.subplots(nrows=plots, ncols=1, sharex=True, sharey=True, figsize=(5, 3*plots)) + + feature_kernel = feature_kernel.mean(axis=1) + + for p in range(plots): + legend = f"image {p}" if p < plots-1 else "observations" + print(f"{legend} mean and std: ", [feature_kernel[p*256:(p+1)*256].mean(), feature_kernel[p*256:(p+1)*256].std()]) + axes[p].hist(feature_kernel[p*256:(p+1)*256], bins=50) + axes[p].set_title(legend) + plt.show() From aa7ff862d03b6255c036cf9a93b26c8f8915f035 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:14:30 +0200 Subject: [PATCH 170/338] cleanup --- examples/robotiq_sac/sac_policy_robotiq.py | 2 +- .../data/memory_efficient_replay_buffer.py | 14 ++++++++++++++ .../serl_launcher/networks/actor_critic_nets.py | 2 -- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 3 +-- 4 files changed, 16 insertions(+), 5 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index e4bd4dbe..16ed865e 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -313,7 +313,7 @@ def main(_): camera_mode=None, ) if FLAGS.actor: - env = SpacemouseIntervention(env) # TODO really needed? + env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = SerlObsWrapperNoImages(env) diff --git a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py index 3d71164c..64e2088e 100644 --- a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py +++ b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py @@ -123,6 +123,9 @@ def sample( else: # raise NotImplementedError() # print(f"indx is {indx}") + for i in range(batch_size): + if not self._is_correct_index[indx[i]]: + print(f"index {indx[i]} is not correct!") assert type(indx) == np.ndarray if keys is None: @@ -164,3 +167,14 @@ def sample( batch["next_observations"][pixel_key] = obs_pixels[:, 1:, ...] return frozen_dict.freeze(batch) + + def save_to_file(self, path): + import pickle as pkl + obj = {} + for attr, value in self.__dict__.items(): + print(attr, type(value)) + if "lock" not in attr: + obj[attr] = value + + with open(path, "wb") as f: + pkl.dump(obj, f) \ No newline at end of file diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index 0c48307a..276d070d 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -181,8 +181,6 @@ class Policy(nn.Module): def __call__( self, observations: jnp.ndarray, temperature: float = 1.0, train: bool = False ) -> distrax.Distribution: - # info_dict = {key:value.shape for key, value in observations.items()} - # print(f"policy observations shape: {info_dict}") # TODO remove if self.encoder is None: obs_enc = observations else: diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 190f58cf..46404d95 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -464,8 +464,7 @@ def _get_obs(self) -> dict: if self.camera_mode is not None: images = self.get_image() - # TODO remove, temporarily set every image to black - # images = np.ones_like(image) * 255 + # images = np.ones_like(images) * 255 return copy.deepcopy(dict(images=images, state=state_observation)) else: return copy.deepcopy(dict(state=state_observation)) From f68fc2e1b034633154f8a86483f518e348072216 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:15:25 +0200 Subject: [PATCH 171/338] added model examination tools and cleanup --- examples/robotiq_drq/drq_policy_robotiq.py | 41 +++++++++++----------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index b9f2ad0b..4c88ab3b 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -19,7 +19,11 @@ from serl_launcher.common.evaluation import evaluate from serl_launcher.utils.timer_utils import Timer from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.utils.train_utils import concat_batches, print_agent_params +from serl_launcher.utils.train_utils import ( + print_agent_params, + parameter_overview, + plot_feature_kernel_histogram +) from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore @@ -54,7 +58,8 @@ flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 5000, "Replay buffer capacity.") # quite low to forget old ones +flags.DEFINE_integer("replay_buffer_capacity", 10000, + "Replay buffer capacity.") # quite low to forget demo trajectories flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") @@ -134,6 +139,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): ) agent = agent.replace(state=ckpt) + parameter_overview(agent) + plot_feature_kernel_histogram(agent) + for episode in range(FLAGS.eval_n_trajs): obs, _ = env.reset() done = False @@ -149,13 +157,12 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): obs = next_obs if done: - if reward: + if reward > 50.: dt = time.time() - start_time time_list.append(dt) - print(dt) + print(f"time: {dt}") - success_counter += reward - print(reward) + success_counter += (reward > 50.) print(f"{success_counter}/{episode + 1}") # if pause event is requested, pause the actor @@ -170,7 +177,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): print("Stopping actor eval") break - print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") + print(f"success rate: {success_counter / FLAGS.eval_n_trajs if FLAGS.eval_n_trajs else 0.}") print(f"average time: {np.mean(time_list)}") return # after done eval, return and exit @@ -324,14 +331,6 @@ def stats_callback(type: str, payload: dict) -> dict: # wait till the replay buffer is filled with enough data timer = Timer() for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): - # Train the networks - """with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) if len(replay_buffer) > 0 else None - demo_batch = next(demo_iterator) - batch = concat_batches(batch, demo_batch, axis=0) if len(replay_buffer) > 0 else demo_batch - - with timer.context("train"): - agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio)""" # run n-1 critic updates and 1 critic + actor update. # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU @@ -340,7 +339,7 @@ def stats_callback(type: str, payload: dict) -> dict: batch = next(replay_iterator) with timer.context("train_critics"): - agent, critics_info = agent.update_critics(batch,) + agent, critics_info = agent.update_critics(batch, ) with timer.context("train"): batch = next(replay_iterator) @@ -364,7 +363,6 @@ def stats_callback(type: str, payload: dict) -> dict: FLAGS.checkpoint_path, agent.state, step=update_steps, keep=100 ) - if PAUSE_EVENT_FLAG.is_set(): print("Learner loop interrupted") response = input( @@ -388,9 +386,7 @@ def stats_callback(type: str, payload: dict) -> dict: print("Stopping learner client") break - # Wrap up the learner loop server.stop() - print("Learner loop finished") ############################################################################## @@ -398,7 +394,8 @@ def stats_callback(type: str, payload: dict) -> dict: def main(_): assert FLAGS.batch_size % num_devices == 0 - FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") + if FLAGS.checkpoint_path.split('/')[-1] == "checkpoints": + FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") # seed rng = jax.random.PRNGKey(FLAGS.seed) @@ -414,7 +411,7 @@ def main(_): # env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2EulerWrapper(env) - env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) + env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -489,7 +486,9 @@ def create_replay_buffer_and_wandb_logger(): except KeyboardInterrupt: print_green("leraner loop interrupted") finally: + # Wrap up the learner loop env.close() + print("Learner loop finished") elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) From 4a8bfcdb93f9b7b446b65476d9f400089d5acbbe Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:15:56 +0200 Subject: [PATCH 172/338] new reward computation (orientation & pose cost) --- .../envs/camera_env/robotiq_camera_env.py | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 819ce56e..9ea91433 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -4,11 +4,6 @@ from robotiq_env.envs.camera_env.config import RobotiqCameraConfig -# used for float value comparisons (pressure of vacuum-gripper) -def is_close(value, target): - return abs(value - target) < 1e-3 - - class RobotiqCameraEnv(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCameraConfig) @@ -49,17 +44,22 @@ def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 - downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 5., 0.) + downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.5 * float(obs["state"]["gripper_state"][1] > 0.9) + suction_cost = 0.3 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99)) + + orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 + orientation_cost *= 25. - # TODO make cost for being at orientation limit - # TODO make cost for being too far away from starting position + max_pose_diff = 0.05 # set to 5cm + pos_diff = obs["state"]["tcp_pose"][:2] - self.curr_reset_pose[:2] + position_cost = 10. * np.sum( + np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0)) if self.reached_goal_state(obs): - # TODO make offset end position cost with self.curr_reset_pose - return 100. - action_cost - step_cost - downward_force_cost + return 100. - action_cost - orientation_cost - position_cost else: - return 0. + suction_reward - action_cost - step_cost - downward_force_cost + return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From c83a4974a96c2c072418c445008efe74f00e148f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:16:15 +0200 Subject: [PATCH 173/338] added evaluation script --- examples/robotiq_drq/run_evaluation.sh | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 examples/robotiq_drq/run_evaluation.sh diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/robotiq_drq/run_evaluation.sh new file mode 100644 index 00000000..2af764f6 --- /dev/null +++ b/examples/robotiq_drq/run_evaluation.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name=drq_robotiq_policy_evaluation \ + --max_traj_length 100 \ + --camera_mode depth \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0523 rgb stable pooling=avg"\ + --eval_checkpoint_step 20000 \ + --encoder_type resnet-pretrained \ + --eval_n_trajs 10 \ + --debug \ No newline at end of file From e4eae40851687baff78a7b32fae003e260ac7582 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:20:07 +0200 Subject: [PATCH 174/338] bugfix 2 --- serl_robot_infra/robot_controllers/robotiq_controller.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 124408e5..1dad4938 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -255,7 +255,8 @@ def plot(self): async def send_gripper_command(self): timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout[ "timeout"] - if self.target_grip[0] > 0.5 and timeout_exceeded: + # target grip above threshold and timeout exceeded and not gripping something already + if self.target_grip[0] > 0.5 and timeout_exceeded and self.gripper_state[1] < 0.5: await self.robotiq_gripper.automatic_grip() self.target_grip[0] = 0.0 self.gripper_timeout["last_grip"] = time.monotonic() From defa69064e46915cc3e90c1dd97b72c279bfd893 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:25:10 +0200 Subject: [PATCH 175/338] examination if trajs==0 --- examples/robotiq_drq/drq_policy_robotiq.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 4c88ab3b..e8f2665e 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -139,8 +139,10 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): ) agent = agent.replace(state=ckpt) - parameter_overview(agent) - plot_feature_kernel_histogram(agent) + # examine model parameters if trajs==0 + if FLAGS.eval_n_trajs == 0: + parameter_overview(agent) + plot_feature_kernel_histogram(agent) for episode in range(FLAGS.eval_n_trajs): obs, _ = env.reset() From 1abfd96db6afdb859e6361d9d06fcbf804ba0165 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 23 May 2024 16:36:40 +0200 Subject: [PATCH 176/338] do not log anymore --- serl_launcher/serl_launcher/agents/continuous/sac.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index c777c77a..6160aaba 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -187,8 +187,8 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): "critic_loss": critic_loss, "predicted_qs": jnp.mean(predicted_qs), "target_qs": jnp.mean(target_qs), - "log_probs": jnp.mean(next_actions_log_probs), - "temp_log_probs": jnp.mean(next_actions_log_probs * temperature * batch["masks"] * self.config["discount"]), + # "log_probs": jnp.mean(next_actions_log_probs), + # "temp_log_probs": jnp.mean(next_actions_log_probs * temperature * batch["masks"] * self.config["discount"]), } return critic_loss, info From 3d8efe63c79b22e9ad13cf867e760df67d69b354 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 31 May 2024 17:47:23 +0200 Subject: [PATCH 177/338] added env with 5 different boxes --- .../robotiq_env/envs/camera_env/config.py | 38 +++++++++++++++++-- .../envs/camera_env/robotiq_camera_env.py | 10 ++--- 2 files changed, 39 insertions(+), 9 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index d62f985e..a65e8c05 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -5,10 +5,8 @@ class RobotiqCameraConfig(DefaultEnvConfig): RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) RANDOM_RESET = False - RANDOM_XY_RANGE = (0.05,) - RANDOM_RZ_RANGE = (0.0,) - # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ - # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) + RANDOM_XY_RANGE = (0.00,) + RANDOM_RZ_RANGE = (0.78,) ABS_POSE_LIMIT_HIGH = np.array([0.2, -0.4, 0.22, 3.2, 0.18, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.7, - 0.006, 2.8, -0.18, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) @@ -26,3 +24,35 @@ class RobotiqCameraConfig(DefaultEnvConfig): "wrist": "218622279756", # "shoulder": "218622277164" } + + +class RobotiqCameraConfigBox5(DefaultEnvConfig): + RESET_Q = np.array([ + [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], + [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], + [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], + [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], + [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] + ]) + RANDOM_RESET = False + RANDOM_XY_RANGE = (0.00,) + RANDOM_RZ_RANGE = (0.0,) + ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.18, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 2.8, -0.18, -3.2]) + ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + + ROBOT_IP: str = "172.22.22.2" + CONTROLLER_HZ = 100 + GRIPPER_TIMEOUT = 2000 # in milliseconds + ERROR_DELTA: float = 0.05 + FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_TASK_FRAME = np.zeros(6) + FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) + + REALSENSE_CAMERAS = { + "wrist": "218622279756", + # "shoulder": "218622277164" + } + + diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 9ea91433..28f4f9ef 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -1,18 +1,18 @@ import numpy as np from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.camera_env.config import RobotiqCameraConfig +from robotiq_env.envs.camera_env.config import RobotiqCameraConfig, RobotiqCameraConfigBox5 class RobotiqCameraEnv(RobotiqEnv): def __init__(self, **kwargs): - super().__init__(**kwargs, config=RobotiqCameraConfig) + super().__init__(**kwargs, config=RobotiqCameraConfigBox5) self.plot_costs_yes = False if self.plot_costs_yes: self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], downward_force_cost=[]) - """def compute_reward(self, obs, action) -> float: + """def compute_reward(self, obs, action) -> float: old reward computation # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 @@ -46,7 +46,7 @@ def compute_reward(self, obs, action) -> float: downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.5 * float(obs["state"]["gripper_state"][1] > 0.9) - suction_cost = 0.3 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99)) + suction_cost = 0.5 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99)) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 orientation_cost *= 25. @@ -59,7 +59,7 @@ def compute_reward(self, obs, action) -> float: if self.reached_goal_state(obs): return 100. - action_cost - orientation_cost - position_cost else: - return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost + return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - suction_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From 10fa2946dc5a33d626525e637cf969506c809b00 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 31 May 2024 17:47:35 +0200 Subject: [PATCH 178/338] depth to pointcloud calculation --- serl_robot_infra/robotiq_env/camera/utils.py | 41 ++++++++++++++++++++ 1 file changed, 41 insertions(+) create mode 100644 serl_robot_infra/robotiq_env/camera/utils.py diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py new file mode 100644 index 00000000..0d7ea7be --- /dev/null +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -0,0 +1,41 @@ +import numpy as np +import pyrealsense2 as rs + + +def convert_depth_frame_to_pointcloud(depth_image: np.ndarray, camera_intrinsics: rs.intrinsics): + """ + Convert the depthmap to a 3D point cloud + + Parameters: + ----------- + depth_frame (np.ndarray): the depth_frame containing the depth map + camera_intrinsics : The intrinsic values of the imager in whose coordinate system the depth_frame is computed + + Return: + ---------- + x : array + The x values of the pointcloud in meters + y : array + The y values of the pointcloud in meters + z : array + The z values of the pointcloud in meters + """ + + assert len(depth_image.shape) == 2 or depth_image.shape[2] == 1 + [height, width] = depth_image.shape[:2] + + nx = np.linspace(0, width - 1, width) + ny = np.linspace(0, height - 1, height) + u, v = np.meshgrid(nx, ny) + x = (u.flatten() - camera_intrinsics.ppx) / camera_intrinsics.fx + y = (v.flatten() - camera_intrinsics.ppy) / camera_intrinsics.fy + + z = depth_image.flatten() / 1000 + x = np.multiply(x, z) + y = np.multiply(y, z) + + x = x[np.nonzero(z)] + y = y[np.nonzero(z)] + z = z[np.nonzero(z)] + + return x, y, z From 1cdaba11ad88a128641c4890d46a966ab6e3004b Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 31 May 2024 17:47:57 +0200 Subject: [PATCH 179/338] get camera intrinsics for the calculation of the pointcloud --- serl_robot_infra/robotiq_env/camera/rs_capture.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index d63cb19f..542fccce 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -17,7 +17,7 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.pipe = rs.pipeline() self.cfg = rs.config() self.cfg.enable_device(self.serial_number) - self.colorizer = None + self.camera_intrinsics = None assert self.rgb or self.depth if self.rgb: @@ -33,6 +33,11 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.max_clipping_distance = 1. / depth_scale # 1m max clipping distance self.min_clipping_distance = 0.0 / depth_scale # might mess things up + # get the camera intrinsics + profile = self.pipe.get_active_profile() + depth_profile = rs.video_stream_profile(profile.get_stream(rs.stream.depth)) + self.camera_intrinsics = depth_profile.get_intrinsics() + # for some weird reason, these values have to be set in order for the image to appear with good lightning for sensor in self.profile.get_device().query_sensors(): sensor.set_option(rs.option.enable_auto_exposure, False) From 811a745dbc5636a330ad583ed326c0a346ec7cc3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 5 Jun 2024 14:57:14 +0200 Subject: [PATCH 180/338] added pretrained ResNet18 from pytorch (converted) --- .../serl_launcher/agents/continuous/drq.py | 31 +- .../serl_launcher/vision/resnet_v1.py | 4 +- .../serl_launcher/vision/resnet_v1_18.py | 428 ++++++++++++++++++ 3 files changed, 459 insertions(+), 4 deletions(-) create mode 100644 serl_launcher/serl_launcher/vision/resnet_v1_18.py diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 900ff3d3..f1167b4a 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -91,7 +91,7 @@ def create( target_entropy = -prod(actions.shape) print(f"config: discount: {discount}, target_entropy: {target_entropy}") - print(f"actor_optimizer {actor_optimizer_kwargs} critic_optimizer {critic_optimizer_kwargs} temperature {temperature_optimizer_kwargs}") + # print(f"actor_optimizer {actor_optimizer_kwargs} critic_optimizer {critic_optimizer_kwargs} temperature {temperature_optimizer_kwargs}") return cls( state=state, @@ -183,16 +183,41 @@ def create_drq( encoders = { image_key: PreTrainedResNetEncoder( + rng=rng, + pooling_method="spatial_learned_embeddings", # default was "spatial_learned_embeddings" + num_spatial_blocks=8, + bottleneck_dim=256, # default was 256 + pretrained_encoder=pretrained_encoder, + name=f"encoder_{image_key}", + use_depth_only=use_depth_only, + ) + for image_key in image_keys + } + elif encoder_type == "resnet-pretrained-18": + # pretrained ResNet18 from microsoft + from serl_launcher.vision.resnet_v1_18 import resnetv1_18_configs + from serl_launcher.vision.resnet_v1 import PreTrainedResNetEncoder + + pretrained_encoder = resnetv1_18_configs["resnetv1-18-frozen"]( + name="pretrained_encoder", + ) + + use_depth_only = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + print(f"use depth only: {use_depth_only}") + + encoders = { + image_key: PreTrainedResNetEncoder( + rng=rng, pooling_method="spatial_learned_embeddings", num_spatial_blocks=8, - bottleneck_dim=256, + bottleneck_dim=256, # default was 256 pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", use_depth_only=use_depth_only, ) for image_key in image_keys } - elif encoder_type == "None": + elif encoder_type.lower() == "none": encoders = None else: raise NotImplementedError(f"Unknown encoder type: {encoder_type}") diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index f3e3048f..5dcd05f4 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -8,6 +8,7 @@ import numpy as np from serl_launcher.vision.film_conditioning_layer import FilmConditioning +from serl_launcher.common.typing import PRNGKey ModuleDef = Any @@ -324,6 +325,7 @@ def __call__( class PreTrainedResNetEncoder(nn.Module): + rng: PRNGKey = None pooling_method: str = "avg" # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 @@ -357,7 +359,7 @@ def __call__( channel=channel, num_features=self.num_spatial_blocks, )(x) - x = nn.Dropout(0.1, deterministic=not train)(x) + x = nn.Dropout(0.1, deterministic=not train)(x, rng=self.rng) elif self.pooling_method == "spatial_softmax": height, width, channel = x.shape[-3:] pos_x, pos_y = jnp.meshgrid( diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py new file mode 100644 index 00000000..1ded295d --- /dev/null +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -0,0 +1,428 @@ +import jax.lax +import jax.numpy as jnp +import flax.linen as nn +import functools +from typing import (Any, Callable, Iterable, Optional, Tuple, Union) +import h5py +import warnings + +from flax.linen.module import compact, merge_param +from jax.nn import initializers +from jax import lax + +from serl_launcher.vision.resnet_v1 import SpatialLearnedEmbeddings, SpatialSoftmax + +PRNGKey = Any +Array = Any +Shape = Tuple[int] +Dtype = Any + + +# ---------------------------------------------------------------# +# Normalization +# ---------------------------------------------------------------# +def batch_norm(x, train, epsilon=1e-05, momentum=0.99, params=None, dtype='float32'): + if params is None: + x = BatchNorm(epsilon=epsilon, + momentum=momentum, + use_running_average=not train, + dtype=dtype)(x) + else: + x = BatchNorm(epsilon=epsilon, + momentum=momentum, + bias_init=lambda *_: jnp.array(params['bias']), + scale_init=lambda *_: jnp.array(params['scale']), + mean_init=lambda *_: jnp.array(params['mean']), + var_init=lambda *_: jnp.array(params['var']), + use_running_average=not train, + dtype=dtype)(x) + return x + + +def _absolute_dims(rank, dims): + return tuple([rank + dim if dim < 0 else dim for dim in dims]) + + +class BatchNorm(nn.Module): + """BatchNorm Module. + + Taken from: https://github.com/google/flax/blob/master/flax/linen/normalization.py + + Attributes: + use_running_average: if True, the statistics stored in batch_stats + will be used instead of computing the batch statistics on the input. + axis: the feature or non-batch axis of the input. + momentum: decay rate for the exponential moving average of the batch statistics. + epsilon: a small float added to variance to avoid dividing by zero. + dtype: the dtype of the computation (default: float32). + use_bias: if True, bias (beta) is added. + use_scale: if True, multiply by scale (gamma). + When the next layer is linear (also e.g. nn.relu), this can be disabled + since the scaling will be done by the next layer. + bias_init: initializer for bias, by default, zero. + scale_init: initializer for scale, by default, one. + axis_name: the axis name used to combine batch statistics from multiple + devices. See `jax.pmap` for a description of axis names (default: None). + axis_index_groups: groups of axis indices within that named axis + representing subsets of devices to reduce over (default: None). For + example, `[[0, 1], [2, 3]]` would independently batch-normalize over + the examples on the first two and last two devices. See `jax.lax.psum` + for more details. + """ + use_running_average: Optional[bool] = None + axis: int = -1 + momentum: float = 0.99 + epsilon: float = 1e-5 + dtype: Dtype = jnp.float32 + use_bias: bool = True + use_scale: bool = True + bias_init: Callable[[PRNGKey, Shape, Dtype], Array] = initializers.zeros + scale_init: Callable[[PRNGKey, Shape, Dtype], Array] = initializers.ones + mean_init: Callable[[Shape], Array] = lambda s: jnp.zeros(s, jnp.float32) + var_init: Callable[[Shape], Array] = lambda s: jnp.ones(s, jnp.float32) + axis_name: Optional[str] = None + axis_index_groups: Any = None + + @compact + def __call__(self, x, use_running_average: Optional[bool] = None): + """Normalizes the input using batch statistics. + + NOTE: + During initialization (when parameters are mutable) the running average + of the batch statistics will not be updated. Therefore, the inputs + fed during initialization don't need to match that of the actual input + distribution and the reduction axis (set with `axis_name`) does not have + to exist. + Args: + x: the input to be normalized. + use_running_average: if true, the statistics stored in batch_stats + will be used instead of computing the batch statistics on the input. + Returns: + Normalized inputs (the same shape as inputs). + """ + use_running_average = merge_param( + 'use_running_average', self.use_running_average, use_running_average) + x = jnp.asarray(x, jnp.float32) + axis = self.axis if isinstance(self.axis, tuple) else (self.axis,) + axis = _absolute_dims(x.ndim, axis) + feature_shape = tuple(d if i in axis else 1 for i, d in enumerate(x.shape)) + reduced_feature_shape = tuple(d for i, d in enumerate(x.shape) if i in axis) + reduction_axis = tuple(i for i in range(x.ndim) if i not in axis) + + # see NOTE above on initialization behavior + initializing = self.is_mutable_collection('params') + + ra_mean = self.variable('batch_stats', 'mean', + self.mean_init, + reduced_feature_shape) + ra_var = self.variable('batch_stats', 'var', + self.var_init, + reduced_feature_shape) + + if use_running_average: + mean, var = ra_mean.value, ra_var.value + else: + mean = jnp.mean(x, axis=reduction_axis, keepdims=False) + mean2 = jnp.mean(lax.square(x), axis=reduction_axis, keepdims=False) + if self.axis_name is not None and not initializing: + concatenated_mean = jnp.concatenate([mean, mean2]) + mean, mean2 = jnp.split( + lax.pmean( + concatenated_mean, + axis_name=self.axis_name, + axis_index_groups=self.axis_index_groups), 2) + var = mean2 - lax.square(mean) + + if not initializing: + ra_mean.value = self.momentum * ra_mean.value + (1 - self.momentum) * mean + ra_var.value = self.momentum * ra_var.value + (1 - self.momentum) * var + + y = x - mean.reshape(feature_shape) + mul = lax.rsqrt(var + self.epsilon) + if self.use_scale: + scale = self.param('scale', + self.scale_init, + reduced_feature_shape).reshape(feature_shape) + mul = mul * scale + y = y * mul + if self.use_bias: + bias = self.param('bias', + self.bias_init, + reduced_feature_shape).reshape(feature_shape) + y = y + bias + return jnp.asarray(y, self.dtype) + + +LAYERS = {'resnet18': [2, 2, 2, 2]} + + +class BasicBlock(nn.Module): + """ + Basic Block. + + Attributes: + features (int): Number of output channels. + kernel_size (Tuple): Kernel size. + downsample (bool): If True, downsample spatial resolution. + stride (bool): If True, use strides (2, 2). Not used in this module. + The attribute is only here for compatibility with Bottleneck. + param_dict (h5py.Group): Parameter dict with pretrained parameters. + kernel_init (functools.partial): Kernel initializer. + bias_init (functools.partial): Bias initializer. + block_name (str): Name of block. + dtype (str): Data type. + """ + features: int + kernel_size: Union[int, Iterable[int]] = (3, 3) + downsample: bool = False + stride: bool = True + param_dict: h5py.Group = None + kernel_init: functools.partial = nn.initializers.lecun_normal() + bias_init: functools.partial = nn.initializers.zeros + block_name: str = None + dtype: str = 'float32' + + @nn.compact + def __call__(self, x, act, train=True): + """ + Run Basic Block. + + Args: + x (tensor): Input tensor of shape [N, H, W, C]. + act (dict): Dictionary containing activations. + train (bool): Training mode. + + Returns: + (tensor): Output shape of shape [N, H', W', features]. + """ + residual = x + + x = nn.Conv(features=self.features, + kernel_size=self.kernel_size, + strides=(2, 2) if self.downsample else (1, 1), + padding=((1, 1), (1, 1)), + kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['conv1']['weight']), + use_bias=False, + dtype=self.dtype)(x) + + x = batch_norm(x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict['bn1'], + dtype=self.dtype) + x = nn.relu(x) + + x = nn.Conv(features=self.features, + kernel_size=self.kernel_size, + strides=(1, 1), + padding=((1, 1), (1, 1)), + kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['conv2']['weight']), + use_bias=False, + dtype=self.dtype)(x) + + x = batch_norm(x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict['bn2'], + dtype=self.dtype) + + if self.downsample: + residual = nn.Conv(features=self.features, + kernel_size=(1, 1), + strides=(2, 2), + kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['downsample']['conv']['weight']), + use_bias=False, + dtype=self.dtype)(residual) + + residual = batch_norm(residual, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict['downsample']['bn'], + dtype=self.dtype) + + x += residual + x = nn.relu(x) + act[self.block_name] = x + return x + + +class ResNet(nn.Module): + """ + ResNet. + + Attributes: + output (str): + Output of the module. Available options are: + - 'softmax': Output is a softmax tensor of shape [N, 1000] + - 'log_softmax': Output is a softmax tensor of shape [N, 1000] + - 'logits': Output is a tensor of shape [N, 1000] + - 'activations': Output is a dictionary containing the ResNet activations + pretrained (str): + Indicates if and what type of weights to load. Options are: + - 'imagenet': Loads the network parameters trained on ImageNet + - None: Parameters of the module are initialized randomly + normalize (bool): + If True, the input will be normalized with the ImageNet statistics. + architecture (str): + Which ResNet model to use: + - 'resnet18' + num_classes (int): + Number of classes. + block (nn.Module): + Type of residual block: + - BasicBlock + kernel_init (function): + A function that takes in a shape and returns a tensor. + bias_init (function): + A function that takes in a shape and returns a tensor. + ckpt_dir (str): + The directory to which the pretrained weights are downloaded. + Only relevant if a pretrained model is used. + If this argument is None, the weights will be saved to a temp directory. + dtype (str): Data type. + """ + output: str = 'softmax' + pretrained: str = 'imagenet' + normalize: bool = True + architecture: str = 'resnet18' + num_classes: int = 1000 + block: nn.Module = BasicBlock + kernel_init: functools.partial = nn.initializers.lecun_normal() + bias_init: functools.partial = nn.initializers.zeros + ckpt_dir: str = None + dtype: str = 'float32' + pre_pooling: bool = True # skip pooling + + def setup(self): + # self.param_dict = None + if self.pretrained == 'imagenet': + # ckpt_file = utils.download(self.ckpt_dir, URLS[self.architecture]) + self.param_dict = h5py.File(self.ckpt_dir, 'r') + print(f"loaded pretrained weights from {self.ckpt_dir}") + + @nn.compact + def __call__(self, observations, train=False): + """ + Args: + x (tensor): Input tensor of shape [N, H, W, 3]. Images must be in range [0, 1]. + train (bool): Training mode. + + Returns: + (tensor): Out + if pre_pooling is True: features of shape (B, 7, 7, 512) + """ + # assert observations.shape[-3:] == (224, 224, 3) + + if self.normalize: + mean = jnp.array([0.485, 0.456, 0.406]).reshape(1, 1, 1, -1) + std = jnp.array([0.229, 0.224, 0.225]).reshape(1, 1, 1, -1) + x = (observations.astype(jnp.float32) / 255.0 - mean) / std + + if self.pretrained == 'imagenet': + if self.num_classes != 1000: + warnings.warn(f'The user specified parameter \'num_classes\' was set to {self.num_classes} ' + 'but will be overwritten with 1000 to match the specified pretrained checkpoint \'imagenet\', if ', + UserWarning) + num_classes = 1000 + else: + num_classes = self.num_classes + + act = {} + + x = nn.Conv(features=64, + kernel_size=(7, 7), + kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['conv1']['weight']), + strides=(2, 2), + padding=((3, 3), (3, 3)), + use_bias=False, + dtype=self.dtype)(x) + act['conv1'] = x + + x = batch_norm(x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict['bn1'], + dtype=self.dtype) + x = nn.relu(x) + x = nn.max_pool(x, window_shape=(3, 3), strides=(2, 2), padding=((1, 1), (1, 1))) + + # Layer 1 + down = self.block.__name__ == 'Bottleneck' + for i in range(LAYERS[self.architecture][0]): + params = None if self.param_dict is None else self.param_dict['layer1'][f'block{i}'] + x = self.block(features=64, + kernel_size=(3, 3), + downsample=i == 0 and down, + stride=i != 0, + param_dict=params, + block_name=f'block1_{i}', + dtype=self.dtype)(x, act, train) + + # Layer 2 + for i in range(LAYERS[self.architecture][1]): + params = None if self.param_dict is None else self.param_dict['layer2'][f'block{i}'] + x = self.block(features=128, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f'block2_{i}', + dtype=self.dtype)(x, act, train) + + # Layer 3 + for i in range(LAYERS[self.architecture][2]): + params = None if self.param_dict is None else self.param_dict['layer3'][f'block{i}'] + x = self.block(features=256, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f'block3_{i}', + dtype=self.dtype)(x, act, train) + + # Layer 4 + for i in range(LAYERS[self.architecture][3]): + params = None if self.param_dict is None else self.param_dict['layer4'][f'block{i}'] + x = self.block(features=512, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f'block4_{i}', + dtype=self.dtype)(x, act, train) + + # if we want the pre_pooling output, return here + if self.pre_pooling: + return jax.lax.stop_gradient(x) # shape (b, 7, 7, 512) + + # Classifier + x = jnp.mean(x, axis=(1, 2)) + x = nn.Dense(features=num_classes, + kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['fc']['weight']), + bias_init=self.bias_init if self.param_dict is None else lambda *_: jnp.array( + self.param_dict['fc']['bias']), + dtype=self.dtype)(x) + act['fc'] = x + + if self.output == 'softmax': + return nn.softmax(x) + if self.output == 'log_softmax': + return nn.log_softmax(x) + if self.output == 'activations': + return act + return x + + +resnetv1_18_configs = { + "resnetv1-18-frozen": functools.partial( + ResNet, architecture='resnet18', + ckpt_dir="/home/nico/real-world-rl/serl/examples/robotiq_drq/resnet18_weights.h5", + pre_pooling=True + ) +} \ No newline at end of file From 84c8aca695b645dfd79231cade57c80de06586a5 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 5 Jun 2024 16:35:41 +0200 Subject: [PATCH 181/338] improved hyperparameter handling --- .../serl_launcher/agents/continuous/drq.py | 18 ++++----- serl_launcher/serl_launcher/utils/launcher.py | 37 +++++++++++-------- 2 files changed, 29 insertions(+), 26 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index f1167b4a..45f985c2 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -114,7 +114,6 @@ def create_drq( actions: jnp.ndarray, # Model architecture encoder_type: str = "small", - shared_encoder: bool = True, use_proprio: bool = False, critic_network_kwargs: dict = { "hidden_dims": [256, 256], @@ -126,6 +125,11 @@ def create_drq( "tanh_squash_distribution": True, "std_parameterization": "uniform", }, + encoder_kwargs: dict = { + "pooling_method": "spatial_learned_embeddings", + "num_spatial_blocks" : 8, + "bottleneck_dim" : 256, + }, critic_ensemble_size: int = 2, critic_subsample_size: Optional[int] = None, temperature_init: float = 1.0, @@ -160,10 +164,8 @@ def create_drq( encoders = { image_key: resnetv1_configs["resnetv1-10"]( - pooling_method="spatial_learned_embeddings", - num_spatial_blocks=8, - bottleneck_dim=256, name=f"encoder_{image_key}", + **encoder_kwargs ) for image_key in image_keys } @@ -184,12 +186,10 @@ def create_drq( encoders = { image_key: PreTrainedResNetEncoder( rng=rng, - pooling_method="spatial_learned_embeddings", # default was "spatial_learned_embeddings" - num_spatial_blocks=8, - bottleneck_dim=256, # default was 256 pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", use_depth_only=use_depth_only, + **encoder_kwargs ) for image_key in image_keys } @@ -208,12 +208,10 @@ def create_drq( encoders = { image_key: PreTrainedResNetEncoder( rng=rng, - pooling_method="spatial_learned_embeddings", - num_spatial_blocks=8, - bottleneck_dim=256, # default was 256 pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", use_depth_only=use_depth_only, + **encoder_kwargs ) for image_key in image_keys } diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index f873f249..2de57195 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -112,27 +112,32 @@ def make_drq_agent( encoder_type=encoder_type, use_proprio=True, image_keys=image_keys, - policy_kwargs={ - "tanh_squash_distribution": True, - "std_parameterization": "exp", - "std_min": 1e-5, - "std_max": 5, - }, - critic_network_kwargs={ - "activations": nn.tanh, - "use_layer_norm": True, - "hidden_dims": [256, 256], - }, - policy_network_kwargs={ - "activations": nn.tanh, - "use_layer_norm": True, - "hidden_dims": [256, 256], - }, + policy_kwargs=dict( + tanh_squash_distribution=True, + std_parameterization="exp", + std_min=1e-5, + std_max=5, + ), + critic_network_kwargs=dict( + activations=nn.tanh, + use_layer_norm=True, + hidden_dims=[256, 256], + ), + policy_network_kwargs=dict( + activations=nn.tanh, + use_layer_norm=True, + hidden_dims=[256, 256], + ), temperature_init=1e-2, discount=0.99, # 0.99 backup_entropy=True, # default: False critic_ensemble_size=10, critic_subsample_size=2, + encoder_kwargs=dict( + pooling_method="spatial_learned_embeddings", # default "spatial_learned_embeddings" + num_spatial_blocks=8, + bottleneck_dim=256, + ), actor_optimizer_kwargs={ "learning_rate": 3e-3, # 3e-4 }, From 82f69512bc10d405efae5b529689aac5e88bc351 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 6 Jun 2024 18:33:24 +0200 Subject: [PATCH 182/338] pretrained is from pytorch --- serl_launcher/serl_launcher/agents/continuous/drq.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 45f985c2..931bdb26 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -194,7 +194,7 @@ def create_drq( for image_key in image_keys } elif encoder_type == "resnet-pretrained-18": - # pretrained ResNet18 from microsoft + # pretrained ResNet18 from pytorch from serl_launcher.vision.resnet_v1_18 import resnetv1_18_configs from serl_launcher.vision.resnet_v1 import PreTrainedResNetEncoder From a756c16a386c2fc6211388af8eb4966ee3b6e95c Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 6 Jun 2024 18:34:19 +0200 Subject: [PATCH 183/338] do not use statistics stored in batch_stats (too much effort to implement...) --- .../serl_launcher/vision/resnet_v1_18.py | 42 +++++++------------ 1 file changed, 14 insertions(+), 28 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py index 1ded295d..e545186f 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1_18.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -95,8 +95,6 @@ def __call__(self, x, use_running_average: Optional[bool] = None): to exist. Args: x: the input to be normalized. - use_running_average: if true, the statistics stored in batch_stats - will be used instead of computing the batch statistics on the input. Returns: Normalized inputs (the same shape as inputs). """ @@ -112,30 +110,18 @@ def __call__(self, x, use_running_average: Optional[bool] = None): # see NOTE above on initialization behavior initializing = self.is_mutable_collection('params') - ra_mean = self.variable('batch_stats', 'mean', - self.mean_init, - reduced_feature_shape) - ra_var = self.variable('batch_stats', 'var', - self.var_init, - reduced_feature_shape) + # use_running_average is not used, calculate the batch norm on each batch - if use_running_average: - mean, var = ra_mean.value, ra_var.value - else: - mean = jnp.mean(x, axis=reduction_axis, keepdims=False) - mean2 = jnp.mean(lax.square(x), axis=reduction_axis, keepdims=False) - if self.axis_name is not None and not initializing: - concatenated_mean = jnp.concatenate([mean, mean2]) - mean, mean2 = jnp.split( - lax.pmean( - concatenated_mean, - axis_name=self.axis_name, - axis_index_groups=self.axis_index_groups), 2) - var = mean2 - lax.square(mean) - - if not initializing: - ra_mean.value = self.momentum * ra_mean.value + (1 - self.momentum) * mean - ra_var.value = self.momentum * ra_var.value + (1 - self.momentum) * var + mean = jnp.mean(x, axis=reduction_axis, keepdims=False) + mean2 = jnp.mean(lax.square(x), axis=reduction_axis, keepdims=False) + if self.axis_name is not None and not initializing: + concatenated_mean = jnp.concatenate([mean, mean2]) + mean, mean2 = jnp.split( + lax.pmean( + concatenated_mean, + axis_name=self.axis_name, + axis_index_groups=self.axis_index_groups), 2) + var = mean2 - lax.square(mean) y = x - mean.reshape(feature_shape) mul = lax.rsqrt(var + self.epsilon) @@ -304,7 +290,7 @@ def setup(self): if self.pretrained == 'imagenet': # ckpt_file = utils.download(self.ckpt_dir, URLS[self.architecture]) self.param_dict = h5py.File(self.ckpt_dir, 'r') - print(f"loaded pretrained weights from {self.ckpt_dir}") + # print(f"loaded pretrained weights from {self.ckpt_dir}") @nn.compact def __call__(self, observations, train=False): @@ -398,7 +384,7 @@ def __call__(self, observations, train=False): # if we want the pre_pooling output, return here if self.pre_pooling: - return jax.lax.stop_gradient(x) # shape (b, 7, 7, 512) + return jax.lax.stop_gradient(x) # shape (b, 7, 7, 512) # Classifier x = jnp.mean(x, axis=(1, 2)) @@ -425,4 +411,4 @@ def __call__(self, observations, train=False): ckpt_dir="/home/nico/real-world-rl/serl/examples/robotiq_drq/resnet18_weights.h5", pre_pooling=True ) -} \ No newline at end of file +} From c56e91fa8b6bcf0dd97597b28069878b6d31e2ab Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 6 Jun 2024 18:35:10 +0200 Subject: [PATCH 184/338] controller can somewhat ignore singularities (with human input & time) --- .../robot_controllers/robotiq_controller.py | 74 +++++++++++-------- 1 file changed, 43 insertions(+), 31 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 1dad4938..bc2407a0 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -51,7 +51,7 @@ def __init__( self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} self.verbose = verbose self.do_plot = plot - self.old_obs = old_obs # use the old observation layout + self.old_obs = old_obs # use the old observation layout self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) @@ -81,6 +81,7 @@ def __init__( self.err = 0 self.noerr = 0 + # log to file (reset every new run) with open("/tmp/console2.txt", 'w') as f: f.write("reset\n") self.second_console = open("/tmp/console2.txt", 'a') @@ -97,22 +98,34 @@ def print(self, msg, probability=1., both=False): print(msg) async def start_robotiq_interfaces(self, gripper=True): - for _ in range(5): # try it 5 times - try: - self.robotiq_control = RTDEControlInterface(self.robot_ip) - self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) - if gripper: - self.robotiq_gripper = VacuumGripper(self.robot_ip) - await self.robotiq_gripper.connect() - await self.robotiq_gripper.activate() - if self.verbose: - gr_string = "(with gripper) " if gripper else "" - print(f"[RIC] Controller connected to robot {gr_string}at: {self.robot_ip}") - return - except RuntimeError as e: - print("[RIC] ", e.__str__()) - continue - raise RuntimeError(f"[RIC] Could not connect to robot [{self.robot_ip}]") + self.robotiq_control = RTDEControlInterface(self.robot_ip) + self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) + if gripper: + self.robotiq_gripper = VacuumGripper(self.robot_ip) + await self.robotiq_gripper.connect() + await self.robotiq_gripper.activate() + if self.verbose: + gr_string = "(with gripper) " if gripper else "" + print(f"[RIC] Controller connected to robot {gr_string}at: {self.robot_ip}") + + async def restart_robotiq_interface(self): + self._is_truncated.set() + self.print("[RIC] forcemode failed, is now truncated!") + + # disconnect and reconnect, otherwise the controller won't take any commands + self.robotiq_control.disconnect() + try: + self.robotiq_control.reconnect() + except RuntimeError: + self.robotiq_receive.disconnect() + for _ in range(10): + try: + self.robotiq_control.disconnect() + self.robotiq_receive.disconnect() + await self.start_robotiq_interfaces(gripper=False) + except Exception as e: + print(e) + time.sleep(0.2) def stop(self): self._stop.set() @@ -135,7 +148,7 @@ def set_target_pos(self, target_pos: np.ndarray): self.target_pos[:3] = target_pos[:3] self.target_pos[3:] = target_orientation - self.print(f"target: {self.target_pos}") + self.print(f"target: {self.target_pos}") def set_reset_Q(self, reset_Q: np.ndarray): with self.lock: @@ -162,7 +175,7 @@ async def _update_robot_state(self): pressure = await self.robotiq_gripper.get_current_pressure() obj_status = await self.robotiq_gripper.get_object_status() - pressure /= 100. # pressure between [0, 1] + pressure /= 100. # pressure between [0, 1] grip_status = [0., 1., 1., 0.][obj_status.value] # 3-> no object detected, [0, 1, 2]-> obj detected with self.lock: self.curr_pos[:] = pose2quat(pos) @@ -170,7 +183,7 @@ async def _update_robot_state(self): self.curr_Q[:] = Q self.curr_Qd[:] = Qd if self.old_obs: - self.curr_force[:] = np.asarray(force) # old representation for SAC policy + self.curr_force[:] = np.asarray(force) # old representation for SAC policy self.gripper_state[:] = [pressure, float(obj_status.value)] else: # use moving average (5), since the force fluctuates heavily @@ -197,7 +210,7 @@ def is_reset(self): return not self._reset.is_set() def _calculate_force(self): - target_pos = self.get_target_pos(copy=False) + target_pos = self.get_target_pos(copy=True) with self.lock: curr_pos = self.curr_pos curr_vel = self.curr_vel @@ -293,14 +306,15 @@ async def _go_to_reset_pose(self): time.sleep(0.2) # then move up (so no boxes are moved) + success = True while self.curr_pos[2] < self.reset_height: - assert self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) + success = success and self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) await self._update_robot_state() time.sleep(0.01) self.robotiq_control.speedStop(a=1.) # then move to desired Jointspace position - assert self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) + success = success and self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) await self._update_robot_state() @@ -310,7 +324,10 @@ async def _go_to_reset_pose(self): self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster self.robotiq_control.zeroFtSensor() - self._reset.clear() + if not success: # restart if not successful + await self.restart_robotiq_interface() + else: + self._reset.clear() async def run_async(self): await self.start_robotiq_interfaces(gripper=True) @@ -355,12 +372,7 @@ async def run_async(self): self.fm_limits ) if not fm_successful: # truncate if the robot ends up in a singularity - self._is_truncated.set() - - # disconnect and reconnect, otherwise the controller won't take any commands - self.robotiq_control.disconnect() - time.sleep(0.5) - self.robotiq_control.reconnect() + await self.restart_robotiq_interface() if self.robotiq_gripper: await self.send_gripper_command() @@ -369,7 +381,7 @@ async def run_async(self): a = dt - (time.monotonic() - t_now) time.sleep(max(0., a)) - self.err, self.noerr = self.err + int(a < 0.), self.noerr + int(a >= 0.) # some logging + self.err, self.noerr = self.err + int(a < 0.), self.noerr + int(a >= 0.) # some logging finally: if self.verbose: From 05e018cd86183a84212678a6bc1b79b0fb22f14a Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 6 Jun 2024 18:35:35 +0200 Subject: [PATCH 185/338] downgraded RealSense firmware to 5.13 --- serl_robot_infra/robotiq_env/camera/rs_capture.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 542fccce..31dbb6d1 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -39,9 +39,10 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.camera_intrinsics = depth_profile.get_intrinsics() # for some weird reason, these values have to be set in order for the image to appear with good lightning + # for firmware >5.13, auto_exposure False & auto_white_balance True, below only auto_exposure True for sensor in self.profile.get_device().query_sensors(): - sensor.set_option(rs.option.enable_auto_exposure, False) - sensor.set_option(rs.option.enable_auto_white_balance, True) + sensor.set_option(rs.option.enable_auto_exposure, True) + # sensor.set_option(rs.option.enable_auto_white_balance, True) # Create an align object # rs.align allows us to perform alignment of depth frames to others frames From 4b5209c402e522da04babf61cd4fde9a896bb349 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 6 Jun 2024 18:36:20 +0200 Subject: [PATCH 186/338] new training and actor params for ResNet18 --- examples/robotiq_drq/run_actor.sh | 19 ++++++++++--------- examples/robotiq_drq/run_evaluation.sh | 14 +++++++------- examples/robotiq_drq/run_learner.sh | 14 +++++++------- 3 files changed, 24 insertions(+), 23 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index f8dc178f..a40331bb 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -1,17 +1,18 @@ +sh ~/stop.sh && \ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name=drq_robotiq_policy \ --max_traj_length 100 \ + --exp_name=drq_rgb_5box \ --camera_mode rgb \ - --seed 2 \ - --max_steps 20000 \ - --random_steps 100 \ - --training_starts 100 \ + --seed 1 \ + --max_steps 30000 \ + --random_steps 500 \ + --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1000 \ - --encoder_type resnet-pretrained \ -# --debug \ No newline at end of file + --eval_period 2500 \ + --encoder_type resnet-pretrained-18 \ +# --debug diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/robotiq_drq/run_evaluation.sh index 2af764f6..67cbe773 100644 --- a/examples/robotiq_drq/run_evaluation.sh +++ b/examples/robotiq_drq/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name=drq_robotiq_policy_evaluation \ + --exp_name=drq_evaluation \ --max_traj_length 100 \ - --camera_mode depth \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0523 rgb stable pooling=avg"\ + --camera_mode rgb \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0606-16:05 rgb Res18 avg"\ --eval_checkpoint_step 20000 \ - --encoder_type resnet-pretrained \ - --eval_n_trajs 10 \ - --debug \ No newline at end of file + --encoder_type resnet-pretrained-18 \ + --eval_n_trajs 20 \ + --debug diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index a2ca3754..fc7875ef 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -3,17 +3,17 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name=drq_robotiq_policy \ + --exp_name=drq_rgb_5box \ --camera_mode rgb \ --max_traj_length 100 \ - --seed 2 \ + --seed 1 \ --max_steps 20000 \ - --random_steps 100 \ - --training_starts 100 \ + --random_steps 500 \ + --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 1000 \ - --encoder_type resnet-pretrained \ - --checkpoint_period 5000 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai16_100transition.pkl \ + --encoder_type resnet-pretrained-18 \ + --checkpoint_period 2500 \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai31_5box.pkl \ # --debug From be49bdc81047c70f28241568d3d0038aa12a4c53 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 10 Jun 2024 16:12:34 +0200 Subject: [PATCH 187/338] name change --- serl_launcher/serl_launcher/agents/continuous/drq.py | 12 ++++++------ serl_launcher/serl_launcher/vision/resnet_v1.py | 6 +++--- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 931bdb26..006a0058 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -180,15 +180,15 @@ def create_drq( name="pretrained_encoder", ) - use_depth_only = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) - print(f"use depth only: {use_depth_only}") + use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + print(f"use single channel only: {use_single_channel}") encoders = { image_key: PreTrainedResNetEncoder( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - use_depth_only=use_depth_only, + use_single_channel=use_single_channel, **encoder_kwargs ) for image_key in image_keys @@ -202,15 +202,15 @@ def create_drq( name="pretrained_encoder", ) - use_depth_only = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) - print(f"use depth only: {use_depth_only}") + use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + print(f"use single channel only: {use_single_channel}") encoders = { image_key: PreTrainedResNetEncoder( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - use_depth_only=use_depth_only, + use_single_channel=use_single_channel, **encoder_kwargs ) for image_key in image_keys diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index 5dcd05f4..e33257a0 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -332,7 +332,7 @@ class PreTrainedResNetEncoder(nn.Module): num_spatial_blocks: int = 8 bottleneck_dim: Optional[int] = None pretrained_encoder: nn.module = None - use_depth_only: bool = False + use_single_channel: bool = False @nn.compact def __call__( @@ -343,8 +343,8 @@ def __call__( ): x = observations - # use DDD instead of RGB and pass it through resnet - if self.use_depth_only: + # if we want to use single channel image data (grayscale) + if self.use_single_channel: assert x.shape[-3:] == (128, 128, 1) # check shape x = jnp.repeat(x, 3, axis=-1) From 77957f4b9ea116286a8153526c428e47e47e87a3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 10 Jun 2024 16:12:53 +0200 Subject: [PATCH 188/338] bugfixes --- examples/robotiq_sac/sac_policy_robotiq.py | 2 +- .../serl_launcher/vision/resnet_v1_18.py | 38 ++++++++++++------- 2 files changed, 25 insertions(+), 15 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 16ed865e..630feb29 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -310,7 +310,7 @@ def main(_): FLAGS.env, fake_env=FLAGS.learner, max_episode_length=FLAGS.max_traj_length, - camera_mode=None, + camera_mode="none", ) if FLAGS.actor: env = SpacemouseIntervention(env) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py index e545186f..a22412ce 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1_18.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -22,10 +22,11 @@ # Normalization # ---------------------------------------------------------------# def batch_norm(x, train, epsilon=1e-05, momentum=0.99, params=None, dtype='float32'): + # we do not use running average in the implementation (set to False) if params is None: x = BatchNorm(epsilon=epsilon, momentum=momentum, - use_running_average=not train, + use_running_average=False, # was not train dtype=dtype)(x) else: x = BatchNorm(epsilon=epsilon, @@ -34,7 +35,7 @@ def batch_norm(x, train, epsilon=1e-05, momentum=0.99, params=None, dtype='float scale_init=lambda *_: jnp.array(params['scale']), mean_init=lambda *_: jnp.array(params['mean']), var_init=lambda *_: jnp.array(params['var']), - use_running_average=not train, + use_running_average=False, # was not train dtype=dtype)(x) return x @@ -95,6 +96,8 @@ def __call__(self, x, use_running_average: Optional[bool] = None): to exist. Args: x: the input to be normalized. + use_running_average: if true, the statistics stored in batch_stats + will be used instead of computing the batch statistics on the input. Returns: Normalized inputs (the same shape as inputs). """ @@ -110,18 +113,25 @@ def __call__(self, x, use_running_average: Optional[bool] = None): # see NOTE above on initialization behavior initializing = self.is_mutable_collection('params') - # use_running_average is not used, calculate the batch norm on each batch - - mean = jnp.mean(x, axis=reduction_axis, keepdims=False) - mean2 = jnp.mean(lax.square(x), axis=reduction_axis, keepdims=False) - if self.axis_name is not None and not initializing: - concatenated_mean = jnp.concatenate([mean, mean2]) - mean, mean2 = jnp.split( - lax.pmean( - concatenated_mean, - axis_name=self.axis_name, - axis_index_groups=self.axis_index_groups), 2) - var = mean2 - lax.square(mean) + if use_running_average: + ra_mean = self.variable('batch_stats', 'mean', + self.mean_init, + reduced_feature_shape) + ra_var = self.variable('batch_stats', 'var', + self.var_init, + reduced_feature_shape) + mean, var = ra_mean.value, ra_var.value + else: + mean = jnp.mean(x, axis=reduction_axis, keepdims=False) + mean2 = jnp.mean(lax.square(x), axis=reduction_axis, keepdims=False) + if self.axis_name is not None and not initializing: + concatenated_mean = jnp.concatenate([mean, mean2]) + mean, mean2 = jnp.split( + lax.pmean( + concatenated_mean, + axis_name=self.axis_name, + axis_index_groups=self.axis_index_groups), 2) + var = mean2 - lax.square(mean) y = x - mean.reshape(feature_shape) mul = lax.rsqrt(var + self.epsilon) From 2d3d383d4916eb5bdf01205dd88dd6364774c176 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 18 Jun 2024 16:02:02 +0200 Subject: [PATCH 189/338] prototype distance sensor --- .../serl_launcher/agents/continuous/drq.py | 18 ++++++++++ .../serl_launcher/vision/range_sensor.py | 34 +++++++++++++++++++ 2 files changed, 52 insertions(+) create mode 100644 serl_launcher/serl_launcher/vision/range_sensor.py diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 006a0058..0acdab0a 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -215,6 +215,24 @@ def create_drq( ) for image_key in image_keys } + elif encoder_type == "distance-sensor": + from serl_launcher.vision.range_sensor import RangeSensorEncoder + # use depth image as range-like sensor + assert [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + import numpy as np + + # 3x3 points centered in the middle + keypoints = [tuple(k) for k in np.stack(np.meshgrid([32, 64, 96], [32, 64, 96])).reshape((-1, 2))] + keypoint_size = (5, 5) + + encoders = { + image_key: RangeSensorEncoder( + name=f"encoder_{image_key}", + keypoints=keypoints, + keypoint_size=keypoint_size, + ) + for image_key in image_keys + } elif encoder_type.lower() == "none": encoders = None else: diff --git a/serl_launcher/serl_launcher/vision/range_sensor.py b/serl_launcher/serl_launcher/vision/range_sensor.py new file mode 100644 index 00000000..6ff1c3da --- /dev/null +++ b/serl_launcher/serl_launcher/vision/range_sensor.py @@ -0,0 +1,34 @@ +from typing import Any, Callable, Optional, Sequence, Tuple, Optional + +import flax.linen as nn +import jax.numpy as jnp + + +class RangeSensorEncoder(nn.Module): + """ + Takes depth-images as input with shape (B, H, W, 1) and returns range values for each keypoint tuple provided. The + values are pooled with 'func_pool' over a size of 'keypoint_size'. The output is scaled to [0., 1.] + """ + keypoints: Tuple[Tuple[int, int], ...] # (x, y) coordinates in depth image + keypoint_size: Tuple[int, int] = (3, 3) + pool_func: Callable = jnp.median + + @nn.compact + def __call__(self, observations: jnp.ndarray, train: bool = False, encode: bool = True): + x = observations / 255 # convert to float and within [0, 1] + assert x.shape[-1] == 1 + assert self.keypoint_size[0] % 2 == 1 and self.keypoint_size[1] % 2 == 1 + + # add batch dim if missing + if len(x.shape) < 4: + x = x[None] + points = jnp.zeros((x.shape[0], len(self.keypoints))) + + for i, keypoint in enumerate(self.keypoints): + k_x, k_y = keypoint + s_x, s_y = self.keypoint_size[0] // 2, self.keypoint_size[1] // 2 + points.at[:, i].set(self.pool_func(x[:, k_x - s_x:k_x + s_x + 1, k_y - s_y:k_y + s_y + 1, 0], axis=(1, 2))) + + if points.shape[0] == 1: + points = points[0] + return points From d134d2cc846feacf3dedfec85770651c572032f7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 18 Jun 2024 16:02:42 +0200 Subject: [PATCH 190/338] added num keypoints in spatial softmax --- .../serl_launcher/vision/resnet_v1.py | 52 +++++++++++++------ 1 file changed, 35 insertions(+), 17 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index e33257a0..73b80f72 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -63,7 +63,7 @@ def __call__(self, features): batch_size, num_featuremaps, self.height * self.width ) - softmax_attention = nn.softmax(features / temperature) + softmax_attention = nn.softmax(features / temperature, axis=-1) expected_x = jnp.sum( self.pos_x * softmax_attention, axis=2, keepdims=True ).reshape(batch_size, num_featuremaps) @@ -138,8 +138,8 @@ class ResNetBlock(nn.Module): @nn.compact def __call__( - self, - x, + self, + x, ): residual = x y = self.conv(self.filters, (3, 3), self.strides)(x) @@ -209,16 +209,16 @@ class ResNetEncoder(nn.Module): @nn.compact def __call__( - self, - observations: jnp.ndarray, - train: bool = True, - cond_var=None, - stop_gradient=False, + self, + observations: jnp.ndarray, + train: bool = True, + cond_var=None, + stop_gradient=False, ): # put inputs in [-1, 1] # x = observations.astype(jnp.float32) / 127.5 - 1.0 - assert observations.shape[-3:] == (128, 128, 3) # check for shape + assert observations.shape[-3:] == (128, 128, 3) # check for shape # imagenet mean and std mean = jnp.array([0.485, 0.456, 0.406]) @@ -264,7 +264,7 @@ def __call__( for j in range(block_size): stride = (2, 2) if i > 0 and j == 0 else (1, 1) x = self.block_cls( - self.num_filters * 2**i, + self.num_filters * 2 ** i, strides=stride, conv=conv, norm=norm, @@ -272,12 +272,12 @@ def __call__( )(x) if self.use_film: assert ( - cond_var is not None + cond_var is not None ), "Cond var is None, nothing to condition on" x = FilmConditioning()(x, cond_var) if self.use_multiplicative_cond: assert ( - cond_var is not None + cond_var is not None ), "Cond var is None, nothing to condition on" cond_out = nn.Dense( x.shape[-1], kernel_init=nn.initializers.xavier_normal() @@ -330,22 +330,23 @@ class PreTrainedResNetEncoder(nn.Module): # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 num_spatial_blocks: int = 8 + num_kp: int = 64 # for Spatial Softmax bottleneck_dim: Optional[int] = None pretrained_encoder: nn.module = None use_single_channel: bool = False @nn.compact def __call__( - self, - observations: jnp.ndarray, - encode: bool = True, - train: bool = True, + self, + observations: jnp.ndarray, + encode: bool = True, + train: bool = True, ): x = observations # if we want to use single channel image data (grayscale) if self.use_single_channel: - assert x.shape[-3:] == (128, 128, 1) # check shape + assert x.shape[-3:] == (128, 128, 1) # check shape x = jnp.repeat(x, 3, axis=-1) if encode: @@ -361,6 +362,23 @@ def __call__( )(x) x = nn.Dropout(0.1, deterministic=not train)(x, rng=self.rng) elif self.pooling_method == "spatial_softmax": + """ + implemented as in https://github.com/huggingface/lerobot/blob/ff8f6aa6cde2957f08547eb081aac12ca4669b6a/lerobot/common/policies/diffusion/modeling_diffusion.py#L316 + In this case it would result in 512 keypoints (corresponding to the 512 input channels). We can optionally + provide num_kp != None to control the number of keypoints. This is achieved by a first applying a learnable + linear mapping (in_channels, H, W) -> (num_kp, H, W). + """ + + print(f"before {x.shape}") + x = nn.Conv( + features=self.num_kp, + kernel_size=1, + use_bias=False, + dtype=jnp.float32, + kernel_init=nn.initializers.kaiming_normal(), + name="spatial_softmax_conv", + )(x) + print(f"after {x.shape}") height, width, channel = x.shape[-3:] pos_x, pos_y = jnp.meshgrid( jnp.linspace(-1.0, 1.0, height), jnp.linspace(-1.0, 1.0, width) From 1405e5595f04c9f6efa9464a1c7b8937e9f822d4 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 19 Jun 2024 16:37:56 +0200 Subject: [PATCH 191/338] cam change --- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index a65e8c05..eccc15d7 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -21,8 +21,8 @@ class RobotiqCameraConfig(DefaultEnvConfig): FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) REALSENSE_CAMERAS = { - "wrist": "218622279756", - # "shoulder": "218622277164" + "wrist": "218622277164", + # "shoulder": "218622279756" } @@ -51,8 +51,8 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) REALSENSE_CAMERAS = { - "wrist": "218622279756", - # "shoulder": "218622277164" + "wrist": "218622277164", + # "shoulder": "218622279756" } From 77f1d4b01eda6d94d43a87c9c0a74cf297260572 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 19 Jun 2024 16:38:30 +0200 Subject: [PATCH 192/338] cleanup --- serl_launcher/serl_launcher/vision/resnet_v1.py | 3 --- serl_robot_infra/robot_controllers/robotiq_controller.py | 3 ++- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index 73b80f72..6744c5a3 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -368,8 +368,6 @@ def __call__( provide num_kp != None to control the number of keypoints. This is achieved by a first applying a learnable linear mapping (in_channels, H, W) -> (num_kp, H, W). """ - - print(f"before {x.shape}") x = nn.Conv( features=self.num_kp, kernel_size=1, @@ -378,7 +376,6 @@ def __call__( kernel_init=nn.initializers.kaiming_normal(), name="spatial_softmax_conv", )(x) - print(f"after {x.shape}") height, width, channel = x.shape[-3:] pos_x, pos_y = jnp.meshgrid( jnp.linspace(-1.0, 1.0, height), jnp.linspace(-1.0, 1.0, width) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index bc2407a0..b16c952f 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -303,7 +303,7 @@ async def _go_to_reset_pose(self): if self.robotiq_gripper: self.target_grip[0] = -1. await self.send_gripper_command() - time.sleep(0.2) + time.sleep(0.1) # then move up (so no boxes are moved) success = True @@ -345,6 +345,7 @@ async def run_async(self): while not self.stopped(): if self._reset.is_set(): + await self._update_robot_state() await self._go_to_reset_pose() t_now = time.monotonic() From ce376b1d9066cbc43629184e9a84bb14a7ff15d1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 21 Jun 2024 18:36:00 +0200 Subject: [PATCH 193/338] implemented pointcloud fusion & calibration (multi camera setup) --- .../robotiq_env/camera/rs_capture.py | 35 ++-- serl_robot_infra/robotiq_env/camera/utils.py | 149 +++++++++++++----- .../robotiq_env/envs/camera_env/config.py | 2 +- .../robotiq_env/envs/robotiq_env.py | 118 +++++++++++--- 4 files changed, 231 insertions(+), 73 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 31dbb6d1..8bf22fd0 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -1,5 +1,6 @@ import numpy as np import pyrealsense2 as rs # Intel RealSense cross-platform open-source API +import time class RSCapture: @@ -7,23 +8,25 @@ def get_device_serial_numbers(self): devices = rs.context().devices return [d.get_info(rs.camera_info.serial_number) for d in devices] - def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth=False): + def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth=False, pointcloud=False): self.name = name # print(self.get_device_serial_numbers()) assert serial_number in self.get_device_serial_numbers() self.serial_number = serial_number self.rgb = rgb self.depth = depth + self.pointcloud = pointcloud self.pipe = rs.pipeline() self.cfg = rs.config() self.cfg.enable_device(self.serial_number) - self.camera_intrinsics = None - assert self.rgb or self.depth + assert self.rgb or self.depth or self.pointcloud if self.rgb: self.cfg.enable_stream(rs.stream.color, dim[0], dim[1], rs.format.bgr8, fps) if self.depth: self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) + if self.pointcloud: + self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) self.profile = self.pipe.start(self.cfg) @@ -33,10 +36,12 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.max_clipping_distance = 1. / depth_scale # 1m max clipping distance self.min_clipping_distance = 0.0 / depth_scale # might mess things up - # get the camera intrinsics - profile = self.pipe.get_active_profile() - depth_profile = rs.video_stream_profile(profile.get_stream(rs.stream.depth)) - self.camera_intrinsics = depth_profile.get_intrinsics() + if self.pointcloud: + self.pc = rs.pointcloud() + self.threshold_filter = rs.threshold_filter() + self.threshold_filter.set_option(rs.option.max_distance, 0.3) # in [m] + self.threshold_filter.set_option(rs.option.min_distance, 0.) # in [m] + self.decimation_filter = rs.decimation_filter(magnitude=2.) # for some weird reason, these values have to be set in order for the image to appear with good lightning # for firmware >5.13, auto_exposure False & auto_white_balance True, below only auto_exposure True @@ -52,16 +57,17 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= def read(self): frames = self.pipe.wait_for_frames() - aligned_frames = self.align.process(frames) - image, depth = None, None + image, depth, pointcloud = None, None, None if self.rgb: + aligned_frames = self.align.process(frames) color_frame = aligned_frames.get_color_frame() if color_frame.is_video_frame(): image = np.asarray(color_frame.get_data()) if self.depth: + aligned_frames = self.align.process(frames) depth_frame = aligned_frames.get_depth_frame() if depth_frame.is_depth_frame(): @@ -75,12 +81,21 @@ def read(self): depth = (depth * (256. / self.max_clipping_distance)).astype(np.uint8) depth = depth[..., None] + if self.pointcloud: + depth_frame = self.threshold_filter.process(frames.get_depth_frame()) + depth_frame = self.decimation_filter.process(depth_frame) + if depth_frame.is_depth_frame(): + points = self.pc.calculate(depth_frame) + pointcloud = np.asanyarray(points.get_vertices()).view(np.float32).reshape(-1, 3) + if isinstance(image, np.ndarray) and isinstance(depth, np.ndarray): return True, np.concatenate((image, depth), axis=-1) elif isinstance(image, np.ndarray): return True, image elif isinstance(depth, np.ndarray): - return True, depth # maybe invert depth and convert it to uint8 (maybe also filter for far away objects) + return True, depth + elif isinstance(pointcloud, np.ndarray): + return True, pointcloud else: return False, None diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 0d7ea7be..3edec1ea 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -1,41 +1,110 @@ import numpy as np -import pyrealsense2 as rs - - -def convert_depth_frame_to_pointcloud(depth_image: np.ndarray, camera_intrinsics: rs.intrinsics): - """ - Convert the depthmap to a 3D point cloud - - Parameters: - ----------- - depth_frame (np.ndarray): the depth_frame containing the depth map - camera_intrinsics : The intrinsic values of the imager in whose coordinate system the depth_frame is computed - - Return: - ---------- - x : array - The x values of the pointcloud in meters - y : array - The y values of the pointcloud in meters - z : array - The z values of the pointcloud in meters - """ - - assert len(depth_image.shape) == 2 or depth_image.shape[2] == 1 - [height, width] = depth_image.shape[:2] - - nx = np.linspace(0, width - 1, width) - ny = np.linspace(0, height - 1, height) - u, v = np.meshgrid(nx, ny) - x = (u.flatten() - camera_intrinsics.ppx) / camera_intrinsics.fx - y = (v.flatten() - camera_intrinsics.ppy) / camera_intrinsics.fy - - z = depth_image.flatten() / 1000 - x = np.multiply(x, z) - y = np.multiply(y, z) - - x = x[np.nonzero(z)] - y = y[np.nonzero(z)] - z = z[np.nonzero(z)] - - return x, y, z +import open3d as o3d +from scipy.spatial.transform import Rotation as R + + +def pointcloud_2_o3d(pointcloud) -> o3d.geometry.PointCloud: + if type(pointcloud) == o3d.geometry.PointCloud: + return pointcloud + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(pointcloud) + return pcd + + +def finetune_pointcloud_fusion(pcd1: o3d.geometry.PointCloud, pcd2: o3d.geometry.PointCloud): + pcd1.estimate_normals() + pcd2.estimate_normals() + + with o3d.utility.VerbosityContextManager(o3d.utility.VerbosityLevel.Error) as cm: + transformation, info = pairwise_registration(pcd1, pcd2, max_correspondence_distance=1e-3) + + r = R.from_matrix(transformation[:3, :3].copy()).as_euler("xyz") + t = transformation[:3, 3].copy().flatten() + print(f"fusion result--> r: {r} t: {t}") + return transformation + + +def pairwise_registration(source, target, max_correspondence_distance): + # see https://www.open3d.org/docs/latest/tutorial/Advanced/multiway_registration.html + icp = o3d.pipelines.registration.registration_icp( + source, target, max_correspondence_distance, + np.eye(4), + o3d.pipelines.registration.TransformationEstimationPointToPlane()) + transformation_icp = icp.transformation + information_icp = o3d.pipelines.registration.get_information_matrix_from_point_clouds( + source, target, max_correspondence_distance, + icp.transformation) + return transformation_icp, information_icp + + +class PointCloudFusion: + def __init__(self, angle=30., x_distance=0.195): + self.pcd1 = o3d.geometry.PointCloud() + self.pcd2 = o3d.geometry.PointCloud() + self.fine_tuned_transformation = np.eye(4) + self.coarse_transformed = False + + t1 = np.eye(4) + t1[:3, :3] = R.from_euler("xyz", [angle, 0., 0.], degrees=True).as_matrix() + t1[1, 3] = x_distance / 2. + self.t1 = t1 + + t2 = np.eye(4) + t2[:3, :3] = R.from_euler("xyz", [-angle, 0., 0.], degrees=True).as_matrix() + t2[1, 3] = -x_distance / 2. + self.t2 = t2 + + def append(self, pcd: np.ndarray): + if self.pcd1.is_empty(): + self.pcd1 = pointcloud_2_o3d(pcd) + elif self.pcd2.is_empty(): + self.pcd2 = pointcloud_2_o3d(pcd) + else: + raise NotImplementedError("3 pointclouds not supported") + + def calibrate_fusion(self): + assert self.is_complete() + # rough transform + if not self.coarse_transformed: + self._coarse_transform() + + # then calibrate + t = finetune_pointcloud_fusion(pcd1=self.pcd1, pcd2=self.pcd2) + return t + + def set_fine_tuned_transformation(self, transformation): + self.fine_tuned_transformation[...] = transformation + + def clear(self): + self.pcd1.clear() + self.pcd2.clear() + self.coarse_transformed = False + + def _coarse_transform(self): + self.pcd1.transform(self.t1) + self.pcd2.transform(self.t2) + self.coarse_transformed = True + + def fuse_pointclouds(self): + if not self.coarse_transformed: + self._coarse_transform() + self.pcd1.transform(self.fine_tuned_transformation) + + self.pcd1 += self.pcd2 + return self.pcd1 + + def get_first(self): + self.pcd1.transform(self.t1) + return self.pcd1 + + def get_both(self): + return self.pcd1.__copy__(), self.pcd2.__copy__() + + def get_calibration_history(self): + return np.array(self.calibration_history) + + def is_complete(self): + return not self.pcd1.is_empty() and not self.pcd2.is_empty() + + def is_empty(self): + return self.pcd1.is_empty() and self.pcd2.is_empty() \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index eccc15d7..7796bc87 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -22,7 +22,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): REALSENSE_CAMERAS = { "wrist": "218622277164", - # "shoulder": "218622279756" + "wrist2": "218622279756" } diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 46404d95..96c736df 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -15,6 +15,8 @@ from robotiq_env.camera.video_capture import VideoCapture from robotiq_env.camera.rs_capture import RSCapture +from robotiq_env.camera.utils import PointCloudFusion + from robotiq_env.utils.real_time_plotter import DataClient from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController @@ -94,7 +96,7 @@ def __init__( self.curr_pos = np.zeros((7,), dtype=np.float32) self.curr_vel = np.zeros((6,), dtype=np.float32) - self.curr_Q = np.zeros((6,), dtype=np.float32) # TODO is (7,) for some reason in franka?? same in dq + self.curr_Q = np.zeros((6,), dtype=np.float32) self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((3,), dtype=np.float32) self.curr_torque = np.zeros((3,), dtype=np.float32) @@ -133,7 +135,7 @@ def __init__( image_space_definition = {} if camera_mode in ["rgb", "both"]: - # image_space_definition["shoulder"] = gym.spaces.Box( # TODO only temporary with one image + # image_space_definition["shoulder"] = gym.spaces.Box( # 0, 255, shape=(128, 128, 3), dtype=np.uint8 # ) image_space_definition["wrist"] = gym.spaces.Box( @@ -148,7 +150,12 @@ def __init__( 0, 255, shape=(128, 128, 1), dtype=np.uint8 ) - if camera_mode is not None and camera_mode not in ["rgb", "both", "depth"]: + if camera_mode in ["pointcloud"]: + image_space_definition["wrist_pointcloud"] = gym.spaces.Box( + -np.inf, np.inf, shape=(10000, 3), dtype=np.float32 + ) + + if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") state_space = gym.spaces.Dict( @@ -164,7 +171,7 @@ def __init__( ) obs_space_definition = {"state": state_space} - if self.camera_mode in ["rgb", "both", "depth"]: + if self.camera_mode in ["rgb", "both", "depth", "pointcloud"]: obs_space_definition["images"] = gym.spaces.Dict( image_space_definition ) @@ -198,6 +205,9 @@ def __init__( self.displayer.start() print("[CAM] Cameras are ready!") + if self.camera_mode in ["pointcloud"]: + self.pointcloud_fusion = PointCloudFusion(angle=31., x_distance=0.196) + if self.realtime_plot: try: self.plotting_client = DataClient() @@ -256,16 +266,16 @@ def step(self, action: np.ndarray) -> tuple: self.curr_path_length += 1 - dt = time.time() - start_time - time.sleep(max(0, (1.0 / self.hz) - dt)) - self._update_currpos() obs = self._get_obs() + dt = time.time() - start_time + time.sleep(max(0, (1.0 / self.hz) - dt)) + reward = self.compute_reward(obs, action) truncated = self._is_truncated() - reward = reward if not truncated else reward - 100. # truncation penalty + reward = reward if not truncated else reward - 10. # truncation penalty done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated return obs, reward, done, truncated, {} @@ -305,12 +315,12 @@ def go_to_rest(self, joint_reset=False): # reset_pose = self.resetpos.copy() reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) reset_pose[:2] += reset_shift + + random_rz_rot = np.random.uniform(np.negative(self.random_rz_range), self.random_rz_range)[0] + reset_pose[3:][:] = (R.from_quat(reset_pose[3:]) * R.from_euler("xyz", [0., 0., random_rz_rot])).as_quat() + self.curr_reset_pose[:] = reset_pose - # euler_random = reset_pose[3:] - # euler_random[-1] += np.random.uniform( - # np.negative(self.random_rz_range), self.random_rz_range - # ) self.controller.set_target_pos(reset_pose) # random movement after resetting time.sleep(0.1) while self.controller.is_moving(): @@ -359,17 +369,18 @@ def init_cameras(self, name_serial_dict=None): print(f"cam serial: {cam_serial}") rgb = self.camera_mode in ["rgb", "both"] depth = self.camera_mode in ["depth", "both"] + pointcloud = self.camera_mode in ["pointcloud"] cap = VideoCapture( - RSCapture(name=cam_name, serial_number=cam_serial, rgb=rgb, depth=depth) + RSCapture(name=cam_name, serial_number=cam_serial, rgb=rgb, depth=depth, pointcloud=pointcloud) ) self.cap[cam_name] = cap def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" if name == "wrist": - return image[:, 80:560, :] + return image[:, 124:604, :] elif name == "shoulder": - return image[:, 80:560, :] + raise NotImplementedError("shoulder needs to be implemented") else: raise ValueError(f"Camera {name} not recognized in cropping") @@ -377,6 +388,7 @@ def get_image(self) -> Dict[str, np.ndarray]: """Get images from the realsense cameras.""" images = {} display_images = {} + self.pointcloud_fusion.clear() for key, cap in self.cap.items(): try: image = cap.read() @@ -384,10 +396,15 @@ def get_image(self) -> Dict[str, np.ndarray]: rgb = image[..., :3].astype(np.uint8) cropped_rgb = self.crop_image(key, rgb) resized = cv2.resize( - cropped_rgb, self.observation_space["images"][key].shape[:2][::-1] + cropped_rgb, self.observation_space["images"][key].shape[:2][::-1], ) + # convert to grayscale here + # gray = np.array([0.2989, 0.5870, 0.1140]) + # resized = np.dot(resized, gray)[..., None] + # resized = resized.astype(np.uint8) + images[key] = resized[..., ::-1] - display_images[key] = resized + # display_images[key] = np.repeat(resized, 3, axis=-1) display_images[key + "_full"] = cropped_rgb if self.camera_mode in ["depth", "both"]: @@ -396,26 +413,83 @@ def get_image(self) -> Dict[str, np.ndarray]: cropped_depth = self.crop_image(key, depth) resized = cv2.resize( - cropped_depth, self.observation_space["images"][depth_key].shape[:2] + cropped_depth, np.array(self.observation_space["images"][depth_key].shape[:2]) * 3, + # (128 * 3, 128 * 3) image )[..., None] + resized = resized.reshape((128, 3, 128, 3, 1)).max((1, 3)) # max pool with 3x3 + # TODO check if better! + images[depth_key] = resized display_images[depth_key] = cv2.applyColorMap(resized, cv2.COLORMAP_JET) display_images[depth_key + "_full"] = cv2.applyColorMap(cropped_depth, cv2.COLORMAP_JET) + if self.camera_mode in ["pointcloud"]: + pointcloud = image + self.pointcloud_fusion.append(pointcloud) + except queue.Empty: input(f"{key} camera frozen. Check connect, then press enter to relaunch...") cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() + # self.recording_frames.append( + # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) + # ) + # self.img_queue.put(display_images) + + if self.camera_mode in ["pointcloud"]: + images["wrist_pointcloud"] = np.zeros((10000, 3)) + + if self.pointcloud_fusion.is_complete(): + # fused = np.asarray(self.pointcloud_fusion.fuse_pointclouds().points) + # images["wrist_pointcloud"][:fused.shape[0], :] = fused + pass + elif not self.pointcloud_fusion.is_empty(): + pc = np.asarray(self.pointcloud_fusion.get_first().points) + # images["wrist_pointcloud"][:pc.shape[0], :] = pc - self.recording_frames.append( - np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) - ) - self.img_queue.put(display_images) return images + def calibrate_pointcloud_fusion(self): + assert self.camera_mode in ["pointcloud"] + print("calibrating pointcloud fusion...") + # calibrate pc fusion here + p_backlog = [] + t_hist = [] + + # get samples + for i in range(20): + action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), + -.3 * np.cos(i * np.pi / 10.), 0., 0.] + + obs, reward, done, truncated, _ = self.step(np.array(action)) + + p_backlog += [*self.pointcloud_fusion.get_both()] + + # stop for now + self.controller.stop() + + # do the calibration + import open3d as o3d + for i in range(20): + self.pointcloud_fusion.clear() + self.pointcloud_fusion.append(p_backlog[i * 2]) + self.pointcloud_fusion.append(p_backlog[i * 2 + 1]) + + t = self.pointcloud_fusion.calibrate_fusion() + t_hist.append(t) + self.pointcloud_fusion.set_fine_tuned_transformation(t) + pcd = self.pointcloud_fusion.fuse_pointclouds() + o3d.visualization.draw_geometries([pcd]) + + t_hist = np.array(t_hist) + print(np.mean(t_hist, axis=0)) + print(np.max(t_hist, axis=0)) + print(np.min(t_hist, axis=0)) + self.pointcloud_fusion.set_fine_tuned_transformation(np.mean(t_hist, axis=0)) + def close_cameras(self): """Close both wrist cameras.""" try: From c9e87c624d4f8367a2fe4d0eaea32d9691205429 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 26 Jun 2024 17:40:08 +0200 Subject: [PATCH 194/338] implemented pointcloud visualization and finalized pointcloud fusion with voxelization --- .../robotiq_env/camera/rs_capture.py | 13 +- serl_robot_infra/robotiq_env/camera/utils.py | 133 ++++++++++++++---- .../robotiq_env/envs/robotiq_env.py | 125 +++++++++++----- 3 files changed, 198 insertions(+), 73 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 8bf22fd0..2233ced5 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -1,6 +1,7 @@ import numpy as np import pyrealsense2 as rs # Intel RealSense cross-platform open-source API import time +import open3d as o3d class RSCapture: @@ -38,10 +39,9 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= if self.pointcloud: self.pc = rs.pointcloud() - self.threshold_filter = rs.threshold_filter() - self.threshold_filter.set_option(rs.option.max_distance, 0.3) # in [m] - self.threshold_filter.set_option(rs.option.min_distance, 0.) # in [m] - self.decimation_filter = rs.decimation_filter(magnitude=2.) + self.threshold_filter = rs.threshold_filter(min_dist=0., max_dist=0.25) + self.decimation_filter = rs.decimation_filter(magnitude=2.) # 2 or 4 + self.temporal_filter = rs.temporal_filter(smooth_alpha=0.53, smooth_delta=24., persistence_control=2) # standard values # for some weird reason, these values have to be set in order for the image to appear with good lightning # for firmware >5.13, auto_exposure False & auto_white_balance True, below only auto_exposure True @@ -82,8 +82,9 @@ def read(self): depth = depth[..., None] if self.pointcloud: - depth_frame = self.threshold_filter.process(frames.get_depth_frame()) - depth_frame = self.decimation_filter.process(depth_frame) + depth_frame = self.decimation_filter.process(frames.get_depth_frame()) + depth_frame = self.threshold_filter.process(depth_frame) + depth_frame = self.temporal_filter.process(depth_frame) if depth_frame.is_depth_frame(): points = self.pc.calculate(depth_frame) pointcloud = np.asanyarray(points.get_vertices()).view(np.float32).reshape(-1, 3) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 3edec1ea..624b42e6 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -1,14 +1,7 @@ import numpy as np import open3d as o3d from scipy.spatial.transform import Rotation as R - - -def pointcloud_2_o3d(pointcloud) -> o3d.geometry.PointCloud: - if type(pointcloud) == o3d.geometry.PointCloud: - return pointcloud - pcd = o3d.geometry.PointCloud() - pcd.points = o3d.utility.Vector3dVector(pointcloud) - return pcd +import threading def finetune_pointcloud_fusion(pcd1: o3d.geometry.PointCloud, pcd2: o3d.geometry.PointCloud): @@ -41,8 +34,11 @@ class PointCloudFusion: def __init__(self, angle=30., x_distance=0.195): self.pcd1 = o3d.geometry.PointCloud() self.pcd2 = o3d.geometry.PointCloud() - self.fine_tuned_transformation = np.eye(4) - self.coarse_transformed = False + self._is_transformed = False + self.fine_transformed = False + # 14cm width and 12.5 height for the box + self.crop_volume = o3d.geometry.AxisAlignedBoundingBox(min_bound=(-0.07, -0.07, 0.075), + max_bound=(0.07, 0.07, 0.2)) t1 = np.eye(4) t1[:3, :3] = R.from_euler("xyz", [angle, 0., 0.], degrees=True).as_matrix() @@ -54,57 +50,136 @@ def __init__(self, angle=30., x_distance=0.195): t2[1, 3] = -x_distance / 2. self.t2 = t2 + def save_finetuned(self): + assert self.fine_transformed + t_finetuned = np.zeros((2, *self.t1.shape)) + t_finetuned[0, ...] = self.t1 + t_finetuned[1, ...] = self.t2 + with open("PointCloudFusionFinetuned.npy", "wb") as f: + np.save(f, t_finetuned) + + def load_finetuned(self): + from os.path import exists + if not exists("PointCloudFusionFinetuned.npy"): + return False + with open("PointCloudFusionFinetuned.npy", "rb") as f: + t_finetuned = np.load(f) + self.t1 = t_finetuned[0, ...] + self.t2 = t_finetuned[1, ...] + self.fine_transformed = True + print(f"loaded finetuned Point Cloud fusion parameters!") + return True + def append(self, pcd: np.ndarray): + # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 if self.pcd1.is_empty(): - self.pcd1 = pointcloud_2_o3d(pcd) + self.pcd1.points = o3d.utility.Vector3dVector(pcd.astype(np.float64)) elif self.pcd2.is_empty(): - self.pcd2 = pointcloud_2_o3d(pcd) + self.pcd2.points = o3d.utility.Vector3dVector(pcd.astype(np.float64)) else: raise NotImplementedError("3 pointclouds not supported") def calibrate_fusion(self): assert self.is_complete() # rough transform - if not self.coarse_transformed: - self._coarse_transform() + if not self._is_transformed: + self._transform() # then calibrate t = finetune_pointcloud_fusion(pcd1=self.pcd1, pcd2=self.pcd2) return t def set_fine_tuned_transformation(self, transformation): - self.fine_tuned_transformation[...] = transformation + assert not self.fine_transformed + + t = transformation.copy()[:3, 3] / 2. # half the translation + rot = np.zeros((2, 3, 3)) + rot[0, ...] = transformation[:3, :3] + rot[1, ...] = np.eye(3) + r = R.from_matrix(rot).mean() # half the rotation + + t1_fine = np.eye(4) + t1_fine[:3, :3] = r.as_matrix() + t1_fine[:3, 3] = t + self.t1 = np.dot(self.t1, t1_fine) + + t2_fine = np.eye(4) + t2_fine[:3, :3] = r.inv().as_matrix() + t2_fine[:3, 3] = -t + self.t2 = np.dot(self.t2, t2_fine) + + self.fine_transformed = True def clear(self): self.pcd1.clear() self.pcd2.clear() - self.coarse_transformed = False + self._is_transformed = False - def _coarse_transform(self): + def _transform(self): self.pcd1.transform(self.t1) self.pcd2.transform(self.t2) - self.coarse_transformed = True + self._is_transformed = True - def fuse_pointclouds(self): - if not self.coarse_transformed: - self._coarse_transform() - self.pcd1.transform(self.fine_tuned_transformation) + def fuse_pointclouds(self, voxelize=False): + if not self._is_transformed: + self._transform() self.pcd1 += self.pcd2 - return self.pcd1 + mm = 1e-3 + if voxelize: + return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), voxel_size=1 * mm) + else: + return self.pcd1.crop(self.crop_volume) - def get_first(self): + def get_first(self, cropped=True): self.pcd1.transform(self.t1) - return self.pcd1 + if cropped: + return self.pcd1.crop(self.crop_volume) + else: + return self.pcd1 def get_both(self): return self.pcd1.__copy__(), self.pcd2.__copy__() - def get_calibration_history(self): - return np.array(self.calibration_history) - def is_complete(self): return not self.pcd1.is_empty() and not self.pcd2.is_empty() def is_empty(self): - return self.pcd1.is_empty() and self.pcd2.is_empty() \ No newline at end of file + return self.pcd1.is_empty() and self.pcd2.is_empty() + + +class CalibrationTread(threading.Thread): + def __init__(self, pc_fusion: PointCloudFusion, num_samples=20, verbose=False, *args, **kwargs): + super(CalibrationTread, self).__init__(*args, **kwargs) + self.pc_fusion = pc_fusion + self.samples = np.zeros((num_samples, 4, 4)) # transformation matrix samples + self.pc_backlog = [] + self.verbose = verbose + + def start(self): + super().start() + if self.verbose: + print(f"Calibration Thread started at {self.native_id}") + + def append_backlog(self, pc1, pc2): + self.pc_backlog.append([pc1, pc2]) + assert self.samples.shape[0] >= len(self.pc_backlog) + + def calibrate(self): + print(f"calibrating for {len(self.pc_backlog)} samples...") + for i, (pc1, pc2) in enumerate(self.pc_backlog): + self.pc_fusion.clear() + self.pc_fusion.append(pc1) + self.pc_fusion.append(pc2) + + self.samples[i, ...] = self.pc_fusion.calibrate_fusion() + + rotations = R.from_matrix(self.samples[:, :3, :3]) + mean_rot = rotations.mean().as_matrix() + translation = np.mean(self.samples[:, :3, 3], axis=0) + + final = np.eye(4) + final[:3, :3] = mean_rot + final[:3, 3] = translation + print(f"calibration result: {final}") + self.pc_fusion.set_fine_tuned_transformation(final) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 96c736df..1dd0bfd0 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -7,6 +7,7 @@ import gymnasium as gym import cv2 import queue +import warnings from typing import Dict from datetime import datetime from collections import OrderedDict @@ -15,7 +16,7 @@ from robotiq_env.camera.video_capture import VideoCapture from robotiq_env.camera.rs_capture import RSCapture -from robotiq_env.camera.utils import PointCloudFusion +from robotiq_env.camera.utils import PointCloudFusion, CalibrationTread from robotiq_env.utils.real_time_plotter import DataClient from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec @@ -43,6 +44,31 @@ def run(self): cv2.waitKey(1) +class PointCloudDisplayer: + def __init__(self): + import open3d as o3d + self.window = o3d.visualization.Visualizer() + self.window.create_window(height=400, width=400, visible=True) + + self.window.get_render_option().load_from_json( + "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/render_options.json") + + self.param = o3d.io.read_pinhole_camera_parameters( + "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/camera_parameters.json") + self.ctr = self.window.get_view_control() + + def display(self, voxelgrid): + self.window.clear_geometries() + self.window.add_geometry(voxelgrid) + self.ctr.convert_from_pinhole_camera_parameters(self.param, True) + + self.window.poll_events() + # self.window.update_renderer() + + def close(self): + self.window.destroy_window() + + ############################################################################## @@ -201,12 +227,20 @@ def __init__( if self.camera_mode is not None: self.init_cameras(config.REALSENSE_CAMERAS) self.img_queue = queue.Queue() - self.displayer = ImageDisplayer(self.img_queue) - self.displayer.start() + if self.camera_mode in ["pointcloud"]: + self.displayer = PointCloudDisplayer() + else: + self.displayer = ImageDisplayer(self.img_queue) + self.displayer.start() print("[CAM] Cameras are ready!") if self.camera_mode in ["pointcloud"]: - self.pointcloud_fusion = PointCloudFusion(angle=31., x_distance=0.196) + self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196) + + # load pre calibrated, else calibrate + if not self.pointcloud_fusion.load_finetuned(): + self.calibration_thread = CalibrationTread(pc_fusion=self.pointcloud_fusion, verbose=True) + self.calibration_thread.start() if self.realtime_plot: try: @@ -270,7 +304,10 @@ def step(self, action: np.ndarray) -> tuple: obs = self._get_obs() dt = time.time() - start_time - time.sleep(max(0, (1.0 / self.hz) - dt)) + to_sleep = max(0, (1.0 / self.hz) - dt) + if to_sleep == 0: + warnings.warn(f"environment could not be within {self.hz} Hz, took {dt:.4f}s!") + time.sleep(to_sleep) reward = self.compute_reward(obs, action) truncated = self._is_truncated() @@ -434,61 +471,73 @@ def get_image(self) -> Dict[str, np.ndarray]: self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() - # self.recording_frames.append( - # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) - # ) - # self.img_queue.put(display_images) - if self.camera_mode in ["pointcloud"]: images["wrist_pointcloud"] = np.zeros((10000, 3)) if self.pointcloud_fusion.is_complete(): - # fused = np.asarray(self.pointcloud_fusion.fuse_pointclouds().points) - # images["wrist_pointcloud"][:fused.shape[0], :] = fused + fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) + self.displayer.display(fused) + # images["wrist_pointcloud"][:fused.shape[0], :] = np.asarray(fused.points) pass elif not self.pointcloud_fusion.is_empty(): pc = np.asarray(self.pointcloud_fusion.get_first().points) # images["wrist_pointcloud"][:pc.shape[0], :] = pc + # self.recording_frames.append( + # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) + # ) + self.img_queue.put(display_images) + return images - def calibrate_pointcloud_fusion(self): + def temporary_pointcloud_visualization(self): + obs, reward, done, truncated, _ = self.step(np.zeros(7)) + fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) + print("what") + + self.controller.robotiq_control.forceModeStop() + self.controller.stop() + input("stopped!") + + import open3d as o3d + o3d.visualization.draw_geometries([fused]) + self.close() + + def calibrate_pointcloud_fusion(self, save=True, visualize=False): assert self.camera_mode in ["pointcloud"] print("calibrating pointcloud fusion...") # calibrate pc fusion here - p_backlog = [] - t_hist = [] # get samples for i in range(20): - action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), - -.3 * np.cos(i * np.pi / 10.), 0., 0.] + # action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), + # -.3 * np.cos(i * np.pi / 10.), 0., 0.] + # action = [0., 0., 0., 0., 0., 1., 0.] + action = [-1. if i % 4 < 2 else 1, -1. if i % 4 in [1, 2] else 1, 0., 0., 0., 1., 0.] + print(action) obs, reward, done, truncated, _ = self.step(np.array(action)) - p_backlog += [*self.pointcloud_fusion.get_both()] + self.calibration_thread.append_backlog(*self.pointcloud_fusion.get_both()) - # stop for now + # calibrate() self.controller.stop() - - # do the calibration - import open3d as o3d - for i in range(20): - self.pointcloud_fusion.clear() - self.pointcloud_fusion.append(p_backlog[i * 2]) - self.pointcloud_fusion.append(p_backlog[i * 2 + 1]) - - t = self.pointcloud_fusion.calibrate_fusion() - t_hist.append(t) - self.pointcloud_fusion.set_fine_tuned_transformation(t) - pcd = self.pointcloud_fusion.fuse_pointclouds() - o3d.visualization.draw_geometries([pcd]) - - t_hist = np.array(t_hist) - print(np.mean(t_hist, axis=0)) - print(np.max(t_hist, axis=0)) - print(np.min(t_hist, axis=0)) - self.pointcloud_fusion.set_fine_tuned_transformation(np.mean(t_hist, axis=0)) + self.calibration_thread.calibrate() + + if save: + self.pointcloud_fusion.save_finetuned() + + if visualize: + import open3d as o3d + for i in range(20): + pcs = self.calibration_thread.pc_backlog[i] + self.pointcloud_fusion.clear() + self.pointcloud_fusion.append(pcs[0]) + self.pointcloud_fusion.append(pcs[1]) + fused = self.pointcloud_fusion.fuse_pointclouds() + o3d.visualization.draw_geometries([fused]) + + self.calibration_thread.join() def close_cameras(self): """Close both wrist cameras.""" From 8bf54b83ea3c9f85e5ace704f9e3c37583c7205c Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 27 Jun 2024 13:28:38 +0200 Subject: [PATCH 195/338] continuous box change instead of random (better setup, easier to reproduce) --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 1dd0bfd0..ba3be9e9 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -110,7 +110,7 @@ def __init__( max_episode_length: int = 100, save_video: bool = False, realtime_plot: bool = False, - camera_mode: str = "rgb", # one of (rgb, depth, both, None) + camera_mode: str = "rgb", # one of (rgb, depth, both, pointcloud, none) ): self.max_episode_length = max_episode_length self.action_scale = config.ACTION_SCALE @@ -335,8 +335,8 @@ def go_to_rest(self, joint_reset=False): if self.resetQ.shape == (1, 6): reset_Q[:] = self.resetQ.copy() elif self.resetQ.shape[1] == 6 and self.resetQ.shape[0] > 1: - choice = np.random.randint(self.resetQ.shape[0]) - reset_Q[:] = self.resetQ[choice, :].copy() # make random guess + reset_Q[:] = self.resetQ[0, :].copy() # make random guess + self.resetQ[:] = np.roll(self.resetQ, 1, axis=0) # roll one (not random) else: raise ValueError(f"invalid resetQ dimension: {self.resetQ.shape}") From fb79d9f9c7f690280b594b458c5a3576ee58aa44 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 27 Jun 2024 14:20:11 +0200 Subject: [PATCH 196/338] some bugfixes regarding pc calibration --- serl_robot_infra/robotiq_env/camera/utils.py | 23 ++++++--- .../robotiq_env/envs/robotiq_env.py | 48 ++++++++----------- 2 files changed, 37 insertions(+), 34 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 624b42e6..fe5b8197 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -2,6 +2,7 @@ import open3d as o3d from scipy.spatial.transform import Rotation as R import threading +from typing import Any def finetune_pointcloud_fusion(pcd1: o3d.geometry.PointCloud, pcd2: o3d.geometry.PointCloud): @@ -34,6 +35,7 @@ class PointCloudFusion: def __init__(self, angle=30., x_distance=0.195): self.pcd1 = o3d.geometry.PointCloud() self.pcd2 = o3d.geometry.PointCloud() + self.original_pcds = [] self._is_transformed = False self.fine_transformed = False # 14cm width and 12.5 height for the box @@ -70,12 +72,16 @@ def load_finetuned(self): print(f"loaded finetuned Point Cloud fusion parameters!") return True - def append(self, pcd: np.ndarray): + def append(self, pcd: np.ndarray | o3d.utility.Vector3dVector): + assert type(pcd) == np.ndarray or type(pcd) == o3d.utility.Vector3dVector # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 + func = lambda x: o3d.utility.Vector3dVector(x.astype(np.float64)) if isinstance(pcd, np.ndarray) else x if self.pcd1.is_empty(): - self.pcd1.points = o3d.utility.Vector3dVector(pcd.astype(np.float64)) + self.original_pcds.append(func(pcd)) + self.pcd1.points = func(pcd) elif self.pcd2.is_empty(): - self.pcd2.points = o3d.utility.Vector3dVector(pcd.astype(np.float64)) + self.original_pcds.append(func(pcd)) + self.pcd2.points = func(pcd) else: raise NotImplementedError("3 pointclouds not supported") @@ -114,6 +120,7 @@ def clear(self): self.pcd1.clear() self.pcd2.clear() self._is_transformed = False + self.original_pcds = [] def _transform(self): self.pcd1.transform(self.t1) @@ -132,14 +139,18 @@ def fuse_pointclouds(self, voxelize=False): return self.pcd1.crop(self.crop_volume) def get_first(self, cropped=True): - self.pcd1.transform(self.t1) + if not self._is_transformed: + self.pcd1.transform(self.t1) if cropped: return self.pcd1.crop(self.crop_volume) else: return self.pcd1 - def get_both(self): - return self.pcd1.__copy__(), self.pcd2.__copy__() + def get_original_pcds(self): + if len(self.original_pcds) == 1: + return self.original_pcds[0] + else: + return self.original_pcds def is_complete(self): return not self.pcd1.is_empty() and not self.pcd2.is_empty() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index ba3be9e9..f8c9b45a 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -113,6 +113,7 @@ def __init__( camera_mode: str = "rgb", # one of (rgb, depth, both, pointcloud, none) ): self.max_episode_length = max_episode_length + self.curr_path_length = 0 self.action_scale = config.ACTION_SCALE self.config = config @@ -234,14 +235,6 @@ def __init__( self.displayer.start() print("[CAM] Cameras are ready!") - if self.camera_mode in ["pointcloud"]: - self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196) - - # load pre calibrated, else calibrate - if not self.pointcloud_fusion.load_finetuned(): - self.calibration_thread = CalibrationTread(pc_fusion=self.pointcloud_fusion, verbose=True) - self.calibration_thread.start() - if self.realtime_plot: try: self.plotting_client = DataClient() @@ -253,6 +246,16 @@ def __init__( time.sleep(0.1) print("[RIC] Controller has started and is ready!") + if self.camera_mode in ["pointcloud"]: + self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196) + + # load pre calibrated, else calibrate + if not self.pointcloud_fusion.load_finetuned(): + self.calibration_thread = CalibrationTread(pc_fusion=self.pointcloud_fusion, verbose=True) + self.calibration_thread.start() + + self.calibrate_pointcloud_fusion(visualize=True) + def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat """Clip the pose to be within the safety box.""" @@ -336,7 +339,7 @@ def go_to_rest(self, joint_reset=False): reset_Q[:] = self.resetQ.copy() elif self.resetQ.shape[1] == 6 and self.resetQ.shape[0] > 1: reset_Q[:] = self.resetQ[0, :].copy() # make random guess - self.resetQ[:] = np.roll(self.resetQ, 1, axis=0) # roll one (not random) + self.resetQ[:] = np.roll(self.resetQ, 1, axis=0) # roll one (not random) else: raise ValueError(f"invalid resetQ dimension: {self.resetQ.shape}") @@ -349,7 +352,6 @@ def go_to_rest(self, joint_reset=False): reset_pose = self.controller.get_target_pos() if self.random_reset: # randomize reset position in xy plane - # reset_pose = self.resetpos.copy() reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) reset_pose[:2] += reset_shift @@ -472,7 +474,7 @@ def get_image(self) -> Dict[str, np.ndarray]: return self.get_image() if self.camera_mode in ["pointcloud"]: - images["wrist_pointcloud"] = np.zeros((10000, 3)) + images["wrist_pointcloud"] = np.zeros((10000, 3)) # TODO make clean if self.pointcloud_fusion.is_complete(): fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) @@ -490,38 +492,27 @@ def get_image(self) -> Dict[str, np.ndarray]: return images - def temporary_pointcloud_visualization(self): - obs, reward, done, truncated, _ = self.step(np.zeros(7)) - fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) - print("what") - - self.controller.robotiq_control.forceModeStop() - self.controller.stop() - input("stopped!") - - import open3d as o3d - o3d.visualization.draw_geometries([fused]) - self.close() + def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20): + self.reset() - def calibrate_pointcloud_fusion(self, save=True, visualize=False): assert self.camera_mode in ["pointcloud"] print("calibrating pointcloud fusion...") # calibrate pc fusion here # get samples - for i in range(20): + for i in range(num_samples): # action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), # -.3 * np.cos(i * np.pi / 10.), 0., 0.] - # action = [0., 0., 0., 0., 0., 1., 0.] action = [-1. if i % 4 < 2 else 1, -1. if i % 4 in [1, 2] else 1, 0., 0., 0., 1., 0.] print(action) obs, reward, done, truncated, _ = self.step(np.array(action)) - self.calibration_thread.append_backlog(*self.pointcloud_fusion.get_both()) + self.calibration_thread.append_backlog(*self.pointcloud_fusion.get_original_pcds()) # calibrate() self.controller.stop() + time.sleep(1) self.calibration_thread.calibrate() if save: @@ -529,7 +520,7 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False): if visualize: import open3d as o3d - for i in range(20): + for i in range(num_samples): pcs = self.calibration_thread.pc_backlog[i] self.pointcloud_fusion.clear() self.pointcloud_fusion.append(pcs[0]) @@ -538,6 +529,7 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False): o3d.visualization.draw_geometries([fused]) self.calibration_thread.join() + exit(f"restart the program to use the calibrated values") def close_cameras(self): """Close both wrist cameras.""" From dc54e440e4a64bf56672fd97076b4cb4c1a5d9de Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 27 Jun 2024 14:45:35 +0200 Subject: [PATCH 197/338] added new X & Y max range for the robot arm in the final configuration --- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 10 +++++----- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 9 +++++++++ 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 28f4f9ef..9c2358f0 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -1,12 +1,12 @@ import numpy as np from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.camera_env.config import RobotiqCameraConfig, RobotiqCameraConfigBox5 +from robotiq_env.envs.camera_env.config import RobotiqCameraConfig, RobotiqCameraConfigBox5, RobotiqCameraConfigFinal class RobotiqCameraEnv(RobotiqEnv): def __init__(self, **kwargs): - super().__init__(**kwargs, config=RobotiqCameraConfigBox5) + super().__init__(**kwargs, config=RobotiqCameraConfigFinal) self.plot_costs_yes = False if self.plot_costs_yes: self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], @@ -46,12 +46,12 @@ def compute_reward(self, obs, action) -> float: downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.5 * float(obs["state"]["gripper_state"][1] > 0.9) - suction_cost = 0.5 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99)) + suction_cost = 0.5 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 orientation_cost *= 25. - max_pose_diff = 0.05 # set to 5cm + max_pose_diff = 0.03 # set to 3cm pos_diff = obs["state"]["tcp_pose"][:2] - self.curr_reset_pose[:2] position_cost = 10. * np.sum( np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0)) @@ -64,7 +64,7 @@ def compute_reward(self, obs, action) -> float: def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.10 # new min height with box + return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > self.curr_reset_pose[2] + 0.02 # +2cm def close(self): if self.plot_costs_yes: diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index f8c9b45a..a889c1ed 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -81,6 +81,7 @@ class DefaultEnvConfig: RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.zeros((6,)) ABS_POSE_LIMIT_LOW = np.zeros((6,)) + ABS_POSE_RANGE_LIMITS = np.zeros((2,)) ACTION_SCALE = np.zeros((3,), dtype=np.float32) ROBOT_IP: str = "localhost" @@ -149,6 +150,11 @@ def __init__( config.ABS_POSE_LIMIT_HIGH[:3], dtype=np.float64, ) + self.xy_range = gym.spaces.Box( + config.ABS_POSE_RANGE_LIMITS[0], + config.ABS_POSE_RANGE_LIMITS[1], + dtype=np.float64, + ) self.rpy_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[3:], config.ABS_POSE_LIMIT_HIGH[3:], @@ -262,6 +268,9 @@ def clip_safety_box(self, next_pos[:3] = np.clip( next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high ) + xy_range = np.clip(np.linalg.norm(next_pos[:2], 2), self.xy_range.low, self.xy_range.high) + next_pos[:2] = next_pos[:2] / np.linalg.norm(next_pos[:2]) * xy_range + euler = R.from_quat(next_pos[3:]).as_euler("xyz") # Clip first euler angle separately due to discontinuity from pi to -pi From bbf8f64b0ff78a187b9f888a0c9e9a93bdd17762 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 27 Jun 2024 15:58:03 +0200 Subject: [PATCH 198/338] more bugfixes --- serl_robot_infra/robotiq_env/camera/utils.py | 19 +++++++----- .../robotiq_env/envs/camera_env/config.py | 31 +++++++++++++++++++ .../robotiq_env/envs/robotiq_env.py | 9 +++--- 3 files changed, 47 insertions(+), 12 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index fe5b8197..894676a5 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -32,15 +32,17 @@ def pairwise_registration(source, target, max_correspondence_distance): class PointCloudFusion: - def __init__(self, angle=30., x_distance=0.195): + def __init__(self, angle=30., x_distance=0.195, voxel_size=1): self.pcd1 = o3d.geometry.PointCloud() self.pcd2 = o3d.geometry.PointCloud() - self.original_pcds = [] - self._is_transformed = False - self.fine_transformed = False + self.voxel_size = 1e-3 * voxel_size # in mm + # 14cm width and 12.5 height for the box self.crop_volume = o3d.geometry.AxisAlignedBoundingBox(min_bound=(-0.07, -0.07, 0.075), max_bound=(0.07, 0.07, 0.2)) + self.original_pcds = [] + self._is_transformed = False + self.fine_transformed = False t1 = np.eye(4) t1[:3, :3] = R.from_euler("xyz", [angle, 0., 0.], degrees=True).as_matrix() @@ -132,17 +134,18 @@ def fuse_pointclouds(self, voxelize=False): self._transform() self.pcd1 += self.pcd2 - mm = 1e-3 if voxelize: - return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), voxel_size=1 * mm) + return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), voxel_size=self.voxel_size) else: return self.pcd1.crop(self.crop_volume) - def get_first(self, cropped=True): + def get_first(self, cropped=True, voxelize=False): if not self._is_transformed: self.pcd1.transform(self.t1) if cropped: - return self.pcd1.crop(self.crop_volume) + self.pcd1 = self.pcd1.crop(self.crop_volume) + if voxelize: + return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1, voxel_size=self.voxel_size) else: return self.pcd1 diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 7796bc87..12f6a5a4 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -56,3 +56,34 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): } +class RobotiqCameraConfigFinal(DefaultEnvConfig): + RESET_Q = np.array([ # TODO new ones and more + [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], + [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], + [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], + [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], + [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] + ]) + RANDOM_RESET = False + RANDOM_XY_RANGE = (0.00,) + RANDOM_RZ_RANGE = (0.0,) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.18, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.8, -0.18, -3.2]) + ABS_POSE_RANGE_LIMITS = np.array([0.35, 0.85]) + ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + + ROBOT_IP: str = "172.22.22.2" + CONTROLLER_HZ = 100 + GRIPPER_TIMEOUT = 2000 # in milliseconds + ERROR_DELTA: float = 0.05 + FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_TASK_FRAME = np.zeros(6) + FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) + + REALSENSE_CAMERAS = { + "wrist": "218622277164", + "wrist2": "218622279756" + } + + diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index a889c1ed..82f65239 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -235,7 +235,7 @@ def __init__( self.init_cameras(config.REALSENSE_CAMERAS) self.img_queue = queue.Queue() if self.camera_mode in ["pointcloud"]: - self.displayer = PointCloudDisplayer() + self.displayer = PointCloudDisplayer() # o3d displayer cannot be threaded :/ else: self.displayer = ImageDisplayer(self.img_queue) self.displayer.start() @@ -483,15 +483,16 @@ def get_image(self) -> Dict[str, np.ndarray]: return self.get_image() if self.camera_mode in ["pointcloud"]: - images["wrist_pointcloud"] = np.zeros((10000, 3)) # TODO make clean + images["wrist_pointcloud"] = np.zeros((10000, 3), dtype=np.float32) # TODO make clean if self.pointcloud_fusion.is_complete(): fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) self.displayer.display(fused) + # images["wrist_pointcloud"][:fused.shape[0], :] = np.asarray(fused.points) - pass elif not self.pointcloud_fusion.is_empty(): - pc = np.asarray(self.pointcloud_fusion.get_first().points) + pc = self.pointcloud_fusion.get_first(cropped=True, voxelize=True) + self.displayer.display(pc) # images["wrist_pointcloud"][:pc.shape[0], :] = pc # self.recording_frames.append( From b49c0e68d5bcf7cd432d1688b27ade8e8acb7010 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:13:34 +0200 Subject: [PATCH 199/338] Important Relative Env fix (do not use adjoint with matrix with actions) --- .../franka_env/utils/transformations.py | 8 ++++++++ serl_robot_infra/robotiq_env/envs/relative_env.py | 14 +++++++++----- 2 files changed, 17 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/franka_env/utils/transformations.py b/serl_robot_infra/franka_env/utils/transformations.py index 52a55527..3687237b 100644 --- a/serl_robot_infra/franka_env/utils/transformations.py +++ b/serl_robot_infra/franka_env/utils/transformations.py @@ -23,6 +23,14 @@ def construct_adjoint_matrix(tcp_pose): return adjoint_matrix +def construct_rotation_matrix(tcp_pose): + """ + Construct the adjoint matrix for a spatial velocity vector + :args: tcp_pose: (x, y, z, qx, qy, qz, qw) + """ + return R.from_quat(tcp_pose[3:]).as_matrix() + + def construct_homogeneous_matrix(tcp_pose): """ Construct the homogeneous transformation matrix from given pose. diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index 0f08da0d..07f9a169 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -5,6 +5,7 @@ from franka_env.utils.transformations import ( construct_adjoint_matrix, construct_homogeneous_matrix, + construct_rotation_matrix ) @@ -29,6 +30,7 @@ class RelativeFrame(gym.Wrapper): def __init__(self, env: Env, include_relative_pose=True): super().__init__(env) self.adjoint_matrix = np.zeros((6, 6)) + self.rotation_matrix = np.eye((3)) self.include_relative_pose = include_relative_pose if self.include_relative_pose: @@ -46,8 +48,9 @@ def step(self, action: np.ndarray): if "intervene_action" in info: info["intervene_action"] = self.transform_action_inv(info["intervene_action"]) - # Update adjoint matrix + # Update adjoint and rotation matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) + self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) # Transform observation to spatial frame transformed_obs = self.transform_observation(obs) @@ -58,8 +61,9 @@ def reset(self, **kwargs): # obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) - # Update adjoint matrix + # Update adjoint and rotation matrix self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) + self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) if self.include_relative_pose: # Update transformation matrix from the reset pose's relative frame to base frame self.T_r_o_inv = np.linalg.inv( @@ -90,11 +94,11 @@ def transform_observation(self, obs): def transform_action(self, action: np.ndarray): """ - Transform action from body(end-effector) frame into into spatial(base) frame + Transform action from body(end-effector) frame into spatial(base) frame using the adjoint matrix """ action = np.array(action) # in case action is a jax read-only array - action[:6] = self.adjoint_matrix @ action[:6] + action[:3] = self.rotation_matrix @ action[:3] return action def transform_action_inv(self, action: np.ndarray): @@ -103,5 +107,5 @@ def transform_action_inv(self, action: np.ndarray): using the adjoint matrix. """ action = np.array(action) - action[:6] = np.linalg.inv(self.adjoint_matrix) @ action[:6] + action[:3] = np.linalg.inv(self.rotation_matrix) @ action[:3] return action From 854d007e718fb624f3b2ba78f303172ed639674b Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:27:07 +0200 Subject: [PATCH 200/338] Voxel Grid Env setup (for now too slow, optimize or use gpu) --- .../serl_launcher/agents/continuous/drq.py | 10 ++++++++ .../robotiq_env/envs/robotiq_env.py | 23 +++++++++++-------- 2 files changed, 24 insertions(+), 9 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 0acdab0a..6a42bb74 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -233,6 +233,16 @@ def create_drq( ) for image_key in image_keys } + elif encoder_type == "voxel_mlp": + encoders = { + image_key: MLP( + hidden_dims=[128, 128], + activations=nn.relu, + activate_final=True, + use_layer_norm=True, + ) + for image_key in image_keys + } # TODO check if stop_gradient has to be removed elif encoder_type.lower() == "none": encoders = None else: diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 82f65239..1e95db51 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -185,7 +185,7 @@ def __init__( if camera_mode in ["pointcloud"]: image_space_definition["wrist_pointcloud"] = gym.spaces.Box( - -np.inf, np.inf, shape=(10000, 3), dtype=np.float32 + 0, 1, shape=(140, 140, 125), dtype=np.bool_ ) if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud"]: @@ -348,7 +348,7 @@ def go_to_rest(self, joint_reset=False): reset_Q[:] = self.resetQ.copy() elif self.resetQ.shape[1] == 6 and self.resetQ.shape[0] > 1: reset_Q[:] = self.resetQ[0, :].copy() # make random guess - self.resetQ[:] = np.roll(self.resetQ, 1, axis=0) # roll one (not random) + self.resetQ[:] = np.roll(self.resetQ, -1, axis=0) # roll one (not random) else: raise ValueError(f"invalid resetQ dimension: {self.resetQ.shape}") @@ -483,17 +483,22 @@ def get_image(self) -> Dict[str, np.ndarray]: return self.get_image() if self.camera_mode in ["pointcloud"]: - images["wrist_pointcloud"] = np.zeros((10000, 3), dtype=np.float32) # TODO make clean + voxel_grid = np.zeros(self.pointcloud_fusion.get_voxelgrid_shape(), dtype=np.bool_) if self.pointcloud_fusion.is_complete(): - fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) - self.displayer.display(fused) - - # images["wrist_pointcloud"][:fused.shape[0], :] = np.asarray(fused.points) + pc = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) elif not self.pointcloud_fusion.is_empty(): pc = self.pointcloud_fusion.get_first(cropped=True, voxelize=True) - self.displayer.display(pc) - # images["wrist_pointcloud"][:pc.shape[0], :] = pc + + self.displayer.display(pc) + # TODO takes too long to calculate, do it with numba or otherwise faster + # t = time.time() + # indices = np.stack(list(vx.grid_index for vx in pc.get_voxels())) + # x, y, z = np.moveaxis(indices, -1, 0) + # voxel_grid[x, y, z] = True # fill voxel grid + # images["wrist_pointcloud"] = voxel_grid + # print(f"took {time.time() - t:.4f}s") + images["wrist_pointcloud"] = voxel_grid # self.recording_frames.append( # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) From 96905df2afc26fc42764c582b9f7f56a9773a14f Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:27:35 +0200 Subject: [PATCH 201/338] New config file for Box setup --- .../robotiq_env/envs/camera_env/config.py | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 12f6a5a4..f03f06b2 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -57,12 +57,17 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): class RobotiqCameraConfigFinal(DefaultEnvConfig): - RESET_Q = np.array([ # TODO new ones and more - [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], - [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], - [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], - [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], - [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] + RESET_Q = np.array([ + [2.6259, - 1.5196, 2.1287, - 2.1784, - 1.5665, - 0.4741], + [2.0131, - 1.271, 1.9316, - 2.2306, - 1.566, 0.4537], + [1.8937, - 0.8222, 1.239, - 1.9868, - 1.565, 0.3668], + [1.4173, - 1.6375, 2.2516, - 2.1841, - 1.5668, - 0.1285], + [1.4715, - 0.8744, 1.2767, - 1.9723, - 1.5653, - 0.0874], + [1.12, - 0.7634, 1.1184, - 1.9248, - 1.5653, - 0.4334], + [1.0242, - 1.3104, 2.0986, - 2.358, - 1.5664, - 2.0496], + [0.7431, - 1.0746, 1.6486, - 2.1441, - 1.5655, - 0.7738], + [0.4391, - 1.5926, 2.3356, - 2.3129, - 1.5668, - 1.1115], + [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.00,) @@ -85,5 +90,3 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): "wrist": "218622277164", "wrist2": "218622279756" } - - From c530b78ca1bc183fc13bb345f16a2a380e0f6880 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:33:40 +0200 Subject: [PATCH 202/338] new cost config --- .../envs/camera_env/robotiq_camera_env.py | 37 +++---------------- 1 file changed, 5 insertions(+), 32 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 9c2358f0..3f1b37e5 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -12,40 +12,12 @@ def __init__(self, **kwargs): self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], downward_force_cost=[]) - """def compute_reward(self, obs, action) -> float: old reward computation - # huge action gives negative reward (like in mountain car) - action_cost = 0.1 * np.sum(np.power(action, 2)) - step_cost = 0.01 - - gripper_state = obs["state"]['gripper_state'] - suction_cost = 0.2 * float(is_close(gripper_state[0], 0.99)) - suction_reward = 0.1 * float(0.1 < gripper_state[0] < 0.85) - downward_force_cost = 0.4 * max(obs["state"]["tcp_force"][2] - 5, 0.) - - torque = obs["state"]['tcp_torque'] - non_central_cost = 0.5 * max(np.linalg.norm(torque[:2]) - 0.07, 0.) - - if self.plot_costs_yes: - self.reward_hist['action_cost'].append(-action_cost) - self.reward_hist['suction_cost'].append(-suction_cost) - self.reward_hist['non_central_cost'].append(-non_central_cost) - self.reward_hist['suction_reward'].append(suction_reward) - self.reward_hist['downward_force_cost'].append(-downward_force_cost) - - total_cost = action_cost + step_cost + suction_cost + non_central_cost + downward_force_cost - if self.reached_goal_state(obs): - box_is_central = np.sum(np.power(torque[:2], 2)) - 0.1 < 0. - # return (100. if box_is_central else 50.) - action_cost - step_cost - suction_cost - return 100. - total_cost - else: - return 0.0 - total_cost + suction_reward""" - def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) - step_cost = 0.01 + step_cost = 0.05 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) - suction_reward = 0.5 * float(obs["state"]["gripper_state"][1] > 0.9) + suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.9) suction_cost = 0.5 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 @@ -59,7 +31,8 @@ def compute_reward(self, obs, action) -> float: if self.reached_goal_state(obs): return 100. - action_cost - orientation_cost - position_cost else: - return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - suction_cost + return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ + suction_cost - step_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis @@ -71,7 +44,7 @@ def close(self): self.plot_costs() super().close() - def plot_costs(self): + def plot_costs(self): # not used anymore import matplotlib.pyplot as plt fig, ax = plt.subplots(6, 1, figsize=(12, 10), sharey=True, sharex=True) y = np.arange(len(self.reward_hist["action_cost"])) From a7c5e8376e8cfab28a3ae31bcd59c0390985d07d Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:48:52 +0200 Subject: [PATCH 203/338] implemented image space dynamic adaption (if multi or single cam) --- .../robotiq_env/envs/robotiq_env.py | 36 +++++++++++-------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 1e95db51..2a21a14b 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -168,20 +168,24 @@ def __init__( image_space_definition = {} if camera_mode in ["rgb", "both"]: - # image_space_definition["shoulder"] = gym.spaces.Box( - # 0, 255, shape=(128, 128, 3), dtype=np.uint8 - # ) - image_space_definition["wrist"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 - ) + if "wrist" in config.REALSENSE_CAMERAS.keys(): + image_space_definition["wrist"] = gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ) + if "wrist_2" in config.REALSENSE_CAMERAS.keys(): + image_space_definition["wrist_2"] = gym.spaces.Box( + 0, 255, shape=(128, 128, 3), dtype=np.uint8 + ) if camera_mode in ["depth", "both"]: - # image_space_definition["shoulder_depth"] = gym.spaces.Box( - # 0, 255, shape=(128, 128, 1), dtype=np.uint8 - # ) - image_space_definition["wrist_depth"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 1), dtype=np.uint8 - ) + if "wrist" in config.REALSENSE_CAMERAS.keys(): + image_space_definition["wrist_depth"] = gym.spaces.Box( + 0, 255, shape=(128, 128, 1), dtype=np.uint8 + ) + if "wrist_2" in config.REALSENSE_CAMERAS.keys(): + image_space_definition["wrist_2_depth"] = gym.spaces.Box( + 0, 255, shape=(128, 128, 1), dtype=np.uint8 + ) if camera_mode in ["pointcloud"]: image_space_definition["wrist_pointcloud"] = gym.spaces.Box( @@ -427,8 +431,8 @@ def crop_image(self, name, image) -> np.ndarray: """Crop realsense images to be a square.""" if name == "wrist": return image[:, 124:604, :] - elif name == "shoulder": - raise NotImplementedError("shoulder needs to be implemented") + elif name == "wrist_2": + return image[:, 124:604, :] else: raise ValueError(f"Camera {name} not recognized in cropping") @@ -436,7 +440,8 @@ def get_image(self) -> Dict[str, np.ndarray]: """Get images from the realsense cameras.""" images = {} display_images = {} - self.pointcloud_fusion.clear() + if self.camera_mode == "pointcloud": + self.pointcloud_fusion.clear() for key, cap in self.cap.items(): try: image = cap.read() @@ -452,6 +457,7 @@ def get_image(self) -> Dict[str, np.ndarray]: # resized = resized.astype(np.uint8) images[key] = resized[..., ::-1] + display_images[key] = resized # display_images[key] = np.repeat(resized, 3, axis=-1) display_images[key + "_full"] = cropped_rgb From c077c36e27178c7562f5d693eadf4907a1c47731 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:49:15 +0200 Subject: [PATCH 204/338] updated config --- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index f03f06b2..61fccced 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -22,7 +22,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): REALSENSE_CAMERAS = { "wrist": "218622277164", - "wrist2": "218622279756" + "wrist_2": "218622279756" } @@ -88,5 +88,5 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): REALSENSE_CAMERAS = { "wrist": "218622277164", - "wrist2": "218622279756" + "wrist_2": "218622279756" } From deef2863ee19dd40b11856ee37fbad28f5c7e932 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:49:40 +0200 Subject: [PATCH 205/338] pointcloud and voxel bugfixes --- serl_robot_infra/robotiq_env/camera/utils.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 894676a5..69b62226 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -32,14 +32,16 @@ def pairwise_registration(source, target, max_correspondence_distance): class PointCloudFusion: - def __init__(self, angle=30., x_distance=0.195, voxel_size=1): + def __init__(self, angle=30., x_distance=0.195, voxel_size: int = 1): self.pcd1 = o3d.geometry.PointCloud() self.pcd2 = o3d.geometry.PointCloud() - self.voxel_size = 1e-3 * voxel_size # in mm + self.voxel_size = 1e-3 * voxel_size # in mm # 14cm width and 12.5 height for the box self.crop_volume = o3d.geometry.AxisAlignedBoundingBox(min_bound=(-0.07, -0.07, 0.075), - max_bound=(0.07, 0.07, 0.2)) + max_bound=( + 0.07 - self.voxel_size, 0.07 - self.voxel_size, + 0.2 - self.voxel_size)) self.original_pcds = [] self._is_transformed = False self.fine_transformed = False @@ -62,6 +64,10 @@ def save_finetuned(self): with open("PointCloudFusionFinetuned.npy", "wb") as f: np.save(f, t_finetuned) + def get_voxelgrid_shape(self): + return ((np.asarray(self.crop_volume.get_max_bound()) - np.asarray( + self.crop_volume.get_min_bound())) / self.voxel_size).astype(np.int16) + 1 + def load_finetuned(self): from os.path import exists if not exists("PointCloudFusionFinetuned.npy"): @@ -135,7 +141,8 @@ def fuse_pointclouds(self, voxelize=False): self.pcd1 += self.pcd2 if voxelize: - return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), voxel_size=self.voxel_size) + return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), + voxel_size=self.voxel_size) else: return self.pcd1.crop(self.crop_volume) From d08b205662d0f809b7f6934f734edc777af03bc0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 14:57:18 +0200 Subject: [PATCH 206/338] new actor learner configs --- examples/robotiq_drq/drq_policy_robotiq.py | 13 +++++++++---- examples/robotiq_drq/run_actor.sh | 2 +- examples/robotiq_drq/run_learner.sh | 8 ++++---- 3 files changed, 14 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index e8f2665e..806964fd 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -58,7 +58,7 @@ flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 10000, +flags.DEFINE_integer("replay_buffer_capacity", 15000, "Replay buffer capacity.") # quite low to forget demo trajectories flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") @@ -72,7 +72,6 @@ flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") @@ -473,6 +472,12 @@ def create_replay_buffer_and_wandb_logger(): for obs_name in to_pop: traj["observations"].pop(obs_name) traj["next_observations"].pop(obs_name) + + # TODO remove afterwards, set all images to grayscale + # gray = np.array([0.2989, 0.5870, 0.1140]) + # traj["observations"]["wrist"] = np.dot(traj["observations"]["wrist"], gray)[..., None] + # traj["next_observations"]["wrist"] = np.dot(traj["next_observations"]["wrist"], gray)[..., None] + replay_buffer.insert(traj) print(f"replay buffer size: {len(replay_buffer)}") @@ -501,8 +506,8 @@ def create_replay_buffer_and_wandb_logger(): try: actor(agent, data_store, env, sampling_rng) print_green("actor loop finished") - except KeyboardInterrupt: - print_green("actor loop interrupted") + except (KeyboardInterrupt, RuntimeError) as e: + print_green("actor loop interrupted: " + str(e)) finally: env.close() diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index a40331bb..eca0d550 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -5,7 +5,7 @@ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ --max_traj_length 100 \ - --exp_name=drq_rgb_5box \ + --exp_name=drq_10box \ --camera_mode rgb \ --seed 1 \ --max_steps 30000 \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index fc7875ef..ee7706fb 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -3,17 +3,17 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name=drq_rgb_5box \ + --exp_name=drq_10box \ --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ - --max_steps 20000 \ + --max_steps 25000 \ --random_steps 500 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1000 \ + --eval_period 2500 \ --encoder_type resnet-pretrained-18 \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai31_5box.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jun28_10box.pkl \ # --debug From c66abd254f1443be6a7f00a86933ad337e6ed670 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 17:21:41 +0200 Subject: [PATCH 207/338] made now Env config to test policy on --- examples/robotiq_drq/run_evaluation.sh | 4 ++-- serl_robot_infra/robotiq_env/__init__.py | 8 +++++++- .../robotiq_env/envs/camera_env/__init__.py | 2 +- .../robotiq_env/envs/camera_env/config.py | 10 ++++++++-- .../envs/camera_env/robotiq_camera_env.py | 16 ++++++++++++---- 5 files changed, 30 insertions(+), 10 deletions(-) diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/robotiq_drq/run_evaluation.sh index 67cbe773..74d20c61 100644 --- a/examples/robotiq_drq/run_evaluation.sh +++ b/examples/robotiq_drq/run_evaluation.sh @@ -2,11 +2,11 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_tests \ --exp_name=drq_evaluation \ --max_traj_length 100 \ --camera_mode rgb \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0606-16:05 rgb Res18 avg"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0628-14:59 10box res18 avg"\ --eval_checkpoint_step 20000 \ --encoder_type resnet-pretrained-18 \ --eval_n_trajs 20 \ diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index ce5844db..8257406c 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -11,4 +11,10 @@ id="robotiq_camera_env", entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnv", max_episode_steps=100, -) \ No newline at end of file +) + +register( + id="robotiq_camera_env_tests", + entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnvTest", + max_episode_steps=100, +) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py index 7117d00e..b29e3c64 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py @@ -1 +1 @@ -from robotiq_env.envs.camera_env.robotiq_camera_env import RobotiqCameraEnv \ No newline at end of file +from robotiq_env.envs.camera_env.robotiq_camera_env import RobotiqCameraEnv, RobotiqCameraEnvTest \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 61fccced..44b92374 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -74,7 +74,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.18, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.8, -0.18, -3.2]) - ABS_POSE_RANGE_LIMITS = np.array([0.35, 0.85]) + ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" @@ -88,5 +88,11 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): REALSENSE_CAMERAS = { "wrist": "218622277164", - "wrist_2": "218622279756" + # "wrist_2": "218622279756" } + + +class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): + RESET_Q = np.array([ + [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], + ]) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 3f1b37e5..dbb32d6d 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -1,12 +1,15 @@ import numpy as np from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.camera_env.config import RobotiqCameraConfig, RobotiqCameraConfigBox5, RobotiqCameraConfigFinal +from robotiq_env.envs.camera_env.config import RobotiqCameraConfigFinal, RobotiqCameraConfigFinalTests class RobotiqCameraEnv(RobotiqEnv): - def __init__(self, **kwargs): - super().__init__(**kwargs, config=RobotiqCameraConfigFinal) + def __init__(self, load_config=True, **kwargs): + if load_config: + super().__init__(**kwargs, config=RobotiqCameraConfigFinal) + else: + super().__init__(**kwargs) self.plot_costs_yes = False if self.plot_costs_yes: self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], @@ -44,7 +47,7 @@ def close(self): self.plot_costs() super().close() - def plot_costs(self): # not used anymore + def plot_costs(self): # not used anymore import matplotlib.pyplot as plt fig, ax = plt.subplots(6, 1, figsize=(12, 10), sharey=True, sharex=True) y = np.arange(len(self.reward_hist["action_cost"])) @@ -66,3 +69,8 @@ def plot_costs(self): # not used anymore ax6.legend() plt.show() + + +class RobotiqCameraEnvTest(RobotiqCameraEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, load_config=False, config=RobotiqCameraConfigFinalTests) From dec750fed6364733a147ed6535760cfd052a3fea Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 18:17:53 +0200 Subject: [PATCH 208/338] test boxes at an angle --- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 44b92374..a05edb06 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -94,5 +94,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RESET_Q = np.array([ - [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], + [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237], ]) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.3, 3.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.6, -0.3, -3.2]) From 7a2c2c2da69b61e5d3296cf8fd5f808f56ef31fe Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 18:18:05 +0200 Subject: [PATCH 209/338] new name for wandb --- examples/robotiq_drq/drq_policy_robotiq.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 806964fd..8ef0fa25 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -447,7 +447,7 @@ def create_replay_buffer_and_wandb_logger(): ) # set up wandb and logging wandb_logger = make_wandb_logger( - project="serl_dev", + project="drq_picking", description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) From 480a5645ea4e5a23826c07abba45c0e0f1d2a126 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 28 Jun 2024 18:18:55 +0200 Subject: [PATCH 210/338] added Observation statistics wrapper to investigate episodes --- .../observation_statistics_wrapper.py | 83 +++++++++++++++++++ 1 file changed, 83 insertions(+) create mode 100644 serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py diff --git a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py new file mode 100644 index 00000000..8726a124 --- /dev/null +++ b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py @@ -0,0 +1,83 @@ +import numpy as np +from collections import deque +import gymnasium as gym + + +class ObservationStatisticsWrapper(gym.Wrapper, gym.utils.RecordConstructorArgs): + """ + This wrapper will keep track of the observation statistics. + + At the end of an episode, the statistics of the episode will be added to ``info`` + using the key ``obsStat``. + """ + + def __init__(self, env: gym.Env, deque_size: int = 100): + gym.utils.RecordConstructorArgs.__init__(self, deque_size=deque_size) + gym.Wrapper.__init__(self, env) + + self.buffer = {} + + # make buffer + for name, space in self.env.observation_space["state"].items(): + self.buffer[name] = np.zeros(shape=(self.max_episode_length, space.shape[0])) + + # may not be used + self.num_envs = getattr(env, "num_envs", 1) + self.episode_count = 0 + self.episode_start_times: np.ndarray = None + self.episode_returns = None + self.episode_lengths = None + self.return_queue = deque(maxlen=deque_size) + self.length_queue = deque(maxlen=deque_size) + self.is_vector_env = getattr(env, "is_vector_env", False) + + def step(self, action): + """Steps through the environment, recording the episode statistics.""" + ( + observations, + rewards, + terminations, + truncations, + infos, + ) = self.env.step(action) + assert isinstance( + infos, dict + ), f"`info` dtype is {type(infos)} while supported dtype is `dict`. This may be due to usage of other wrappers in the wrong order." + + for name, obs in observations["state"].items(): + self.buffer[name][self.curr_path_length - 1, :] = obs + + dones = np.logical_or(terminations, truncations) + num_dones = np.sum(dones) + if num_dones: + calc_buffs = {} + calc_buffs.update({ + name + "_mean": np.mean(obs[:self.curr_path_length], axis=0) for name, obs in self.buffer.items() + }) + calc_buffs.update({ + name + "_std": np.std(obs[:self.curr_path_length], axis=0) for name, obs in self.buffer.items() + }) + buff = {} + for name, value in calc_buffs.items(): + for i in range(value.shape[0]): + buff[name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz'][i]}"] = value[i] + infos["obsStat"] = buff + print(buff) + + return ( + observations, + rewards, + terminations, + truncations, + infos, + ) + + def reset(self, **kwargs): + """Resets the environment using kwargs and resets the episode returns and lengths.""" + obs, info = super().reset(**kwargs) + + # reset buffer to zero + for name, value in self.buffer.items(): + value[...] = 0 + + return obs, info From e63063fce2f5029ead01cc89d8364dca3aab77e9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 11:43:45 +0200 Subject: [PATCH 211/338] no invert --- serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 1cf01ee9..9ed32025 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -22,7 +22,7 @@ def __init__(self, env, gripper_action_span=3): self.left = np.array([False] * gripper_action_span, dtype=np.bool_) self.right = self.left.copy() - self.invert_axes = [-1, -1, 1, 1, -1, -1] + self.invert_axes = [1, 1, 1, 1, 1, -1] self.deadspace = 0.15 def action(self, action: np.ndarray) -> np.ndarray: From 6f21a35e000b32a036cd8b3070037ddd70fdc50a Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 11:44:33 +0200 Subject: [PATCH 212/338] bugfix --- serl_robot_infra/robot_controllers/robotiq_controller.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index b16c952f..c26c79aa 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -115,6 +115,7 @@ async def restart_robotiq_interface(self): # disconnect and reconnect, otherwise the controller won't take any commands self.robotiq_control.disconnect() try: + print(f"[RTDE] trying to reconnect") self.robotiq_control.reconnect() except RuntimeError: self.robotiq_receive.disconnect() @@ -123,6 +124,7 @@ async def restart_robotiq_interface(self): self.robotiq_control.disconnect() self.robotiq_receive.disconnect() await self.start_robotiq_interfaces(gripper=False) + return except Exception as e: print(e) time.sleep(0.2) @@ -374,6 +376,7 @@ async def run_async(self): ) if not fm_successful: # truncate if the robot ends up in a singularity await self.restart_robotiq_interface() + self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) if self.robotiq_gripper: await self.send_gripper_command() From d9c1328439bdb0de4440a5c0683d982659221561 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 11:44:58 +0200 Subject: [PATCH 213/338] added cost to info stats --- .../envs/basic_env/robotiq_basic_env.py | 7 +-- .../envs/camera_env/robotiq_camera_env.py | 51 ++++++++----------- 2 files changed, 24 insertions(+), 34 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py index 73f88934..59efd2a6 100644 --- a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py +++ b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py @@ -1,4 +1,5 @@ import numpy as np +from typing import Tuple from robotiq_env.envs.robotiq_env import RobotiqEnv from robotiq_env.envs.basic_env.config import RobotiqCornerConfig @@ -13,7 +14,7 @@ class RobotiqBasicEnv(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) - def compute_reward(self, obs, action) -> float: + def compute_reward(self, obs, action) -> Tuple[float, dict]: # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 @@ -27,9 +28,9 @@ def compute_reward(self, obs, action) -> float: # print(f"action_cost: {action_cost}, xy_cost: {xy_cost}") if self.reached_goal_state(obs): - return 10. - action_cost - step_cost - suck_cost + return 10. - action_cost - step_cost - suck_cost, {} else: - return 0.0 - action_cost - step_cost - suck_cost + return 0.0 - action_cost - step_cost - suck_cost, {} def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index dbb32d6d..98bf1aec 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -1,4 +1,5 @@ import numpy as np +from typing import Tuple from robotiq_env.envs.robotiq_env import RobotiqEnv from robotiq_env.envs.camera_env.config import RobotiqCameraConfigFinal, RobotiqCameraConfigFinalTests @@ -10,18 +11,16 @@ def __init__(self, load_config=True, **kwargs): super().__init__(**kwargs, config=RobotiqCameraConfigFinal) else: super().__init__(**kwargs) - self.plot_costs_yes = False - if self.plot_costs_yes: - self.reward_hist = dict(action_cost=[], suction_cost=[], non_central_cost=[], suction_reward=[], - downward_force_cost=[]) - def compute_reward(self, obs, action) -> float: + self.cost_infos = {} + + def compute_reward(self, obs, action) -> Tuple[float, dict]: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.05 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.9) - suction_cost = 0.5 * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) + suction_cost = 2. * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 orientation_cost *= 25. @@ -31,11 +30,24 @@ def compute_reward(self, obs, action) -> float: position_cost = 10. * np.sum( np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0)) + cost_info = dict( + action_cost=-action_cost, + step_cost=-step_cost, + downward_force_cost=-downward_force_cost, + suction_reward=suction_reward, + suction_cost=-suction_cost, + orientation_cost=-orientation_cost, + ) + for key, info in cost_info.items(): + self.cost_infos[key] = info + 0. if key not in self.cost_infos else self.cost_infos[key] + if self.reached_goal_state(obs): - return 100. - action_cost - orientation_cost - position_cost + cost_infos = self.cost_infos.copy() + self.cost_infos = {} + return 100. - action_cost - orientation_cost - position_cost, cost_infos else: return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ - suction_cost - step_cost + suction_cost - step_cost, {} def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis @@ -47,29 +59,6 @@ def close(self): self.plot_costs() super().close() - def plot_costs(self): # not used anymore - import matplotlib.pyplot as plt - fig, ax = plt.subplots(6, 1, figsize=(12, 10), sharey=True, sharex=True) - y = np.arange(len(self.reward_hist["action_cost"])) - - ax1, ax2, ax3, ax4, ax5, ax6 = ax - ax1.plot(y, self.reward_hist["action_cost"], label="action_cost") - ax1.legend() - ax2.plot(y, self.reward_hist["suction_cost"], label="suction_cost") - ax2.legend() - ax3.plot(y, self.reward_hist["non_central_cost"], label="non_central_cost") - ax3.legend() - ax4.plot(y, self.reward_hist["suction_reward"], label="suction_reward") - ax4.legend() - ax5.plot(y, self.reward_hist["downward_force_cost"], label="downward_force_cost") - ax5.legend() - - total = [sum(i) for i in zip(*self.reward_hist.values())] - ax6.plot(y, total, label="total") - ax6.legend() - - plt.show() - class RobotiqCameraEnvTest(RobotiqCameraEnv): def __init__(self, **kwargs): From 3288fc06daab5fb868325f9fd3f1dbc6d8b3d0e1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 12:06:11 +0200 Subject: [PATCH 214/338] better structure of cost info --- .../envs/camera_env/robotiq_camera_env.py | 14 ++----- .../robotiq_env/envs/robotiq_env.py | 39 ++++++++++++------- 2 files changed, 29 insertions(+), 24 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 98bf1aec..73a9a0fe 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -12,15 +12,13 @@ def __init__(self, load_config=True, **kwargs): else: super().__init__(**kwargs) - self.cost_infos = {} - def compute_reward(self, obs, action) -> Tuple[float, dict]: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.05 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.9) - suction_cost = 2. * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) + suction_cost = 5. * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 orientation_cost *= 25. @@ -39,15 +37,13 @@ def compute_reward(self, obs, action) -> Tuple[float, dict]: orientation_cost=-orientation_cost, ) for key, info in cost_info.items(): - self.cost_infos[key] = info + 0. if key not in self.cost_infos else self.cost_infos[key] + self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) if self.reached_goal_state(obs): - cost_infos = self.cost_infos.copy() - self.cost_infos = {} - return 100. - action_cost - orientation_cost - position_cost, cost_infos + return 100. - action_cost - orientation_cost - position_cost, self.cost_infos.copy() else: return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ - suction_cost - step_cost, {} + suction_cost - step_cost, self.cost_infos.copy() def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis @@ -55,8 +51,6 @@ def reached_goal_state(self, obs) -> bool: return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > self.curr_reset_pose[2] + 0.02 # +2cm def close(self): - if self.plot_costs_yes: - self.plot_costs() super().close() diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 2a21a14b..85909fee 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -8,7 +8,7 @@ import cv2 import queue import warnings -from typing import Dict +from typing import Dict, Tuple from datetime import datetime from collections import OrderedDict from scipy.spatial.transform import Rotation as R @@ -144,6 +144,7 @@ def __init__( self.camera_mode = camera_mode self.realtime_plot = realtime_plot + self.cost_infos = {} self.xyz_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[:3], @@ -170,7 +171,7 @@ def __init__( if camera_mode in ["rgb", "both"]: if "wrist" in config.REALSENSE_CAMERAS.keys(): image_space_definition["wrist"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 + 0, 255, shape=(128, 128, 3), dtype=np.uint8 ) if "wrist_2" in config.REALSENSE_CAMERAS.keys(): image_space_definition["wrist_2"] = gym.spaces.Box( @@ -239,7 +240,7 @@ def __init__( self.init_cameras(config.REALSENSE_CAMERAS) self.img_queue = queue.Queue() if self.camera_mode in ["pointcloud"]: - self.displayer = PointCloudDisplayer() # o3d displayer cannot be threaded :/ + self.displayer = PointCloudDisplayer() # o3d displayer cannot be threaded :/ else: self.displayer = ImageDisplayer(self.img_queue) self.displayer.start() @@ -294,6 +295,13 @@ def clip_safety_box(self, return next_pos + def get_cost_infos(self, done=False): + if not done: + return {} + cost_infos = self.cost_infos.copy() + self.cost_infos = {} + return cost_infos + def step(self, action: np.ndarray) -> tuple: """standard gym step function.""" start_time = time.time() @@ -325,16 +333,16 @@ def step(self, action: np.ndarray) -> tuple: warnings.warn(f"environment could not be within {self.hz} Hz, took {dt:.4f}s!") time.sleep(to_sleep) - reward = self.compute_reward(obs, action) + reward, infos = self.compute_reward(obs, action) truncated = self._is_truncated() reward = reward if not truncated else reward - 10. # truncation penalty done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated - return obs, reward, done, truncated, {} + return obs, reward, done, truncated, self.get_cost_infos(done) - def compute_reward(self, obs, action) -> float: - return 0. # overwrite for each task + def compute_reward(self, obs, action) -> Tuple[float, dict]: + return 0., {} # overwrite for each task def reached_goal_state(self, obs) -> bool: return False # overwrite for each task @@ -484,7 +492,7 @@ def get_image(self) -> Dict[str, np.ndarray]: except queue.Empty: input(f"{key} camera frozen. Check connect, then press enter to relaunch...") - cap.close() + # cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() @@ -498,12 +506,15 @@ def get_image(self) -> Dict[str, np.ndarray]: self.displayer.display(pc) # TODO takes too long to calculate, do it with numba or otherwise faster - # t = time.time() - # indices = np.stack(list(vx.grid_index for vx in pc.get_voxels())) - # x, y, z = np.moveaxis(indices, -1, 0) - # voxel_grid[x, y, z] = True # fill voxel grid - # images["wrist_pointcloud"] = voxel_grid - # print(f"took {time.time() - t:.4f}s") + t = time.time() + a = [] + voxels = pc.get_voxels() + indices = np.stack(list(vx.grid_index for vx in voxels)) + + t2 = time.time() + voxel_grid[indices[:, 0], indices[:, 1], indices[:, 2]] = True # fill voxel grid + images["wrist_pointcloud"] = voxel_grid + print(f"took {time.time() - t2:.4f}s and {t2 - t:.4f}s") images["wrist_pointcloud"] = voxel_grid # self.recording_frames.append( From 8d161d7d9c72e389209f8eff1101fc3816d17181 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 12:44:34 +0200 Subject: [PATCH 215/338] cleanup --- .../wrappers/observation_statistics_wrapper.py | 2 +- .../robotiq_env/envs/basic_env/robotiq_basic_env.py | 6 +++--- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 6 +++--- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 8 ++++---- 4 files changed, 11 insertions(+), 11 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py index 8726a124..44f4fbd4 100644 --- a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py +++ b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py @@ -62,7 +62,7 @@ def step(self, action): for i in range(value.shape[0]): buff[name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz'][i]}"] = value[i] infos["obsStat"] = buff - print(buff) + # print(buff) return ( observations, diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py index 59efd2a6..3bae0af0 100644 --- a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py +++ b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py @@ -14,7 +14,7 @@ class RobotiqBasicEnv(RobotiqEnv): def __init__(self, **kwargs): super().__init__(**kwargs, config=RobotiqCornerConfig) - def compute_reward(self, obs, action) -> Tuple[float, dict]: + def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 @@ -28,9 +28,9 @@ def compute_reward(self, obs, action) -> Tuple[float, dict]: # print(f"action_cost: {action_cost}, xy_cost: {xy_cost}") if self.reached_goal_state(obs): - return 10. - action_cost - step_cost - suck_cost, {} + return 10. - action_cost - step_cost - suck_cost else: - return 0.0 - action_cost - step_cost - suck_cost, {} + return 0.0 - action_cost - step_cost - suck_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 73a9a0fe..a9196dc3 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -12,7 +12,7 @@ def __init__(self, load_config=True, **kwargs): else: super().__init__(**kwargs) - def compute_reward(self, obs, action) -> Tuple[float, dict]: + def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.05 @@ -40,10 +40,10 @@ def compute_reward(self, obs, action) -> Tuple[float, dict]: self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) if self.reached_goal_state(obs): - return 100. - action_cost - orientation_cost - position_cost, self.cost_infos.copy() + return 100. - action_cost - orientation_cost - position_cost else: return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ - suction_cost - step_cost, self.cost_infos.copy() + suction_cost - step_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 85909fee..2becf474 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -295,7 +295,7 @@ def clip_safety_box(self, return next_pos - def get_cost_infos(self, done=False): + def get_cost_infos(self, done): if not done: return {} cost_infos = self.cost_infos.copy() @@ -333,7 +333,7 @@ def step(self, action: np.ndarray) -> tuple: warnings.warn(f"environment could not be within {self.hz} Hz, took {dt:.4f}s!") time.sleep(to_sleep) - reward, infos = self.compute_reward(obs, action) + reward = self.compute_reward(obs, action) truncated = self._is_truncated() reward = reward if not truncated else reward - 10. # truncation penalty @@ -341,8 +341,8 @@ def step(self, action: np.ndarray) -> tuple: done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated return obs, reward, done, truncated, self.get_cost_infos(done) - def compute_reward(self, obs, action) -> Tuple[float, dict]: - return 0., {} # overwrite for each task + def compute_reward(self, obs, action) -> float: + return 0. # overwrite for each task def reached_goal_state(self, obs) -> bool: return False # overwrite for each task From 426b6718e3aa77052bfdcf308ec40f5132be735b Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 13:07:44 +0200 Subject: [PATCH 216/338] bugfix for starting resetq --- serl_robot_infra/robot_controllers/robotiq_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index c26c79aa..44aa2990 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -62,7 +62,7 @@ def __init__( self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip - self.reset_Q = np.zeros((6,), dtype=np.float32) # reset state in Joint Space + self.reset_Q = np.array([np.pi / 2., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.], dtype=np.float32) # reset state in Joint Space self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable self.delta = config.ERROR_DELTA From 060d46b2858c7b48bfaedcc22100aef568f5c31e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 13:17:20 +0200 Subject: [PATCH 217/338] implemented grey camera mode --- examples/robotiq_drq/drq_policy_robotiq.py | 13 ++++++---- .../robotiq_env/envs/robotiq_env.py | 24 ++++++++++--------- 2 files changed, 21 insertions(+), 16 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 8ef0fa25..61f83757 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -35,6 +35,7 @@ ) from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper +from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper from robotiq_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper @@ -58,7 +59,7 @@ flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 15000, +flags.DEFINE_integer("replay_buffer_capacity", 10000, "Replay buffer capacity.") # quite low to forget demo trajectories flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") @@ -413,6 +414,7 @@ def main(_): env = RelativeFrame(env) env = Quat2EulerWrapper(env) env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) + env = ObservationStatisticsWrapper(env) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -473,10 +475,11 @@ def create_replay_buffer_and_wandb_logger(): traj["observations"].pop(obs_name) traj["next_observations"].pop(obs_name) - # TODO remove afterwards, set all images to grayscale - # gray = np.array([0.2989, 0.5870, 0.1140]) - # traj["observations"]["wrist"] = np.dot(traj["observations"]["wrist"], gray)[..., None] - # traj["next_observations"]["wrist"] = np.dot(traj["next_observations"]["wrist"], gray)[..., None] + # convert to grey here + if FLAGS.camera_mode == "grey": + gray = np.array([0.2989, 0.5870, 0.1140]) + traj["observations"]["wrist"] = np.dot(traj["observations"]["wrist"], gray)[..., None] + traj["next_observations"]["wrist"] = np.dot(traj["next_observations"]["wrist"], gray)[..., None] replay_buffer.insert(traj) print(f"replay buffer size: {len(replay_buffer)}") diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 2becf474..6d14f4b1 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -111,7 +111,7 @@ def __init__( max_episode_length: int = 100, save_video: bool = False, realtime_plot: bool = False, - camera_mode: str = "rgb", # one of (rgb, depth, both, pointcloud, none) + camera_mode: str = "rgb", # one of (rgb, grey, depth, both, pointcloud, none) ): self.max_episode_length = max_episode_length self.curr_path_length = 0 @@ -168,14 +168,15 @@ def __init__( ) image_space_definition = {} - if camera_mode in ["rgb", "both"]: + if camera_mode in ["rgb", "grey", "both"]: + channel = 1 if camera_mode == "grey" else 3 if "wrist" in config.REALSENSE_CAMERAS.keys(): image_space_definition["wrist"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 + 0, 255, shape=(128, 128, channel), dtype=np.uint8 ) if "wrist_2" in config.REALSENSE_CAMERAS.keys(): image_space_definition["wrist_2"] = gym.spaces.Box( - 0, 255, shape=(128, 128, 3), dtype=np.uint8 + 0, 255, shape=(128, 128, channel), dtype=np.uint8 ) if camera_mode in ["depth", "both"]: @@ -193,7 +194,7 @@ def __init__( 0, 1, shape=(140, 140, 125), dtype=np.bool_ ) - if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud"]: + if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") state_space = gym.spaces.Dict( @@ -209,7 +210,7 @@ def __init__( ) obs_space_definition = {"state": state_space} - if self.camera_mode in ["rgb", "both", "depth", "pointcloud"]: + if self.camera_mode in ["rgb", "both", "depth", "pointcloud", "grey"]: obs_space_definition["images"] = gym.spaces.Dict( image_space_definition ) @@ -453,20 +454,21 @@ def get_image(self) -> Dict[str, np.ndarray]: for key, cap in self.cap.items(): try: image = cap.read() - if self.camera_mode in ["rgb", "both"]: + if self.camera_mode in ["rgb", "both", "grey"]: rgb = image[..., :3].astype(np.uint8) cropped_rgb = self.crop_image(key, rgb) resized = cv2.resize( cropped_rgb, self.observation_space["images"][key].shape[:2][::-1], ) # convert to grayscale here - # gray = np.array([0.2989, 0.5870, 0.1140]) - # resized = np.dot(resized, gray)[..., None] - # resized = resized.astype(np.uint8) + if self.camera_mode == "grey": + grey = np.array([0.2989, 0.5870, 0.1140]) + resized = np.dot(resized, grey)[..., None] + resized = np.repeat(resized.astype(np.uint8), 3, axis=-1) images[key] = resized[..., ::-1] display_images[key] = resized - # display_images[key] = np.repeat(resized, 3, axis=-1) + # display_images[key] = display_images[key + "_full"] = cropped_rgb if self.camera_mode in ["depth", "both"]: From 20d668a32e08b4c6bf8ce7e85cb856902a897786 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 14:12:55 +0200 Subject: [PATCH 218/338] grey bugfix --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 6d14f4b1..b037068d 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -464,11 +464,12 @@ def get_image(self) -> Dict[str, np.ndarray]: if self.camera_mode == "grey": grey = np.array([0.2989, 0.5870, 0.1140]) resized = np.dot(resized, grey)[..., None] - resized = np.repeat(resized.astype(np.uint8), 3, axis=-1) + resized = resized.astype(np.uint8) + display_images[key] = np.repeat(resized, 3, axis=-1) + else: + display_images[key] = resized images[key] = resized[..., ::-1] - display_images[key] = resized - # display_images[key] = display_images[key + "_full"] = cropped_rgb if self.camera_mode in ["depth", "both"]: From 59f5f1a028d3c322b2420e654dc840f5b4e0edb5 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 14:14:43 +0200 Subject: [PATCH 219/338] grey bugfix 2 --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index b037068d..92b6fc37 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -428,7 +428,7 @@ def init_cameras(self, name_serial_dict=None): self.cap = OrderedDict() for cam_name, cam_serial in name_serial_dict.items(): print(f"cam serial: {cam_serial}") - rgb = self.camera_mode in ["rgb", "both"] + rgb = self.camera_mode in ["rgb", "both", "grey"] depth = self.camera_mode in ["depth", "both"] pointcloud = self.camera_mode in ["pointcloud"] cap = VideoCapture( From 327684be8d256ab99851a241cd34dc4e151f710d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 18:38:06 +0200 Subject: [PATCH 220/338] range sensor bugfix --- serl_launcher/serl_launcher/vision/range_sensor.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/range_sensor.py b/serl_launcher/serl_launcher/vision/range_sensor.py index 6ff1c3da..7e908cce 100644 --- a/serl_launcher/serl_launcher/vision/range_sensor.py +++ b/serl_launcher/serl_launcher/vision/range_sensor.py @@ -2,6 +2,7 @@ import flax.linen as nn import jax.numpy as jnp +import jax class RangeSensorEncoder(nn.Module): @@ -15,20 +16,23 @@ class RangeSensorEncoder(nn.Module): @nn.compact def __call__(self, observations: jnp.ndarray, train: bool = False, encode: bool = True): - x = observations / 255 # convert to float and within [0, 1] + x = observations / 255. # convert to float and within [0, 1] + assert x.shape[-1] == 1 assert self.keypoint_size[0] % 2 == 1 and self.keypoint_size[1] % 2 == 1 # add batch dim if missing if len(x.shape) < 4: x = x[None] - points = jnp.zeros((x.shape[0], len(self.keypoints))) + points = [] for i, keypoint in enumerate(self.keypoints): k_x, k_y = keypoint s_x, s_y = self.keypoint_size[0] // 2, self.keypoint_size[1] // 2 - points.at[:, i].set(self.pool_func(x[:, k_x - s_x:k_x + s_x + 1, k_y - s_y:k_y + s_y + 1, 0], axis=(1, 2))) + points.append(self.pool_func(x[:, k_x - s_x:k_x + s_x + 1, k_y - s_y:k_y + s_y + 1, 0], axis=(1, 2))) + points = jnp.stack(points, axis=-1) if points.shape[0] == 1: points = points[0] + return points From affc0ef888dffa9de217206bebe6dc20cf6360c1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 2 Jul 2024 18:38:56 +0200 Subject: [PATCH 221/338] move away from open3d and do pointcloud fusion and voxelization in pure numpy (except for visualization) --- serl_robot_infra/robotiq_env/camera/utils.py | 130 +++++++++++------- .../robotiq_env/envs/robotiq_env.py | 34 ++--- 2 files changed, 89 insertions(+), 75 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 69b62226..b2ab5be5 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -5,10 +5,25 @@ from typing import Any -def finetune_pointcloud_fusion(pcd1: o3d.geometry.PointCloud, pcd2: o3d.geometry.PointCloud): +def finetune_pointcloud_fusion(pc1: np.ndarray, pc2: np.ndarray): + pcd1, pcd2 = o3d.geometry.PointCloud(), o3d.geometry.PointCloud() + pcd1.points = o3d.utility.Vector3dVector(pc1) + pcd2.points = o3d.utility.Vector3dVector(pc2) pcd1.estimate_normals() pcd2.estimate_normals() + def pairwise_registration(source, target, max_correspondence_distance): + # see https://www.open3d.org/docs/latest/tutorial/Advanced/multiway_registration.html + icp = o3d.pipelines.registration.registration_icp( + source, target, max_correspondence_distance, + np.eye(4), + o3d.pipelines.registration.TransformationEstimationPointToPlane()) + transformation_icp = icp.transformation + information_icp = o3d.pipelines.registration.get_information_matrix_from_point_clouds( + source, target, max_correspondence_distance, + icp.transformation) + return transformation_icp, information_icp + with o3d.utility.VerbosityContextManager(o3d.utility.VerbosityLevel.Error) as cm: transformation, info = pairwise_registration(pcd1, pcd2, max_correspondence_distance=1e-3) @@ -18,30 +33,43 @@ def finetune_pointcloud_fusion(pcd1: o3d.geometry.PointCloud, pcd2: o3d.geometry return transformation -def pairwise_registration(source, target, max_correspondence_distance): - # see https://www.open3d.org/docs/latest/tutorial/Advanced/multiway_registration.html - icp = o3d.pipelines.registration.registration_icp( - source, target, max_correspondence_distance, - np.eye(4), - o3d.pipelines.registration.TransformationEstimationPointToPlane()) - transformation_icp = icp.transformation - information_icp = o3d.pipelines.registration.get_information_matrix_from_point_clouds( - source, target, max_correspondence_distance, - icp.transformation) - return transformation_icp, information_icp +def pointcloud_to_voxel_grid(points: np.ndarray, voxel_size: float, min_bounds: np.ndarray, max_bounds: np.ndarray): + points_filtered = crop_pointcloud(points, min_bounds=min_bounds, max_bounds=max_bounds) + dimensions = np.ceil((max_bounds - min_bounds) / voxel_size).astype(int) + voxel_indices = ((points_filtered - min_bounds) / voxel_size).astype(int) + + voxel_grid = np.zeros(dimensions, dtype=bool) + valid_indices = np.all((voxel_indices >= 0) & (voxel_indices < dimensions), axis=1) + voxel_grid[voxel_indices[valid_indices, 0], voxel_indices[valid_indices, 1], voxel_indices[valid_indices, 2]] = True + return voxel_grid + + +def crop_pointcloud(points: np.ndarray, min_bounds: np.ndarray, max_bounds: np.ndarray): + within_bounds = np.all((points >= min_bounds) & (points <= max_bounds), axis=1) + return points[within_bounds] + + +def transform_point_cloud(points, transform_matrix): + if points.shape[1] == 3: + points = np.hstack([points, np.ones((points.shape[0], 1))]) + + transformed_points = np.dot(points, transform_matrix.T) + + if transformed_points.shape[1] == 4: + transformed_points = transformed_points[:, :3] + + return transformed_points class PointCloudFusion: def __init__(self, angle=30., x_distance=0.195, voxel_size: int = 1): - self.pcd1 = o3d.geometry.PointCloud() - self.pcd2 = o3d.geometry.PointCloud() + self.pcd1, self.pcd2 = None, None self.voxel_size = 1e-3 * voxel_size # in mm # 14cm width and 12.5 height for the box - self.crop_volume = o3d.geometry.AxisAlignedBoundingBox(min_bound=(-0.07, -0.07, 0.075), - max_bound=( - 0.07 - self.voxel_size, 0.07 - self.voxel_size, - 0.2 - self.voxel_size)) + self.min_bounds = np.array([-0.07, -0.07, 0.075]) + self.max_bounds = np.array([0.07, 0.07, 0.2]) - self.voxel_size + self.original_pcds = [] self._is_transformed = False self.fine_transformed = False @@ -65,8 +93,7 @@ def save_finetuned(self): np.save(f, t_finetuned) def get_voxelgrid_shape(self): - return ((np.asarray(self.crop_volume.get_max_bound()) - np.asarray( - self.crop_volume.get_min_bound())) / self.voxel_size).astype(np.int16) + 1 + return np.ceil((self.max_bounds - self.min_bounds) / self.voxel_size).astype(int) def load_finetuned(self): from os.path import exists @@ -80,16 +107,13 @@ def load_finetuned(self): print(f"loaded finetuned Point Cloud fusion parameters!") return True - def append(self, pcd: np.ndarray | o3d.utility.Vector3dVector): - assert type(pcd) == np.ndarray or type(pcd) == o3d.utility.Vector3dVector - # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 - func = lambda x: o3d.utility.Vector3dVector(x.astype(np.float64)) if isinstance(pcd, np.ndarray) else x - if self.pcd1.is_empty(): - self.original_pcds.append(func(pcd)) - self.pcd1.points = func(pcd) - elif self.pcd2.is_empty(): - self.original_pcds.append(func(pcd)) - self.pcd2.points = func(pcd) + def append(self, pcd: np.ndarray): + if self.pcd1 is None: + self.original_pcds.append(pcd) + self.pcd1 = pcd + elif self.pcd2 is None: + self.original_pcds.append(pcd) + self.pcd2 = pcd else: raise NotImplementedError("3 pointclouds not supported") @@ -125,36 +149,38 @@ def set_fine_tuned_transformation(self, transformation): self.fine_transformed = True def clear(self): - self.pcd1.clear() - self.pcd2.clear() + self.pcd1, self.pcd2 = None, None self._is_transformed = False self.original_pcds = [] def _transform(self): - self.pcd1.transform(self.t1) - self.pcd2.transform(self.t2) + assert not self.is_empty() + self.pcd1 = transform_point_cloud(points=self.pcd1, transform_matrix=self.t1) + if self.pcd2 is not None: + self.pcd2 = transform_point_cloud(points=self.pcd2, transform_matrix=self.t2) self._is_transformed = True - def fuse_pointclouds(self, voxelize=False): + def voxelize(self, points: np.ndarray): + return pointcloud_to_voxel_grid(points, voxel_size=self.voxel_size, min_bounds=self.min_bounds, + max_bounds=self.max_bounds) + + def get_pointcloud_representation(self, voxelize=True): + if self.is_complete(): + return self.fuse_pointclouds(voxelize=voxelize) + elif not self.is_empty(): + return self.get_first(voxelize=voxelize) + + def fuse_pointclouds(self, voxelize=True): if not self._is_transformed: self._transform() + swap = lambda x: np.moveaxis(x, 0, 1) + fused = swap(np.hstack([swap(self.pcd1), swap(self.pcd2)])) + return self.voxelize(fused) if voxelize else fused - self.pcd1 += self.pcd2 - if voxelize: - return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1.crop(self.crop_volume), - voxel_size=self.voxel_size) - else: - return self.pcd1.crop(self.crop_volume) - - def get_first(self, cropped=True, voxelize=False): + def get_first(self, voxelize=True): if not self._is_transformed: - self.pcd1.transform(self.t1) - if cropped: - self.pcd1 = self.pcd1.crop(self.crop_volume) - if voxelize: - return o3d.geometry.VoxelGrid.create_from_point_cloud(input=self.pcd1, voxel_size=self.voxel_size) - else: - return self.pcd1 + self.pcd1 = transform_point_cloud(self.pcd1, transform_matrix=self.t1) + return self.voxelize(self.pcd1) if voxelize else self.pcd1 def get_original_pcds(self): if len(self.original_pcds) == 1: @@ -163,10 +189,10 @@ def get_original_pcds(self): return self.original_pcds def is_complete(self): - return not self.pcd1.is_empty() and not self.pcd2.is_empty() + return self.pcd1 is not None and self.pcd2 is not None def is_empty(self): - return self.pcd1.is_empty() and self.pcd2.is_empty() + return self.pcd1 is None and self.pcd2 is None class CalibrationTread(threading.Thread): diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 92b6fc37..0ceabbba 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -12,6 +12,7 @@ from datetime import datetime from collections import OrderedDict from scipy.spatial.transform import Rotation as R +import open3d as o3d from robotiq_env.camera.video_capture import VideoCapture from robotiq_env.camera.rs_capture import RSCapture @@ -46,10 +47,10 @@ def run(self): class PointCloudDisplayer: def __init__(self): - import open3d as o3d self.window = o3d.visualization.Visualizer() self.window.create_window(height=400, width=400, visible=True) + self.pc = o3d.geometry.PointCloud() self.window.get_render_option().load_from_json( "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/render_options.json") @@ -57,9 +58,12 @@ def __init__(self): "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/camera_parameters.json") self.ctr = self.window.get_view_control() - def display(self, voxelgrid): + def display(self, points): + self.pc.clear() + # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 + self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64)) self.window.clear_geometries() - self.window.add_geometry(voxelgrid) + self.window.add_geometry(self.pc) self.ctr.convert_from_pinhole_camera_parameters(self.param, True) self.window.poll_events() @@ -495,30 +499,14 @@ def get_image(self) -> Dict[str, np.ndarray]: except queue.Empty: input(f"{key} camera frozen. Check connect, then press enter to relaunch...") - # cap.close() self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() if self.camera_mode in ["pointcloud"]: - voxel_grid = np.zeros(self.pointcloud_fusion.get_voxelgrid_shape(), dtype=np.bool_) - - if self.pointcloud_fusion.is_complete(): - pc = self.pointcloud_fusion.fuse_pointclouds(voxelize=True) - elif not self.pointcloud_fusion.is_empty(): - pc = self.pointcloud_fusion.get_first(cropped=True, voxelize=True) - - self.displayer.display(pc) - # TODO takes too long to calculate, do it with numba or otherwise faster - t = time.time() - a = [] - voxels = pc.get_voxels() - indices = np.stack(list(vx.grid_index for vx in voxels)) - - t2 = time.time() - voxel_grid[indices[:, 0], indices[:, 1], indices[:, 2]] = True # fill voxel grid - images["wrist_pointcloud"] = voxel_grid - print(f"took {time.time() - t2:.4f}s and {t2 - t:.4f}s") - images["wrist_pointcloud"] = voxel_grid + pc = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) + + self.displayer.display(self.pointcloud_fusion.get_pointcloud_representation(voxelize=False)) + images["wrist_pointcloud"] = pc # self.recording_frames.append( # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) From 434aeffed2474de125f1d47b3b72bb497dc4971e Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 8 Jul 2024 15:52:40 +0200 Subject: [PATCH 222/338] new implementation of VoxNet encoder (conv3d on downsampled voxelgrid) --- examples/robotiq_drq/record_demo.py | 4 +- examples/robotiq_drq/run_actor.sh | 5 +- examples/robotiq_drq/run_learner.sh | 12 +-- .../serl_launcher/agents/continuous/drq.py | 26 +++-- serl_launcher/serl_launcher/utils/launcher.py | 7 +- .../vision/voxel_grid_encoders.py | 100 ++++++++++++++++++ serl_robot_infra/robotiq_env/camera/utils.py | 24 +++-- .../robotiq_env/envs/camera_env/config.py | 6 +- .../robotiq_env/envs/robotiq_env.py | 16 +-- 9 files changed, 160 insertions(+), 40 deletions(-) create mode 100644 serl_launcher/serl_launcher/vision/voxel_grid_encoders.py diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index 58385e66..b173c1e5 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -33,8 +33,8 @@ def on_esc(key): if __name__ == "__main__": env = gym.make("robotiq_camera_env", - camera_mode="both", - max_episode_length=100 + camera_mode="pointcloud", + max_episode_length=100, ) env = SpacemouseIntervention(env) env = RelativeFrame(env) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index eca0d550..9b7c22b1 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -1,4 +1,3 @@ -sh ~/stop.sh && \ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python drq_policy_robotiq.py "$@" \ @@ -6,7 +5,7 @@ python drq_policy_robotiq.py "$@" \ --env robotiq_camera_env \ --max_traj_length 100 \ --exp_name=drq_10box \ - --camera_mode rgb \ + --camera_mode pointcloud \ --seed 1 \ --max_steps 30000 \ --random_steps 500 \ @@ -14,5 +13,5 @@ python drq_policy_robotiq.py "$@" \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 2500 \ - --encoder_type resnet-pretrained-18 \ + --encoder_type voxnet \ # --debug diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index ee7706fb..48aa5581 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -1,19 +1,19 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ --exp_name=drq_10box \ - --camera_mode rgb \ + --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ - --max_steps 25000 \ + --max_steps 15000 \ --random_steps 500 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 2500 \ - --encoder_type resnet-pretrained-18 \ + --eval_period 20000 \ + --encoder_type voxnet \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jun28_10box.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul8_voxelgrid.pkl \ # --debug diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 6a42bb74..b0d12e93 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -16,6 +16,7 @@ from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize from serl_launcher.networks.lagrange import GeqLagrangeMultiplier from serl_launcher.networks.mlp import MLP +from serl_launcher.vision.voxel_grid_encoders import MLPEncoder, VoxNet from serl_launcher.utils.train_utils import _unpack, concat_batches from serl_launcher.vision.data_augmentations import batched_random_crop @@ -233,16 +234,27 @@ def create_drq( ) for image_key in image_keys } - elif encoder_type == "voxel_mlp": + elif encoder_type == "voxel-mlp": encoders = { - image_key: MLP( - hidden_dims=[128, 128], - activations=nn.relu, - activate_final=True, - use_layer_norm=True, + image_key: MLPEncoder( + mlp=MLP( + hidden_dims=[64], + activations=nn.relu, + activate_final=True, + use_layer_norm=True, + ), + bottleneck_dim=encoder_kwargs["bottleneck_dim"], ) for image_key in image_keys - } # TODO check if stop_gradient has to be removed + } + elif encoder_type == "voxnet": + encoders = { + image_key: VoxNet( + bottleneck_dim=encoder_kwargs["bottleneck_dim"], + use_conv_bias=False, + ) + for image_key in image_keys + } # TODO check weights elif encoder_type.lower() == "none": encoders = None else: diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 2de57195..ec3eaf18 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -134,9 +134,10 @@ def make_drq_agent( critic_ensemble_size=10, critic_subsample_size=2, encoder_kwargs=dict( - pooling_method="spatial_learned_embeddings", # default "spatial_learned_embeddings" - num_spatial_blocks=8, - bottleneck_dim=256, + # pooling_method="spatial_softmax", # default "spatial_learned_embeddings" + bottleneck_dim=64, + # num_spatial_blocks=8, + # num_kp=64, ), actor_optimizer_kwargs={ "learning_rate": 3e-3, # 3e-4 diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py new file mode 100644 index 00000000..c375bc75 --- /dev/null +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -0,0 +1,100 @@ +from functools import partial +from typing import Any, Callable, Optional, Sequence, Tuple + +import flax.linen as nn +import jax.numpy as jnp +import jax.lax as lax + + +class MLPEncoder(nn.Module): + mlp: nn.module = None + bottleneck_dim: Optional[int] = None + + @nn.compact + def __call__( + self, + observations: jnp.ndarray, + encode: bool = True, + train: bool = True, + ): + # add batch dim if missing + no_batch_dim = len(observations.shape) < 4 + if no_batch_dim: + observations = observations[None] + + # flatten but keep batch tim + x = jnp.reshape(observations, (observations.shape[0], -1)) + + if encode: + x = self.mlp(x, train=train) + + if self.bottleneck_dim is not None: + x = nn.Dense(self.bottleneck_dim)(x) + x = nn.LayerNorm()(x) + x = nn.tanh(x) + + return x[0] if no_batch_dim else x + + +class VoxNet(nn.Module): + """ + Voxnet implementation: https://github.com/AutoDeep/VoxNet/blob/master/src/nets/voxNet.py + """ + + use_conv_bias: bool = False + bottleneck_dim: Optional[int] = None + + @nn.compact + def __call__( + self, + observations: jnp.ndarray, + encode: bool = True, + train: bool = True, + ): + # observations has shape (B, X, Y, Z) (boolean for now) + no_batch_dim = len(observations.shape) < 4 + if no_batch_dim: + observations = observations[None] + + observations = observations.astype(jnp.float32)[..., None] / 8. # add conv channel and scale to [0, 1] + + conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, padding="valid") + l_relu = partial(nn.leaky_relu, negative_slope=0.1) + + x = observations + x = conv( + features=32, + kernel_size=(5, 5, 5), + strides=(2, 2, 2), + name="conv_5x5", + )(x) + x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2) + + x = conv( + features=32, + kernel_size=(3, 3, 3), + strides=(1, 1, 1), + name="conv_3x3" + )(x) + x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2) + + x = lax.reduce_window( + x, + init_value=-jnp.inf, + computation=lax.max, + window_dimensions=(1, 2, 2, 2, 1), + window_strides=(1, 2, 2, 2, 1), + padding='VALID' + ) + # print(x.shape, end=' ') + + # reshape and dense (preserve batch dim) + x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) + # print(x.shape) + + if self.bottleneck_dim is not None: + x = nn.Dense(self.bottleneck_dim)(x) + x = nn.LayerNorm()(x) + x = nn.tanh(x) + + return x[0] if no_batch_dim else x diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index b2ab5be5..207ab012 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -62,13 +62,16 @@ def transform_point_cloud(points, transform_matrix): class PointCloudFusion: - def __init__(self, angle=30., x_distance=0.195, voxel_size: int = 1): + def __init__(self, angle=30., x_distance=0.195, voxel_grid_shape=(100, 100, 80)): self.pcd1, self.pcd2 = None, None - self.voxel_size = 1e-3 * voxel_size # in mm - # 14cm width and 12.5 height for the box - self.min_bounds = np.array([-0.07, -0.07, 0.075]) - self.max_bounds = np.array([0.07, 0.07, 0.2]) - self.voxel_size + # 10cm width and 8cm height for the box + self.min_bounds = np.array([-0.05, -0.05, 0.075]) + self.max_bounds = np.array([0.05, 0.05, 0.155]) + + vox_size = (self.max_bounds - self.min_bounds) / voxel_grid_shape + assert np.all(np.isclose(vox_size, vox_size[0])) + self.voxel_size: float = float(vox_size[0]) self.original_pcds = [] self._is_transformed = False @@ -124,7 +127,7 @@ def calibrate_fusion(self): self._transform() # then calibrate - t = finetune_pointcloud_fusion(pcd1=self.pcd1, pcd2=self.pcd2) + t = finetune_pointcloud_fusion(pc1=self.pcd1, pc2=self.pcd2) return t def set_fine_tuned_transformation(self, transformation): @@ -164,6 +167,9 @@ def voxelize(self, points: np.ndarray): return pointcloud_to_voxel_grid(points, voxel_size=self.voxel_size, min_bounds=self.min_bounds, max_bounds=self.max_bounds) + def crop(self, points: np.ndarray): + return crop_pointcloud(points=points, min_bounds=self.min_bounds, max_bounds=self.max_bounds) + def get_pointcloud_representation(self, voxelize=True): if self.is_complete(): return self.fuse_pointclouds(voxelize=voxelize) @@ -173,14 +179,14 @@ def get_pointcloud_representation(self, voxelize=True): def fuse_pointclouds(self, voxelize=True): if not self._is_transformed: self._transform() - swap = lambda x: np.moveaxis(x, 0, 1) + swap = lambda x: np.moveaxis(x, 0, 1) fused = swap(np.hstack([swap(self.pcd1), swap(self.pcd2)])) - return self.voxelize(fused) if voxelize else fused + return self.voxelize(fused) if voxelize else self.crop(fused) def get_first(self, voxelize=True): if not self._is_transformed: self.pcd1 = transform_point_cloud(self.pcd1, transform_matrix=self.t1) - return self.voxelize(self.pcd1) if voxelize else self.pcd1 + return self.voxelize(self.pcd1) if voxelize else self.crop(self.pcd1) def get_original_pcds(self): if len(self.original_pcds) == 1: diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index a05edb06..070c5660 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -56,7 +56,7 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): } -class RobotiqCameraConfigFinal(DefaultEnvConfig): +class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes RESET_Q = np.array([ [2.6259, - 1.5196, 2.1287, - 2.1784, - 1.5665, - 0.4741], [2.0131, - 1.271, 1.9316, - 2.2306, - 1.566, 0.4537], @@ -70,7 +70,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) RANDOM_RESET = False - RANDOM_XY_RANGE = (0.00,) + RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.18, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.8, -0.18, -3.2]) @@ -88,7 +88,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): REALSENSE_CAMERAS = { "wrist": "218622277164", - # "wrist_2": "218622279756" + "wrist_2": "218622279756" } diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 0ceabbba..705f0375 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -195,7 +195,7 @@ def __init__( if camera_mode in ["pointcloud"]: image_space_definition["wrist_pointcloud"] = gym.spaces.Box( - 0, 1, shape=(140, 140, 125), dtype=np.bool_ + 0, 1, shape=(50, 50, 40), dtype=np.uint8 ) if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: @@ -503,10 +503,10 @@ def get_image(self) -> Dict[str, np.ndarray]: return self.get_image() if self.camera_mode in ["pointcloud"]: - pc = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) - + voxel_grid = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) + voxel_grid = np.sum(np.reshape(voxel_grid, (50, 2, 50, 2, 40, 2)), axis=(1, 3, 5)) + images["wrist_pointcloud"] = voxel_grid.astype(np.uint8) self.displayer.display(self.pointcloud_fusion.get_pointcloud_representation(voxelize=False)) - images["wrist_pointcloud"] = pc # self.recording_frames.append( # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) @@ -543,13 +543,16 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 if visualize: import open3d as o3d + pc = o3d.geometry.PointCloud() for i in range(num_samples): + pc.clear() pcs = self.calibration_thread.pc_backlog[i] self.pointcloud_fusion.clear() self.pointcloud_fusion.append(pcs[0]) self.pointcloud_fusion.append(pcs[1]) - fused = self.pointcloud_fusion.fuse_pointclouds() - o3d.visualization.draw_geometries([fused]) + fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=False) + pc.points = o3d.utility.Vector3dVector(fused) + o3d.visualization.draw_geometries([pc]) self.calibration_thread.join() exit(f"restart the program to use the calibrated values") @@ -602,7 +605,6 @@ def _get_obs(self) -> dict: if self.camera_mode is not None: images = self.get_image() - # images = np.ones_like(images) * 255 return copy.deepcopy(dict(images=images, state=state_observation)) else: return copy.deepcopy(dict(state=state_observation)) From c035ada7308ffae5bec61852a22b342376bf56fb Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 8 Jul 2024 15:53:13 +0200 Subject: [PATCH 223/338] some slight improvements --- serl_launcher/serl_launcher/utils/train_utils.py | 12 ++++++++++++ serl_launcher/serl_launcher/vision/resnet_v1.py | 1 + .../envs/camera_env/robotiq_camera_env.py | 3 ++- serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- 4 files changed, 16 insertions(+), 2 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index d681e062..82a4ab70 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -11,6 +11,7 @@ import tensorflow as tf import wandb from flax.core import frozen_dict +from jaxlib.xla_extension import ArrayImpl def concat_batches(offline_batch, online_batch, axis=1): @@ -178,3 +179,14 @@ def plot_feature_kernel_histogram(agent): axes[p].hist(feature_kernel[p*256:(p+1)*256], bins=50) axes[p].set_title(legend) plt.show() + + +def find_zero_weights(params, print_str=""): + if isinstance(params, dict): + for key in params.keys(): + find_zero_weights(params[key], print_str=print_str + " " + key) + else: + if abs(params.mean()) < 1e-5: + print(f" zero weights--> {print_str} std: {params.std()}") + else: + print(".", end='') diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index 6744c5a3..03bc3a97 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -353,6 +353,7 @@ def __call__( x = self.pretrained_encoder(x, train=train) if self.pooling_method == "spatial_learned_embeddings": + # TODO maybe make the same as in spatial softmax height, width, channel = x.shape[-3:] x = SpatialLearnedEmbeddings( height=height, diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index a9196dc3..7caa8f29 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -14,7 +14,7 @@ def __init__(self, load_config=True, **kwargs): def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) - step_cost = 0.05 + step_cost = 0.1 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.9) @@ -35,6 +35,7 @@ def compute_reward(self, obs, action) -> float: suction_reward=suction_reward, suction_cost=-suction_cost, orientation_cost=-orientation_cost, + position_cost=-position_cost ) for key, info in cost_info.items(): self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 9ed32025..e4d63ba1 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -22,7 +22,7 @@ def __init__(self, env, gripper_action_span=3): self.left = np.array([False] * gripper_action_span, dtype=np.bool_) self.right = self.left.copy() - self.invert_axes = [1, 1, 1, 1, 1, -1] + self.invert_axes = [-1, -1, 1, 1, 1, -1] self.deadspace = 0.15 def action(self, action: np.ndarray) -> np.ndarray: From 15dc1c463da2e8adc559a2068a021cb5416485e0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 10 Jul 2024 11:33:11 +0200 Subject: [PATCH 224/338] added all the costs and total cost --- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 7caa8f29..b8d9bee7 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -35,7 +35,8 @@ def compute_reward(self, obs, action) -> float: suction_reward=suction_reward, suction_cost=-suction_cost, orientation_cost=-orientation_cost, - position_cost=-position_cost + position_cost=-position_cost, + total_cost=-action_cost - step_cost - downward_force_cost + suction_reward - suction_cost - orientation_cost - position_cost ) for key, info in cost_info.items(): self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) @@ -44,7 +45,7 @@ def compute_reward(self, obs, action) -> float: return 100. - action_cost - orientation_cost - position_cost else: return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ - suction_cost - step_cost + suction_cost - step_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From 5912c8729deba6ae8950a8b7b95e765b8229c510 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 10 Jul 2024 11:33:46 +0200 Subject: [PATCH 225/338] slight change in voxel dim and visualization --- serl_robot_infra/robotiq_env/camera/utils.py | 9 +++++---- .../robotiq_env/envs/robotiq_env.py | 17 ++++++++--------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 207ab012..007542b2 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -38,10 +38,10 @@ def pointcloud_to_voxel_grid(points: np.ndarray, voxel_size: float, min_bounds: dimensions = np.ceil((max_bounds - min_bounds) / voxel_size).astype(int) voxel_indices = ((points_filtered - min_bounds) / voxel_size).astype(int) - voxel_grid = np.zeros(dimensions, dtype=bool) + voxel_grid = np.zeros(dimensions, dtype=np.bool_) valid_indices = np.all((voxel_indices >= 0) & (voxel_indices < dimensions), axis=1) voxel_grid[voxel_indices[valid_indices, 0], voxel_indices[valid_indices, 1], voxel_indices[valid_indices, 2]] = True - return voxel_grid + return voxel_grid, voxel_indices[valid_indices, :].astype(np.uint8) def crop_pointcloud(points: np.ndarray, min_bounds: np.ndarray, max_bounds: np.ndarray): @@ -164,8 +164,9 @@ def _transform(self): self._is_transformed = True def voxelize(self, points: np.ndarray): - return pointcloud_to_voxel_grid(points, voxel_size=self.voxel_size, min_bounds=self.min_bounds, - max_bounds=self.max_bounds) + grid, indices = pointcloud_to_voxel_grid(points, voxel_size=self.voxel_size, min_bounds=self.min_bounds, + max_bounds=self.max_bounds) + return grid, indices def crop(self, points: np.ndarray): return crop_pointcloud(points=points, min_bounds=self.min_bounds, max_bounds=self.max_bounds) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 705f0375..06aa24a7 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -61,7 +61,7 @@ def __init__(self): def display(self, points): self.pc.clear() # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 - self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64)) + self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64) / 1000.) self.window.clear_geometries() self.window.add_geometry(self.pc) self.ctr.convert_from_pinhole_camera_parameters(self.param, True) @@ -194,10 +194,9 @@ def __init__( ) if camera_mode in ["pointcloud"]: - image_space_definition["wrist_pointcloud"] = gym.spaces.Box( - 0, 1, shape=(50, 50, 40), dtype=np.uint8 + image_space_definition["wrist_pointcloud"] = gym.spaces.Box( # TODO change here as well + 0, 255, shape=(50, 50, 40), dtype=np.bool_ ) - if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") @@ -263,7 +262,7 @@ def __init__( print("[RIC] Controller has started and is ready!") if self.camera_mode in ["pointcloud"]: - self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196) + self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196, voxel_grid_shape=(50, 50, 40)) # load pre calibrated, else calibrate if not self.pointcloud_fusion.load_finetuned(): @@ -503,10 +502,10 @@ def get_image(self) -> Dict[str, np.ndarray]: return self.get_image() if self.camera_mode in ["pointcloud"]: - voxel_grid = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) - voxel_grid = np.sum(np.reshape(voxel_grid, (50, 2, 50, 2, 40, 2)), axis=(1, 3, 5)) - images["wrist_pointcloud"] = voxel_grid.astype(np.uint8) - self.displayer.display(self.pointcloud_fusion.get_pointcloud_representation(voxelize=False)) + voxel_grid, voxel_indices = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) + # print(voxel_grid.shape, voxel_grid.dtype, voxel_grid.nbytes*8) + images["wrist_pointcloud"] = voxel_grid.astype(np.bool_) + self.displayer.display(voxel_indices) # self.recording_frames.append( # np.concatenate([image for key, image in display_images.items() if "full" in key], axis=0) From 8ab5bbc5320d02ca968d69a68371b06830c91505 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 10 Jul 2024 15:42:33 +0200 Subject: [PATCH 226/338] improved memory efficiency of pointcloud data --- .../serl_launcher/utils/numpy_utils.py | 33 +++++++++++++++++++ .../vision/voxel_grid_encoders.py | 20 ++++++++--- .../robotiq_env/envs/robotiq_env.py | 12 ++++--- 3 files changed, 57 insertions(+), 8 deletions(-) create mode 100644 serl_launcher/serl_launcher/utils/numpy_utils.py diff --git a/serl_launcher/serl_launcher/utils/numpy_utils.py b/serl_launcher/serl_launcher/utils/numpy_utils.py new file mode 100644 index 00000000..15a79094 --- /dev/null +++ b/serl_launcher/serl_launcher/utils/numpy_utils.py @@ -0,0 +1,33 @@ +import numpy as np +import jax.numpy as jnp + +""" +numpy uses uint8 to save a boolean array, so it is really inefficient. +with this simple conversion, we increase the efficiency by 8 fold. +""" + + +def bool_2_int8(array: np.ndarray) -> np.ndarray: + # from bool (x, y, z) to uint8 (x, y, z/8) + assert array.shape[-1] % 8 == 0 + return np.dot(array.reshape((*array.shape[:-1], array.shape[-1] // 8, 8)), 2 ** np.arange(8)).astype(np.uint8) + + +def int8_2_bool(array: np.ndarray) -> np.ndarray: + bool_arr = np.zeros((*array.shape[:], 8)).astype(np.bool_) + for i in range(8): + bool_arr[..., i] = np.bitwise_and(np.right_shift(array, i), 0x1) + return bool_arr.reshape(*array.shape[:-1], array.shape[-1] * 8) + + +def int8_2_bool_jnp(array: jnp.ndarray) -> jnp.ndarray: + bool_arr = [] + for i in range(8): + bool_arr.append(jnp.bitwise_and(jnp.right_shift(array, i), 0x1)) + bool_arr = jnp.stack(bool_arr, axis=-1) + return bool_arr.reshape(*array.shape[:-1], array.shape[-1] * 8) + + +def bool_2_int8_jnp(array: jnp.ndarray) -> jnp.ndarray: + assert array.shape[-1] % 8 == 0 + return jnp.dot(array.reshape((*array.shape[:-1], array.shape[-1] // 8, 8)), 2 ** np.arange(8)).astype(np.uint8) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index c375bc75..70840a06 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -5,6 +5,8 @@ import jax.numpy as jnp import jax.lax as lax +from serl_launcher.utils.numpy_utils import int8_2_bool_jnp + class MLPEncoder(nn.Module): mlp: nn.module = None @@ -56,9 +58,13 @@ def __call__( if no_batch_dim: observations = observations[None] - observations = observations.astype(jnp.float32)[..., None] / 8. # add conv channel and scale to [0, 1] + if observations.dtype == jnp.uint8: + observations = int8_2_bool_jnp(observations) # bit conversion here + + observations = observations.astype(jnp.float32)[..., None] # add conv channel - conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, padding="valid") + conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, + padding="valid") l_relu = partial(nn.leaky_relu, negative_slope=0.1) x = observations @@ -68,7 +74,7 @@ def __call__( strides=(2, 2, 2), name="conv_5x5", )(x) - x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2) + x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) x = conv( features=32, @@ -76,7 +82,13 @@ def __call__( strides=(1, 1, 1), name="conv_3x3" )(x) - x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2) + x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, 32) + + # TODO test 1x1 convolution (dimensionality reduction, no features) + # x = conv( + # features=1, + # kernel_size=(1, 1, 1), + # )(x) x = lax.reduce_window( x, diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 06aa24a7..e35e4f95 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -23,6 +23,8 @@ from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController +from serl_launcher.utils.numpy_utils import bool_2_int8 + class ImageDisplayer(threading.Thread): def __init__(self, queue): @@ -195,7 +197,7 @@ def __init__( if camera_mode in ["pointcloud"]: image_space_definition["wrist_pointcloud"] = gym.spaces.Box( # TODO change here as well - 0, 255, shape=(50, 50, 40), dtype=np.bool_ + 0, 255, shape=(50, 50, 5), dtype=np.uint8 ) if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") @@ -262,7 +264,10 @@ def __init__( print("[RIC] Controller has started and is ready!") if self.camera_mode in ["pointcloud"]: - self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196, voxel_grid_shape=(50, 50, 40)) + voxel_grid_shape = self.observation_space["images"]["wrist_pointcloud"].shape + voxel_grid_shape[-1] *= 8 + print(f"pointcloud resolution set to: {voxel_grid_shape}") + self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196, voxel_grid_shape=voxel_grid_shape) # load pre calibrated, else calibrate if not self.pointcloud_fusion.load_finetuned(): @@ -503,8 +508,7 @@ def get_image(self) -> Dict[str, np.ndarray]: if self.camera_mode in ["pointcloud"]: voxel_grid, voxel_indices = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) - # print(voxel_grid.shape, voxel_grid.dtype, voxel_grid.nbytes*8) - images["wrist_pointcloud"] = voxel_grid.astype(np.bool_) + images["wrist_pointcloud"] = bool_2_int8(voxel_grid) self.displayer.display(voxel_indices) # self.recording_frames.append( From 0c5f2e379a18d6c16bf66dc7a3385389fdf7ed4a Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 10 Jul 2024 15:43:23 +0200 Subject: [PATCH 227/338] small improvements --- examples/robotiq_drq/drq_policy_robotiq.py | 9 +++++++-- serl_launcher/serl_launcher/agents/continuous/drq.py | 2 +- serl_launcher/serl_launcher/utils/launcher.py | 2 +- serl_launcher/serl_launcher/utils/train_utils.py | 12 +++++++++--- 4 files changed, 18 insertions(+), 7 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 61f83757..0092208e 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -22,7 +22,8 @@ from serl_launcher.utils.train_utils import ( print_agent_params, parameter_overview, - plot_feature_kernel_histogram + plot_feature_kernel_histogram, + find_zero_weights ) from agentlace.trainer import TrainerServer, TrainerClient @@ -138,6 +139,8 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): step=FLAGS.eval_checkpoint_step, ) agent = agent.replace(state=ckpt) + print("finding zero weights") + find_zero_weights(agent.state.params, print_all=False) # examine model parameters if trajs==0 if FLAGS.eval_n_trajs == 0: @@ -321,7 +324,6 @@ def stats_callback(type: str, payload: dict) -> dict: server.publish_network(agent.state.params) print_green("sent initial network to actor") - # 50/50 sampling from RLPD, half from demo and half from online experience replay_iterator = replay_buffer.get_iterator( sample_args={ "batch_size": FLAGS.batch_size, @@ -333,6 +335,7 @@ def stats_callback(type: str, payload: dict) -> dict: # wait till the replay buffer is filled with enough data timer = Timer() for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): + timer.tick("learner_total") # run n-1 critic updates and 1 critic + actor update. # This makes training on GPU faster by reducing the large batch transfer time from CPU to GPU @@ -347,6 +350,8 @@ def stats_callback(type: str, payload: dict) -> dict: batch = next(replay_iterator) agent, update_info = agent.update_high_utd(batch, utd_ratio=1) + timer.tock("learner_total") + # publish the updated network if step > 0 and step % (FLAGS.steps_per_update) == 0: agent = jax.block_until_ready(agent) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index b0d12e93..f84a9792 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -234,7 +234,7 @@ def create_drq( ) for image_key in image_keys } - elif encoder_type == "voxel-mlp": + elif encoder_type == "voxel-mlp": # not used, too many weights... encoders = { image_key: MLPEncoder( mlp=MLP( diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index ec3eaf18..da166438 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -119,7 +119,7 @@ def make_drq_agent( std_max=5, ), critic_network_kwargs=dict( - activations=nn.tanh, + activations=nn.tanh, # TODO test relu use_layer_norm=True, hidden_dims=[256, 256], ), diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 82a4ab70..634efc1d 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -143,7 +143,10 @@ def get_size(params): actor, critic = agent.state.params["modules_actor"], agent.state.params["modules_critic"] # calculate encoder params - pretrained_encoder_count = get_size(actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"]) + try: + pretrained_encoder_count = get_size(actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"]) + except Exception as e: + pretrained_encoder_count = 0 encoder_count = get_size(actor["encoder"]) actor_count = get_size(actor) @@ -181,11 +184,14 @@ def plot_feature_kernel_histogram(agent): plt.show() -def find_zero_weights(params, print_str=""): +def find_zero_weights(params, print_str="", print_all=False): if isinstance(params, dict): for key in params.keys(): - find_zero_weights(params[key], print_str=print_str + " " + key) + find_zero_weights(params[key], print_str=print_str + " " + key, print_all=print_all) else: + if print_all: + print(f"{print_str} m:{params.mean()} s:{params.std()}") + return if abs(params.mean()) < 1e-5: print(f" zero weights--> {print_str} std: {params.std()}") else: From 2f97694fc73eacb1bfe99d769a57fc95df24aa2e Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Jul 2024 15:59:25 +0200 Subject: [PATCH 228/338] added voxel augmentation (3d shift) --- .../serl_launcher/agents/continuous/drq.py | 29 ++++--- .../vision/data_augmentations.py | 82 +++++++++++++------ 2 files changed, 75 insertions(+), 36 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index f84a9792..50423e54 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -18,7 +18,7 @@ from serl_launcher.networks.mlp import MLP from serl_launcher.vision.voxel_grid_encoders import MLPEncoder, VoxNet from serl_launcher.utils.train_utils import _unpack, concat_batches -from serl_launcher.vision.data_augmentations import batched_random_crop +from serl_launcher.vision.data_augmentations import batched_random_crop, batched_random_shift_voxel class DrQAgent(SACAgent): @@ -234,7 +234,7 @@ def create_drq( ) for image_key in image_keys } - elif encoder_type == "voxel-mlp": # not used, too many weights... + elif encoder_type == "voxel-mlp": # not used, too many weights... encoders = { image_key: MLPEncoder( mlp=MLP( @@ -254,7 +254,7 @@ def create_drq( use_conv_bias=False, ) for image_key in image_keys - } # TODO check weights + } elif encoder_type.lower() == "none": encoders = None else: @@ -320,13 +320,22 @@ def create_drq( def data_augmentation_fn(self, rng, observations): for pixel_key in self.config["image_keys"]: - observations = observations.copy( - add_or_replace={ - pixel_key: batched_random_crop( - observations[pixel_key], rng, padding=4, num_batch_dims=2 - ) - } - ) + if "pointcloud" in pixel_key: + observations = observations.copy( + add_or_replace={ + pixel_key: batched_random_shift_voxel( + observations[pixel_key], rng, padding=3, num_batch_dims=2 + ) + } + ) + else: + observations = observations.copy( + add_or_replace={ + pixel_key: batched_random_crop( + observations[pixel_key], rng, padding=4, num_batch_dims=2 + ) + } + ) return observations @partial(jax.jit, static_argnames=("utd_ratio", "pmap_axis")) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 2c2440fa..4cc4676b 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -36,6 +36,36 @@ def batched_random_crop(img, rng, *, padding, num_batch_dims: int = 1): return img +def random_shift_3d(img, rng, *, padding): + crop_from = jax.random.randint(rng, (3,), 0, 2 * padding + 1) + padded_img = jnp.pad( + img, + ( + (padding, padding), + (padding, padding), + (padding, padding), + ), + mode="constant" + ) + return jax.lax.dynamic_slice(padded_img, crop_from, img.shape) + + +@partial(jax.jit, static_argnames=("padding", "num_batch_dims")) +def batched_random_shift_voxel(img, rng, *, padding, num_batch_dims: int = 1): + original_shape = img.shape + img = jnp.reshape(img, (-1, *img.shape[num_batch_dims:])) + # shape (B, X, Y, Z) + + rngs = jax.random.split(rng, img.shape[0]) + img = jax.vmap( + lambda i, r: random_shift_3d(i, r, padding=padding), in_axes=(0, 0), out_axes=0 + )(img, rngs) + + # Restore batch dims + img = jnp.reshape(img, original_shape) + return img + + def _maybe_apply(apply_fn, inputs, rng, apply_prob): should_apply = jax.random.uniform(rng, shape=()) <= apply_prob return jax.lax.cond(should_apply, inputs, apply_fn, inputs, lambda x: x) @@ -66,7 +96,7 @@ def _gaussian_blur_single_image(image, kernel_size, padding, sigma): radius = int(kernel_size / 2) kernel_size_ = 2 * radius + 1 x = jnp.arange(-radius, radius + 1).astype(jnp.float32) - blur_filter = jnp.exp(-(x**2) / (2.0 * sigma**2)) + blur_filter = jnp.exp(-(x ** 2) / (2.0 * sigma ** 2)) blur_filter = blur_filter / jnp.sum(blur_filter) blur_v = jnp.reshape(blur_filter, [kernel_size_, 1, 1, 1]) blur_h = jnp.reshape(blur_filter, [1, kernel_size_, 1, 1]) @@ -83,7 +113,7 @@ def _gaussian_blur_single_image(image, kernel_size, padding, sigma): def _random_gaussian_blur( - image, rng, *, kernel_size, padding, sigma_min, sigma_max, apply_prob + image, rng, *, kernel_size, padding, sigma_min, sigma_max, apply_prob ): """Applies a random gaussian blur.""" apply_rng, transform_rng = jax.random.split(rng) @@ -148,22 +178,22 @@ def hsv_to_rgb(h, s, v): x = c * (1 - jnp.abs(fmodu - 1)) hcat = jnp.floor(dh).astype(jnp.int32) rr = ( - jnp.where( - (hcat == 0) | (hcat == 5), c, jnp.where((hcat == 1) | (hcat == 4), x, 0) - ) - + m + jnp.where( + (hcat == 0) | (hcat == 5), c, jnp.where((hcat == 1) | (hcat == 4), x, 0) + ) + + m ) gg = ( - jnp.where( - (hcat == 1) | (hcat == 2), c, jnp.where((hcat == 0) | (hcat == 3), x, 0) - ) - + m + jnp.where( + (hcat == 1) | (hcat == 2), c, jnp.where((hcat == 0) | (hcat == 3), x, 0) + ) + + m ) bb = ( - jnp.where( - (hcat == 3) | (hcat == 4), c, jnp.where((hcat == 2) | (hcat == 5), x, 0) - ) - + m + jnp.where( + (hcat == 3) | (hcat == 4), c, jnp.where((hcat == 2) | (hcat == 5), x, 0) + ) + + m ) return rr, gg, bb @@ -224,17 +254,17 @@ def _to_grayscale(image): def color_transform( - image, - rng, - *, - brightness, - contrast, - saturation, - hue, - to_grayscale_prob, - color_jitter_prob, - apply_prob, - shuffle + image, + rng, + *, + brightness, + contrast, + saturation, + hue, + to_grayscale_prob, + color_jitter_prob, + apply_prob, + shuffle ): """Applies color jittering to a single image.""" apply_rng, transform_rng = jax.random.split(rng) @@ -306,7 +336,7 @@ def random_flip(image, rng): def gaussian_blur( - image, rng, *, blur_divider=10.0, sigma_min=0.1, sigma_max=2.0, apply_prob=1.0 + image, rng, *, blur_divider=10.0, sigma_min=0.1, sigma_max=2.0, apply_prob=1.0 ): """Applies gaussian blur to a batch of images. Args: From c24cb2dc4e17027a1a9664d782c5325f9938c80b Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Jul 2024 16:00:16 +0200 Subject: [PATCH 229/338] do not use bool compacting anymore (interferes with augmentation & no significant speedup) --- .../serl_launcher/vision/voxel_grid_encoders.py | 10 +--------- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 14 ++++++++++---- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 70840a06..99e5cef4 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -5,8 +5,6 @@ import jax.numpy as jnp import jax.lax as lax -from serl_launcher.utils.numpy_utils import int8_2_bool_jnp - class MLPEncoder(nn.Module): mlp: nn.module = None @@ -58,9 +56,6 @@ def __call__( if no_batch_dim: observations = observations[None] - if observations.dtype == jnp.uint8: - observations = int8_2_bool_jnp(observations) # bit conversion here - observations = observations.astype(jnp.float32)[..., None] # add conv channel conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, @@ -84,7 +79,7 @@ def __call__( )(x) x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, 32) - # TODO test 1x1 convolution (dimensionality reduction, no features) + # 1x1 convolution (dimensionality reduction, no features), not used for now # x = conv( # features=1, # kernel_size=(1, 1, 1), @@ -98,12 +93,9 @@ def __call__( window_strides=(1, 2, 2, 2, 1), padding='VALID' ) - # print(x.shape, end=' ') # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) - # print(x.shape) - if self.bottleneck_dim is not None: x = nn.Dense(self.bottleneck_dim)(x) x = nn.LayerNorm()(x) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index e35e4f95..27563d91 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -197,7 +197,7 @@ def __init__( if camera_mode in ["pointcloud"]: image_space_definition["wrist_pointcloud"] = gym.spaces.Box( # TODO change here as well - 0, 255, shape=(50, 50, 5), dtype=np.uint8 + 0, 255, shape=(50, 50, 40), dtype=np.uint8 ) if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") @@ -264,8 +264,9 @@ def __init__( print("[RIC] Controller has started and is ready!") if self.camera_mode in ["pointcloud"]: - voxel_grid_shape = self.observation_space["images"]["wrist_pointcloud"].shape - voxel_grid_shape[-1] *= 8 + voxel_grid_shape = np.array(self.observation_space["images"]["wrist_pointcloud"].shape) + # voxel_grid_shape[-1] *= 8 # do not use compacting for now + # voxel_grid_shape *= 2 print(f"pointcloud resolution set to: {voxel_grid_shape}") self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196, voxel_grid_shape=voxel_grid_shape) @@ -508,7 +509,12 @@ def get_image(self) -> Dict[str, np.ndarray]: if self.camera_mode in ["pointcloud"]: voxel_grid, voxel_indices = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) - images["wrist_pointcloud"] = bool_2_int8(voxel_grid) + # images["wrist_pointcloud"] = bool_2_int8(voxel_grid) + vs = self.observation_space["images"]["wrist_pointcloud"].shape + + # downsample on 2x2x2 grid with sum of points (8 as max) + # voxel_grid = np.sum(np.reshape(voxel_grid, (vs[0], 2, vs[1], 2, vs[2], 2)), axis=(1, 3, 5)) + images["wrist_pointcloud"] = voxel_grid.astype(np.uint8) self.displayer.display(voxel_indices) # self.recording_frames.append( From fcfb9e473d179efb33ab71fc5e5b7763159afc6f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Jul 2024 16:00:45 +0200 Subject: [PATCH 230/338] bugfix and new gripper release fix --- .../robot_controllers/robotiq_controller.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 44aa2990..55531016 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -178,7 +178,7 @@ async def _update_robot_state(self): obj_status = await self.robotiq_gripper.get_object_status() pressure /= 100. # pressure between [0, 1] - grip_status = [0., 1., 1., 0.][obj_status.value] # 3-> no object detected, [0, 1, 2]-> obj detected + grip_status = [1., 1., 1., 0.][obj_status.value] # 3-> no object detected, [0, 1, 2]-> obj detected with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = vel @@ -303,9 +303,13 @@ async def _go_to_reset_pose(self): # first disable vaccum gripper if self.robotiq_gripper: - self.target_grip[0] = -1. - await self.send_gripper_command() - time.sleep(0.1) + for _ in range(100): + self.target_grip[0] = -1. + await self.send_gripper_command() + time.sleep(0.1) + gripper_status = await self.robotiq_gripper.get_object_status() + if gripper_status.value == 3: + break # then move up (so no boxes are moved) success = True From c63096340c11a125118c29fb839dde4843b7179f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Jul 2024 17:15:34 +0200 Subject: [PATCH 231/338] changing pressure and grip status (more distinct) --- serl_robot_infra/robot_controllers/robotiq_controller.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 55531016..59650805 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -177,8 +177,13 @@ async def _update_robot_state(self): pressure = await self.robotiq_gripper.get_current_pressure() obj_status = await self.robotiq_gripper.get_object_status() - pressure /= 100. # pressure between [0, 1] - grip_status = [1., 1., 1., 0.][obj_status.value] # 3-> no object detected, [0, 1, 2]-> obj detected + # 3-> no object detected, 0-> sucking empty, [1, 2] obj detected + grip_status = [-1., 1., 1., 0.][obj_status.value] + + pressure = pressure if pressure < 99 else 0 # 100 no obj, 99 sucking empty, so they are ignored + # grip status, 0->neutral, -1->bad (sucking but no obj), 1-> good (sucking and obj) + grip_status = 1. if pressure > 0 else grip_status + pressure /= 98. # pressure between [0, 1] with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = vel From 6d3866c3033dea0b0e29016deae7065eb4fdb5be Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 11 Jul 2024 17:16:01 +0200 Subject: [PATCH 232/338] 16 features are enough (faster training) --- serl_launcher/serl_launcher/vision/voxel_grid_encoders.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 99e5cef4..15a8755f 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -5,6 +5,8 @@ import jax.numpy as jnp import jax.lax as lax +import jax + class MLPEncoder(nn.Module): mlp: nn.module = None @@ -56,7 +58,7 @@ def __call__( if no_batch_dim: observations = observations[None] - observations = observations.astype(jnp.float32)[..., None] # add conv channel + observations = observations.astype(jnp.float32)[..., None] / 1. # add conv channel conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, padding="valid") @@ -64,7 +66,7 @@ def __call__( x = observations x = conv( - features=32, + features=16, kernel_size=(5, 5, 5), strides=(2, 2, 2), name="conv_5x5", @@ -72,7 +74,7 @@ def __call__( x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) x = conv( - features=32, + features=16, kernel_size=(3, 3, 3), strides=(1, 1, 1), name="conv_3x3" From 05f636f73651da03711279fc59f5794478b65f3f Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 15 Jul 2024 14:45:43 +0200 Subject: [PATCH 233/338] bugfix with releasing the gripper --- serl_robot_infra/robot_controllers/robotiq_controller.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 59650805..96fed5a2 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -282,7 +282,8 @@ async def send_gripper_command(self): self.gripper_timeout["last_grip"] = time.monotonic() # print("grip") - elif self.target_grip[0] < -0.5 and not np.isclose(self.gripper_state[0], 1., atol=1e-4): + # release if below neg threshold and gripper activated (grip_status not zero) + elif self.target_grip[0] < -0.5 and abs(self.gripper_state[1]) > 0.5: await self.robotiq_gripper.automatic_release() self.target_grip[0] = 0.0 # print("release") From 5ed726d2ab2b7083b813e578de18fdbee260a52e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 15:49:30 +0200 Subject: [PATCH 234/338] cost for the suction reward fix --- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index b8d9bee7..baa6df43 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -17,8 +17,8 @@ def compute_reward(self, obs, action) -> float: step_cost = 0.1 downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) - suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.9) - suction_cost = 5. * float(np.isclose(obs["state"]["gripper_state"][0], 0.99, atol=1e-3)) + suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.5) + suction_cost = 3. * float(obs["state"]["gripper_state"][1] < -0.5) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 orientation_cost *= 25. @@ -50,7 +50,7 @@ def compute_reward(self, obs, action) -> float: def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > self.curr_reset_pose[2] + 0.02 # +2cm + return 0.1 < state['gripper_state'][0] < 1. and state['tcp_pose'][2] > self.curr_reset_pose[2] + 0.01 # +1cm def close(self): super().close() From 5327f9aa941eb2b79186adde739f6cac041246c8 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 15:50:00 +0200 Subject: [PATCH 235/338] bugfix --- .../robot_controllers/robotiq_controller.py | 15 +++++---------- 1 file changed, 5 insertions(+), 10 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 96fed5a2..c319b450 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -33,7 +33,6 @@ def __init__( config=None, verbose=False, plot=False, - old_obs=False, *args, **kwargs ): @@ -51,7 +50,6 @@ def __init__( self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} self.verbose = verbose self.do_plot = plot - self.old_obs = old_obs # use the old observation layout self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) @@ -189,13 +187,9 @@ async def _update_robot_state(self): self.curr_vel[:] = vel self.curr_Q[:] = Q self.curr_Qd[:] = Qd - if self.old_obs: - self.curr_force[:] = np.asarray(force) # old representation for SAC policy - self.gripper_state[:] = [pressure, float(obj_status.value)] - else: - # use moving average (5), since the force fluctuates heavily - self.curr_force[:] = 0.1 * np.array(force) + 0.9 * self.curr_force[:] - self.gripper_state[:] = [pressure, grip_status] + # use moving average (5), since the force fluctuates heavily + self.curr_force[:] = 0.1 * np.array(force) + 0.9 * self.curr_force[:] + self.gripper_state[:] = [pressure, grip_status] def get_state(self): with self.lock: @@ -309,8 +303,9 @@ async def _go_to_reset_pose(self): # first disable vaccum gripper if self.robotiq_gripper: - for _ in range(100): + for _ in range(10): self.target_grip[0] = -1. + await self._update_robot_state() await self.send_gripper_command() time.sleep(0.1) gripper_status = await self.robotiq_gripper.get_object_status() From ecfab6325a328bb7c1fb0ca7f177c57c72580804 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 15:50:48 +0200 Subject: [PATCH 236/338] timing change in getting the current position of the robot arm --- .../robotiq_env/envs/robotiq_env.py | 31 ++++++++++--------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 27563d91..df9a3052 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -196,7 +196,7 @@ def __init__( ) if camera_mode in ["pointcloud"]: - image_space_definition["wrist_pointcloud"] = gym.spaces.Box( # TODO change here as well + image_space_definition["wrist_pointcloud"] = gym.spaces.Box( 0, 255, shape=(50, 50, 40), dtype=np.uint8 ) if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: @@ -233,12 +233,11 @@ def __init__( self.controller = RobotiqImpedanceController( robot_ip=config.ROBOT_IP, frequency=config.CONTROLLER_HZ, - kp=10000, - kd=2200, + kp=15000, + kd=3300, config=config, verbose=False, plot=False, - # old_obs=camera_mode is None # do not use anymore ) self.controller.start() # start Thread @@ -334,21 +333,19 @@ def step(self, action: np.ndarray) -> tuple: self.curr_path_length += 1 - self._update_currpos() obs = self._get_obs() + reward = self.compute_reward(obs, action) + truncated = self._is_truncated() + reward = reward if not truncated else reward - 10. # truncation penalty + done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated + dt = time.time() - start_time to_sleep = max(0, (1.0 / self.hz) - dt) if to_sleep == 0: warnings.warn(f"environment could not be within {self.hz} Hz, took {dt:.4f}s!") time.sleep(to_sleep) - reward = self.compute_reward(obs, action) - truncated = self._is_truncated() - - reward = reward if not truncated else reward - 10. # truncation penalty - - done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated return obs, reward, done, truncated, self.get_cost_infos(done) def compute_reward(self, obs, action) -> float: @@ -409,7 +406,6 @@ def reset(self, joint_reset=False, **kwargs): shift = self.go_to_rest(joint_reset=joint_reset) self.curr_path_length = 0 - self._update_currpos() obs = self._get_obs() return obs, {"reset_shift": shift} @@ -602,6 +598,13 @@ def _is_truncated(self): return self.controller.is_truncated() def _get_obs(self) -> dict: + # get image before state observation, so they match better in time + + images = None + if self.camera_mode is not None: + images = self.get_image() + + self._update_currpos() state_observation = { "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, @@ -609,11 +612,11 @@ def _get_obs(self) -> dict: "tcp_force": self.curr_force, "tcp_torque": self.curr_torque, } + if self.realtime_plot: self.plotting_client.send(np.concatenate([self.curr_force, self.curr_torque])) - if self.camera_mode is not None: - images = self.get_image() + if images is not None: return copy.deepcopy(dict(images=images, state=state_observation)) else: return copy.deepcopy(dict(state=state_observation)) From 7720de4486779c11b9313d473342f407298b4119 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 15:51:38 +0200 Subject: [PATCH 237/338] do use damping, so the controller does not run into things that easily (no thread prios in python :/ ...) --- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 070c5660..f94835ac 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -81,7 +81,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes CONTROLLER_HZ = 100 GRIPPER_TIMEOUT = 2000 # in milliseconds ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_DAMPING: float = 0.02 # faster but more vulnerable to crash... FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) @@ -93,8 +93,13 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): + RANDOM_RESET = False + RANDOM_XY_RANGE = (0.0,) + RANDOM_RZ_RANGE = (0.0,) + RESET_Q = np.array([ - [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237], + # [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237], # schräge position + [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384] # gerade pos ]) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.3, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.6, -0.3, -3.2]) From 695ac81e6bb1f93037886afd0b757db299ffbec9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 16:42:07 +0200 Subject: [PATCH 238/338] bugfix in downward force check --- .../robot_controllers/robotiq_controller.py | 45 +++++++++---------- 1 file changed, 21 insertions(+), 24 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index c319b450..c1f5a92b 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -58,7 +58,8 @@ def __init__( self.gripper_state = np.zeros((2,), dtype=np.float32) self.curr_Q = np.zeros((6,), dtype=np.float32) self.curr_Qd = np.zeros((6,), dtype=np.float32) - self.curr_force = np.zeros((6,), dtype=np.float32) # force of tool tip + self.curr_force_lowpass = np.zeros((6,), dtype=np.float32) # force of tool tip + self.curr_force = np.zeros((6,), dtype=np.float32) self.reset_Q = np.array([np.pi / 2., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.], dtype=np.float32) # reset state in Joint Space self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable @@ -187,8 +188,9 @@ async def _update_robot_state(self): self.curr_vel[:] = vel self.curr_Q[:] = Q self.curr_Qd[:] = Qd + self.curr_force[:] = np.array(force) # use moving average (5), since the force fluctuates heavily - self.curr_force[:] = 0.1 * np.array(force) + 0.9 * self.curr_force[:] + self.curr_force_lowpass[:] = 0.1 * np.array(force) + 0.9 * self.curr_force_lowpass[:] self.gripper_state[:] = [pressure, grip_status] def get_state(self): @@ -198,8 +200,8 @@ def get_state(self): "vel": self.curr_vel, "Q": self.curr_Q, "Qd": self.curr_Qd, - "force": self.curr_force[:3], - "torque": self.curr_force[3:], + "force": self.curr_force_lowpass[:3], + "torque": self.curr_force_lowpass[3:], "gripper": self.gripper_state } return state @@ -228,12 +230,9 @@ def _calculate_force(self): vel_rot_diff = R.from_rotvec(curr_vel[3:]).inv() torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable - # TODO make better and more general (tcp force check) # check for big downward tcp force and adapt accordingly - if self.curr_force[2] > 0.5 and force_pos[2] < 0.: - # print(force_pos[2], end=" ") - force_pos[2] = max((1.5 - self.curr_force[2]), 0.) * force_pos[2] + min(self.curr_force[2] - 0.5, 1.) * 20. - # print(force_pos[2]) + if self.curr_force[2] > 3.5 and force_pos[2] < 0.: + force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. return np.concatenate((force_pos, torque)) @@ -266,7 +265,12 @@ def plot(self): plt.show(block=True) self.stop() - async def send_gripper_command(self): + async def send_gripper_command(self, force_release=False): + if force_release: + await self.robotiq_gripper.automatic_release() + self.target_grip[0] = 0.0 + return + timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout[ "timeout"] # target grip above threshold and timeout exceeded and not gripping something already @@ -283,7 +287,7 @@ async def send_gripper_command(self): # print("release") def _truncate_check(self): - downward_force = self.curr_force[2] > 20. + downward_force = self.curr_force_lowpass[2] > 20. if downward_force: # TODO add better criteria self._is_truncated.set() else: @@ -303,14 +307,8 @@ async def _go_to_reset_pose(self): # first disable vaccum gripper if self.robotiq_gripper: - for _ in range(10): - self.target_grip[0] = -1. - await self._update_robot_state() - await self.send_gripper_command() - time.sleep(0.1) - gripper_status = await self.robotiq_gripper.get_object_status() - if gripper_status.value == 3: - break + await self.send_gripper_command(force_release=True) + time.sleep(0.01) # then move up (so no boxes are moved) success = True @@ -368,7 +366,7 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f" p:{self.curr_pos} f:{self.curr_force} gr:{self.gripper_state}") # log to file + self.print(f" p:{self.curr_pos} f:{self.curr_force_lowpass} gr:{self.gripper_state}") # log to file # send command to robot t_start = self.robotiq_control.initPeriod() @@ -381,7 +379,7 @@ async def run_async(self): ) if not fm_successful: # truncate if the robot ends up in a singularity await self.restart_robotiq_interface() - self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) + await self._go_to_reset_pose() if self.robotiq_gripper: await self.send_gripper_command() @@ -400,9 +398,8 @@ async def run_async(self): # release gripper if self.robotiq_gripper: - self.target_grip[0] = -1. - await self.send_gripper_command() - time.sleep(0.1) + await self.send_gripper_command(force_release=True) + time.sleep(0.05) # move to real home pi = 3.1415 From 26683d0860bf2659d2eb7690769636a15a736756 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 16:42:46 +0200 Subject: [PATCH 239/338] new: use conv instead of maxpool and reduce over z dim --- .../vision/voxel_grid_encoders.py | 36 ++++++++++++------- 1 file changed, 23 insertions(+), 13 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 15a8755f..85cb1a0e 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -66,7 +66,7 @@ def __call__( x = observations x = conv( - features=16, + features=32, kernel_size=(5, 5, 5), strides=(2, 2, 2), name="conv_5x5", @@ -74,12 +74,22 @@ def __call__( x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) x = conv( - features=16, + features=32, kernel_size=(3, 3, 3), - strides=(1, 1, 1), - name="conv_3x3" + strides=(2, 2, 2), + name="conv_3x3_1" )(x) - x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, 32) + x = l_relu(x) # shape (B, (X-4)/4, (Y-4)/4, (Z-4)/4, 32) + + x = conv( + features=32, + kernel_size=(3, 3, 3), + strides=(2, 2, 2), + name="conv_3x3_2" + )(x) + x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, 32) + + x = jnp.mean(x, axis=(-2)) # average over z dim # 1x1 convolution (dimensionality reduction, no features), not used for now # x = conv( @@ -87,14 +97,14 @@ def __call__( # kernel_size=(1, 1, 1), # )(x) - x = lax.reduce_window( - x, - init_value=-jnp.inf, - computation=lax.max, - window_dimensions=(1, 2, 2, 2, 1), - window_strides=(1, 2, 2, 2, 1), - padding='VALID' - ) + # x = lax.reduce_window( + # x, + # init_value=-jnp.inf, + # computation=lax.max, + # window_dimensions=(1, 2, 2, 2, 1), + # window_strides=(1, 2, 2, 2, 1), + # padding='VALID' + # ) # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) From bc4737f88eb5dbc107a23c28d44b092f368a8fe7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 16 Jul 2024 18:26:30 +0200 Subject: [PATCH 240/338] bugfix for using dropout in the critic network --- serl_launcher/serl_launcher/networks/actor_critic_nets.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index 276d070d..b7b4b66a 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -159,7 +159,7 @@ def ensemblize(cls, num_qs, out_axes=0): return nn.vmap( cls, variable_axes={"params": 0}, - split_rngs={"params": True}, + split_rngs={"params": True, "dropout": True}, in_axes=None, out_axes=out_axes, axis_size=num_qs, From fcac56c9079a97464f5d8d01e0355d9392a855d9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 17 Jul 2024 12:34:12 +0200 Subject: [PATCH 241/338] cleanup --- examples/robotiq_drq/record_demo.py | 2 +- serl_launcher/serl_launcher/agents/continuous/drq.py | 3 --- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index b173c1e5..a1000a66 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -52,7 +52,7 @@ def on_esc(key): pbar = tqdm(total=success_needed) info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, - 'force': env.unwrapped.curr_force} + 'force': env.unwrapped.curr_force, 'reset_pose': env.unwrapped.curr_reset_pose} listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) listener_1.start() diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 50423e54..b7f35eb9 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -92,7 +92,6 @@ def create( target_entropy = -prod(actions.shape) print(f"config: discount: {discount}, target_entropy: {target_entropy}") - # print(f"actor_optimizer {actor_optimizer_kwargs} critic_optimizer {critic_optimizer_kwargs} temperature {temperature_optimizer_kwargs}") return cls( state=state, @@ -267,8 +266,6 @@ def create_drq( image_keys=image_keys, ) - # print(f"encoder def: {encoder_def}") - encoders = { "critic": encoder_def, "actor": encoder_def, From 95cc778d5c91e138fb6db2cd4f3cd74eca2a294f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 17 Jul 2024 12:34:45 +0200 Subject: [PATCH 242/338] dropout successful run --- examples/robotiq_drq/run_actor.sh | 4 ++-- examples/robotiq_drq/run_learner.sh | 6 +++--- serl_launcher/serl_launcher/utils/launcher.py | 2 ++ 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index 9b7c22b1..ad9d70ee 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -6,8 +6,8 @@ python drq_policy_robotiq.py "$@" \ --max_traj_length 100 \ --exp_name=drq_10box \ --camera_mode pointcloud \ - --seed 1 \ - --max_steps 30000 \ + --seed 2 \ + --max_steps 20000 \ --random_steps 500 \ --training_starts 500 \ --utd_ratio 8 \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index 48aa5581..04447f01 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -6,8 +6,8 @@ python drq_policy_robotiq.py "$@" \ --exp_name=drq_10box \ --camera_mode pointcloud \ --max_traj_length 100 \ - --seed 1 \ - --max_steps 15000 \ + --seed 2 \ + --max_steps 20000 \ --random_steps 500 \ --training_starts 500 \ --utd_ratio 8 \ @@ -15,5 +15,5 @@ python drq_policy_robotiq.py "$@" \ --eval_period 20000 \ --encoder_type voxnet \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul8_voxelgrid.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul15_vox_554b_newgripstat.pkl \ # --debug diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index da166438..ad7f7374 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -122,11 +122,13 @@ def make_drq_agent( activations=nn.tanh, # TODO test relu use_layer_norm=True, hidden_dims=[256, 256], + dropout_rate=0.1 # TODO test dropout ), policy_network_kwargs=dict( activations=nn.tanh, use_layer_norm=True, hidden_dims=[256, 256], + dropout_rate=0.1 # TODO test dropout ), temperature_init=1e-2, discount=0.99, # 0.99 From 4dff73c22e787cd562229fb00e646185cda5290f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 17 Jul 2024 14:29:57 +0200 Subject: [PATCH 243/338] added voxnet final activation choice --- serl_launcher/serl_launcher/agents/continuous/drq.py | 1 + serl_launcher/serl_launcher/vision/voxel_grid_encoders.py | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index b7f35eb9..95bccdcb 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -251,6 +251,7 @@ def create_drq( image_key: VoxNet( bottleneck_dim=encoder_kwargs["bottleneck_dim"], use_conv_bias=False, + final_activation=nn.tanh, ) for image_key in image_keys } diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 85cb1a0e..ab8d58d8 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -45,6 +45,7 @@ class VoxNet(nn.Module): use_conv_bias: bool = False bottleneck_dim: Optional[int] = None + final_activation: Callable[[jnp.ndarray], jnp.ndarray] | str = nn.tanh @nn.compact def __call__( @@ -111,6 +112,6 @@ def __call__( if self.bottleneck_dim is not None: x = nn.Dense(self.bottleneck_dim)(x) x = nn.LayerNorm()(x) - x = nn.tanh(x) + x = self.final_activation(x) return x[0] if no_batch_dim else x From 890546905544973a2abbb95d58349e75e3d2d0b8 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 18 Jul 2024 14:46:00 +0200 Subject: [PATCH 244/338] tests done --- serl_launcher/serl_launcher/utils/launcher.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index ad7f7374..52179426 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -119,16 +119,16 @@ def make_drq_agent( std_max=5, ), critic_network_kwargs=dict( - activations=nn.tanh, # TODO test relu + activations=nn.tanh, use_layer_norm=True, hidden_dims=[256, 256], - dropout_rate=0.1 # TODO test dropout + dropout_rate=0.1 ), policy_network_kwargs=dict( activations=nn.tanh, use_layer_norm=True, hidden_dims=[256, 256], - dropout_rate=0.1 # TODO test dropout + dropout_rate=0.1 ), temperature_init=1e-2, discount=0.99, # 0.99 From dfd7268569264b1ef8d794354bc893e5214a80e9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 18 Jul 2024 14:48:11 +0200 Subject: [PATCH 245/338] new PointCloudFusion starting parameters --- serl_robot_infra/robotiq_env/camera/utils.py | 23 +++++++++++++++---- .../robotiq_env/envs/robotiq_env.py | 8 ++++--- 2 files changed, 24 insertions(+), 7 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 007542b2..19c8ff01 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -62,7 +62,7 @@ def transform_point_cloud(points, transform_matrix): class PointCloudFusion: - def __init__(self, angle=30., x_distance=0.195, voxel_grid_shape=(100, 100, 80)): + def __init__(self, angle=30., x_distance=0.195, y_distance=-0.0, voxel_grid_shape=(100, 100, 80)): self.pcd1, self.pcd2 = None, None # 10cm width and 8cm height for the box @@ -80,11 +80,13 @@ def __init__(self, angle=30., x_distance=0.195, voxel_grid_shape=(100, 100, 80)) t1 = np.eye(4) t1[:3, :3] = R.from_euler("xyz", [angle, 0., 0.], degrees=True).as_matrix() t1[1, 3] = x_distance / 2. + t1[0, 3] = y_distance / 2. self.t1 = t1 t2 = np.eye(4) t2[:3, :3] = R.from_euler("xyz", [-angle, 0., 0.], degrees=True).as_matrix() t2[1, 3] = -x_distance / 2. + t2[0, 3] = -y_distance / 2. self.t2 = t2 def save_finetuned(self): @@ -177,12 +179,12 @@ def get_pointcloud_representation(self, voxelize=True): elif not self.is_empty(): return self.get_first(voxelize=voxelize) - def fuse_pointclouds(self, voxelize=True): + def fuse_pointclouds(self, voxelize=True, cropped=True): if not self._is_transformed: self._transform() swap = lambda x: np.moveaxis(x, 0, 1) fused = swap(np.hstack([swap(self.pcd1), swap(self.pcd2)])) - return self.voxelize(fused) if voxelize else self.crop(fused) + return self.voxelize(fused) if voxelize else (self.crop(fused) if cropped else fused) def get_first(self, voxelize=True): if not self._is_transformed: @@ -219,7 +221,7 @@ def append_backlog(self, pc1, pc2): self.pc_backlog.append([pc1, pc2]) assert self.samples.shape[0] >= len(self.pc_backlog) - def calibrate(self): + def calibrate(self, visualize=False): print(f"calibrating for {len(self.pc_backlog)} samples...") for i, (pc1, pc2) in enumerate(self.pc_backlog): self.pc_fusion.clear() @@ -228,6 +230,19 @@ def calibrate(self): self.samples[i, ...] = self.pc_fusion.calibrate_fusion() + if visualize: + # visualize for testing + pc = self.pc_fusion.pcd1.copy() + pc2 = self.pc_fusion.pcd2.copy() + pc = transform_point_cloud(points=pc, transform_matrix=self.samples[i]) # transform + + swap = lambda x: np.moveaxis(x, 0, 1) + fused = swap(np.hstack([swap(pc), swap(pc2)])) + + pc = o3d.geometry.PointCloud() + pc.points = o3d.utility.Vector3dVector(fused) + o3d.visualization.draw_geometries([pc]) + rotations = R.from_matrix(self.samples[:, :3, :3]) mean_rot = rotations.mean().as_matrix() translation = np.mean(self.samples[:, :3, 3], axis=0) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index df9a3052..13215e4a 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -267,10 +267,11 @@ def __init__( # voxel_grid_shape[-1] *= 8 # do not use compacting for now # voxel_grid_shape *= 2 print(f"pointcloud resolution set to: {voxel_grid_shape}") - self.pointcloud_fusion = PointCloudFusion(angle=32., x_distance=0.196, voxel_grid_shape=voxel_grid_shape) + self.pointcloud_fusion = PointCloudFusion(angle=31., x_distance=0.205, voxel_grid_shape=voxel_grid_shape) # load pre calibrated, else calibrate if not self.pointcloud_fusion.load_finetuned(): + # TODO make calibration more robust! self.calibration_thread = CalibrationTread(pc_fusion=self.pointcloud_fusion, verbose=True) self.calibration_thread.start() @@ -522,6 +523,7 @@ def get_image(self) -> Dict[str, np.ndarray]: def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20): self.reset() + import open3d as o3d assert self.camera_mode in ["pointcloud"] print("calibrating pointcloud fusion...") @@ -535,6 +537,7 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 print(action) obs, reward, done, truncated, _ = self.step(np.array(action)) + time.sleep(0.1) self.calibration_thread.append_backlog(*self.pointcloud_fusion.get_original_pcds()) @@ -547,7 +550,6 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 self.pointcloud_fusion.save_finetuned() if visualize: - import open3d as o3d pc = o3d.geometry.PointCloud() for i in range(num_samples): pc.clear() @@ -555,7 +557,7 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 self.pointcloud_fusion.clear() self.pointcloud_fusion.append(pcs[0]) self.pointcloud_fusion.append(pcs[1]) - fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=False) + fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=False, cropped=False) pc.points = o3d.utility.Vector3dVector(fused) o3d.visualization.draw_geometries([pc]) From 892918420073503995020d2d7df844513d73d9d2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Jul 2024 16:58:51 +0200 Subject: [PATCH 246/338] implemented 4-fold voxel augmentation (randomly rotate the state, voxel grid and action n*90 degrees) --- .../serl_launcher/agents/continuous/drq.py | 240 ++++++++++++------ .../vision/data_augmentations.py | 82 +++++- 2 files changed, 242 insertions(+), 80 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 95bccdcb..4b8706b0 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -18,39 +18,45 @@ from serl_launcher.networks.mlp import MLP from serl_launcher.vision.voxel_grid_encoders import MLPEncoder, VoxNet from serl_launcher.utils.train_utils import _unpack, concat_batches -from serl_launcher.vision.data_augmentations import batched_random_crop, batched_random_shift_voxel +from serl_launcher.vision.data_augmentations import ( + batched_random_crop, + batched_random_shift_voxel, + batched_random_rot90_action, + batched_random_rot90_state, + batched_random_rot90_voxel +) class DrQAgent(SACAgent): @classmethod def create( - cls, - rng: PRNGKey, - observations: Data, - actions: jnp.ndarray, - # Models - actor_def: nn.Module, - critic_def: nn.Module, - temperature_def: nn.Module, - # Optimizer - actor_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 - }, - critic_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 - }, - temperature_optimizer_kwargs={ - "learning_rate": 3e-4, - }, - # Algorithm config - discount: float = 0.95, - soft_target_update_rate: float = 0.005, - target_entropy: Optional[float] = None, - entropy_per_dim: bool = False, - backup_entropy: bool = False, - critic_ensemble_size: int = 2, - critic_subsample_size: Optional[int] = None, - image_keys: Iterable[str] = ("image",), + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Models + actor_def: nn.Module, + critic_def: nn.Module, + temperature_def: nn.Module, + # Optimizer + actor_optimizer_kwargs={ + "learning_rate": 3e-4, # 3e-4 + }, + critic_optimizer_kwargs={ + "learning_rate": 3e-4, # 3e-4 + }, + temperature_optimizer_kwargs={ + "learning_rate": 3e-4, + }, + # Algorithm config + discount: float = 0.95, + soft_target_update_rate: float = 0.005, + target_entropy: Optional[float] = None, + entropy_per_dim: bool = False, + backup_entropy: bool = False, + critic_ensemble_size: int = 2, + critic_subsample_size: Optional[int] = None, + image_keys: Iterable[str] = ("image",), ): networks = { "actor": actor_def, @@ -108,33 +114,33 @@ def create( @classmethod def create_drq( - cls, - rng: PRNGKey, - observations: Data, - actions: jnp.ndarray, - # Model architecture - encoder_type: str = "small", - use_proprio: bool = False, - critic_network_kwargs: dict = { - "hidden_dims": [256, 256], - }, - policy_network_kwargs: dict = { - "hidden_dims": [256, 256], - }, - policy_kwargs: dict = { - "tanh_squash_distribution": True, - "std_parameterization": "uniform", - }, - encoder_kwargs: dict = { - "pooling_method": "spatial_learned_embeddings", - "num_spatial_blocks" : 8, - "bottleneck_dim" : 256, - }, - critic_ensemble_size: int = 2, - critic_subsample_size: Optional[int] = None, - temperature_init: float = 1.0, - image_keys: Iterable[str] = ("image",), - **kwargs, + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Model architecture + encoder_type: str = "small", + use_proprio: bool = False, + critic_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_kwargs: dict = { + "tanh_squash_distribution": True, + "std_parameterization": "uniform", + }, + encoder_kwargs: dict = { + "pooling_method": "spatial_learned_embeddings", + "num_spatial_blocks": 8, + "bottleneck_dim": 256, + }, + critic_ensemble_size: int = 2, + critic_subsample_size: Optional[int] = None, + temperature_init: float = 1.0, + image_keys: Iterable[str] = ("image",), + **kwargs, ): """ Create a new pixel-based agent. @@ -180,7 +186,8 @@ def create_drq( name="pretrained_encoder", ) - use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == ( + 128, 128, 1) print(f"use single channel only: {use_single_channel}") encoders = { @@ -202,7 +209,8 @@ def create_drq( name="pretrained_encoder", ) - use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) + use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == ( + 128, 128, 1) print(f"use single channel only: {use_single_channel}") encoders = { @@ -268,8 +276,8 @@ def create_drq( ) encoders = { - "critic": encoder_def, - "actor": encoder_def, + "critic": encoder_def, + "actor": encoder_def, } # Define networks @@ -316,33 +324,87 @@ def create_drq( return agent - def data_augmentation_fn(self, rng, observations): + def batch_augmentation_fn(self, observations, next_observations, actions, rng): for pixel_key in self.config["image_keys"]: + if not "pointcloud" in pixel_key: + continue # skip if not pointcloud + + # rotation of state, action and voxel grid (use the same rng for all of them, so same rotation) + # jax.debug.print("before {} {} {}", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) + # jax.debug.print("voxel: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) + observations = observations.copy( + add_or_replace={ + "state": batched_random_rot90_state( + observations["state"], rng, num_batch_dims=2 + ), + pixel_key: batched_random_rot90_voxel( + observations[pixel_key], rng, num_batch_dims=2 + ), + } + ) + next_observations = next_observations.copy( + add_or_replace={ + "state": batched_random_rot90_state( + next_observations["state"], rng, num_batch_dims=2 + ), + pixel_key: batched_random_rot90_voxel( + next_observations[pixel_key], rng, num_batch_dims=2 + ) + } + ) + actions = batched_random_rot90_action( + actions, rng, + ) + # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) + # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) + return observations, next_observations, actions + + def image_augmentation_fn(self, obs_rng, observations, next_obs_rng, next_observations): + # TODO make it configurable: see https://github.com/rail-berkeley/serl/pull/67 + + for pixel_key in self.config["image_keys"]: + # pointcloud augmentation if "pointcloud" in pixel_key: observations = observations.copy( add_or_replace={ pixel_key: batched_random_shift_voxel( - observations[pixel_key], rng, padding=3, num_batch_dims=2 + observations[pixel_key], obs_rng, padding=3, num_batch_dims=2 + ) + } + ) + next_observations = next_observations.copy( + add_or_replace={ + pixel_key: batched_random_shift_voxel( + next_observations[pixel_key], next_obs_rng, padding=3, num_batch_dims=2 ) } ) + + # image augmentation else: observations = observations.copy( add_or_replace={ pixel_key: batched_random_crop( - observations[pixel_key], rng, padding=4, num_batch_dims=2 + observations[pixel_key], obs_rng, padding=4, num_batch_dims=2 ) } ) - return observations + next_observations = next_observations.copy( + add_or_replace={ + pixel_key: batched_random_crop( + next_observations[pixel_key], next_obs_rng, padding=4, num_batch_dims=2 + ) + } + ) + return observations, next_observations @partial(jax.jit, static_argnames=("utd_ratio", "pmap_axis")) def update_high_utd( - self, - batch: Batch, - *, - utd_ratio: int, - pmap_axis: Optional[str] = None, + self, + batch: Batch, + *, + utd_ratio: int, + pmap_axis: Optional[str] = None, ) -> Tuple["DrQAgent", dict]: """ Fast JITted high-UTD version of `.update`. @@ -360,9 +422,19 @@ def update_high_utd( batch = _unpack(batch) rng = new_agent.state.rng - rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) - obs = self.data_augmentation_fn(obs_rng, batch["observations"]) - next_obs = self.data_augmentation_fn(next_obs_rng, batch["next_observations"]) + rng, obs_rng, next_obs_rng, rot90_rng = jax.random.split(rng, 4) + obs, next_obs = self.image_augmentation_fn( + obs_rng=obs_rng, + observations=batch["observations"], + next_obs_rng=next_obs_rng, + next_observations=batch["next_observations"] + ) + obs, next_obs, actions = self.batch_augmentation_fn( + observations=obs, + next_observations=next_obs, + actions=batch["actions"], + rng=rot90_rng + ) batch = batch.copy( add_or_replace={ "observations": obs, @@ -381,10 +453,10 @@ def update_high_utd( @partial(jax.jit, static_argnames=("pmap_axis",)) def update_critics( - self, - batch: Batch, - *, - pmap_axis: Optional[str] = None, + self, + batch: Batch, + *, + pmap_axis: Optional[str] = None, ) -> Tuple["DrQAgent", dict]: new_agent = self if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: @@ -393,13 +465,25 @@ def update_critics( # TODO implement K=2 and M=2 rng = new_agent.state.rng - rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) - obs = self.data_augmentation_fn(obs_rng, batch["observations"]) - next_obs = self.data_augmentation_fn(next_obs_rng, batch["next_observations"]) + rng, obs_rng, next_obs_rng, rot90_rng = jax.random.split(rng, 4) + obs, next_obs = self.image_augmentation_fn( + obs_rng=obs_rng, + observations=batch["observations"], + next_obs_rng=next_obs_rng, + next_observations=batch["next_observations"] + ) + obs, next_obs, actions = self.batch_augmentation_fn( + observations=obs, + next_observations=next_obs, + actions=batch["actions"], + rng=rot90_rng + ) + batch = batch.copy( add_or_replace={ "observations": obs, "next_observations": next_obs, + "actions": actions, } ) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 4cc4676b..bb5ea791 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -2,8 +2,86 @@ import jax import jax.numpy as jnp +import jax.lax as lax +ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) +# Rotations are in the array transposed for easy dot product +ROT_GENERAL = jnp.array([jnp.eye(3), ROT90.transpose(), ROT90 @ ROT90, ROT90]) + +@jax.jit +def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gripper) + xyz_rotated = jnp.dot(action[:3], ROT_GENERAL[num_rot]) + orientation_rotated = jnp.dot(action[3:6], ROT_GENERAL[num_rot]) + return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) + + +@jax.jit +def batched_random_rot90_action(actions, rng): + assert actions.shape[-1:] == (7,) + num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) + # jax.debug.print("rotation: {}", num_rot[:20]) + + actions = jax.vmap( + lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 + )(actions, num_rot) + return actions + + +@partial(jax.jit, static_argnames="num_batch_dims") +def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1): + original_shape = state.shape + state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) + num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) + + state = jax.vmap( + lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 + )(state, num_rot) + + return state.reshape(original_shape) + + +def random_rot90_state(state, num_rot): + assert state.shape[-1] == 20 + + # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) + start_indexes = jnp.array([2, 8, 11, 14, 17]) + + def rotate_part(i, state): + part = lax.dynamic_slice(state, (start_indexes[i],), (3,)) + rotated = jnp.dot(part, ROT_GENERAL[num_rot]) + return lax.dynamic_update_slice(state, rotated, (start_indexes[i],)) + + # Apply rotations sequentially + state = jax.lax.fori_loop(0, start_indexes.shape[0], rotate_part, state) + + return state + + +@partial(jax.jit, static_argnames="num_batch_dims") +def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): + original_shape = voxel_grid.shape + voxel_grid = jnp.reshape(voxel_grid, (-1, *voxel_grid.shape[num_batch_dims:])) + num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) + + voxel_grid = jax.vmap( + lambda v, k: random_rot90_voxel(v, k), in_axes=(0, 0), out_axes=0 + )(voxel_grid, num_rot) + + return voxel_grid.reshape(original_shape) + + +@partial(jax.jit, static_argnames="axes") +def rot90_traceable(m, k=1, axes=(0, 1)): + return jax.lax.switch(k, [partial(jnp.rot90, m, k=i, axes=axes) for i in range(4)]) + + +@jax.jit +def random_rot90_voxel(voxel_grid, num_rot): + return rot90_traceable(voxel_grid, k=num_rot, axes=(-3, -2)) + + +@partial(jax.jit, static_argnames="padding") def random_crop(img, rng, *, padding): crop_from = jax.random.randint(rng, (2,), 0, 2 * padding + 1) crop_from = jnp.concatenate([crop_from, jnp.zeros((1,), dtype=jnp.int32)]) @@ -44,7 +122,7 @@ def random_shift_3d(img, rng, *, padding): (padding, padding), (padding, padding), (padding, padding), - ), + ), mode="constant" ) return jax.lax.dynamic_slice(padded_img, crop_from, img.shape) @@ -54,7 +132,7 @@ def random_shift_3d(img, rng, *, padding): def batched_random_shift_voxel(img, rng, *, padding, num_batch_dims: int = 1): original_shape = img.shape img = jnp.reshape(img, (-1, *img.shape[num_batch_dims:])) - # shape (B, X, Y, Z) + # shape (B, B2, X, Y, Z) rngs = jax.random.split(rng, img.shape[0]) img = jax.vmap( From 30db4610f36295092b4fe1debd48a68bad151b54 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Jul 2024 18:42:41 +0200 Subject: [PATCH 247/338] augmentation bugfixes --- serl_launcher/serl_launcher/agents/continuous/drq.py | 6 +++--- serl_launcher/serl_launcher/vision/data_augmentations.py | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 4b8706b0..5cef24db 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -352,9 +352,9 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng): ) } ) - actions = batched_random_rot90_action( - actions, rng, - ) + # actions = batched_random_rot90_action( + # actions, rng, + # ) # maybe action are the problem # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) return observations, next_observations, actions diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index bb5ea791..ca550193 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -45,7 +45,7 @@ def random_rot90_state(state, num_rot): assert state.shape[-1] == 20 # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) - start_indexes = jnp.array([2, 8, 11, 14, 17]) + start_indexes = jnp.array([2, 5, 8, 11, 14, 17]) # rotate everything (except gripper) def rotate_part(i, state): part = lax.dynamic_slice(state, (start_indexes[i],), (3,)) @@ -72,7 +72,7 @@ def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): @partial(jax.jit, static_argnames="axes") -def rot90_traceable(m, k=1, axes=(0, 1)): +def rot90_traceable(m, k=1, axes=(0, 1)): # TODO check if rotation is the wrong way around! return jax.lax.switch(k, [partial(jnp.rot90, m, k=i, axes=axes) for i in range(4)]) From f0439edd7c027169bf8599ff54b1f266385696d0 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 19 Jul 2024 18:43:33 +0200 Subject: [PATCH 248/338] reset position bugfix for controller --- serl_robot_infra/robot_controllers/robotiq_controller.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index c1f5a92b..66ba6a08 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -313,7 +313,10 @@ async def _go_to_reset_pose(self): # then move up (so no boxes are moved) success = True while self.curr_pos[2] < self.reset_height: - success = success and self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) + if self.curr_Q[2] < 0.5: # if the shoulder joint is near 180deg --> do not move into singularity + success = success and self.robotiq_control.speedJ([0., -1., 1., 0., 0., 0.], acceleration=0.8) + else: + success = success and self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) await self._update_robot_state() time.sleep(0.01) self.robotiq_control.speedStop(a=1.) @@ -389,6 +392,8 @@ async def run_async(self): a = dt - (time.monotonic() - t_now) time.sleep(max(0., a)) self.err, self.noerr = self.err + int(a < 0.), self.noerr + int(a >= 0.) # some logging + if a < -0.04: # log if delay more than 50ms + self.print(f"Controller Thread stopped for {(time.monotonic() - t_now)*1e3:.1f} ms") finally: if self.verbose: From 9a9b03630476a239ffec959680a23271ee23fbb9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 22 Jul 2024 15:38:01 +0200 Subject: [PATCH 249/338] transform force and torque to relative frame as well --- .../robotiq_env/envs/relative_env.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index 07f9a169..71f7480e 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -14,13 +14,16 @@ class RelativeFrame(gym.Wrapper): This wrapper transforms the observation and action to be expressed in the end-effector frame. Optionally, it can transform the tcp_pose into a relative frame defined as the reset pose. - This wrapper is expected to be used on top of the base Franka environment, which has the following + This wrapper is expected to be used on top of the base Robotiq environment, which has the following observation space: { "state": spaces.Dict( { "tcp_pose": spaces.Box(-np.inf, np.inf, shape=(7,)), # xyz + quat - ...... + "tcp_vel": spaces.Box(-np.inf, np.inf, shape=(6,)), + "tcp_force": spaces.Box(-np.inf, np.inf, shape=(3,)), + "tcp_torque": spaces.Box(-np.inf, np.inf, shape=(3,)), + "gripper_state": spaces.Box(-np.inf, np.inf, shape=(2,)), } ), ...... @@ -76,10 +79,12 @@ def reset(self, **kwargs): def transform_observation(self, obs): """ Transform observations from spatial(base) frame into body(end-effector) frame - using the adjoint matrix + using the rotation, adjoint and homogeneous matrix """ adjoint_inv = np.linalg.inv(self.adjoint_matrix) obs["state"]["tcp_vel"] = adjoint_inv @ obs["state"]["tcp_vel"] + obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] + obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] if self.include_relative_pose: T_b_o = construct_homogeneous_matrix(obs["state"]["tcp_pose"]) @@ -95,7 +100,7 @@ def transform_observation(self, obs): def transform_action(self, action: np.ndarray): """ Transform action from body(end-effector) frame into spatial(base) frame - using the adjoint matrix + using the rotation matrix """ action = np.array(action) # in case action is a jax read-only array action[:3] = self.rotation_matrix @ action[:3] @@ -104,8 +109,8 @@ def transform_action(self, action: np.ndarray): def transform_action_inv(self, action: np.ndarray): """ Transform action from spatial(base) frame into body(end-effector) frame - using the adjoint matrix. + using the rotation matrix. """ action = np.array(action) - action[:3] = np.linalg.inv(self.rotation_matrix) @ action[:3] + action[:3] = self.rotation_matrix.transpose() @ action[:3] return action From a4aaf84d2fcee2d48f43ca43556fc6a899491801 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 22 Jul 2024 15:38:34 +0200 Subject: [PATCH 250/338] rlds path fix --- examples/robotiq_drq/drq_policy_robotiq.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 0092208e..4fbee6a7 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -83,7 +83,7 @@ flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") From 43cb564fd0c8b6ee38d2459679a1b4193b41ba95 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 22 Jul 2024 15:38:51 +0200 Subject: [PATCH 251/338] action needs to be roatated as well in augmentation --- serl_launcher/serl_launcher/agents/continuous/drq.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 5cef24db..96a1f0e8 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -332,6 +332,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng): # rotation of state, action and voxel grid (use the same rng for all of them, so same rotation) # jax.debug.print("before {} {} {}", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) + # jax.debug.print("action: {}", actions[0, :]) observations = observations.copy( add_or_replace={ "state": batched_random_rot90_state( @@ -352,11 +353,12 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng): ) } ) - # actions = batched_random_rot90_action( - # actions, rng, - # ) # maybe action are the problem + actions = batched_random_rot90_action( + actions, rng, + ) # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) + # jax.debug.print("action after: {}", actions[0, :]) return observations, next_observations, actions def image_augmentation_fn(self, obs_rng, observations, next_obs_rng, next_observations): From b19f93959cc12adebb89dae44605a801245d9a37 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 22 Jul 2024 15:41:10 +0200 Subject: [PATCH 252/338] voxel rotation needs to be clockwise (tcp frame is upside down) --- serl_launcher/serl_launcher/vision/data_augmentations.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index ca550193..c50bc740 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -20,7 +20,7 @@ def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz def batched_random_rot90_action(actions, rng): assert actions.shape[-1:] == (7,) num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) - # jax.debug.print("rotation: {}", num_rot[:20]) + # jax.debug.print("rotation: {}", num_rot[0]) actions = jax.vmap( lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 @@ -72,8 +72,8 @@ def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): @partial(jax.jit, static_argnames="axes") -def rot90_traceable(m, k=1, axes=(0, 1)): # TODO check if rotation is the wrong way around! - return jax.lax.switch(k, [partial(jnp.rot90, m, k=i, axes=axes) for i in range(4)]) +def rot90_traceable(m, k=1, axes=(0, 1)): + return jax.lax.switch(k, [partial(jnp.rot90, m, k=-i, axes=axes) for i in range(4)]) @jax.jit From 6180ac91893e5dd30a3cb59452b24717f988615b Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 22 Jul 2024 17:51:03 +0200 Subject: [PATCH 253/338] drq bugfix (actions were not updated, stupid me...) --- serl_launcher/serl_launcher/agents/continuous/drq.py | 1 + 1 file changed, 1 insertion(+) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 96a1f0e8..dfc52b99 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -441,6 +441,7 @@ def update_high_utd( add_or_replace={ "observations": obs, "next_observations": next_obs, + "actions": actions, } ) From 4448ffd35fdea9037518e4e909fe6ab6e7537e5f Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 23 Jul 2024 16:11:59 +0200 Subject: [PATCH 254/338] deactivate batch rotation for now --- serl_launcher/serl_launcher/agents/continuous/drq.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index dfc52b99..20776e48 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -324,10 +324,12 @@ def create_drq( return agent - def batch_augmentation_fn(self, observations, next_observations, actions, rng): + def batch_augmentation_fn(self, observations, next_observations, actions, rng, activated=True): + if not activated: + return observations, next_observations, actions for pixel_key in self.config["image_keys"]: if not "pointcloud" in pixel_key: - continue # skip if not pointcloud + continue # skip if not pointcloud # rotation of state, action and voxel grid (use the same rng for all of them, so same rotation) # jax.debug.print("before {} {} {}", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) @@ -435,7 +437,8 @@ def update_high_utd( observations=obs, next_observations=next_obs, actions=batch["actions"], - rng=rot90_rng + rng=rot90_rng, + activated=False, ) batch = batch.copy( add_or_replace={ @@ -479,7 +482,8 @@ def update_critics( observations=obs, next_observations=next_obs, actions=batch["actions"], - rng=rot90_rng + rng=rot90_rng, + activated=False, ) batch = batch.copy( From 8c0f018bc3a9f97b6d0b2f24e0716f611866e736 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 12:32:01 +0200 Subject: [PATCH 255/338] adjoint matrix should not be used at all, bug found after some velocity orientation tests --- serl_robot_infra/robotiq_env/envs/relative_env.py | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index 71f7480e..d54eb123 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -3,7 +3,6 @@ import numpy as np from gym import Env from franka_env.utils.transformations import ( - construct_adjoint_matrix, construct_homogeneous_matrix, construct_rotation_matrix ) @@ -32,7 +31,6 @@ class RelativeFrame(gym.Wrapper): def __init__(self, env: Env, include_relative_pose=True): super().__init__(env) - self.adjoint_matrix = np.zeros((6, 6)) self.rotation_matrix = np.eye((3)) self.include_relative_pose = include_relative_pose @@ -51,8 +49,7 @@ def step(self, action: np.ndarray): if "intervene_action" in info: info["intervene_action"] = self.transform_action_inv(info["intervene_action"]) - # Update adjoint and rotation matrix - self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) + # Update rotation matrix self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) # Transform observation to spatial frame @@ -64,8 +61,6 @@ def reset(self, **kwargs): # obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) - # Update adjoint and rotation matrix - self.adjoint_matrix = construct_adjoint_matrix(obs["state"]["tcp_pose"]) self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) if self.include_relative_pose: # Update transformation matrix from the reset pose's relative frame to base frame @@ -79,10 +74,10 @@ def reset(self, **kwargs): def transform_observation(self, obs): """ Transform observations from spatial(base) frame into body(end-effector) frame - using the rotation, adjoint and homogeneous matrix + using the rotation and homogeneous matrix """ - adjoint_inv = np.linalg.inv(self.adjoint_matrix) - obs["state"]["tcp_vel"] = adjoint_inv @ obs["state"]["tcp_vel"] + obs["state"]["tcp_vel"][:3] = self.rotation_matrix.transpose() @ obs["state"]["tcp_vel"][:3] + obs["state"]["tcp_vel"][3:6] = self.rotation_matrix.transpose() @ obs["state"]["tcp_vel"][3:6] obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] From 59092ebfbf2993f4800f8ff2d9a32ab7c9773ede Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 12:33:30 +0200 Subject: [PATCH 256/338] added a scale factor to scale voxel input in between [0, 1] --- serl_launcher/serl_launcher/agents/continuous/drq.py | 2 ++ serl_launcher/serl_launcher/vision/voxel_grid_encoders.py | 7 ++++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 20776e48..1ed3a35a 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -260,6 +260,7 @@ def create_drq( bottleneck_dim=encoder_kwargs["bottleneck_dim"], use_conv_bias=False, final_activation=nn.tanh, + scale_factor=1. # if down-sampling from more refined grid_shape is used, otherwise 1. ) for image_key in image_keys } @@ -273,6 +274,7 @@ def create_drq( use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, + proprio_latent_dim=64, ) encoders = { diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index ab8d58d8..e09a5574 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -46,6 +46,7 @@ class VoxNet(nn.Module): use_conv_bias: bool = False bottleneck_dim: Optional[int] = None final_activation: Callable[[jnp.ndarray], jnp.ndarray] | str = nn.tanh + scale_factor: float = 1. @nn.compact def __call__( @@ -59,7 +60,7 @@ def __call__( if no_batch_dim: observations = observations[None] - observations = observations.astype(jnp.float32)[..., None] / 1. # add conv channel + observations = observations.astype(jnp.float32)[..., None] / self.scale_factor # add conv channel conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, padding="valid") @@ -90,7 +91,7 @@ def __call__( )(x) x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, 32) - x = jnp.mean(x, axis=(-2)) # average over z dim + # x = jnp.mean(x, axis=(-2)) # average over z dim # 1x1 convolution (dimensionality reduction, no features), not used for now # x = conv( @@ -111,7 +112,7 @@ def __call__( x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) if self.bottleneck_dim is not None: x = nn.Dense(self.bottleneck_dim)(x) - x = nn.LayerNorm()(x) + # x = nn.LayerNorm()(x) x = self.final_activation(x) return x[0] if no_batch_dim else x From 63e0d44c221bee2cea169391a225da6571458027 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 16:34:32 +0200 Subject: [PATCH 257/338] transform the velocity relative to the start rotation and not the current one --- serl_robot_infra/robotiq_env/envs/relative_env.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index d54eb123..3be9761d 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -32,6 +32,7 @@ class RelativeFrame(gym.Wrapper): def __init__(self, env: Env, include_relative_pose=True): super().__init__(env) self.rotation_matrix = np.eye((3)) + self.rotation_matrix_reset = np.eye((3)) self.include_relative_pose = include_relative_pose if self.include_relative_pose: @@ -62,6 +63,7 @@ def reset(self, **kwargs): # obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) + self.rotation_matrix_reset = self.rotation_matrix.copy() if self.include_relative_pose: # Update transformation matrix from the reset pose's relative frame to base frame self.T_r_o_inv = np.linalg.inv( @@ -76,8 +78,8 @@ def transform_observation(self, obs): Transform observations from spatial(base) frame into body(end-effector) frame using the rotation and homogeneous matrix """ - obs["state"]["tcp_vel"][:3] = self.rotation_matrix.transpose() @ obs["state"]["tcp_vel"][:3] - obs["state"]["tcp_vel"][3:6] = self.rotation_matrix.transpose() @ obs["state"]["tcp_vel"][3:6] + obs["state"]["tcp_vel"][:3] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][:3] + obs["state"]["tcp_vel"][3:6] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][3:6] obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] From 53f40d37ef3a3e107a919eaabd42db99b5ae4dda Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 16:35:30 +0200 Subject: [PATCH 258/338] implemented real rot90 (orientation rotation is different because of euler "xyz" angles) --- .../vision/data_augmentations.py | 56 ++++++++++++++++--- 1 file changed, 47 insertions(+), 9 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index c50bc740..04076d56 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -4,15 +4,47 @@ import jax.numpy as jnp import jax.lax as lax +import jaxlie + ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) # Rotations are in the array transposed for easy dot product ROT_GENERAL = jnp.array([jnp.eye(3), ROT90.transpose(), ROT90 @ ROT90, ROT90]) +# big TODO: action scale and euler angles have to be considered!!! @jax.jit -def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gripper) +def euler_xyz_to_yxz(xyz_angles): + # Create SO3 object from xyz Euler angles + so3 = jaxlie.SO3.from_rpy_radians( + roll=xyz_angles[0], + pitch=xyz_angles[1], + yaw=xyz_angles[2] + ) + rot_matrix = so3.as_matrix() + + # Extract yxz Euler angles from rotation matrix + y = jnp.arctan2(-rot_matrix[2, 0], rot_matrix[2, 2]) + x = jnp.arcsin(rot_matrix[2, 1]) + z = jnp.arctan2(-rot_matrix[0, 1], rot_matrix[1, 1]) + return jnp.array([y, x, z]) + + +@jax.jit +def orient_rot90_jax(array: jnp.ndarray, rot: int, action_scale=0.1) -> jnp.ndarray: + assert array.shape == (3,) + + def single_90_rotation(arr): + yxz = euler_xyz_to_yxz(arr * action_scale) + return yxz.at[1].set(-yxz[1]) / action_scale + + # Apply the rotation 'rot' number of times + return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) + + +@jax.jit +def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gripper) xyz_rotated = jnp.dot(action[:3], ROT_GENERAL[num_rot]) - orientation_rotated = jnp.dot(action[3:6], ROT_GENERAL[num_rot]) + orientation_rotated = orient_rot90_jax(action[3:6], num_rot) return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) @@ -45,16 +77,22 @@ def random_rot90_state(state, num_rot): assert state.shape[-1] == 20 # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) - start_indexes = jnp.array([2, 5, 8, 11, 14, 17]) # rotate everything (except gripper) + normal_indices = jnp.array([2, 5, 11, 14]) + orientation_indices = jnp.array([8, 17]) - def rotate_part(i, state): - part = lax.dynamic_slice(state, (start_indexes[i],), (3,)) + def normal_rotate(i, state): + part = lax.dynamic_slice(state, (normal_indices[i],), (3,)) rotated = jnp.dot(part, ROT_GENERAL[num_rot]) - return lax.dynamic_update_slice(state, rotated, (start_indexes[i],)) + return lax.dynamic_update_slice(state, rotated, (normal_indices[i],)) - # Apply rotations sequentially - state = jax.lax.fori_loop(0, start_indexes.shape[0], rotate_part, state) + def orientation_rotate(i, state): + part = lax.dynamic_slice(state, (orientation_indices[i],), (3,)) + rotated = orient_rot90_jax(part, num_rot) + return lax.dynamic_update_slice(state, rotated, (orientation_indices[i],)) + # Apply rotations sequentially + state = jax.lax.fori_loop(0, normal_indices.shape[0], normal_rotate, state) + state = jax.lax.fori_loop(0, orientation_indices.shape[0], orientation_rotate, state) return state @@ -73,7 +111,7 @@ def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): @partial(jax.jit, static_argnames="axes") def rot90_traceable(m, k=1, axes=(0, 1)): - return jax.lax.switch(k, [partial(jnp.rot90, m, k=-i, axes=axes) for i in range(4)]) + return jax.lax.switch(k, [partial(jnp.rot90, m, k=i, axes=axes) for i in range(4)]) @jax.jit From 5ba0752776368862f1d932daffde1af9538f1238 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 17:20:50 +0200 Subject: [PATCH 259/338] bugfixes and TODO removal --- .../serl_launcher/vision/data_augmentations.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 04076d56..bf6350f1 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -8,10 +8,9 @@ ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) # Rotations are in the array transposed for easy dot product -ROT_GENERAL = jnp.array([jnp.eye(3), ROT90.transpose(), ROT90 @ ROT90, ROT90]) +ROT_GENERAL = jnp.array([jnp.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) -# big TODO: action scale and euler angles have to be considered!!! @jax.jit def euler_xyz_to_yxz(xyz_angles): # Create SO3 object from xyz Euler angles @@ -29,13 +28,13 @@ def euler_xyz_to_yxz(xyz_angles): return jnp.array([y, x, z]) -@jax.jit -def orient_rot90_jax(array: jnp.ndarray, rot: int, action_scale=0.1) -> jnp.ndarray: +@jax.partial(jax.jit, static_argnames="action_scale") +def orient_rot90_jax(array: jnp.ndarray, rot: int, action_scale: float = 0.1) -> jnp.ndarray: assert array.shape == (3,) def single_90_rotation(arr): yxz = euler_xyz_to_yxz(arr * action_scale) - return yxz.at[1].set(-yxz[1]) / action_scale + return yxz.at[0].set(-yxz[0]) / action_scale # Apply the rotation 'rot' number of times return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) @@ -43,7 +42,8 @@ def single_90_rotation(arr): @jax.jit def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gripper) - xyz_rotated = jnp.dot(action[:3], ROT_GENERAL[num_rot]) + assert action.shape == (7,) + xyz_rotated = jnp.dot(ROT_GENERAL[num_rot], action[:3]) orientation_rotated = orient_rot90_jax(action[3:6], num_rot) return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) @@ -82,7 +82,7 @@ def random_rot90_state(state, num_rot): def normal_rotate(i, state): part = lax.dynamic_slice(state, (normal_indices[i],), (3,)) - rotated = jnp.dot(part, ROT_GENERAL[num_rot]) + rotated = jnp.dot(ROT_GENERAL[num_rot], part) return lax.dynamic_update_slice(state, rotated, (normal_indices[i],)) def orientation_rotate(i, state): From 570b0bda9e9b3f0e98b4cc178f7cc09e3f2c7f0f Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 24 Jul 2024 17:27:00 +0200 Subject: [PATCH 260/338] bugfixe 2 --- serl_launcher/serl_launcher/vision/data_augmentations.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index bf6350f1..0784482d 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -28,7 +28,7 @@ def euler_xyz_to_yxz(xyz_angles): return jnp.array([y, x, z]) -@jax.partial(jax.jit, static_argnames="action_scale") +@partial(jax.jit, static_argnames="action_scale") def orient_rot90_jax(array: jnp.ndarray, rot: int, action_scale: float = 0.1) -> jnp.ndarray: assert array.shape == (3,) From c3925e15333bb29511cbfd1875c6e612c8e76fc9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 25 Jul 2024 12:28:07 +0200 Subject: [PATCH 261/338] consider observation and action scaling in augmentation --- examples/robotiq_drq/drq_policy_robotiq.py | 4 +++ .../serl_launcher/agents/continuous/drq.py | 16 ++++++----- .../vision/data_augmentations.py | 27 +++++++++++++------ 3 files changed, 32 insertions(+), 15 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 4fbee6a7..2c480224 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -445,6 +445,10 @@ def main(_): # print useful info print_agent_params(agent, image_keys) + # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) + agent.config["observation_rotation_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] + agent.config["action_rot_scale"] = env.action_scale[1] + def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( env.observation_space, diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 1ed3a35a..2206c2b1 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -260,7 +260,7 @@ def create_drq( bottleneck_dim=encoder_kwargs["bottleneck_dim"], use_conv_bias=False, final_activation=nn.tanh, - scale_factor=1. # if down-sampling from more refined grid_shape is used, otherwise 1. + scale_factor=1. # if down-sampling from more refined grid_shape is used, otherwise 1. ) for image_key in image_keys } @@ -340,17 +340,19 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a observations = observations.copy( add_or_replace={ "state": batched_random_rot90_state( - observations["state"], rng, num_batch_dims=2 + observations["state"], rng, num_batch_dims=2, + state_rotation_scale=self.config["observation_rotation_scale"] ), pixel_key: batched_random_rot90_voxel( - observations[pixel_key], rng, num_batch_dims=2 + observations[pixel_key], rng, num_batch_dims=2, ), } ) next_observations = next_observations.copy( add_or_replace={ "state": batched_random_rot90_state( - next_observations["state"], rng, num_batch_dims=2 + next_observations["state"], rng, num_batch_dims=2, + state_rotation_scale=self.config["observation_rotation_scale"] ), pixel_key: batched_random_rot90_voxel( next_observations[pixel_key], rng, num_batch_dims=2 @@ -358,7 +360,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a } ) actions = batched_random_rot90_action( - actions, rng, + actions, rng, action_rotation_scale=self.config["action_rotation_scale"] ) # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) @@ -440,7 +442,7 @@ def update_high_utd( next_observations=next_obs, actions=batch["actions"], rng=rot90_rng, - activated=False, + activated=True, ) batch = batch.copy( add_or_replace={ @@ -485,7 +487,7 @@ def update_critics( next_observations=next_obs, actions=batch["actions"], rng=rot90_rng, - activated=False, + activated=True, ) batch = batch.copy( diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 0784482d..a12be1e5 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -28,13 +28,13 @@ def euler_xyz_to_yxz(xyz_angles): return jnp.array([y, x, z]) -@partial(jax.jit, static_argnames="action_scale") -def orient_rot90_jax(array: jnp.ndarray, rot: int, action_scale: float = 0.1) -> jnp.ndarray: +@jax.jit +def orient_rot90_jax(array: jnp.ndarray, rot: int) -> jnp.ndarray: assert array.shape == (3,) def single_90_rotation(arr): - yxz = euler_xyz_to_yxz(arr * action_scale) - return yxz.at[0].set(-yxz[0]) / action_scale + yxz = euler_xyz_to_yxz(arr) + return yxz.at[0].set(-yxz[0]) # Apply the rotation 'rot' number of times return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) @@ -48,28 +48,39 @@ def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gri return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) -@jax.jit -def batched_random_rot90_action(actions, rng): +@partial(jax.jit, static_argnames="action_rotation_scale") +def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = 0.1): assert actions.shape[-1:] == (7,) num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) # jax.debug.print("rotation: {}", num_rot[0]) + # scale the actions back to normal rad angles + actions = actions.at[:, 3:6].multiply(action_rotation_scale) + actions = jax.vmap( lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 )(actions, num_rot) - return actions + + return actions.at[3:6].multiply(1 / action_rotation_scale) @partial(jax.jit, static_argnames="num_batch_dims") -def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1): +def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, state_rotation_scale: float = 10.): original_shape = state.shape state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) + # reverse the scaling here + state = state.at[8:11].multiply(1 / state_rotation_scale) + state = state.at[17:20].multiply(1 / state_rotation_scale) + state = jax.vmap( lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 )(state, num_rot) + # apply the scaling again + state = state.at[8:11].multiply(state_rotation_scale) + state = state.at[17:20].multiply(state_rotation_scale) return state.reshape(original_shape) From d15015d758b4ab5f4b14cacfe9d357c5a3c56949 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 25 Jul 2024 12:28:30 +0200 Subject: [PATCH 262/338] consider observation and action scaling in augmentation --- .../serl_launcher/wrappers/serl_obs_wrappers.py | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index a7dee819..0cde490a 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -52,24 +52,28 @@ def __init__(self, env, translation_scale=100., rotation_scale=10., - velocity_scale=10., - rotational_velocity_scale=10., force_scale=1., torque_scale=10. ): super().__init__(env) self.translation_scale = translation_scale self.rotation_scale = rotation_scale - self.velocity_scale = velocity_scale - self.rotational_velocity_scale = rotational_velocity_scale self.force_scale = force_scale self.torque_scale = torque_scale + def scale_wrapper_get_scales(self): + return dict( + translation_scale=self.translation_scale, + rotation_scale=self.rotation_scale, + force_scale=self.force_scale, + torque_scale=self.torque_scale + ) + def observation(self, obs): obs["state"]["tcp_pose"][:3] *= self.translation_scale obs["state"]["tcp_pose"][3:] *= self.rotation_scale - obs["state"]["tcp_vel"][:3] *= self.velocity_scale - obs["state"]["tcp_vel"][3:] *= self.rotational_velocity_scale + obs["state"]["tcp_vel"][:3] *= self.translation_scale + obs["state"]["tcp_vel"][3:] *= self.rotation_scale obs["state"]["tcp_force"] *= self.force_scale obs["state"]["tcp_torque"] *= self.torque_scale return obs From e55c2280b507514739fead6de612f7e3cdef14cb Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 25 Jul 2024 12:47:52 +0200 Subject: [PATCH 263/338] bugfixes for augmentation --- examples/robotiq_drq/drq_policy_robotiq.py | 2 +- .../serl_launcher/agents/continuous/drq.py | 40 +++++++++++++++++-- .../vision/data_augmentations.py | 2 +- 3 files changed, 39 insertions(+), 5 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 2c480224..8f40bcef 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -446,7 +446,7 @@ def main(_): print_agent_params(agent, image_keys) # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) - agent.config["observation_rotation_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] + agent.config["observation_rot_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] agent.config["action_rot_scale"] = env.action_scale[1] def create_replay_buffer_and_wandb_logger(): diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 2206c2b1..2903bb8a 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -341,7 +341,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a add_or_replace={ "state": batched_random_rot90_state( observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rotation_scale"] + state_rotation_scale=self.config["observation_rot_scale"] ), pixel_key: batched_random_rot90_voxel( observations[pixel_key], rng, num_batch_dims=2, @@ -352,7 +352,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a add_or_replace={ "state": batched_random_rot90_state( next_observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rotation_scale"] + state_rotation_scale=self.config["observation_rot_scale"] ), pixel_key: batched_random_rot90_voxel( next_observations[pixel_key], rng, num_batch_dims=2 @@ -360,7 +360,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a } ) actions = batched_random_rot90_action( - actions, rng, action_rotation_scale=self.config["action_rotation_scale"] + actions, rng, action_rotation_scale=self.config["action_rot_scale"] ) # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) @@ -437,6 +437,7 @@ def update_high_utd( next_obs_rng=next_obs_rng, next_observations=batch["next_observations"] ) + obs, next_obs, actions = self.batch_augmentation_fn( observations=obs, next_observations=next_obs, @@ -509,3 +510,36 @@ def update_critics( del critic_infos["temperature"] return new_agent, critic_infos + + def test_augmentation(self, batch: Batch): + if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: + batch = _unpack(batch) + + obs_cp, next_obs_cp, actions_cp = batch["observations"].copy(), batch["next_observations"].copy(), batch[ + "actions"].copy() + + rng, rot90_rng = jax.random.split(self.state.rng, 2) + obs, next_obs, actions = self.batch_augmentation_fn( + observations=batch["observations"], + next_observations=batch["next_observations"], + actions=batch["actions"], + rng=rot90_rng, + activated=True, + ) + + for _ in range(3): + obs, next_obs, actions = self.batch_augmentation_fn( + observations=obs, + next_observations=next_obs, + actions=actions, + rng=rot90_rng, + activated=True, + ) + + # each instance of the batch is rotated by 0, 90, 180 or 270 degrees, + # 4 times these should all return to the original one + print("-" * 35, "\nAsugmentation check here!\n", "-" * 35) + jax.debug.print("obs {}", jnp.sum(jnp.abs(obs["state"] - obs_cp["state"]))) + jax.debug.print("next_obs {}", jnp.sum(jnp.abs(next_obs["state"] - next_obs_cp["state"]))) + jax.debug.print("actions {}", jnp.sum(jnp.abs(actions - actions_cp))) + # they are all in range 1e-6 to 1e-7, check done diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index a12be1e5..6e1be114 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -61,7 +61,7 @@ def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 )(actions, num_rot) - return actions.at[3:6].multiply(1 / action_rotation_scale) + return actions.at[:, 3:6].multiply(1 / action_rotation_scale) @partial(jax.jit, static_argnames="num_batch_dims") From 0d75fa528e1dad7ef07e0f212d0f79b4aaab1826 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 25 Jul 2024 17:56:53 +0200 Subject: [PATCH 264/338] added basic PointNet Encoder (not tested yet) --- .../vision/pointcloud_encoders.py | 88 +++++++++++++++++++ 1 file changed, 88 insertions(+) create mode 100644 serl_launcher/serl_launcher/vision/pointcloud_encoders.py diff --git a/serl_launcher/serl_launcher/vision/pointcloud_encoders.py b/serl_launcher/serl_launcher/vision/pointcloud_encoders.py new file mode 100644 index 00000000..f8a8ad17 --- /dev/null +++ b/serl_launcher/serl_launcher/vision/pointcloud_encoders.py @@ -0,0 +1,88 @@ +from functools import partial +from typing import Any, Callable, Optional, Sequence, Tuple + +import flax.linen as nn +import jax.numpy as jnp +import jax.lax as lax + +import jax + + +class PointNetBasic(nn.Module): + """ Basic PointNet, input is BxNx3, output Bx40 """ + @nn.compact + def __call__( + self, + observations: jnp.ndarray, + train: bool = True, + ): + x = observations + + num_points = observations.shape[-2] + + conv = partial( + nn.Conv, + use_bias=True, + kernel_init=nn.initializers.kaiming_normal(), + bias_init=nn.initializers.zeros_init(), + padding="VALID" + ) + batchnorm = partial( + nn.BatchNorm, + momentum=0.9, + epsilon=1e-5, + use_running_average=not train, + ) + dense = partial( + nn.Dense, + use_bias=True, + kernel_init=nn.initializers.kaiming_normal(), + ) + + x = x[..., None] # expand dims + # shape (B, N, 3, 1) + + x = conv( + features=64, + kernel_size=(1, 3), + strides=(1, 1), + name="conv1" + )(x) + # shape (B, N, 1, 64) + + x = batchnorm( + name="bn1" + )(x) + + # conv2, conv3, conv4, conv5 + for i in range(2, 6): + features = {2: 64, 3: 64, 4: 128, 5: 1024} + x = conv( + features=features[i], + kernel_size=(1, 1), + strides=(1, 1), + name=f"conv{i}" + )(x) + + x = batchnorm( + name=f"bn{i}" + )(x) + + # shape (B, N, 1, 1024) + x = nn.max_pool(x, (num_points, 1)) + + # shape (B, 1, 1, 1024) + x = dense(features=512, name="fc1")(x) + x = nn.relu(x) + + x = dense(features=256, name="fc2")(x) + x = nn.relu(x) + + x = nn.Dropout(rate=0.3, name="dp1", deterministic=not train)(x) + x = nn.relu(x) + + x = dense(features=40, name="fn3")(x) + # TODO original has no activation, for me it would me sense + return x + + From 2222c6cb6939f69531fa84230310ea8f290906c1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 26 Jul 2024 12:39:39 +0200 Subject: [PATCH 265/338] NaN bugfix --- .../serl_launcher/vision/data_augmentations.py | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 6e1be114..d70a6800 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -28,13 +28,13 @@ def euler_xyz_to_yxz(xyz_angles): return jnp.array([y, x, z]) -@jax.jit def orient_rot90_jax(array: jnp.ndarray, rot: int) -> jnp.ndarray: assert array.shape == (3,) def single_90_rotation(arr): yxz = euler_xyz_to_yxz(arr) - return yxz.at[0].set(-yxz[0]) + yxz = yxz.at[0].multiply(-1.) + return yxz # Apply the rotation 'rot' number of times return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) @@ -51,7 +51,8 @@ def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gri @partial(jax.jit, static_argnames="action_rotation_scale") def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = 0.1): assert actions.shape[-1:] == (7,) - num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) + # num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) + num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 2) * 3 # jax.debug.print("rotation: {}", num_rot[0]) # scale the actions back to normal rad angles @@ -68,7 +69,8 @@ def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, state_rotation_scale: float = 10.): original_shape = state.shape state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) - num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) + # num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) + num_rot = jax.random.randint(rng, (state.shape[0],), 0, 2) * 2 # reverse the scaling here state = state.at[8:11].multiply(1 / state_rotation_scale) @@ -111,7 +113,8 @@ def orientation_rotate(i, state): def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): original_shape = voxel_grid.shape voxel_grid = jnp.reshape(voxel_grid, (-1, *voxel_grid.shape[num_batch_dims:])) - num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) + # num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) + num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 2) * 2 voxel_grid = jax.vmap( lambda v, k: random_rot90_voxel(v, k), in_axes=(0, 0), out_axes=0 From 94046607ec1fb9a9d846dde2106da6f2fdc47929 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 26 Jul 2024 12:39:58 +0200 Subject: [PATCH 266/338] bugfix to prevent starting velocities --- serl_robot_infra/robot_controllers/robotiq_controller.py | 1 + 1 file changed, 1 insertion(+) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 66ba6a08..5c203f7c 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -325,6 +325,7 @@ async def _go_to_reset_pose(self): success = success and self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) + time.sleep(0.1) # wait for 100ms await self._update_robot_state() with self.lock: self.target_pos = self.curr_pos.copy() From e26c50a3ce18c9a2b1f9c79516d6f9c795fe4df8 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 11:30:45 +0200 Subject: [PATCH 267/338] implemented 3d Spatial Soft Argmax --- .../vision/voxel_grid_encoders.py | 67 ++++++++++++++----- 1 file changed, 51 insertions(+), 16 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index e09a5574..f15a5943 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -38,9 +38,57 @@ def __call__( return x[0] if no_batch_dim else x +class SpatialSoftArgmax3D(nn.Module): + """ + 3D Implementation of Spatial Soft Argmax + why arg-max and not max: see https://github.com/tensorflow/tensorflow/issues/6271#issuecomment-266893850 + """ + x_len: int + y_len: int + z_len: int + channel: int + temperature: float = 1. + + def setup(self): + pos_x, pos_y, pos_z = jnp.meshgrid( + jnp.linspace(-1.0, 1.0, self.x_len), + jnp.linspace(-1.0, 1.0, self.y_len), + jnp.linspace(-1.0, 1.0, self.z_len), + indexing='ij' + ) + self.pos_x = pos_x.reshape(-1) # shape (x*y*z) + self.pos_y = pos_y.reshape(-1) + self.pos_z = pos_z.reshape(-1) + + @nn.compact + def __call__(self, features): + # add batch dim if missing + no_batch_dim = len(features.shape) < 5 + if no_batch_dim: + features = features[None] + + assert len(features.shape) == 5 + batch_size, num_featuremaps = features.shape[0], features.shape[-1] + features = features.transpose(0, 4, 1, 2, 3).reshape( + batch_size, num_featuremaps, self.x_len * self.y_len * self.z_len + ) + + softmax_attention = nn.softmax(features / self.temperature, axis=-1) + expected_x = jnp.sum(self.pos_x * softmax_attention, axis=-1) + expected_y = jnp.sum(self.pos_y * softmax_attention, axis=-1) + expected_z = jnp.sum(self.pos_z * softmax_attention, axis=-1) + expected_xyz = jnp.concatenate([expected_x, expected_y, expected_z], axis=-1) + + expected_xy = jnp.reshape(expected_xyz, (batch_size, 3 * num_featuremaps)) + + if no_batch_dim: + expected_xy = expected_xy[0] + return expected_xy + + class VoxNet(nn.Module): """ - Voxnet implementation: https://github.com/AutoDeep/VoxNet/blob/master/src/nets/voxNet.py + Voxnet-like implementation: https://github.com/AutoDeep/VoxNet/blob/master/src/nets/voxNet.py """ use_conv_bias: bool = False @@ -93,26 +141,13 @@ def __call__( # x = jnp.mean(x, axis=(-2)) # average over z dim - # 1x1 convolution (dimensionality reduction, no features), not used for now - # x = conv( - # features=1, - # kernel_size=(1, 1, 1), - # )(x) - - # x = lax.reduce_window( - # x, - # init_value=-jnp.inf, - # computation=lax.max, - # window_dimensions=(1, 2, 2, 2, 1), - # window_strides=(1, 2, 2, 2, 1), - # padding='VALID' - # ) + x = SpatialSoftArgmax3D(5, 5, 3, 32)(x) # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) if self.bottleneck_dim is not None: x = nn.Dense(self.bottleneck_dim)(x) - # x = nn.LayerNorm()(x) + x = nn.LayerNorm()(x) x = self.final_activation(x) return x[0] if no_batch_dim else x From c1e665a66f7e5da7e69b240716d19538cf8eff8d Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 11:33:19 +0200 Subject: [PATCH 268/338] added sampling rotation (and inverse after) for the actor sampling. ALso only 180 deg rotation (easier with euler) --- examples/robotiq_drq/drq_policy_robotiq.py | 28 +++++++++++++++++-- .../serl_launcher/agents/continuous/drq.py | 15 +++++----- 2 files changed, 34 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 8f40bcef..4d48d895 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 - +import copy import time from functools import partial import jax @@ -39,9 +39,14 @@ from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper from robotiq_env.envs.relative_env import RelativeFrame from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from serl_launcher.vision.data_augmentations import batched_random_rot90_state, batched_random_rot90_voxel, \ + batched_random_rot90_action import robotiq_env +# used to debug nan errors (also in jit-ed functions) +# jax.config.update("jax_debug_nans", True) + devices = jax.local_devices() num_devices = len(devices) sharding = jax.sharding.PositionalSharding(devices) @@ -214,7 +219,7 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: actions = env.action_space.sample() - else: + elif not agent.config["activate_batch_rotation"]: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( observations=jax.device_put(obs), @@ -222,6 +227,24 @@ def update_params(params): deterministic=False, ) actions = np.asarray(jax.device_get(actions)) + else: + # TODO test it more + sampling_rng, rot_rng, key = jax.random.split(sampling_rng, 3) + only_180 = agent.config["activate_batch_rotation"] == 180 + + rotated_obs = copy.deepcopy(obs) + rotated_obs["state"] = batched_random_rot90_state(obs["state"], rot_rng, only_180=only_180) + rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng, only_180=only_180) + + actions = agent.sample_actions( + observations=jax.device_put(rotated_obs), + seed=key, + deterministic=False, + ) + for _ in range(3): + actions = batched_random_rot90_action(actions[None, ...], rot_rng, only_180=only_180)[0, ...] # rotate back + + actions = np.asarray(jax.device_get(actions)) # print(actions) # Step environment @@ -448,6 +471,7 @@ def main(_): # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) agent.config["observation_rot_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] agent.config["action_rot_scale"] = env.action_scale[1] + agent.config["activate_batch_rotation"] = 180 def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 2903bb8a..4f35f930 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -332,6 +332,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a for pixel_key in self.config["image_keys"]: if not "pointcloud" in pixel_key: continue # skip if not pointcloud + only_180 = self.config["activate_batch_rotation"] == 180 # rotation of state, action and voxel grid (use the same rng for all of them, so same rotation) # jax.debug.print("before {} {} {}", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) @@ -341,10 +342,10 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a add_or_replace={ "state": batched_random_rot90_state( observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rot_scale"] + state_rotation_scale=self.config["observation_rot_scale"], only_180=only_180 ), pixel_key: batched_random_rot90_voxel( - observations[pixel_key], rng, num_batch_dims=2, + observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 ), } ) @@ -352,15 +353,15 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a add_or_replace={ "state": batched_random_rot90_state( next_observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rot_scale"] + state_rotation_scale=self.config["observation_rot_scale"], only_180=only_180 ), pixel_key: batched_random_rot90_voxel( - next_observations[pixel_key], rng, num_batch_dims=2 + next_observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 ) } ) actions = batched_random_rot90_action( - actions, rng, action_rotation_scale=self.config["action_rot_scale"] + actions, rng, action_rotation_scale=self.config["action_rot_scale"], only_180=only_180 ) # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) @@ -443,7 +444,7 @@ def update_high_utd( next_observations=next_obs, actions=batch["actions"], rng=rot90_rng, - activated=True, + activated=self.config["activate_batch_rotation"] > 0, ) batch = batch.copy( add_or_replace={ @@ -488,7 +489,7 @@ def update_critics( next_observations=next_obs, actions=batch["actions"], rng=rot90_rng, - activated=True, + activated=self.config["activate_batch_rotation"] > 0, ) batch = batch.copy( From b424c28b4790c93bf8d292d1d671c827f9a86c8b Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 11:33:49 +0200 Subject: [PATCH 269/338] implemented 180 deg rotation and ignoring force/torque --- .../vision/data_augmentations.py | 50 +++++++++++-------- 1 file changed, 28 insertions(+), 22 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index d70a6800..0f50a234 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -11,7 +11,6 @@ ROT_GENERAL = jnp.array([jnp.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) -@jax.jit def euler_xyz_to_yxz(xyz_angles): # Create SO3 object from xyz Euler angles so3 = jaxlie.SO3.from_rpy_radians( @@ -23,7 +22,7 @@ def euler_xyz_to_yxz(xyz_angles): # Extract yxz Euler angles from rotation matrix y = jnp.arctan2(-rot_matrix[2, 0], rot_matrix[2, 2]) - x = jnp.arcsin(rot_matrix[2, 1]) + x = jnp.arcsin(jnp.clip(rot_matrix[2, 1], -1.0, 1.0)) # might prevent NaN's z = jnp.arctan2(-rot_matrix[0, 1], rot_matrix[1, 1]) return jnp.array([y, x, z]) @@ -41,18 +40,20 @@ def single_90_rotation(arr): @jax.jit -def random_rot90_action(action, num_rot): # action is (x, y, z, rx, ry, rz, gripper) +def random_rot90_action(action: jnp.ndarray, num_rot: int): # action is (x, y, z, rx, ry, rz, gripper) assert action.shape == (7,) xyz_rotated = jnp.dot(ROT_GENERAL[num_rot], action[:3]) orientation_rotated = orient_rot90_jax(action[3:6], num_rot) return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) -@partial(jax.jit, static_argnames="action_rotation_scale") -def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = 0.1): +@partial(jax.jit, static_argnames=("action_rotation_scale", "only_180")) +def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = 0.1, only_180=False): assert actions.shape[-1:] == (7,) - # num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) - num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 2) * 3 + num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) + if only_180: + num_rot = (num_rot % 2) * 2 + # jax.debug.print("rotation: {}", num_rot[0]) # scale the actions back to normal rad angles @@ -65,33 +66,36 @@ def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = return actions.at[:, 3:6].multiply(1 / action_rotation_scale) -@partial(jax.jit, static_argnames="num_batch_dims") -def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, state_rotation_scale: float = 10.): +@partial(jax.jit, static_argnames=("num_batch_dims", "only_180")) +def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, state_rotation_scale: float = 10., + only_180=False): original_shape = state.shape state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) - # num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) - num_rot = jax.random.randint(rng, (state.shape[0],), 0, 2) * 2 + num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) + if only_180: + num_rot = (num_rot % 2) * 2 # reverse the scaling here - state = state.at[8:11].multiply(1 / state_rotation_scale) - state = state.at[17:20].multiply(1 / state_rotation_scale) + state = state.at[5:8].multiply(1 / state_rotation_scale) + state = state.at[11:14].multiply(1 / state_rotation_scale) state = jax.vmap( lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 )(state, num_rot) # apply the scaling again - state = state.at[8:11].multiply(state_rotation_scale) - state = state.at[17:20].multiply(state_rotation_scale) + state = state.at[5:8].multiply(state_rotation_scale) + state = state.at[11:14].multiply(state_rotation_scale) return state.reshape(original_shape) def random_rot90_state(state, num_rot): - assert state.shape[-1] == 20 + assert state.shape[-1] == 14 # modified for no FT # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) - normal_indices = jnp.array([2, 5, 11, 14]) - orientation_indices = jnp.array([8, 17]) + # without force and torque: (gripper[0], pose[2], orientation[5], velocity[8], or vel[11]) + normal_indices = jnp.array([2, 8]) + orientation_indices = jnp.array([5, 11]) def normal_rotate(i, state): part = lax.dynamic_slice(state, (normal_indices[i],), (3,)) @@ -109,12 +113,14 @@ def orientation_rotate(i, state): return state -@partial(jax.jit, static_argnames="num_batch_dims") -def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): +@partial(jax.jit, static_argnames=("num_batch_dims", "only_180")) +def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1, only_180=False): original_shape = voxel_grid.shape voxel_grid = jnp.reshape(voxel_grid, (-1, *voxel_grid.shape[num_batch_dims:])) - # num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) - num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 2) * 2 + + num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) + if only_180: + num_rot = (num_rot % 2) * 2 voxel_grid = jax.vmap( lambda v, k: random_rot90_voxel(v, k), in_axes=(0, 0), out_axes=0 From d51499f97b05f0e54e8a7dfc08bfb08aa50499ac Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 11:34:22 +0200 Subject: [PATCH 270/338] ignoring force and torque --- .../serl_launcher/wrappers/serl_obs_wrappers.py | 4 ++-- .../robotiq_env/envs/basic_env/robotiq_basic_env.py | 1 - .../envs/camera_env/robotiq_camera_env.py | 3 ++- serl_robot_infra/robotiq_env/envs/relative_env.py | 4 ++-- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 12 +++++++----- 5 files changed, 13 insertions(+), 11 deletions(-) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 0cde490a..1a0a8a70 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -74,6 +74,6 @@ def observation(self, obs): obs["state"]["tcp_pose"][3:] *= self.rotation_scale obs["state"]["tcp_vel"][:3] *= self.translation_scale obs["state"]["tcp_vel"][3:] *= self.rotation_scale - obs["state"]["tcp_force"] *= self.force_scale - obs["state"]["tcp_torque"] *= self.torque_scale + # obs["state"]["tcp_force"] *= self.force_scale + # obs["state"]["tcp_torque"] *= self.torque_scale return obs diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py index 3bae0af0..5a004ddb 100644 --- a/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py +++ b/serl_robot_infra/robotiq_env/envs/basic_env/robotiq_basic_env.py @@ -35,5 +35,4 @@ def compute_reward(self, obs, action) -> float: def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - # return 0.1 < state['gripper_state'][0] < 0.8 and state['tcp_force'][2] < -3. return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.15 # new min height with box diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index baa6df43..a4b82d4c 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -16,7 +16,8 @@ def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.1 - downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) + # downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) + downward_force_cost = 0. suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.5) suction_cost = 3. * float(obs["state"]["gripper_state"][1] < -0.5) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index 3be9761d..a384497e 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -80,8 +80,8 @@ def transform_observation(self, obs): """ obs["state"]["tcp_vel"][:3] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][:3] obs["state"]["tcp_vel"][3:6] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][3:6] - obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] - obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] + # obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] + # obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] if self.include_relative_pose: T_b_o = construct_homogeneous_matrix(obs["state"]["tcp_pose"]) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 13215e4a..6efa307d 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -59,6 +59,7 @@ def __init__(self): self.param = o3d.io.read_pinhole_camera_parameters( "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/camera_parameters.json") self.ctr = self.window.get_view_control() + self.coord_frame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=0.01, origin=[0, 0, 0]) def display(self, points): self.pc.clear() @@ -66,6 +67,7 @@ def display(self, points): self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64) / 1000.) self.window.clear_geometries() self.window.add_geometry(self.pc) + # self.window.add_geometry(self.coord_frame) self.ctr.convert_from_pinhole_camera_parameters(self.param, True) self.window.poll_events() @@ -208,9 +210,9 @@ def __init__( -np.inf, np.inf, shape=(7,) ), # xyz + quat "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_state": gym.spaces.Box(-np.inf, np.inf, shape=(2,)), - "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + "gripper_state": gym.spaces.Box(-1., 1., shape=(2,)), + # "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + # "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), } ) @@ -611,8 +613,8 @@ def _get_obs(self) -> dict: "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, "gripper_state": self.gripper_state, - "tcp_force": self.curr_force, - "tcp_torque": self.curr_torque, + # "tcp_force": self.curr_force, + # "tcp_torque": self.curr_torque, } if self.realtime_plot: From 2707a747549b8177726e4e89b46932554e47bec1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 17:40:02 +0200 Subject: [PATCH 271/338] use pretrained first Conv3D Layer in Voxnet (ugly for now, but it works) --- examples/robotiq_drq/drq_policy_robotiq.py | 11 ++++-- .../vision/voxel_grid_encoders.py | 35 ++++++++++++------- 2 files changed, 31 insertions(+), 15 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 4d48d895..f7c6e552 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -23,7 +23,9 @@ print_agent_params, parameter_overview, plot_feature_kernel_histogram, - find_zero_weights + find_zero_weights, + plot_conv3d_kernels, + get_pretrained_VoxNet_Conv3d_kernels ) from agentlace.trainer import TrainerServer, TrainerClient @@ -228,7 +230,6 @@ def update_params(params): ) actions = np.asarray(jax.device_get(actions)) else: - # TODO test it more sampling_rng, rot_rng, key = jax.random.split(sampling_rng, 3) only_180 = agent.config["activate_batch_rotation"] == 180 @@ -465,13 +466,17 @@ def main(_): jax.tree_map(jnp.array, agent), sharding.replicate() ) + # manually set the first 3D-conv kernels from pretrained VoxNet + agent.state.params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_3x3x3"]["kernel"] = agent.state.params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_3x3x3"]["kernel"].at[...].set(get_pretrained_VoxNet_Conv3d_kernels(features=32)) + # print useful info print_agent_params(agent, image_keys) + # plot_conv3d_kernels(agent.state.params) # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) agent.config["observation_rot_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] agent.config["action_rot_scale"] = env.action_scale[1] - agent.config["activate_batch_rotation"] = 180 + agent.config["activate_batch_rotation"] = False # deactivate for now def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index f15a5943..126552f5 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -79,7 +79,7 @@ def __call__(self, features): expected_z = jnp.sum(self.pos_z * softmax_attention, axis=-1) expected_xyz = jnp.concatenate([expected_x, expected_y, expected_z], axis=-1) - expected_xy = jnp.reshape(expected_xyz, (batch_size, 3 * num_featuremaps)) + expected_xy = jnp.reshape(expected_xyz, (batch_size, 3, num_featuremaps)) if no_batch_dim: expected_xy = expected_xy[0] @@ -110,38 +110,49 @@ def __call__( observations = observations.astype(jnp.float32)[..., None] / self.scale_factor # add conv channel - conv = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, - padding="valid") + conv3d = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, + padding="valid") l_relu = partial(nn.leaky_relu, negative_slope=0.1) + max_pool = partial(nn.max_pool, window_shape=(2, 2, 2), strides=(2, 2, 2)) x = observations - x = conv( + x = conv3d( features=32, kernel_size=(5, 5, 5), strides=(2, 2, 2), - name="conv_5x5", + name="conv_3x3x3", )(x) x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) + # x = max_pool(x) + x = nn.LayerNorm()(x) - x = conv( + x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now + + x = conv3d( features=32, kernel_size=(3, 3, 3), strides=(2, 2, 2), - name="conv_3x3_1" + name="conv_3x3x3_2" )(x) - x = l_relu(x) # shape (B, (X-4)/4, (Y-4)/4, (Z-4)/4, 32) + x = l_relu(x) # shape (B, (X-4)/4, (Y-4)/4, (Z-4)/4, F) + # x = max_pool(x) + x = nn.LayerNorm()(x) - x = conv( + x = conv3d( features=32, kernel_size=(3, 3, 3), strides=(2, 2, 2), - name="conv_3x3_2" + name="conv_3x3x3_3" )(x) - x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, 32) + x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) + # x = max_pool(x) + x = nn.LayerNorm()(x) # x = jnp.mean(x, axis=(-2)) # average over z dim - x = SpatialSoftArgmax3D(5, 5, 3, 32)(x) + # x = SpatialSoftArgmax3D(9, 9, 6, 32)(x) + + # jax.debug.print("ssam {}", x) # what , all 1s 0s or -1s??? # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) From ea7aa9a0ffc588bd33805f02230ab24ef253a154 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 17:40:30 +0200 Subject: [PATCH 272/338] added 3d kernel plot and pretrained VoxNet kernel weights --- .../serl_launcher/utils/train_utils.py | 52 +++++++++++++++++-- 1 file changed, 48 insertions(+), 4 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 634efc1d..d615c151 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -10,6 +10,7 @@ import numpy as np import tensorflow as tf import wandb +import matplotlib.pyplot as plt from flax.core import frozen_dict from jaxlib.xla_extension import ArrayImpl @@ -172,14 +173,15 @@ def plot_feature_kernel_histogram(agent): print(f"kernel has shape: {feature_kernel.shape}") plots = feature_kernel.shape[0] // 256 + 1 - fig, axes = plt.subplots(nrows=plots, ncols=1, sharex=True, sharey=True, figsize=(5, 3*plots)) + fig, axes = plt.subplots(nrows=plots, ncols=1, sharex=True, sharey=True, figsize=(5, 3 * plots)) feature_kernel = feature_kernel.mean(axis=1) for p in range(plots): - legend = f"image {p}" if p < plots-1 else "observations" - print(f"{legend} mean and std: ", [feature_kernel[p*256:(p+1)*256].mean(), feature_kernel[p*256:(p+1)*256].std()]) - axes[p].hist(feature_kernel[p*256:(p+1)*256], bins=50) + legend = f"image {p}" if p < plots - 1 else "observations" + print(f"{legend} mean and std: ", + [feature_kernel[p * 256:(p + 1) * 256].mean(), feature_kernel[p * 256:(p + 1) * 256].std()]) + axes[p].hist(feature_kernel[p * 256:(p + 1) * 256], bins=50) axes[p].set_title(legend) plt.show() @@ -196,3 +198,45 @@ def find_zero_weights(params, print_str="", print_all=False): print(f" zero weights--> {print_str} std: {params.std()}") else: print(".", end='') + + +def plot_3d_kernel(kernel, nr): + fig = plt.figure() + ax = fig.add_subplot(111, projection='3d') + + x_len, y_len, z_len = kernel.shape + + x = np.arange(x_len) + y = np.arange(y_len) + z = np.arange(z_len) + x, y, z = np.meshgrid(x, y, z, indexing='ij') + + # Normalize the values for color mapping + norm = plt.Normalize(kernel.min(), kernel.max()) + colors = plt.cm.viridis(norm(kernel)) + alpha = np.clip(np.abs(kernel) * 9, 0., 1.) + alpha = np.clip(np.where(alpha < 0.17, 0., alpha), 0., 1.) + + for i in range(x_len): + for j in range(y_len): + for k in range(z_len): + ax.bar3d(i, j, k, .9, .9, .9, color=colors[i, j, k], alpha=alpha[i, j, k]) + + ax.set_title(str(nr)) + ax.set_xticklabels([]) + ax.set_yticklabels([]) + ax.set_zticklabels([]) + plt.show() + + +def plot_conv3d_kernels(params): + kernels = params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_5x5x5"]["kernel"] + # shape (5, 5, 5, 1, 32) + for i in range(kernels.shape[-1]): + print(kernels[..., 0, i].mean(), kernels[..., 0, i].std()) + plot_3d_kernel(kernels[..., 0, i], i) + + +def get_pretrained_VoxNet_Conv3d_kernels(features: int = 32): + ckpt = jnp.load("/home/nico/Downloads/c-11/voxnet/conv1/conv3d/kernel:0.npy") + return ckpt[..., :features] From 06a19de133340948143d904f26264f34694f933b Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 17:58:06 +0200 Subject: [PATCH 273/338] pretrained Conv3D setup --- examples/robotiq_drq/run_actor.sh | 4 ++-- examples/robotiq_drq/run_learner.sh | 8 ++++---- serl_launcher/serl_launcher/utils/launcher.py | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index ad9d70ee..d8264356 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -4,11 +4,11 @@ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ --max_traj_length 100 \ - --exp_name=drq_10box \ + --exp_name=d \ --camera_mode pointcloud \ --seed 2 \ --max_steps 20000 \ - --random_steps 500 \ + --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index 04447f01..30513972 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -3,17 +3,17 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name=drq_10box \ + --exp_name=d \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 2 \ - --max_steps 20000 \ - --random_steps 500 \ + --max_steps 25000 \ + --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 20000 \ --encoder_type voxnet \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul15_vox_554b_newgripstat.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul29_noforcetorque.pkl \ # --debug diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 52179426..cf6d8f72 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -137,7 +137,7 @@ def make_drq_agent( critic_subsample_size=2, encoder_kwargs=dict( # pooling_method="spatial_softmax", # default "spatial_learned_embeddings" - bottleneck_dim=64, + bottleneck_dim=128, # num_spatial_blocks=8, # num_kp=64, ), From ff68b4fc05e5768c5c527f9e2c395a5d1a0aff75 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 31 Jul 2024 17:58:37 +0200 Subject: [PATCH 274/338] abnormal frame wait time checker --- serl_robot_infra/robotiq_env/camera/rs_capture.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 2233ced5..071463a7 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -56,7 +56,11 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= self.align = rs.align(align_to) def read(self): + t = time.time() frames = self.pipe.wait_for_frames() + tdiff = time.time() - t + if tdiff > 0.5: + print(f"wait for frames took {tdiff:.3f} seconds") image, depth, pointcloud = None, None, None if self.rgb: From 0895695c07dd5163fc75afda47a5e64591232451 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:01:13 +0200 Subject: [PATCH 275/338] changed environment step and safety margins to mrp instead of euler, so we do not run into x-before-y rotation stuff at all (mrp is essentially human readable quaternion), huge bugfix --- .../robotiq_env/envs/camera_env/config.py | 13 ++++--- .../robotiq_env/envs/relative_env.py | 6 ++-- .../robotiq_env/envs/robotiq_env.py | 35 ++++++------------- serl_robot_infra/robotiq_env/envs/wrappers.py | 28 +++++++++++++-- .../robotiq_env/utils/rotations.py | 4 +++ 5 files changed, 49 insertions(+), 37 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index f94835ac..540e6c25 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -56,7 +56,7 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): } -class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes +class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes RESET_Q = np.array([ [2.6259, - 1.5196, 2.1287, - 2.1784, - 1.5665, - 0.4741], [2.0131, - 1.271, 1.9316, - 2.2306, - 1.566, 0.4537], @@ -72,8 +72,8 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.18, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.8, -0.18, -3.2]) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 1.]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -1.]) ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) @@ -98,8 +98,7 @@ class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RANDOM_RZ_RANGE = (0.0,) RESET_Q = np.array([ - # [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237], # schräge position - [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384] # gerade pos + # [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi/2.], # schräge position + # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos + [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box ]) - ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 3.2, 0.3, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, 2.6, -0.3, -3.2]) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index a384497e..bf06e971 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -100,7 +100,8 @@ def transform_action(self, action: np.ndarray): using the rotation matrix """ action = np.array(action) # in case action is a jax read-only array - action[:3] = self.rotation_matrix @ action[:3] + action[:3] = self.rotation_matrix_reset @ action[:3] + action[3:6] = self.rotation_matrix_reset @ action[3:6] return action def transform_action_inv(self, action: np.ndarray): @@ -109,5 +110,6 @@ def transform_action_inv(self, action: np.ndarray): using the rotation matrix. """ action = np.array(action) - action[:3] = self.rotation_matrix.transpose() @ action[:3] + action[:3] = self.rotation_matrix_reset.transpose() @ action[:3] + action[3:6] = self.rotation_matrix_reset.transpose() @ action[3:6] return action diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 6efa307d..61c4c9e3 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -20,7 +20,6 @@ from robotiq_env.camera.utils import PointCloudFusion, CalibrationTread from robotiq_env.utils.real_time_plotter import DataClient -from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2quat, pose2rotvec from robot_controllers.robotiq_controller import RobotiqImpedanceController from serl_launcher.utils.numpy_utils import bool_2_int8 @@ -164,7 +163,7 @@ def __init__( config.ABS_POSE_RANGE_LIMITS[1], dtype=np.float64, ) - self.rpy_bounding_box = gym.spaces.Box( + self.mrp_bounding_box = gym.spaces.Box( config.ABS_POSE_LIMIT_LOW[3:], config.ABS_POSE_LIMIT_HIGH[3:], dtype=np.float64, @@ -279,31 +278,18 @@ def __init__( self.calibrate_pointcloud_fusion(visualize=True) - def clip_safety_box(self, - next_pos: np.ndarray) -> np.ndarray: # TODO make better, no euler -> quat -> euler -> quat + def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: """Clip the pose to be within the safety box.""" next_pos[:3] = np.clip( next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high ) - xy_range = np.clip(np.linalg.norm(next_pos[:2], 2), self.xy_range.low, self.xy_range.high) - next_pos[:2] = next_pos[:2] / np.linalg.norm(next_pos[:2]) * xy_range - - euler = R.from_quat(next_pos[3:]).as_euler("xyz") - - # Clip first euler angle separately due to discontinuity from pi to -pi - sign = np.sign(euler[0]) - euler[0] = sign * ( - np.clip( - np.abs(euler[0]), - self.rpy_bounding_box.low[0], - self.rpy_bounding_box.high[0], - ) - ) - - euler[1:] = np.clip( - euler[1:], self.rpy_bounding_box.low[1:], self.rpy_bounding_box.high[1:] + orientation_diff = (R.from_quat(next_pos[3:]) * R.from_quat(self.curr_reset_pose[3:]).inv()).as_mrp() + print(self.curr_reset_pose[3:], next_pos[3:], orientation_diff, end=" ") + orientation_diff = np.clip( + orientation_diff, self.mrp_bounding_box.low, self.mrp_bounding_box.high ) - next_pos[3:] = R.from_euler("xyz", euler).as_quat() + next_pos[3:] = (R.from_mrp(orientation_diff) * R.from_quat(self.curr_reset_pose[3:])).as_quat() + print(orientation_diff, next_pos[3:]) return next_pos @@ -323,10 +309,9 @@ def step(self, action: np.ndarray) -> tuple: next_pos = self.curr_pos.copy() next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] - # orientation next_pos[3:] = ( - R.from_quat(next_pos[3:]) * R.from_euler("xyz", action[3:6] * self.action_scale[1]) - ).as_quat() + R.from_mrp(action[3:6] * self.action_scale[1] / 4.) * R.from_quat(next_pos[3:]) + ).as_quat() # c * r --> applies c after r gripper_action = action[6] * self.action_scale[2] diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index e4d63ba1..1c951375 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -6,7 +6,7 @@ import time from scipy.spatial.transform import Rotation as R -from robotiq_env.utils.rotations import quat_2_euler +from robotiq_env.utils.rotations import quat_2_euler, quat_2_mrp sigmoid = lambda x: 1 / (1 + np.exp(-x)) @@ -34,7 +34,8 @@ def action(self, action: np.ndarray) -> np.ndarray: """ expert_a = self.get_deadspace_action() - if np.linalg.norm(expert_a) > 0.001 or self.left.any() or self.right.any(): # also read buttons with no movement + if np.linalg.norm( + expert_a) > 0.001 or self.left.any() or self.right.any(): # also read buttons with no movement self.last_intervene = time.time() if self.gripper_enabled: @@ -54,7 +55,7 @@ def get_deadspace_action(self) -> np.ndarray: negative = np.clip((expert_a + self.deadspace) / (1. - self.deadspace), a_min=-1.0, a_max=0.0) expert_a = positive + negative - self.left, self.right = np.roll(self.left, -1), np.roll(self.right, -1) # shift them one to the left + self.left, self.right = np.roll(self.left, -1), np.roll(self.right, -1) # shift them one to the left self.left[-1], self.right[-1] = tuple(buttons) return np.array(expert_a, dtype=np.float32) @@ -111,6 +112,27 @@ def observation(self, observation): return observation +class Quat2MrpWrapper(gym.ObservationWrapper): + """ + Convert the quaternion representation of the tcp pose to euler angles + """ + + def __init__(self, env: gym.Env): + super().__init__(env) + # from xyz + quat to xyz + euler + self.observation_space["state"]["tcp_pose"] = gym.spaces.Box( + -np.inf, np.inf, shape=(6,) + ) + + def observation(self, observation): + # convert tcp pose from quat to euler + tcp_pose = observation["state"]["tcp_pose"] + observation["state"]["tcp_pose"] = np.concatenate( + (tcp_pose[:3], quat_2_mrp(tcp_pose[3:])) + ) + return observation + + class BinaryRewardClassifierWrapper(gym.Wrapper): """ Compute reward with custom binary reward classifier fn diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/robotiq_env/utils/rotations.py index 6768f94f..e22c4285 100644 --- a/serl_robot_infra/robotiq_env/utils/rotations.py +++ b/serl_robot_infra/robotiq_env/utils/rotations.py @@ -18,6 +18,10 @@ def quat_2_euler(quat): return R.from_quat(quat).as_euler('xyz') +def quat_2_mrp(quat): + return R.from_quat(quat).as_mrp() + + def euler_2_quat(euler): return R.from_euler(euler).as_quat() From f08c8161553dc0b7fb0c347b9be138ed767061c3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:07:32 +0200 Subject: [PATCH 276/338] changed environment step and safety margins to mrp instead of euler, so we do not run into x-before-y rotation stuff at all (mrp is essentially human readable quaternion), huge bugfix --- examples/robotiq_drq/drq_policy_robotiq.py | 7 +-- .../vision/data_augmentations.py | 44 ++++++------------- 2 files changed, 15 insertions(+), 36 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index f7c6e552..0d2a9c89 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -25,7 +25,7 @@ plot_feature_kernel_histogram, find_zero_weights, plot_conv3d_kernels, - get_pretrained_VoxNet_Conv3d_kernels + load_pretrained_VoxNet_params ) from agentlace.trainer import TrainerServer, TrainerClient @@ -466,16 +466,11 @@ def main(_): jax.tree_map(jnp.array, agent), sharding.replicate() ) - # manually set the first 3D-conv kernels from pretrained VoxNet - agent.state.params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_3x3x3"]["kernel"] = agent.state.params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_3x3x3"]["kernel"].at[...].set(get_pretrained_VoxNet_Conv3d_kernels(features=32)) - # print useful info print_agent_params(agent, image_keys) # plot_conv3d_kernels(agent.state.params) # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) - agent.config["observation_rot_scale"] = env.scale_wrapper_get_scales()["rotation_scale"] - agent.config["action_rot_scale"] = env.action_scale[1] agent.config["activate_batch_rotation"] = False # deactivate for now def create_replay_buffer_and_wandb_logger(): diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 0f50a234..957a10f5 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -4,13 +4,14 @@ import jax.numpy as jnp import jax.lax as lax -import jaxlie ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) -# Rotations are in the array transposed for easy dot product ROT_GENERAL = jnp.array([jnp.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) +""" # not used anymore, since we are no longer using euler angles +import jaxlie + def euler_xyz_to_yxz(xyz_angles): # Create SO3 object from xyz Euler angles so3 = jaxlie.SO3.from_rpy_radians( @@ -37,18 +38,19 @@ def single_90_rotation(arr): # Apply the rotation 'rot' number of times return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) +""" @jax.jit def random_rot90_action(action: jnp.ndarray, num_rot: int): # action is (x, y, z, rx, ry, rz, gripper) assert action.shape == (7,) xyz_rotated = jnp.dot(ROT_GENERAL[num_rot], action[:3]) - orientation_rotated = orient_rot90_jax(action[3:6], num_rot) + orientation_rotated = jnp.dot(ROT_GENERAL[num_rot], action[3:6]) return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) -@partial(jax.jit, static_argnames=("action_rotation_scale", "only_180")) -def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = 0.1, only_180=False): +@partial(jax.jit, static_argnames="only_180") +def batched_random_rot90_action(actions, rng, *, only_180=False): assert actions.shape[-1:] == (7,) num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) if only_180: @@ -56,36 +58,25 @@ def batched_random_rot90_action(actions, rng, *, action_rotation_scale: float = # jax.debug.print("rotation: {}", num_rot[0]) - # scale the actions back to normal rad angles - actions = actions.at[:, 3:6].multiply(action_rotation_scale) - actions = jax.vmap( lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 )(actions, num_rot) - return actions.at[:, 3:6].multiply(1 / action_rotation_scale) + return actions @partial(jax.jit, static_argnames=("num_batch_dims", "only_180")) -def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, state_rotation_scale: float = 10., - only_180=False): +def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, only_180=False): original_shape = state.shape state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) if only_180: num_rot = (num_rot % 2) * 2 - # reverse the scaling here - state = state.at[5:8].multiply(1 / state_rotation_scale) - state = state.at[11:14].multiply(1 / state_rotation_scale) - state = jax.vmap( lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 )(state, num_rot) - # apply the scaling again - state = state.at[5:8].multiply(state_rotation_scale) - state = state.at[11:14].multiply(state_rotation_scale) return state.reshape(original_shape) @@ -94,22 +85,15 @@ def random_rot90_state(state, num_rot): # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) # without force and torque: (gripper[0], pose[2], orientation[5], velocity[8], or vel[11]) - normal_indices = jnp.array([2, 8]) - orientation_indices = jnp.array([5, 11]) + indices = jnp.array([2, 5, 8, 11]) - def normal_rotate(i, state): - part = lax.dynamic_slice(state, (normal_indices[i],), (3,)) + def rotate(i, state): + part = lax.dynamic_slice(state, (indices[i],), (3,)) rotated = jnp.dot(ROT_GENERAL[num_rot], part) - return lax.dynamic_update_slice(state, rotated, (normal_indices[i],)) - - def orientation_rotate(i, state): - part = lax.dynamic_slice(state, (orientation_indices[i],), (3,)) - rotated = orient_rot90_jax(part, num_rot) - return lax.dynamic_update_slice(state, rotated, (orientation_indices[i],)) + return lax.dynamic_update_slice(state, rotated, (indices[i],)) # Apply rotations sequentially - state = jax.lax.fori_loop(0, normal_indices.shape[0], normal_rotate, state) - state = jax.lax.fori_loop(0, orientation_indices.shape[0], orientation_rotate, state) + state = jax.lax.fori_loop(0, indices.shape[0], rotate, state) return state From 23306b23dd31bdaa8af7c40ebae58197a24407f2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:08:07 +0200 Subject: [PATCH 277/338] added pretrained voxnet params loader --- .../serl_launcher/agents/continuous/drq.py | 18 +++++++------ .../serl_launcher/utils/train_utils.py | 25 +++++++++++++++---- .../vision/voxel_grid_encoders.py | 25 +++++++++---------- 3 files changed, 42 insertions(+), 26 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 4f35f930..e3669df5 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -254,7 +254,7 @@ def create_drq( ) for image_key in image_keys } - elif encoder_type == "voxnet": + elif encoder_type == "voxnet" or encoder_type == "voxnet-semi-pretrained": encoders = { image_key: VoxNet( bottleneck_dim=encoder_kwargs["bottleneck_dim"], @@ -324,6 +324,11 @@ def create_drq( agent = load_resnet10_params(agent, image_keys) + if encoder_type == "voxnet-semi-pretrained": + from serl_launcher.utils.train_utils import load_pretrained_VoxNet_params + + agent = load_pretrained_VoxNet_params(agent, image_keys) + return agent def batch_augmentation_fn(self, observations, next_observations, actions, rng, activated=True): @@ -341,8 +346,7 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a observations = observations.copy( add_or_replace={ "state": batched_random_rot90_state( - observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rot_scale"], only_180=only_180 + observations["state"], rng, num_batch_dims=2, only_180=only_180 ), pixel_key: batched_random_rot90_voxel( observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 @@ -352,17 +356,15 @@ def batch_augmentation_fn(self, observations, next_observations, actions, rng, a next_observations = next_observations.copy( add_or_replace={ "state": batched_random_rot90_state( - next_observations["state"], rng, num_batch_dims=2, - state_rotation_scale=self.config["observation_rot_scale"], only_180=only_180 + next_observations["state"], rng, num_batch_dims=2, only_180=only_180 ), pixel_key: batched_random_rot90_voxel( next_observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 ) } ) - actions = batched_random_rot90_action( - actions, rng, action_rotation_scale=self.config["action_rot_scale"], only_180=only_180 - ) + actions = batched_random_rot90_action(actions, rng, only_180=only_180) + # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) # jax.debug.print("action after: {}", actions[0, :]) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index d615c151..bb77ba84 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -132,6 +132,26 @@ def load_resnet10_params(agent, image_keys=("image",), public=True): return agent +def load_pretrained_VoxNet_params(agent, image_keys=("pointcloud",)): + ckpt = jnp.load("/home/nico/Downloads/c-11.npz") + + new_params = agent.state.params + + for image_key in image_keys: + new_encoder_params = new_params["modules_actor"]["encoder"][ + f"encoder_{image_key}" + ] + new_encoder_params["conv_5x5x5"]["kernel"].at[:].set(ckpt["voxnet/conv1/conv3d/kernel:0"]) + new_encoder_params["conv_3x3x3"]["kernel"].at[:].set(ckpt["voxnet/conv2/conv3d/kernel:0"]) + new_encoder_params["conv_2x2x2"]["kernel"].at[:].set(ckpt["voxnet/conv3/conv3d/kernel:0"][..., :128]) + + to_replace = ["conv_5x5x5", "conv_3x3x3", "conv_2x2x2"] + print(f"replaced {to_replace} in {image_key}") + + agent = agent.replace(state=agent.state.replace(params=new_params)) + return agent + + def print_agent_params(agent, image_keys=("image",)): """ helper function to print the parameter count of the actor and critic networks @@ -235,8 +255,3 @@ def plot_conv3d_kernels(params): for i in range(kernels.shape[-1]): print(kernels[..., 0, i].mean(), kernels[..., 0, i].std()) plot_3d_kernel(kernels[..., 0, i], i) - - -def get_pretrained_VoxNet_Conv3d_kernels(features: int = 32): - ckpt = jnp.load("/home/nico/Downloads/c-11/voxnet/conv1/conv3d/kernel:0.npy") - return ckpt[..., :features] diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 126552f5..92c22e88 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -111,46 +111,45 @@ def __call__( observations = observations.astype(jnp.float32)[..., None] / self.scale_factor # add conv channel conv3d = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, - padding="valid") + padding="valid", bias_init=nn.zeros_init()) l_relu = partial(nn.leaky_relu, negative_slope=0.1) max_pool = partial(nn.max_pool, window_shape=(2, 2, 2), strides=(2, 2, 2)) x = observations x = conv3d( - features=32, + features=64, kernel_size=(5, 5, 5), strides=(2, 2, 2), - name="conv_3x3x3", + name="conv_5x5x5", )(x) x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) # x = max_pool(x) x = nn.LayerNorm()(x) - x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now - x = conv3d( - features=32, + features=64, kernel_size=(3, 3, 3), - strides=(2, 2, 2), - name="conv_3x3x3_2" + strides=(1, 1, 1), + name="conv_3x3x3" )(x) x = l_relu(x) # shape (B, (X-4)/4, (Y-4)/4, (Z-4)/4, F) # x = max_pool(x) x = nn.LayerNorm()(x) x = conv3d( - features=32, - kernel_size=(3, 3, 3), + features=128, + kernel_size=(2, 2, 2), strides=(2, 2, 2), - name="conv_3x3x3_3" + name="conv_2x2x2" )(x) x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) - # x = max_pool(x) x = nn.LayerNorm()(x) + x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now + # x = jnp.mean(x, axis=(-2)) # average over z dim - # x = SpatialSoftArgmax3D(9, 9, 6, 32)(x) + x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) # jax.debug.print("ssam {}", x) # what , all 1s 0s or -1s??? From f15cf981c4485b41f83d788a2142310061cc664a Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:21:59 +0200 Subject: [PATCH 278/338] optimized voxnet params loader --- .../serl_launcher/utils/train_utils.py | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index bb77ba84..265f6c02 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -141,12 +141,19 @@ def load_pretrained_VoxNet_params(agent, image_keys=("pointcloud",)): new_encoder_params = new_params["modules_actor"]["encoder"][ f"encoder_{image_key}" ] - new_encoder_params["conv_5x5x5"]["kernel"].at[:].set(ckpt["voxnet/conv1/conv3d/kernel:0"]) - new_encoder_params["conv_3x3x3"]["kernel"].at[:].set(ckpt["voxnet/conv2/conv3d/kernel:0"]) - new_encoder_params["conv_2x2x2"]["kernel"].at[:].set(ckpt["voxnet/conv3/conv3d/kernel:0"][..., :128]) - - to_replace = ["conv_5x5x5", "conv_3x3x3", "conv_2x2x2"] - print(f"replaced {to_replace} in {image_key}") + to_replace = { + "conv_5x5x5": "voxnet/conv1/conv3d/kernel:0", + "conv_3x3x3": "voxnet/conv2/conv3d/kernel:0", + "conv_2x2x2": "voxnet/conv3/conv3d/kernel:0" + } + replaced = [] + for key, weights in to_replace.items(): + if key in new_encoder_params: + shape = new_encoder_params[key]["kernel"].shape + new_encoder_params[key]["kernel"].at[:].set(ckpt[weights][..., :shape[-1]]) + replaced.append(f"{key}:{shape}") + + print(f"replaced {replaced} in {image_key}") agent = agent.replace(state=agent.state.replace(params=new_params)) return agent From e3aa2fafef0b6354eb3ad65053a61100748d4783 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:33:01 +0200 Subject: [PATCH 279/338] actually use mrp wrapper that was created --- examples/robotiq_drq/drq_policy_robotiq.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 0d2a9c89..7877cb1b 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -40,7 +40,7 @@ from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.vision.data_augmentations import batched_random_rot90_state, batched_random_rot90_voxel, \ batched_random_rot90_action @@ -441,7 +441,7 @@ def main(_): # if FLAGS.actor: # env = SpacemouseIntervention(env) env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) env = ObservationStatisticsWrapper(env) env = SERLObsWrapper(env) @@ -471,7 +471,7 @@ def main(_): # plot_conv3d_kernels(agent.state.params) # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) - agent.config["activate_batch_rotation"] = False # deactivate for now + agent.config["activate_batch_rotation"] = 90 # deactivate for now def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( From 0c413724203533f41cc61e549aa2245e7b8562c3 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 6 Aug 2024 14:35:54 +0200 Subject: [PATCH 280/338] print cleanup --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 61c4c9e3..5f28b967 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -284,12 +284,10 @@ def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high ) orientation_diff = (R.from_quat(next_pos[3:]) * R.from_quat(self.curr_reset_pose[3:]).inv()).as_mrp() - print(self.curr_reset_pose[3:], next_pos[3:], orientation_diff, end=" ") orientation_diff = np.clip( orientation_diff, self.mrp_bounding_box.low, self.mrp_bounding_box.high ) next_pos[3:] = (R.from_mrp(orientation_diff) * R.from_quat(self.curr_reset_pose[3:])).as_quat() - print(orientation_diff, next_pos[3:]) return next_pos From b56c04d020e1579d0c17e5acacc9c477ac79817f Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 8 Aug 2024 18:09:02 +0200 Subject: [PATCH 281/338] added a new wrapper that rotates every observation within the first quadrant (more efficient learning) --- examples/robotiq_drq/drq_policy_robotiq.py | 7 ++- serl_robot_infra/robotiq_env/envs/wrappers.py | 58 +++++++++++++------ 2 files changed, 45 insertions(+), 20 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 7877cb1b..ea4b4766 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -40,7 +40,7 @@ from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper from serl_launcher.vision.data_augmentations import batched_random_rot90_state, batched_random_rot90_voxel, \ batched_random_rot90_action @@ -442,7 +442,8 @@ def main(_): # env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) - env = ScaleObservationWrapper(env) # scale obs space (after quat2euler, but before serlobswr) + env = ObservationRotationWrapper(env) # new + env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) env = ObservationStatisticsWrapper(env) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) @@ -471,7 +472,7 @@ def main(_): # plot_conv3d_kernels(agent.state.params) # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) - agent.config["activate_batch_rotation"] = 90 # deactivate for now + agent.config["activate_batch_rotation"] = False # deactivate for now def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 1c951375..9fbd1ad1 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -8,7 +8,8 @@ from robotiq_env.utils.rotations import quat_2_euler, quat_2_mrp -sigmoid = lambda x: 1 / (1 + np.exp(-x)) +ROT90 = np.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) +ROT_GENERAL = np.array([np.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) class SpacemouseIntervention(gym.ActionWrapper): @@ -91,7 +92,7 @@ def step(self, action): return obs, rew, done, truncated, info -class Quat2EulerWrapper(gym.ObservationWrapper): +class Quat2EulerWrapper(gym.ObservationWrapper): # not used anymore (stay away from euler angles!) """ Convert the quaternion representation of the tcp pose to euler angles """ @@ -133,23 +134,46 @@ def observation(self, observation): return observation -class BinaryRewardClassifierWrapper(gym.Wrapper): +def rotate_state(state: np.ndarray, num_rot: int): + assert len(state.shape) == 1 and state.shape[0] % 3 == 0 + state = state.reshape((-1, 3)).transpose() + rotated = np.dot(ROT_GENERAL[num_rot % 4], state).transpose() + return rotated.reshape((-1)) + + +class ObservationRotationWrapper(gym.Wrapper): """ - Compute reward with custom binary reward classifier fn + Convert every observation into the first quadrant of the Relative Frame """ - def __init__(self, env: gym.Env, reward_classifier_func): + def __init__(self, env: gym.Env): super().__init__(env) - self.reward_classifier_func = reward_classifier_func - - def compute_reward(self, obs): - if self.reward_classifier_func is not None: - logit = self.reward_classifier_func(obs).item() - return (sigmoid(logit) >= 0.5) * 1 - return 0 + self.num_rot_quadrant = -1 + + def step(self, action: np.ndarray): + action = self.rotate_action(action=action) + obs, reward, done, truncated, info = self.env.step(action) + print(self.num_rot_quadrant) + rotated_obs = self.rotate_observation(obs) + return rotated_obs, reward, done, truncated, info + + def rotate_observation(self, observation): + x, y = (observation["state"]["tcp_pose"][:2]) + self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info + + for state in observation["state"].keys(): + if state == "gripper_state": + continue + observation["state"][state][:] = rotate_state(observation["state"][state], self.num_rot_quadrant) # rotate + + for image_keys in observation["images"].keys(): + observation["images"][image_keys][:] = np.rot90( + observation["images"][image_keys], + axes=(0, 1), + k=self.num_rot_quadrant + ) + return observation - def step(self, action): - obs, rew, done, truncated, info = self.env.step(action) - rew = self.compute_reward(obs) - done = done or rew - return obs, rew, done, truncated, info + def rotate_action(self, action): + action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate + return action From 701aeccbd86ca1ce207e9d1b27a57a609d9edcc4 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 8 Aug 2024 18:09:38 +0200 Subject: [PATCH 282/338] use new mrp wrapper & some cleanup --- examples/robotiq_bc/record_demo.py | 4 ++-- examples/robotiq_bc/test_demo.py | 4 ++-- examples/robotiq_drq/record_demo.py | 4 ++-- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 3 ++- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 1 - 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index 58e1811a..982b7c2a 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -9,7 +9,7 @@ from pprint import pprint from pynput import keyboard -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.wrappers.chunking import ChunkingWrapper @@ -35,7 +35,7 @@ def on_esc(key): env = gym.make("robotiq-grip-v1") env = SpacemouseIntervention(env) env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = SerlObsWrapperNoImages(env) # env = TransformReward(env, lambda r: 10. * r) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) diff --git a/examples/robotiq_bc/test_demo.py b/examples/robotiq_bc/test_demo.py index b4349fdd..f24e27c3 100644 --- a/examples/robotiq_bc/test_demo.py +++ b/examples/robotiq_bc/test_demo.py @@ -4,7 +4,7 @@ import gymnasium as gym from pynput import keyboard -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages exit_program = threading.Event() @@ -30,7 +30,7 @@ def on_esc(key): env = gym.make("robotiq-grip-v1") env = SpacemouseIntervention(env) # env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index a1000a66..936eb862 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -9,7 +9,7 @@ from pynput import keyboard from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.chunking import ChunkingWrapper @@ -38,7 +38,7 @@ def on_esc(key): ) env = SpacemouseIntervention(env) env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index a4b82d4c..bab07796 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -27,7 +27,8 @@ def compute_reward(self, obs, action) -> float: max_pose_diff = 0.03 # set to 3cm pos_diff = obs["state"]["tcp_pose"][:2] - self.curr_reset_pose[:2] position_cost = 10. * np.sum( - np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0)) + np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0) + ) cost_info = dict( action_cost=-action_cost, diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 5f28b967..81c20362 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -137,7 +137,6 @@ def __init__( self.curr_torque = np.zeros((3,), dtype=np.float32) self.gripper_state = np.zeros((2,), dtype=np.float32) - self.last_sent = time.time() self.random_reset = config.RANDOM_RESET self.random_xy_range = config.RANDOM_XY_RANGE self.random_rz_range = config.RANDOM_RZ_RANGE From 36b141af0dce52b2ee1774e27f3ecc2af2e5d326 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 8 Aug 2024 18:10:26 +0200 Subject: [PATCH 283/338] voxel grid configuration for 6 aug run (and relu after layernorm) --- .../vision/voxel_grid_encoders.py | 28 +++++++++++-------- 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 92c22e88..b63a6af4 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -122,9 +122,9 @@ def __call__( strides=(2, 2, 2), name="conv_5x5x5", )(x) - x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, 32) # x = max_pool(x) x = nn.LayerNorm()(x) + x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, F) x = conv3d( features=64, @@ -132,25 +132,29 @@ def __call__( strides=(1, 1, 1), name="conv_3x3x3" )(x) - x = l_relu(x) # shape (B, (X-4)/4, (Y-4)/4, (Z-4)/4, F) - # x = max_pool(x) + x = max_pool(x) x = nn.LayerNorm()(x) + x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, F) + + x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now + + # x = conv3d( + # features=128, + # kernel_size=(2, 2, 2), + # strides=(2, 2, 2), + # name="conv_2x2x2" + # )(x) # if pretrained is used x = conv3d( - features=128, + features=32, kernel_size=(2, 2, 2), strides=(2, 2, 2), - name="conv_2x2x2" + name="conv_2x2x2_custom" )(x) - x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) x = nn.LayerNorm()(x) + x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) - x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now - - # x = jnp.mean(x, axis=(-2)) # average over z dim - - x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) - + # x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) # jax.debug.print("ssam {}", x) # what , all 1s 0s or -1s??? # reshape and dense (preserve batch dim) From d9fa6d7942b9a4641e206a45cc9d93bd108539af Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 9 Aug 2024 15:13:34 +0200 Subject: [PATCH 284/338] added observation rotation wrapper --- examples/robotiq_drq/record_demo.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index 936eb862..df4c477a 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -9,7 +9,7 @@ from pynput import keyboard from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.chunking import ChunkingWrapper @@ -40,6 +40,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) + env = ObservationRotationWrapper(env) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) From 4b0ac11a3628feabc4398619dc3e08b824562b8f Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 9 Aug 2024 15:14:04 +0200 Subject: [PATCH 285/338] some cleanup --- examples/robotiq_drq/drq_policy_robotiq.py | 8 ++++++-- serl_launcher/serl_launcher/agents/continuous/drq.py | 3 ++- serl_launcher/serl_launcher/common/encoding.py | 1 + serl_launcher/serl_launcher/utils/launcher.py | 1 + serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py | 2 +- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 8 +++++--- serl_robot_infra/robotiq_env/envs/wrappers.py | 4 ++-- 7 files changed, 18 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index ea4b4766..61b5a526 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -209,7 +209,7 @@ def update_params(params): client.recv_network_callback(update_params) obs, _ = env.reset() - done = False + last_actions = np.zeros((7,)) # training loop timer = Timer() @@ -256,6 +256,9 @@ def update_params(params): if "intervene_action" in info: actions = info.pop("intervene_action") + # next_obs["state"][:7][:] = actions # add actions to obs (curr_actions) + # reward -= 0.3 * np.sum(np.power(actions - last_actions, 2)) # cave-man like but otherwise too complex + reward = np.asarray(reward, dtype=np.float32) info = np.asarray(info) running_return = running_return * 0.99 + reward @@ -270,6 +273,7 @@ def update_params(params): data_store.insert(transition) obs = next_obs + last_actions = actions if done or truncated: stats = {"train": info} # send stats to the learner to log client.request("send-stats", stats) @@ -442,9 +446,9 @@ def main(_): # env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) - env = ObservationRotationWrapper(env) # new env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) env = ObservationStatisticsWrapper(env) + env = ObservationRotationWrapper(env) # new env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index e3669df5..3e6307a3 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -121,6 +121,7 @@ def create_drq( # Model architecture encoder_type: str = "small", use_proprio: bool = False, + proprio_latent_dim: int = 64, critic_network_kwargs: dict = { "hidden_dims": [256, 256], }, @@ -274,7 +275,7 @@ def create_drq( use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, - proprio_latent_dim=64, + proprio_latent_dim=proprio_latent_dim, ) encoders = { diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index b6bbaad7..0e98395a 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -19,6 +19,7 @@ class EncodingWrapper(nn.Module): encoder: nn.Module use_proprio: bool + # state_mask: jnp.ndarray # TODO add mask to blent out uneccessary states proprio_latent_dim: int = 64 enable_stacking: bool = False image_keys: Iterable[str] = ("image",) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index cf6d8f72..8689eb95 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -111,6 +111,7 @@ def make_drq_agent( sample_action, encoder_type=encoder_type, use_proprio=True, + proprio_latent_dim=64, image_keys=image_keys, policy_kwargs=dict( tanh_squash_distribution=True, diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index 1a0a8a70..b3438c2f 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -43,11 +43,11 @@ def observation(self, obs): class ScaleObservationWrapper(gym.ObservationWrapper): - """ This observation wrapper scales the observations with the provided hyperparams (to somewhat normalize the observations space) """ + def __init__(self, env, translation_scale=100., diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 81c20362..01a6f3d6 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -211,6 +211,7 @@ def __init__( "gripper_state": gym.spaces.Box(-1., 1., shape=(2,)), # "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), # "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + # "curr_action": gym.spaces.Box(-1., 1., shape=self.action_space.shape) } ) @@ -339,7 +340,7 @@ def compute_reward(self, obs, action) -> float: def reached_goal_state(self, obs) -> bool: return False # overwrite for each task - def go_to_rest(self, joint_reset=False): + def go_to_rest(self): """ The concrete steps to perform reset should be implemented each subclass for the specific task. @@ -383,12 +384,12 @@ def go_to_rest(self, joint_reset=False): self.curr_reset_pose[:] = reset_pose return np.zeros((2,)) - def reset(self, joint_reset=False, **kwargs): + def reset(self, **kwargs): self.cycle_count += 1 if self.save_video: self.save_video_recording() - shift = self.go_to_rest(joint_reset=joint_reset) + shift = self.go_to_rest() self.curr_path_length = 0 obs = self._get_obs() @@ -597,6 +598,7 @@ def _get_obs(self) -> dict: "gripper_state": self.gripper_state, # "tcp_force": self.curr_force, # "tcp_torque": self.curr_torque, + # "curr_action": np.zeros(self.action_space.shape) } if self.realtime_plot: diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 9fbd1ad1..af05b9b7 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -153,7 +153,7 @@ def __init__(self, env: gym.Env): def step(self, action: np.ndarray): action = self.rotate_action(action=action) obs, reward, done, truncated, info = self.env.step(action) - print(self.num_rot_quadrant) + # print("quadrant: ", self.num_rot_quadrant) rotated_obs = self.rotate_observation(obs) return rotated_obs, reward, done, truncated, info @@ -162,7 +162,7 @@ def rotate_observation(self, observation): self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info for state in observation["state"].keys(): - if state == "gripper_state": + if state == "gripper_state" or state == "curr_action": continue observation["state"][state][:] = rotate_state(observation["state"][state], self.num_rot_quadrant) # rotate From c64302255bb5bf714877356abdb3d27ab796e41e Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 9 Aug 2024 17:32:59 +0200 Subject: [PATCH 286/338] bugfix --- serl_robot_infra/robotiq_env/envs/wrappers.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index af05b9b7..97418500 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -153,7 +153,7 @@ def __init__(self, env: gym.Env): def step(self, action: np.ndarray): action = self.rotate_action(action=action) obs, reward, done, truncated, info = self.env.step(action) - # print("quadrant: ", self.num_rot_quadrant) + # print("\nquadrant: ", self.num_rot_quadrant) rotated_obs = self.rotate_observation(obs) return rotated_obs, reward, done, truncated, info @@ -175,5 +175,6 @@ def rotate_observation(self, observation): return observation def rotate_action(self, action): - action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate - return action + rotated_action = action.copy() + rotated_action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate + return rotated_action From ef684e35f282488f76f19ada475d869b14a71062 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 9 Aug 2024 17:33:35 +0200 Subject: [PATCH 287/338] added a state mask to easily ignore observation states --- .../serl_launcher/agents/continuous/drq.py | 5 +- .../serl_launcher/common/encoding.py | 62 ++++++++++++------- serl_launcher/serl_launcher/utils/launcher.py | 25 +++++--- 3 files changed, 60 insertions(+), 32 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 3e6307a3..4378dfc0 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -10,7 +10,7 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.common import JaxRLTrainState, ModuleDict, nonpytree_field -from serl_launcher.common.encoding import EncodingWrapper +from serl_launcher.common.encoding import EncodingWrapper, create_state_mask from serl_launcher.common.optimizers import make_optimizer from serl_launcher.common.typing import Batch, Data, Params, PRNGKey from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize @@ -121,6 +121,7 @@ def create_drq( # Model architecture encoder_type: str = "small", use_proprio: bool = False, + state_mask: str = "all", proprio_latent_dim: int = 64, critic_network_kwargs: dict = { "hidden_dims": [256, 256], @@ -270,12 +271,14 @@ def create_drq( else: raise NotImplementedError(f"Unknown encoder type: {encoder_type}") + state_mask_arr = create_state_mask(state_mask) encoder_def = EncodingWrapper( encoder=encoders, use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, proprio_latent_dim=proprio_latent_dim, + state_mask=state_mask_arr ) encoders = { diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index 0e98395a..7de6fb14 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -7,6 +7,18 @@ from einops import rearrange, repeat +def create_state_mask(mask_str: str) -> jnp.ndarray: + all = jnp.ones((14,), dtype=jnp.bool) + masks = dict( + all=all, + none=jnp.zeros_like(all), + gripper=all.at[2:].set(0), + position_gripper=all.at[8:].set(0) + ) + assert mask_str in masks + return masks[mask_str] + + class EncodingWrapper(nn.Module): """ Encodes observations into a single flat encoding, adding additional @@ -19,18 +31,18 @@ class EncodingWrapper(nn.Module): encoder: nn.Module use_proprio: bool - # state_mask: jnp.ndarray # TODO add mask to blent out uneccessary states + state_mask: jnp.ndarray proprio_latent_dim: int = 64 enable_stacking: bool = False image_keys: Iterable[str] = ("image",) @nn.compact def __call__( - self, - observations: Dict[str, jnp.ndarray], - train=False, - stop_gradient=False, - is_encoded=False, + self, + observations: Dict[str, jnp.ndarray], + train=False, + stop_gradient=False, + is_encoded=False, ) -> jnp.ndarray: # encode images with encoder if self.encoder is None: @@ -72,24 +84,26 @@ def __call__( if self.use_proprio: # project state to embeddings as well state = observations["state"] - if self.enable_stacking: - # Combine stacking and channels into a single dimension - if len(state.shape) == 2: - state = rearrange(state, "T C -> (T C)") - encoded = encoded.reshape(-1) - if len(state.shape) == 3: - state = rearrange(state, "B T C -> B (T C)") - state = nn.Dense( - self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() - )(state) - state = nn.LayerNorm()(state) - state = nn.tanh(state) - encoded = jnp.concatenate([encoded, state], axis=-1) + state = state[..., self.state_mask] # ignore certain elements + if state.shape[-1] != 0: + if self.enable_stacking: + # Combine stacking and channels into a single dimension + if len(state.shape) == 2: + state = rearrange(state, "T C -> (T C)") + encoded = encoded.reshape(-1) + if len(state.shape) == 3: + state = rearrange(state, "B T C -> B (T C)") + state = nn.Dense( + self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() + )(state) + state = nn.LayerNorm()(state) + state = nn.tanh(state) + encoded = jnp.concatenate([encoded, state], axis=-1) return encoded -class GCEncodingWrapper(nn.Module): # never used +class GCEncodingWrapper(nn.Module): # never used """ Encodes observations and goals into a single flat encoding. Handles all the logic about when/how to combine observations and goals. @@ -111,8 +125,8 @@ class GCEncodingWrapper(nn.Module): # never used stop_gradient: bool def __call__( - self, - observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], + self, + observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], ) -> jnp.ndarray: observations, goals = observations_and_goals @@ -171,8 +185,8 @@ class LCEncodingWrapper(nn.Module): stop_gradient: bool def __call__( - self, - observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], + self, + observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], ) -> jnp.ndarray: observations, goals = observations_and_goals diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 8689eb95..2ec5e9d2 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -103,14 +103,24 @@ def make_sac_agent(seed, sample_obs, sample_action): def make_drq_agent( - seed, sample_obs, sample_action, image_keys=("image",), encoder_type="small" + seed, + sample_obs, + sample_action, + image_keys=("image",), + encoder_type="small", + state_mask="none", + encoder_kwargs=None ): + if encoder_kwargs is None: + encoder_kwargs = dict(bottleneck_dim=128) + agent = DrQAgent.create_drq( jax.random.PRNGKey(seed), sample_obs, sample_action, encoder_type=encoder_type, use_proprio=True, + state_mask=state_mask, proprio_latent_dim=64, image_keys=image_keys, policy_kwargs=dict( @@ -136,12 +146,13 @@ def make_drq_agent( backup_entropy=True, # default: False critic_ensemble_size=10, critic_subsample_size=2, - encoder_kwargs=dict( - # pooling_method="spatial_softmax", # default "spatial_learned_embeddings" - bottleneck_dim=128, - # num_spatial_blocks=8, - # num_kp=64, - ), + encoder_kwargs=encoder_kwargs, + # dict( + # # pooling_method="spatial_softmax", # default "spatial_learned_embeddings" + # bottleneck_dim=128, + # # num_spatial_blocks=8, + # # num_kp=64, + # ), actor_optimizer_kwargs={ "learning_rate": 3e-3, # 3e-4 }, From e1dd104b82e2d60fa9716def263002d3602953fa Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 9 Aug 2024 17:40:31 +0200 Subject: [PATCH 288/338] re_added force and torque but ignore them with state mask --- serl_launcher/serl_launcher/common/encoding.py | 9 ++++++--- serl_launcher/serl_launcher/utils/launcher.py | 2 +- serl_launcher/serl_launcher/vision/data_augmentations.py | 4 ++-- .../serl_launcher/wrappers/serl_obs_wrappers.py | 4 ++-- .../robotiq_env/envs/camera_env/robotiq_camera_env.py | 7 ++----- serl_robot_infra/robotiq_env/envs/relative_env.py | 4 ++-- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 8 ++++---- 7 files changed, 19 insertions(+), 19 deletions(-) diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index 7de6fb14..1e4a4c19 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -8,12 +8,15 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: - all = jnp.ones((14,), dtype=jnp.bool) + all = jnp.ones((20,), dtype=jnp.bool) + gripper = all.at[2:].set(False) + no_ForceTorque = all.at[2:5].set(False).at[11:14].set(False) masks = dict( all=all, none=jnp.zeros_like(all), - gripper=all.at[2:].set(0), - position_gripper=all.at[8:].set(0) + gripper=gripper, + position_gripper=gripper.at[5:11].set(True), + no_ForceTorque=no_ForceTorque ) assert mask_str in masks return masks[mask_str] diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 2ec5e9d2..8e188357 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -108,7 +108,7 @@ def make_drq_agent( sample_action, image_keys=("image",), encoder_type="small", - state_mask="none", + state_mask="no_ForceTorque", encoder_kwargs=None ): if encoder_kwargs is None: diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 957a10f5..27008ce3 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -81,11 +81,11 @@ def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, only_180= def random_rot90_state(state, num_rot): - assert state.shape[-1] == 14 # modified for no FT + assert state.shape[-1] == 20 # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) # without force and torque: (gripper[0], pose[2], orientation[5], velocity[8], or vel[11]) - indices = jnp.array([2, 5, 8, 11]) + indices = jnp.array([2, 5, 8, 11, 14, 17]) def rotate(i, state): part = lax.dynamic_slice(state, (indices[i],), (3,)) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index b3438c2f..77b70904 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -74,6 +74,6 @@ def observation(self, obs): obs["state"]["tcp_pose"][3:] *= self.rotation_scale obs["state"]["tcp_vel"][:3] *= self.translation_scale obs["state"]["tcp_vel"][3:] *= self.rotation_scale - # obs["state"]["tcp_force"] *= self.force_scale - # obs["state"]["tcp_torque"] *= self.torque_scale + obs["state"]["tcp_force"] *= self.force_scale + obs["state"]["tcp_torque"] *= self.torque_scale return obs diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index bab07796..9cc756af 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -16,8 +16,6 @@ def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.1 - # downward_force_cost = 0.1 * max(obs["state"]["tcp_force"][2] - 10., 0.) - downward_force_cost = 0. suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.5) suction_cost = 3. * float(obs["state"]["gripper_state"][1] < -0.5) @@ -33,12 +31,11 @@ def compute_reward(self, obs, action) -> float: cost_info = dict( action_cost=-action_cost, step_cost=-step_cost, - downward_force_cost=-downward_force_cost, suction_reward=suction_reward, suction_cost=-suction_cost, orientation_cost=-orientation_cost, position_cost=-position_cost, - total_cost=-action_cost - step_cost - downward_force_cost + suction_reward - suction_cost - orientation_cost - position_cost + total_cost=-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost ) for key, info in cost_info.items(): self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) @@ -46,7 +43,7 @@ def compute_reward(self, obs, action) -> float: if self.reached_goal_state(obs): return 100. - action_cost - orientation_cost - position_cost else: - return 0. + suction_reward - action_cost - downward_force_cost - orientation_cost - position_cost - \ + return 0. + suction_reward - action_cost - orientation_cost - position_cost - \ suction_cost - step_cost def reached_goal_state(self, obs) -> bool: diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/robotiq_env/envs/relative_env.py index bf06e971..82a95a10 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/robotiq_env/envs/relative_env.py @@ -80,8 +80,8 @@ def transform_observation(self, obs): """ obs["state"]["tcp_vel"][:3] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][:3] obs["state"]["tcp_vel"][3:6] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][3:6] - # obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] - # obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] + obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] + obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] if self.include_relative_pose: T_b_o = construct_homogeneous_matrix(obs["state"]["tcp_pose"]) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 01a6f3d6..b373723c 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -209,8 +209,8 @@ def __init__( ), # xyz + quat "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), "gripper_state": gym.spaces.Box(-1., 1., shape=(2,)), - # "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - # "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), + "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), # "curr_action": gym.spaces.Box(-1., 1., shape=self.action_space.shape) } ) @@ -596,8 +596,8 @@ def _get_obs(self) -> dict: "tcp_pose": self.curr_pos, "tcp_vel": self.curr_vel, "gripper_state": self.gripper_state, - # "tcp_force": self.curr_force, - # "tcp_torque": self.curr_torque, + "tcp_force": self.curr_force, + "tcp_torque": self.curr_torque, # "curr_action": np.zeros(self.action_space.shape) } From 66030cdbf44d30d11bbe935d99a7bd2347d16888 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 12 Aug 2024 16:32:46 +0200 Subject: [PATCH 289/338] Added layernorm params and bugfix --- serl_launcher/serl_launcher/utils/train_utils.py | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 265f6c02..70d83d4b 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -150,11 +150,23 @@ def load_pretrained_VoxNet_params(agent, image_keys=("pointcloud",)): for key, weights in to_replace.items(): if key in new_encoder_params: shape = new_encoder_params[key]["kernel"].shape - new_encoder_params[key]["kernel"].at[:].set(ckpt[weights][..., :shape[-1]]) + new_encoder_params[key]["kernel"] = new_encoder_params[key]["kernel"].at[:].set( + ckpt[weights][..., :shape[-1]]) replaced.append(f"{key}:{shape}") print(f"replaced {replaced} in {image_key}") + # replace LayerNorm params with pretrained BN ones + new_encoder_params["LayerNorm_0"]["bias"] = new_encoder_params["LayerNorm_0"]["bias"].at[:].set( + ckpt["voxnet/conv1/batch_normalization/beta:0"]) + new_encoder_params["LayerNorm_0"]["scale"] = new_encoder_params["LayerNorm_0"]["scale"].at[:].set( + ckpt["voxnet/conv1/batch_normalization/gamma:0"]) + + new_encoder_params["LayerNorm_1"]["bias"] = new_encoder_params["LayerNorm_0"]["bias"].at[:].set( + ckpt["voxnet/conv2/batch_normalization/beta:0"]) + new_encoder_params["LayerNorm_1"]["scale"] = new_encoder_params["LayerNorm_0"]["scale"].at[:].set( + ckpt["voxnet/conv2/batch_normalization/gamma:0"]) + agent = agent.replace(state=agent.state.replace(params=new_params)) return agent From a409efdf87d7714e801f712fe4b824b2ef5ec56b Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 13 Aug 2024 17:46:37 +0200 Subject: [PATCH 290/338] cleanup & small improvements --- examples/robotiq_drq/encoder_feature_plot.py | 2 +- examples/robotiq_drq/record_demo.py | 2 +- serl_launcher/serl_launcher/agents/continuous/drq.py | 7 ++++--- serl_launcher/serl_launcher/utils/launcher.py | 3 ++- serl_launcher/serl_launcher/vision/data_augmentations.py | 1 - serl_robot_infra/robotiq_env/camera/utils.py | 4 ++-- serl_robot_infra/robotiq_env/envs/wrappers.py | 1 + 7 files changed, 11 insertions(+), 9 deletions(-) diff --git a/examples/robotiq_drq/encoder_feature_plot.py b/examples/robotiq_drq/encoder_feature_plot.py index 9c352cd3..c29d34e7 100644 --- a/examples/robotiq_drq/encoder_feature_plot.py +++ b/examples/robotiq_drq/encoder_feature_plot.py @@ -134,7 +134,7 @@ def main(_): import pickle as pkl - with open("/home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_mai3_streamlined.pkl", "rb") as f: + with open("/examples/robotiq_drq/old_demos/pcb_insert_20_demos_mai3_streamlined.pkl", "rb") as f: trajs = pkl.load(f) for traj in trajs: demo_buffer.insert(traj) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index df4c477a..2dc1a9a6 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -40,7 +40,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) - env = ObservationRotationWrapper(env) + env = ObservationRotationWrapper(env) # if it should be enabled env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 4378dfc0..7db3b0c6 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -256,13 +256,13 @@ def create_drq( ) for image_key in image_keys } - elif encoder_type == "voxnet" or encoder_type == "voxnet-semi-pretrained": + elif encoder_type == "voxnet" or encoder_type == "voxnet-pretrained": encoders = { image_key: VoxNet( bottleneck_dim=encoder_kwargs["bottleneck_dim"], use_conv_bias=False, final_activation=nn.tanh, - scale_factor=1. # if down-sampling from more refined grid_shape is used, otherwise 1. + pretrained=encoder_type == "voxnet-pretrained", ) for image_key in image_keys } @@ -272,6 +272,7 @@ def create_drq( raise NotImplementedError(f"Unknown encoder type: {encoder_type}") state_mask_arr = create_state_mask(state_mask) + print(f"state_mask: {state_mask} {state_mask_arr}") encoder_def = EncodingWrapper( encoder=encoders, use_proprio=use_proprio, @@ -328,7 +329,7 @@ def create_drq( agent = load_resnet10_params(agent, image_keys) - if encoder_type == "voxnet-semi-pretrained": + if encoder_type == "voxnet-pretrained": from serl_launcher.utils.train_utils import load_pretrained_VoxNet_params agent = load_pretrained_VoxNet_params(agent, image_keys) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 8e188357..378e0e22 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -109,6 +109,7 @@ def make_drq_agent( image_keys=("image",), encoder_type="small", state_mask="no_ForceTorque", + proprio_latent_dim=64, encoder_kwargs=None ): if encoder_kwargs is None: @@ -121,7 +122,7 @@ def make_drq_agent( encoder_type=encoder_type, use_proprio=True, state_mask=state_mask, - proprio_latent_dim=64, + proprio_latent_dim=proprio_latent_dim, image_keys=image_keys, policy_kwargs=dict( tanh_squash_distribution=True, diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 27008ce3..3f33d066 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -84,7 +84,6 @@ def random_rot90_state(state, num_rot): assert state.shape[-1] == 20 # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) - # without force and torque: (gripper[0], pose[2], orientation[5], velocity[8], or vel[11]) indices = jnp.array([2, 5, 8, 11, 14, 17]) def rotate(i, state): diff --git a/serl_robot_infra/robotiq_env/camera/utils.py b/serl_robot_infra/robotiq_env/camera/utils.py index 19c8ff01..5796c0fe 100644 --- a/serl_robot_infra/robotiq_env/camera/utils.py +++ b/serl_robot_infra/robotiq_env/camera/utils.py @@ -102,9 +102,9 @@ def get_voxelgrid_shape(self): def load_finetuned(self): from os.path import exists - if not exists("PointCloudFusionFinetuned.npy"): + if not exists("/home/nico/real-world-rl/serl/examples/robotiq_drq/PointCloudFusionFinetuned.npy"): return False - with open("PointCloudFusionFinetuned.npy", "rb") as f: + with open("/home/nico/real-world-rl/serl/examples/robotiq_drq/PointCloudFusionFinetuned.npy", "rb") as f: t_finetuned = np.load(f) self.t1 = t_finetuned[0, ...] self.t2 = t_finetuned[1, ...] diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 97418500..7bbec369 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -148,6 +148,7 @@ class ObservationRotationWrapper(gym.Wrapper): def __init__(self, env: gym.Env): super().__init__(env) + print("Observation Rotation Wrapper enabled!") self.num_rot_quadrant = -1 def step(self, action: np.ndarray): From c923e61a5eff1714c4550bb5c6e321aa3bde194d Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 13 Aug 2024 17:50:35 +0200 Subject: [PATCH 291/338] added new flags for clearer policy definition --- examples/robotiq_drq/drq_policy_robotiq.py | 42 +++++++++++++++++----- 1 file changed, 34 insertions(+), 8 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 61b5a526..d240026d 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -25,7 +25,6 @@ plot_feature_kernel_histogram, find_zero_weights, plot_conv3d_kernels, - load_pretrained_VoxNet_params ) from agentlace.trainer import TrainerServer, TrainerClient @@ -66,6 +65,18 @@ flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") +flags.DEFINE_string("state_mask", "no_ForceTorque", + "if all the states should be considered, possible: (all, none, no_ForceTorque, gripper, position_gripper)") +flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") +flags.DEFINE_integer("encoder_bottleneck_dim", 128, "bottleneck dimension of the encoder") +flags.DEFINE_integer("proprio_latent_dim", 64, + "the latent dimension for the state, will be concatenated with encoder bottleneck dim before being passed onward") +flags.DEFINE_multi_string("encoder_kwargs", None, "Encoder kwargs in the form ['dict key', 'dict value']") +flags.DEFINE_bool("enable_obs_rotation_wrapper", False, + "Whether to enable observation rotation wrapper (train in one quaternion)") +flags.DEFINE_bool("enable_obs_rotation_augmentation", False, + "Whether to enable observation rotation augmentation (90 deg)") + flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 10000, "Replay buffer capacity.") # quite low to forget demo trajectories @@ -81,7 +92,6 @@ flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', @@ -148,6 +158,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): agent = agent.replace(state=ckpt) print("finding zero weights") find_zero_weights(agent.state.params, print_all=False) + parameter_overview(agent) # examine model parameters if trajs==0 if FLAGS.eval_n_trajs == 0: @@ -235,7 +246,8 @@ def update_params(params): rotated_obs = copy.deepcopy(obs) rotated_obs["state"] = batched_random_rot90_state(obs["state"], rot_rng, only_180=only_180) - rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng, only_180=only_180) + rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng, + only_180=only_180) actions = agent.sample_actions( observations=jax.device_put(rotated_obs), @@ -243,7 +255,8 @@ def update_params(params): deterministic=False, ) for _ in range(3): - actions = batched_random_rot90_action(actions[None, ...], rot_rng, only_180=only_180)[0, ...] # rotate back + actions = batched_random_rot90_action(actions[None, ...], rot_rng, only_180=only_180)[ + 0, ...] # rotate back actions = np.asarray(jax.device_get(actions)) # print(actions) @@ -422,6 +435,7 @@ def stats_callback(type: str, payload: dict) -> dict: break server.stop() + # parameter_overview(agent) ############################################################################## @@ -430,7 +444,8 @@ def stats_callback(type: str, payload: dict) -> dict: def main(_): assert FLAGS.batch_size % num_devices == 0 if FLAGS.checkpoint_path.split('/')[-1] == "checkpoints": - FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") + FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + FLAGS.exp_name + " " + datetime.now().strftime( + "%m%d-%H:%M") # seed rng = jax.random.PRNGKey(FLAGS.seed) @@ -448,7 +463,8 @@ def main(_): env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) env = ObservationStatisticsWrapper(env) - env = ObservationRotationWrapper(env) # new + if FLAGS.enable_obs_rotation_wrapper: + env = ObservationRotationWrapper(env) env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -457,12 +473,21 @@ def main(_): print(f"image keys: {image_keys}") rng, sampling_rng = jax.random.split(rng) + + assert FLAGS.encoder_kwargs is None or len(FLAGS.encoder_kwargs) % 2 == 0 + encoder_kwargs = { + "bottleneck_dim": FLAGS.encoder_bottleneck_dim, + **(dict(zip(*[iter(FLAGS.encoder_kwargs)] * 2)) if FLAGS.encoder_kwargs else {}), + } agent: DrQAgent = make_drq_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), sample_action=env.action_space.sample(), image_keys=image_keys, encoder_type=FLAGS.encoder_type, + state_mask=FLAGS.state_mask, + proprio_latent_dim=FLAGS.proprio_latent_dim, + encoder_kwargs=encoder_kwargs ) # replicate agent across devices @@ -473,10 +498,10 @@ def main(_): # print useful info print_agent_params(agent, image_keys) + parameter_overview(agent) # plot_conv3d_kernels(agent.state.params) - # add ScaleObservationWrapper scales to the agent here (needed in batch rotation augmentation) - agent.config["activate_batch_rotation"] = False # deactivate for now + agent.config["activate_batch_rotation"] = FLAGS.enable_obs_rotation_augmentation # obs batch rotation control def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( @@ -537,6 +562,7 @@ def create_replay_buffer_and_wandb_logger(): # Wrap up the learner loop env.close() print("Learner loop finished") + print_agent_params(agent, image_keys) elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) From 8d2c818defa4f2b9762a2fe86c1b1b3c586d3884 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 13 Aug 2024 17:50:52 +0200 Subject: [PATCH 292/338] name change --- examples/robotiq_drq/run_actor.sh | 2 +- examples/robotiq_drq/run_evaluation.sh | 10 ++++++---- examples/robotiq_drq/run_learner.sh | 4 ++-- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/robotiq_drq/run_actor.sh index d8264356..d6f4c77f 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/robotiq_drq/run_actor.sh @@ -13,5 +13,5 @@ python drq_policy_robotiq.py "$@" \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 2500 \ - --encoder_type voxnet \ + --encoder_type voxnet-pretrained \ # --debug diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/robotiq_drq/run_evaluation.sh index 74d20c61..9d763053 100644 --- a/examples/robotiq_drq/run_evaluation.sh +++ b/examples/robotiq_drq/run_evaluation.sh @@ -4,10 +4,12 @@ python drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env_tests \ --exp_name=drq_evaluation \ + --camera_mode pointcloud \ + --batch_size 128 \ --max_traj_length 100 \ - --camera_mode rgb \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0628-14:59 10box res18 avg"\ - --eval_checkpoint_step 20000 \ - --encoder_type resnet-pretrained-18 \ + --encoder_type voxnet-pretrained \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0809-15:53 pVoxNetOnly 1quat"\ + --eval_checkpoint_step 10000 \ --eval_n_trajs 20 \ + --state_mask none \ --debug diff --git a/examples/robotiq_drq/run_learner.sh b/examples/robotiq_drq/run_learner.sh index 30513972..69987bba 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/robotiq_drq/run_learner.sh @@ -13,7 +13,7 @@ python drq_policy_robotiq.py "$@" \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 20000 \ - --encoder_type voxnet \ + --encoder_type voxnet-pretrained \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul29_noforcetorque.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug9_noFT_1quad.pkl \ # --debug From def5167a803c910295782e4833ed7bc183c012a1 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 13 Aug 2024 17:51:30 +0200 Subject: [PATCH 293/338] new VoxNet architecture --- .../vision/voxel_grid_encoders.py | 25 ++++++++----------- 1 file changed, 10 insertions(+), 15 deletions(-) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index b63a6af4..d2a49681 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -94,6 +94,7 @@ class VoxNet(nn.Module): use_conv_bias: bool = False bottleneck_dim: Optional[int] = None final_activation: Callable[[jnp.ndarray], jnp.ndarray] | str = nn.tanh + pretrained: bool = False scale_factor: float = 1. @nn.compact @@ -117,45 +118,39 @@ def __call__( x = observations x = conv3d( - features=64, + features=32, kernel_size=(5, 5, 5), strides=(2, 2, 2), name="conv_5x5x5", )(x) - # x = max_pool(x) x = nn.LayerNorm()(x) x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, F) x = conv3d( - features=64, + features=16, kernel_size=(3, 3, 3), strides=(1, 1, 1), name="conv_3x3x3" )(x) x = max_pool(x) - x = nn.LayerNorm()(x) - x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, F) - x = jax.lax.stop_gradient(x) # do not change pretrained kernels for now + if self.pretrained: + x = jax.lax.stop_gradient(x) # unfortunately also cuts gradients of the LayerNorm above - # x = conv3d( - # features=128, - # kernel_size=(2, 2, 2), - # strides=(2, 2, 2), - # name="conv_2x2x2" - # )(x) # if pretrained is used + x = nn.LayerNorm()(x) + x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, F) x = conv3d( - features=32, + features=8, # if pretrained, only uses [..] out of 128 pretrained params as initial weights kernel_size=(2, 2, 2), strides=(2, 2, 2), - name="conv_2x2x2_custom" + name="conv_2x2x2" )(x) x = nn.LayerNorm()(x) x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) # x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) - # jax.debug.print("ssam {}", x) # what , all 1s 0s or -1s??? + # jax.debug.print("ssam {}", x) # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) From 0aced4f18716a65d6dcb17840ef95ae878a87b59 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 14 Aug 2024 19:10:19 +0200 Subject: [PATCH 294/338] final VoxNet hyperparams (not pretrained) --- .../VoxNet_1quat/run_actor.sh | 23 ++++++++++++++++++ .../VoxNet_1quat/run_learner.sh | 24 +++++++++++++++++++ .../serl_launcher/agents/continuous/drq.py | 2 +- .../serl_launcher/common/encoding.py | 5 +++- .../vision/voxel_grid_encoders.py | 11 ++++++--- .../envs/camera_env/robotiq_camera_env.py | 15 ++++++++---- 6 files changed, 70 insertions(+), 10 deletions(-) create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh new file mode 100755 index 00000000..75af7f27 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh @@ -0,0 +1,23 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="voxnet only pure 32 16 8" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 24 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 2500 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --proprio_latent_dim 0 \ + --enable_obs_rotation_wrapper True \ + --enable_obs_rotation_augmentation False \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh new file mode 100755 index 00000000..61ba8218 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh @@ -0,0 +1,24 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="voxnet only pure 32 16 8" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 24 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug13_all_1quad.pkl \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --proprio_latent_dim 0 \ + --enable_obs_rotation_wrapper True \ + --enable_obs_rotation_augmentation False \ +# --debug diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 7db3b0c6..2f5542ce 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -260,7 +260,7 @@ def create_drq( encoders = { image_key: VoxNet( bottleneck_dim=encoder_kwargs["bottleneck_dim"], - use_conv_bias=False, + use_conv_bias=True, final_activation=nn.tanh, pretrained=encoder_type == "voxnet-pretrained", ) diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index 1e4a4c19..a6eabf05 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -11,12 +11,14 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: all = jnp.ones((20,), dtype=jnp.bool) gripper = all.at[2:].set(False) no_ForceTorque = all.at[2:5].set(False).at[11:14].set(False) + gripper_Zinfo = gripper.at[7].set(True) masks = dict( all=all, none=jnp.zeros_like(all), gripper=gripper, position_gripper=gripper.at[5:11].set(True), - no_ForceTorque=no_ForceTorque + no_ForceTorque=no_ForceTorque, + gripper_Zinfo=gripper_Zinfo, ) assert mask_str in masks return masks[mask_str] @@ -88,6 +90,7 @@ def __call__( # project state to embeddings as well state = observations["state"] state = state[..., self.state_mask] # ignore certain elements + # jax.debug.print("state {}", state) if state.shape[-1] != 0: if self.enable_stacking: # Combine stacking and channels into a single dimension diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index d2a49681..31085f11 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -116,9 +116,14 @@ def __call__( l_relu = partial(nn.leaky_relu, negative_slope=0.1) max_pool = partial(nn.max_pool, window_shape=(2, 2, 2), strides=(2, 2, 2)) + if self.pretrained: + feature_dimensions = (64, 64, 32) + else: + feature_dimensions = (32, 16, 8) + x = observations x = conv3d( - features=32, + features=feature_dimensions[0], kernel_size=(5, 5, 5), strides=(2, 2, 2), name="conv_5x5x5", @@ -127,7 +132,7 @@ def __call__( x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, F) x = conv3d( - features=16, + features=feature_dimensions[1], kernel_size=(3, 3, 3), strides=(1, 1, 1), name="conv_3x3x3" @@ -141,7 +146,7 @@ def __call__( x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, F) x = conv3d( - features=8, # if pretrained, only uses [..] out of 128 pretrained params as initial weights + features=feature_dimensions[2], # if pretrained, only uses [..] out of 128 pretrained params as initial weights kernel_size=(2, 2, 2), strides=(2, 2, 2), name="conv_2x2x2" diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 9cc756af..92db39be 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -11,18 +11,21 @@ def __init__(self, load_config=True, **kwargs): super().__init__(**kwargs, config=RobotiqCameraConfigFinal) else: super().__init__(**kwargs) + self.last_action = np.zeros(self.action_space.shape) def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) + action_diff_cost = 0.1 * np.sum(np.power(action - self.last_action, 2)) + self.last_action[:] = action step_cost = 0.1 suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.5) suction_cost = 3. * float(obs["state"]["gripper_state"][1] < -0.5) orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 - orientation_cost *= 25. + orientation_cost = max(orientation_cost - 0.005, 0.) * 25. - max_pose_diff = 0.03 # set to 3cm + max_pose_diff = 0.05 # set to 5cm pos_diff = obs["state"]["tcp_pose"][:2] - self.curr_reset_pose[:2] position_cost = 10. * np.sum( np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0) @@ -35,16 +38,18 @@ def compute_reward(self, obs, action) -> float: suction_cost=-suction_cost, orientation_cost=-orientation_cost, position_cost=-position_cost, - total_cost=-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost + action_diff_cost=action_diff_cost, + total_cost=-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost - action_diff_cost ) for key, info in cost_info.items(): self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) if self.reached_goal_state(obs): - return 100. - action_cost - orientation_cost - position_cost + self.last_action[:] = 0. + return 100. - action_cost - orientation_cost - position_cost - action_diff_cost else: return 0. + suction_reward - action_cost - orientation_cost - position_cost - \ - suction_cost - step_cost + suction_cost - step_cost - action_diff_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis From ac473355c800f329787648bd3c0f6d3b1df5de8c Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 15 Aug 2024 16:33:17 +0200 Subject: [PATCH 295/338] name change and bugfixes --- examples/robotiq_bc/bc_policy_robotiq.py | 2 +- examples/robotiq_bc/record_demo.py | 2 +- examples/robotiq_bc/run_rbc_actor.sh | 2 +- examples/robotiq_bc/run_rbc_learner.sh | 2 +- examples/robotiq_bc/test_demo.py | 2 +- examples/robotiq_sac/run_actor.sh | 2 +- examples/robotiq_sac/run_evaluation.sh | 2 +- examples/robotiq_sac/run_learner.sh | 2 +- examples/robotiq_sac/sac_policy_robotiq.py | 2 +- .../serl_launcher/wrappers/observation_statistics_wrapper.py | 2 +- serl_robot_infra/robotiq_env/__init__.py | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index f6c14a9e..4cb12442 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -36,7 +36,7 @@ FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq-grip-v1", "Name of environment.") +flags.DEFINE_string("env", "robotiq_basic_env", "Name of environment.") flags.DEFINE_string("agent", "bc_noimg", "Name of agent.") flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") diff --git a/examples/robotiq_bc/record_demo.py b/examples/robotiq_bc/record_demo.py index 982b7c2a..4153973d 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/robotiq_bc/record_demo.py @@ -32,7 +32,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq-grip-v1") + env = gym.make("robotiq_basic_env") env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) diff --git a/examples/robotiq_bc/run_rbc_actor.sh b/examples/robotiq_bc/run_rbc_actor.sh index 24aeeca6..f0880d4d 100644 --- a/examples/robotiq_bc/run_rbc_actor.sh +++ b/examples/robotiq_bc/run_rbc_actor.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ which python && \ python bc_policy_robotiq.py "$@" \ - --env robotiq-grip-v1 \ + --env robotiq_basic_env \ --exp_name=bc_robotiq_policy \ --seed 42 \ --batch_size 256 \ diff --git a/examples/robotiq_bc/run_rbc_learner.sh b/examples/robotiq_bc/run_rbc_learner.sh index 8142b0d8..e46ca784 100644 --- a/examples/robotiq_bc/run_rbc_learner.sh +++ b/examples/robotiq_bc/run_rbc_learner.sh @@ -1,7 +1,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python bc_policy_robotiq.py "$@" \ - --env robotiq-grip-v1 \ + --env robotiq_basic_env \ --exp_name=bc_robotiq_policy \ --seed 42 \ --batch_size 256 \ diff --git a/examples/robotiq_bc/test_demo.py b/examples/robotiq_bc/test_demo.py index f24e27c3..a7a37c3d 100644 --- a/examples/robotiq_bc/test_demo.py +++ b/examples/robotiq_bc/test_demo.py @@ -27,7 +27,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq-grip-v1") + env = gym.make("robotiq_basic_env") env = SpacemouseIntervention(env) # env = RelativeFrame(env) env = Quat2MrpWrapper(env) diff --git a/examples/robotiq_sac/run_actor.sh b/examples/robotiq_sac/run_actor.sh index 0d758dfa..a00edb04 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/robotiq_sac/run_actor.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python sac_policy_robotiq.py "$@" \ --actor \ - --env robotiq-grip-v1 \ + --env robotiq_basic_env \ --exp_name=sac_robotiq_policy \ --max_traj_length 300 \ --seed 42 \ diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/robotiq_sac/run_evaluation.sh index 27bac681..78f7048c 100644 --- a/examples/robotiq_sac/run_evaluation.sh +++ b/examples/robotiq_sac/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python sac_policy_robotiq.py "$@" \ --actor \ - --env robotiq-grip-v1 \ + --env robotiq_basic_env \ --exp_name=sac_robotiq_policy_evaluation \ --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0411-16:46"\ --eval_checkpoint_step 100000 \ diff --git a/examples/robotiq_sac/run_learner.sh b/examples/robotiq_sac/run_learner.sh index e1c851cd..02ee98c3 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/robotiq_sac/run_learner.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python sac_policy_robotiq.py "$@" \ --learner \ - --env robotiq-grip-v1 \ + --env robotiq_basic_env \ --exp_name=sac_robotiq_policy \ --max_traj_length 300 \ --seed 42 \ diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index 630feb29..ba4c6f13 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -39,7 +39,7 @@ FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq-grip-v1", "Name of environment.") +flags.DEFINE_string("env", "robotiq_basic_env", "Name of environment.") flags.DEFINE_string("agent", "sac", "Name of agent.") flags.DEFINE_string("exp_name", "sac_robotiq_policy", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") diff --git a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py index 44f4fbd4..f40c52de 100644 --- a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py +++ b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py @@ -60,7 +60,7 @@ def step(self, action): buff = {} for name, value in calc_buffs.items(): for i in range(value.shape[0]): - buff[name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz'][i]}"] = value[i] + buff[name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz', 'grip'][i]}"] = value[i] infos["obsStat"] = buff # print(buff) diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index 8257406c..7205bc95 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -2,7 +2,7 @@ import numpy as np register( - id="robotiq-grip-v1", + id="robotiq_basic_env", entry_point="robotiq_env.envs.basic_env:RobotiqBasicEnv", max_episode_steps=200, ) From 7c49e731221ccdf00e9c079766ae80a4d1927f4b Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 15 Aug 2024 16:45:05 +0200 Subject: [PATCH 296/338] some bugfixes in the augmentation handling --- examples/robotiq_drq/drq_policy_robotiq.py | 23 +++++++-------- .../vision/data_augmentations.py | 29 ++++++++----------- 2 files changed, 22 insertions(+), 30 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index d240026d..dd62ef8a 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -156,14 +156,13 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): step=FLAGS.eval_checkpoint_step, ) agent = agent.replace(state=ckpt) - print("finding zero weights") find_zero_weights(agent.state.params, print_all=False) - parameter_overview(agent) # examine model parameters if trajs==0 if FLAGS.eval_n_trajs == 0: - parameter_overview(agent) - plot_feature_kernel_histogram(agent) + # parameter_overview(agent) + # plot_feature_kernel_histogram(agent) + plot_conv3d_kernels(agent.state.params) for episode in range(FLAGS.eval_n_trajs): obs, _ = env.reset() @@ -242,12 +241,10 @@ def update_params(params): actions = np.asarray(jax.device_get(actions)) else: sampling_rng, rot_rng, key = jax.random.split(sampling_rng, 3) - only_180 = agent.config["activate_batch_rotation"] == 180 rotated_obs = copy.deepcopy(obs) - rotated_obs["state"] = batched_random_rot90_state(obs["state"], rot_rng, only_180=only_180) - rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng, - only_180=only_180) + rotated_obs["state"] = batched_random_rot90_state(obs["state"], rot_rng) + rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng) actions = agent.sample_actions( observations=jax.device_put(rotated_obs), @@ -255,11 +252,9 @@ def update_params(params): deterministic=False, ) for _ in range(3): - actions = batched_random_rot90_action(actions[None, ...], rot_rng, only_180=only_180)[ - 0, ...] # rotate back + actions = batched_random_rot90_action(actions[None, ...], rot_rng)[0, ...] # rotate back actions = np.asarray(jax.device_get(actions)) - # print(actions) # Step environment with timer.context("step_env"): @@ -435,7 +430,7 @@ def stats_callback(type: str, payload: dict) -> dict: break server.stop() - # parameter_overview(agent) + parameter_overview(agent) # print end state ############################################################################## @@ -502,6 +497,9 @@ def main(_): # plot_conv3d_kernels(agent.state.params) agent.config["activate_batch_rotation"] = FLAGS.enable_obs_rotation_augmentation # obs batch rotation control + if FLAGS.enable_obs_rotation_augmentation: + print("Batch Observation Rotation enabled!") + assert not FLAGS.enable_obs_rotation_augmentation or not FLAGS.enable_obs_rotation_wrapper # both is pointless def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( @@ -562,7 +560,6 @@ def create_replay_buffer_and_wandb_logger(): # Wrap up the learner loop env.close() print("Learner loop finished") - print_agent_params(agent, image_keys) elif FLAGS.actor: sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 3f33d066..8562bf83 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -4,11 +4,9 @@ import jax.numpy as jnp import jax.lax as lax - ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) ROT_GENERAL = jnp.array([jnp.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) - """ # not used anymore, since we are no longer using euler angles import jaxlie @@ -49,12 +47,10 @@ def random_rot90_action(action: jnp.ndarray, num_rot: int): # action is (x, y, return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) -@partial(jax.jit, static_argnames="only_180") -def batched_random_rot90_action(actions, rng, *, only_180=False): +@jax.jit +def batched_random_rot90_action(actions, rng): assert actions.shape[-1:] == (7,) num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) - if only_180: - num_rot = (num_rot % 2) * 2 # jax.debug.print("rotation: {}", num_rot[0]) @@ -65,13 +61,11 @@ def batched_random_rot90_action(actions, rng, *, only_180=False): return actions -@partial(jax.jit, static_argnames=("num_batch_dims", "only_180")) -def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, only_180=False): +@partial(jax.jit, static_argnames="num_batch_dims") +def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1): original_shape = state.shape state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) - if only_180: - num_rot = (num_rot % 2) * 2 state = jax.vmap( lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 @@ -81,10 +75,13 @@ def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1, only_180= def random_rot90_state(state, num_rot): - assert state.shape[-1] == 20 + assert state.shape[-1] == 27 - # indexes are (gripper[0], force[2], pose[5], orientation[8], torque[11], velocity[14], orientation velocity[17]) - indices = jnp.array([2, 5, 8, 11, 14, 17]) + """ + indexes are (action[0:7], gripper[7:9], force[9:12], pose[12:15], orientation[15:18], + torque[18:21], velocity[21:24], orientation velocity[24:27]) + """ + indices = jnp.array([0, 3, 9, 12, 15, 18, 21, 24]) def rotate(i, state): part = lax.dynamic_slice(state, (indices[i],), (3,)) @@ -96,14 +93,12 @@ def rotate(i, state): return state -@partial(jax.jit, static_argnames=("num_batch_dims", "only_180")) -def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1, only_180=False): +@partial(jax.jit, static_argnames="num_batch_dims") +def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): original_shape = voxel_grid.shape voxel_grid = jnp.reshape(voxel_grid, (-1, *voxel_grid.shape[num_batch_dims:])) num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) - if only_180: - num_rot = (num_rot % 2) * 2 voxel_grid = jax.vmap( lambda v, k: random_rot90_voxel(v, k), in_axes=(0, 0), out_axes=0 From 405206e84cb0de3d3c92f5c2055145d55231cf34 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 15 Aug 2024 16:45:55 +0200 Subject: [PATCH 297/338] added the current action to the observation --- .../serl_launcher/common/encoding.py | 12 ++++++---- .../envs/camera_env/robotiq_camera_env.py | 2 +- .../robotiq_env/envs/robotiq_env.py | 10 ++++---- serl_robot_infra/robotiq_env/envs/wrappers.py | 24 ++++++++++++++----- 4 files changed, 32 insertions(+), 16 deletions(-) diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index a6eabf05..ab9a0fba 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -8,10 +8,13 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: - all = jnp.ones((20,), dtype=jnp.bool) - gripper = all.at[2:].set(False) - no_ForceTorque = all.at[2:5].set(False).at[11:14].set(False) - gripper_Zinfo = gripper.at[7].set(True) + all = jnp.ones((27,), dtype=jnp.bool) + none = jnp.zeros_like(all) + no_action = all.at[:7].set(False) + gripper = none.at[0+7:2+7].set(True) + no_ForceTorque = no_action.at[7+2:7+5].set(False).at[7+11:7+14].set(False) + gripper_Zinfo = gripper.at[7+7].set(True) + action_only = none.at[:7].set(True) masks = dict( all=all, none=jnp.zeros_like(all), @@ -19,6 +22,7 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: position_gripper=gripper.at[5:11].set(True), no_ForceTorque=no_ForceTorque, gripper_Zinfo=gripper_Zinfo, + action_only=action_only, ) assert mask_str in masks return masks[mask_str] diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 92db39be..da18959e 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -15,7 +15,7 @@ def __init__(self, load_config=True, **kwargs): def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) - action_diff_cost = 0.1 * np.sum(np.power(action - self.last_action, 2)) + action_diff_cost = 0.1 * np.sum(np.power(obs["state"]["action"] - self.last_action, 2)) self.last_action[:] = action step_cost = 0.1 diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index b373723c..43ee9868 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -211,7 +211,7 @@ def __init__( "gripper_state": gym.spaces.Box(-1., 1., shape=(2,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - # "curr_action": gym.spaces.Box(-1., 1., shape=self.action_space.shape) + "action": gym.spaces.Box(-1., 1., shape=self.action_space.shape) } ) @@ -319,7 +319,7 @@ def step(self, action: np.ndarray) -> tuple: self.curr_path_length += 1 - obs = self._get_obs() + obs = self._get_obs(action) reward = self.compute_reward(obs, action) truncated = self._is_truncated() @@ -392,7 +392,7 @@ def reset(self, **kwargs): shift = self.go_to_rest() self.curr_path_length = 0 - obs = self._get_obs() + obs = self._get_obs(np.zeros_like(self.last_action)) return obs, {"reset_shift": shift} def save_video_recording(self): @@ -584,7 +584,7 @@ def _update_currpos(self): def _is_truncated(self): return self.controller.is_truncated() - def _get_obs(self) -> dict: + def _get_obs(self, action) -> dict: # get image before state observation, so they match better in time images = None @@ -598,7 +598,7 @@ def _get_obs(self) -> dict: "gripper_state": self.gripper_state, "tcp_force": self.curr_force, "tcp_torque": self.curr_torque, - # "curr_action": np.zeros(self.action_space.shape) + "action": action } if self.realtime_plot: diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 7bbec369..6747282c 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -151,6 +151,11 @@ def __init__(self, env: gym.Env): print("Observation Rotation Wrapper enabled!") self.num_rot_quadrant = -1 + def reset(self, **kwargs): + obs, info = self.env.reset() + obs = self.rotate_observation(obs, random=True) # rotate initial state random + return obs, info + def step(self, action: np.ndarray): action = self.rotate_action(action=action) obs, reward, done, truncated, info = self.env.step(action) @@ -158,14 +163,21 @@ def step(self, action: np.ndarray): rotated_obs = self.rotate_observation(obs) return rotated_obs, reward, done, truncated, info - def rotate_observation(self, observation): - x, y = (observation["state"]["tcp_pose"][:2]) - self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info + def rotate_observation(self, observation, random=False): + if not random: + x, y = (observation["state"]["tcp_pose"][:2]) + self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info + else: + self.num_rot_quadrant = np.random.randint(low=0, high=4) for state in observation["state"].keys(): - if state == "gripper_state" or state == "curr_action": + if state == "gripper_state": continue - observation["state"][state][:] = rotate_state(observation["state"][state], self.num_rot_quadrant) # rotate + elif state == "action": + observation["state"][state][:6] = rotate_state(observation["state"][state][:6], self.num_rot_quadrant) + else: + observation["state"][state][:] = rotate_state(observation["state"][state], + self.num_rot_quadrant) # rotate for image_keys in observation["images"].keys(): observation["images"][image_keys][:] = np.rot90( @@ -177,5 +189,5 @@ def rotate_observation(self, observation): def rotate_action(self, action): rotated_action = action.copy() - rotated_action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate + rotated_action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate return rotated_action From 154e15b5f6f9fcab54f1266cdca8313453cae30a Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 15:52:54 +0200 Subject: [PATCH 298/338] random rotation in x y and z, triangular (so probability is higher near 0) --- .../robotiq_env/envs/basic_env/config.py | 4 +-- .../robotiq_env/envs/camera_env/config.py | 32 +++++++++---------- .../robotiq_env/envs/robotiq_env.py | 12 ++++--- 3 files changed, 25 insertions(+), 23 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/config.py b/serl_robot_infra/robotiq_env/envs/basic_env/config.py index 016e087e..e6e5df44 100644 --- a/serl_robot_infra/robotiq_env/envs/basic_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/basic_env/config.py @@ -14,7 +14,7 @@ class RobotiqCornerConfig(DefaultEnvConfig): ]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.06,) - RANDOM_RZ_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.0,) # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.1, 3.2]) @@ -40,7 +40,7 @@ class RobotiqCornerConfigV1(DefaultEnvConfig): # TODO make multiple reset Q positions, one for each box to train on (randomize it) RANDOM_RESET = False RANDOM_XY_RANGE = (0.06,) - RANDOM_RZ_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 540e6c25..c6254dd0 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -6,7 +6,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.00,) - RANDOM_RZ_RANGE = (0.78,) + RANDOM_ROT_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.2, -0.4, 0.22, 3.2, 0.18, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.7, - 0.006, 2.8, -0.18, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) @@ -35,8 +35,8 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] ]) RANDOM_RESET = False - RANDOM_XY_RANGE = (0.00,) - RANDOM_RZ_RANGE = (0.0,) + RANDOM_XY_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.18, 3.2]) ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 2.8, -0.18, -3.2]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) @@ -58,22 +58,22 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes RESET_Q = np.array([ - [2.6259, - 1.5196, 2.1287, - 2.1784, - 1.5665, - 0.4741], - [2.0131, - 1.271, 1.9316, - 2.2306, - 1.566, 0.4537], - [1.8937, - 0.8222, 1.239, - 1.9868, - 1.565, 0.3668], - [1.4173, - 1.6375, 2.2516, - 2.1841, - 1.5668, - 0.1285], - [1.4715, - 0.8744, 1.2767, - 1.9723, - 1.5653, - 0.0874], - [1.12, - 0.7634, 1.1184, - 1.9248, - 1.5653, - 0.4334], + [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], + [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], + [1.8937, -0.8273, 1.2339, -1.9765, -1.5651, 0.3666], + [1.4174, -1.6403, 2.2494, -2.179, -1.5666, -0.1286], + [1.472, -0.8583, 1.2817, -1.9934, -1.5655, -0.0869], + [1.1117, -0.7666, 1.0792, -1.8871, -1.5639, -0.443], [1.0242, - 1.3104, 2.0986, - 2.358, - 1.5664, - 2.0496], - [0.7431, - 1.0746, 1.6486, - 2.1441, - 1.5655, - 0.7738], + [0.8757, -1.1028, 1.6058, -2.2458, -1.8081, -0.7877], [0.4391, - 1.5926, 2.3356, - 2.3129, - 1.5668, - 1.1115], [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) - RANDOM_RZ_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 1.]) - ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -1.]) + RANDOM_ROT_RANGE = (0.04,) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 0.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -0.2]) ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) @@ -95,10 +95,10 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) - RANDOM_RZ_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.05,) RESET_Q = np.array([ - # [ 0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi/2.], # schräge position + [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos - [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box + # [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box ]) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 43ee9868..c394cf65 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -85,7 +85,7 @@ class DefaultEnvConfig: RESET_Q = np.zeros((6,)) RANDOM_RESET = (False,) RANDOM_XY_RANGE = (0.0,) - RANDOM_RZ_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.0,) ABS_POSE_LIMIT_HIGH = np.zeros((6,)) ABS_POSE_LIMIT_LOW = np.zeros((6,)) ABS_POSE_RANGE_LIMITS = np.zeros((2,)) @@ -139,7 +139,7 @@ def __init__( self.gripper_state = np.zeros((2,), dtype=np.float32) self.random_reset = config.RANDOM_RESET self.random_xy_range = config.RANDOM_XY_RANGE - self.random_rz_range = config.RANDOM_RZ_RANGE + self.random_rot_range = config.RANDOM_ROT_RANGE self.hz = hz camera_mode = None if camera_mode.lower() == "none" else camera_mode @@ -369,8 +369,11 @@ def go_to_rest(self): reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) reset_pose[:2] += reset_shift - random_rz_rot = np.random.uniform(np.negative(self.random_rz_range), self.random_rz_range)[0] - reset_pose[3:][:] = (R.from_quat(reset_pose[3:]) * R.from_euler("xyz", [0., 0., random_rz_rot])).as_quat() + if self.random_rot_range[0] > 0.: + random_rot = np.random.triangular(np.negative(self.random_rot_range), 0., self.random_rot_range, size=(3,)) + else: + random_rot = np.zeros((3,)) + reset_pose[3:][:] = (R.from_quat(reset_pose[3:]) * R.from_mrp(random_rot)).as_quat() self.curr_reset_pose[:] = reset_pose @@ -378,7 +381,6 @@ def go_to_rest(self): time.sleep(0.1) while self.controller.is_moving(): time.sleep(0.1) - # print(reset_shift, reset_pose) return reset_shift else: self.curr_reset_pose[:] = reset_pose From 564904154a27bd314adc5e951bbdff4bed21dcb2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 15:53:42 +0200 Subject: [PATCH 299/338] bugfixes and cleanup --- examples/robotiq_sac/sac_policy_robotiq.py | 4 ++-- .../serl_launcher/agents/continuous/drq.py | 4 ++-- serl_launcher/serl_launcher/common/evaluation.py | 1 + serl_launcher/serl_launcher/utils/launcher.py | 4 ++-- serl_launcher/serl_launcher/vision/resnet_v1.py | 2 -- serl_robot_infra/robotiq_env/envs/wrappers.py | 13 +++++++------ 6 files changed, 14 insertions(+), 14 deletions(-) diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/robotiq_sac/sac_policy_robotiq.py index ba4c6f13..62df86ff 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/robotiq_sac/sac_policy_robotiq.py @@ -33,7 +33,7 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper import robotiq_env @@ -315,7 +315,7 @@ def main(_): if FLAGS.actor: env = SpacemouseIntervention(env) env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) # env = TransformReward(env, lambda r: FLAGS.reward_scale * r) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 2f5542ce..1db0d766 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -272,13 +272,13 @@ def create_drq( raise NotImplementedError(f"Unknown encoder type: {encoder_type}") state_mask_arr = create_state_mask(state_mask) - print(f"state_mask: {state_mask} {state_mask_arr}") + print(f"state_mask: {state_mask} {state_mask_arr.astype(jnp.int32)}") encoder_def = EncodingWrapper( encoder=encoders, use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, - proprio_latent_dim=proprio_latent_dim, + # proprio_latent_dim=proprio_latent_dim, state_mask=state_mask_arr ) diff --git a/serl_launcher/serl_launcher/common/evaluation.py b/serl_launcher/serl_launcher/common/evaluation.py index 7bde12a0..8c0ab538 100644 --- a/serl_launcher/serl_launcher/common/evaluation.py +++ b/serl_launcher/serl_launcher/common/evaluation.py @@ -54,6 +54,7 @@ def evaluate(policy_fn, env: gym.Env, num_episodes: int) -> Dict[str, float]: done = False while not done: action = policy_fn(observation) + action = np.asarray(jax.device_get(action)) observation, _, terminated, truncated, info = env.step(action) done = terminated or truncated add_to(stats, flatten(info)) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 378e0e22..60a0a902 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -109,7 +109,7 @@ def make_drq_agent( image_keys=("image",), encoder_type="small", state_mask="no_ForceTorque", - proprio_latent_dim=64, + # proprio_latent_dim=64, encoder_kwargs=None ): if encoder_kwargs is None: @@ -122,7 +122,7 @@ def make_drq_agent( encoder_type=encoder_type, use_proprio=True, state_mask=state_mask, - proprio_latent_dim=proprio_latent_dim, + # proprio_latent_dim=proprio_latent_dim, image_keys=image_keys, policy_kwargs=dict( tanh_squash_distribution=True, diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index 03bc3a97..57dfe7c8 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -199,7 +199,6 @@ class ResNetEncoder(nn.Module): norm: str = "group" add_spatial_coordinates: bool = False pooling_method: str = "avg" - # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 use_multiplicative_cond: bool = False num_spatial_blocks: int = 8 @@ -327,7 +326,6 @@ def __call__( class PreTrainedResNetEncoder(nn.Module): rng: PRNGKey = None pooling_method: str = "avg" - # use_spatial_softmax: bool = False softmax_temperature: float = 1.0 num_spatial_blocks: int = 8 num_kp: int = 64 # for Spatial Softmax diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 6747282c..99946ffa 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -179,12 +179,13 @@ def rotate_observation(self, observation, random=False): observation["state"][state][:] = rotate_state(observation["state"][state], self.num_rot_quadrant) # rotate - for image_keys in observation["images"].keys(): - observation["images"][image_keys][:] = np.rot90( - observation["images"][image_keys], - axes=(0, 1), - k=self.num_rot_quadrant - ) + if "images" in observation: + for image_keys in observation["images"].keys(): + observation["images"][image_keys][:] = np.rot90( + observation["images"][image_keys], + axes=(0, 1), + k=self.num_rot_quadrant + ) return observation def rotate_action(self, action): From ef307119cc247d30c307bda1b05a3848867548fb Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 15:56:29 +0200 Subject: [PATCH 300/338] added trajectory save and some minor changes --- examples/robotiq_drq/drq_policy_robotiq.py | 47 +++++++++++++++------- 1 file changed, 33 insertions(+), 14 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index dd62ef8a..89421259 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -69,8 +69,8 @@ "if all the states should be considered, possible: (all, none, no_ForceTorque, gripper, position_gripper)") flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") flags.DEFINE_integer("encoder_bottleneck_dim", 128, "bottleneck dimension of the encoder") -flags.DEFINE_integer("proprio_latent_dim", 64, - "the latent dimension for the state, will be concatenated with encoder bottleneck dim before being passed onward") +# flags.DEFINE_integer("proprio_latent_dim", 64, +# "the latent dimension for the state, will be concatenated with encoder bottleneck dim before being passed onward") flags.DEFINE_multi_string("encoder_kwargs", None, "Encoder kwargs in the form ['dict key', 'dict value']") flags.DEFINE_bool("enable_obs_rotation_wrapper", False, "Whether to enable observation rotation wrapper (train in one quaternion)") @@ -86,7 +86,8 @@ flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") flags.DEFINE_integer("log_period", 10, "Logging period.") -flags.DEFINE_integer("eval_period", 1000, "Evaluation period.") +flags.DEFINE_integer("eval_period", 1000, "Evaluation period in seconds") +flags.DEFINE_integer("eval_n_trajs", 10, "Number of trajectories for evaluation.") # flag to indicate if this is a leaner or a actor flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") @@ -98,8 +99,6 @@ "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") - flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") @@ -164,7 +163,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): # plot_feature_kernel_histogram(agent) plot_conv3d_kernels(agent.state.params) + trajectories = [] for episode in range(FLAGS.eval_n_trajs): + trajectory = [] obs, _ = env.reset() done = False start_time = time.time() @@ -176,16 +177,26 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): actions = np.asarray(jax.device_get(actions)) next_obs, reward, done, truncated, info = env.step(actions) + transition = dict( + observations={"state": obs["state"].copy()}, # do not save voxel grid or images + actions=actions, + next_observations={"state": next_obs["state"].copy()}, + rewards=reward, + masks=1.0 - done, + dones=done, + ) + trajectory.append(transition) obs = next_obs if done: + dt = time.time() - start_time if reward > 50.: - dt = time.time() - start_time time_list.append(dt) print(f"time: {dt}") success_counter += (reward > 50.) print(f"{success_counter}/{episode + 1}") + trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) # if pause event is requested, pause the actor if PAUSE_EVENT_FLAG.is_set(): @@ -201,6 +212,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): print(f"success rate: {success_counter / FLAGS.eval_n_trajs if FLAGS.eval_n_trajs else 0.}") print(f"average time: {np.mean(time_list)}") + with open("trajectories.pkl", "wb") as f: + import pickle + pickle.dump(trajectories, f) return # after done eval, return and exit client = TrainerClient( @@ -219,7 +233,6 @@ def update_params(params): client.recv_network_callback(update_params) obs, _ = env.reset() - last_actions = np.zeros((7,)) # training loop timer = Timer() @@ -264,9 +277,6 @@ def update_params(params): if "intervene_action" in info: actions = info.pop("intervene_action") - # next_obs["state"][:7][:] = actions # add actions to obs (curr_actions) - # reward -= 0.3 * np.sum(np.power(actions - last_actions, 2)) # cave-man like but otherwise too complex - reward = np.asarray(reward, dtype=np.float32) info = np.asarray(info) running_return = running_return * 0.99 + reward @@ -281,7 +291,6 @@ def update_params(params): data_store.insert(transition) obs = next_obs - last_actions = actions if done or truncated: stats = {"train": info} # send stats to the learner to log client.request("send-stats", stats) @@ -294,6 +303,16 @@ def update_params(params): timer.tock("total") + if step % FLAGS.eval_period == 0 and step: + with timer.context("eval"): + evaluate_info = evaluate( + policy_fn=partial(agent.sample_actions, argmax=True), + env=env, + num_episodes=FLAGS.eval_n_trajs, + ) + stats = {"eval": evaluate_info} + client.request("send-stats", stats) + if step % FLAGS.log_period == 0: stats = {"timer": timer.get_average_times()} client.request("send-stats", stats) @@ -481,7 +500,7 @@ def main(_): image_keys=image_keys, encoder_type=FLAGS.encoder_type, state_mask=FLAGS.state_mask, - proprio_latent_dim=FLAGS.proprio_latent_dim, + # proprio_latent_dim=FLAGS.proprio_latent_dim, encoder_kwargs=encoder_kwargs ) @@ -492,7 +511,7 @@ def main(_): ) # print useful info - print_agent_params(agent, image_keys) + # print_agent_params(agent, image_keys) parameter_overview(agent) # plot_conv3d_kernels(agent.state.params) @@ -510,7 +529,7 @@ def create_replay_buffer_and_wandb_logger(): ) # set up wandb and logging wandb_logger = make_wandb_logger( - project="drq_picking", + project="paper_experiments", description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) From a0622f8e4c40c804c0fc3ea3ba8b6be5661a8217 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 15:57:30 +0200 Subject: [PATCH 301/338] IMPORTANT CHANGE: proprio-latent-dim is not used anymore, substantial performance decreases if any Dense Layer is used in EncodingWrapper --- .../serl_launcher/common/encoding.py | 28 +++++++++---------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index ab9a0fba..c11567b2 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -12,8 +12,7 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: none = jnp.zeros_like(all) no_action = all.at[:7].set(False) gripper = none.at[0+7:2+7].set(True) - no_ForceTorque = no_action.at[7+2:7+5].set(False).at[7+11:7+14].set(False) - gripper_Zinfo = gripper.at[7+7].set(True) + no_ForceTorque = all.at[7+2:7+5].set(False).at[7+11:7+14].set(False) action_only = none.at[:7].set(True) masks = dict( all=all, @@ -21,7 +20,8 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: gripper=gripper, position_gripper=gripper.at[5:11].set(True), no_ForceTorque=no_ForceTorque, - gripper_Zinfo=gripper_Zinfo, + no_ForceTorqueAction=jnp.bitwise_and(no_ForceTorque, no_action), + gripper_Zinfo=gripper.at[7+7].set(True), action_only=action_only, ) assert mask_str in masks @@ -41,7 +41,7 @@ class EncodingWrapper(nn.Module): encoder: nn.Module use_proprio: bool state_mask: jnp.ndarray - proprio_latent_dim: int = 64 + # proprio_latent_dim: int = 64 enable_stacking: bool = False image_keys: Iterable[str] = ("image",) @@ -63,11 +63,11 @@ def __call__( state = rearrange(state, "T C -> (T C)") if len(state.shape) == 3: state = rearrange(state, "B T C -> B (T C)") - state = nn.Dense( - self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() - )(state) - state = nn.LayerNorm()(state) - state = nn.tanh(state) + # state = nn.Dense( + # self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() + # )(state) + # state = nn.LayerNorm()(state) + # state = nn.tanh(state) return state encoded = [] @@ -103,11 +103,11 @@ def __call__( encoded = encoded.reshape(-1) if len(state.shape) == 3: state = rearrange(state, "B T C -> B (T C)") - state = nn.Dense( - self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() - )(state) - state = nn.LayerNorm()(state) - state = nn.tanh(state) + # state = nn.Dense( + # self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() + # )(state) + # state = nn.LayerNorm()(state) + # state = nn.tanh(state) encoded = jnp.concatenate([encoded, state], axis=-1) return encoded From 61a80d7810776f5c2547d724ea396c6d407de31e Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:10:43 +0200 Subject: [PATCH 302/338] bash files for the different experiments --- .../experiment_setup/Depth Image/run_actor.sh | 22 +++++++++++++++++ .../Depth Image/run_learner.sh | 24 +++++++++++++++++++ .../ResNet18 greyscale/run_actor.sh | 20 ++++++++++++++++ .../ResNet18 greyscale/run_learner.sh | 22 +++++++++++++++++ .../experiment_setup/ResNet18/run_actor.sh | 22 +++++++++++++++++ .../experiment_setup/ResNet18/run_learner.sh | 24 +++++++++++++++++++ .../experiment_setup/SAC/run_actor.sh | 19 +++++++++++++++ .../experiment_setup/SAC/run_learner.sh | 21 ++++++++++++++++ .../experiment_setup/VoxNet/run_actor.sh | 20 ++++++++++++++++ .../experiment_setup/VoxNet/run_learner.sh | 22 +++++++++++++++++ .../VoxNet_1quat/run_actor.sh | 12 ++++------ .../VoxNet_1quat/run_evaluation.sh | 18 ++++++++++++++ .../VoxNet_1quat/run_learner.sh | 15 ++++++------ .../VoxNet_pretrained/run_actor.sh | 20 ++++++++++++++++ .../VoxNet_pretrained/run_learner.sh | 22 +++++++++++++++++ .../VoxNet_pretrained_1quat/run_actor.sh | 21 ++++++++++++++++ .../VoxNet_pretrained_1quat/run_learner.sh | 23 ++++++++++++++++++ 17 files changed, 332 insertions(+), 15 deletions(-) create mode 100755 examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh create mode 100755 examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh create mode 100755 examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh create mode 100755 examples/robotiq_drq/experiment_setup/SAC/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/SAC/run_learner.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh new file mode 100755 index 00000000..b1608aa5 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="ResNet18" \ + --camera_mode rgb \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_learned_embeddings \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh new file mode 100755 index 00000000..593ea7b4 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh @@ -0,0 +1,24 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="Depth image" \ + --camera_mode depth \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth\ Image/checkpoints \ + --demo_path TODO \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_learned_embeddings \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh new file mode 100755 index 00000000..6ffef1a2 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Depth image" \ + --camera_mode depth \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh new file mode 100755 index 00000000..cd8c8176 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="ResNet18 grayscale" \ + --camera_mode grey \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ + --demo_path TODO \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh new file mode 100755 index 00000000..b1608aa5 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="ResNet18" \ + --camera_mode rgb \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_learned_embeddings \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh new file mode 100755 index 00000000..afe8fee9 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh @@ -0,0 +1,24 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="ResNet18" \ + --camera_mode rgb \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints \ + --demo_path TODO \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_learned_embeddings \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh b/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh new file mode 100755 index 00000000..0cca7e0a --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh @@ -0,0 +1,19 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="SAC no images" \ + --camera_mode none \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 2048 \ + --eval_period 1500 \ + \ + --encoder_type none \ + --state_mask all \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh new file mode 100755 index 00000000..c199b2bc --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh @@ -0,0 +1,21 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="SAC no images" \ + --camera_mode none \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 50000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 2048 \ + --checkpoint_period 10000 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + \ + --encoder_type none \ + --state_mask all \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh new file mode 100755 index 00000000..45969e1e --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env_tests \ + --exp_name="voxnet only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 200 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh new file mode 100755 index 00000000..5baa554c --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env_tests \ + --exp_name="voxnet only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 200 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul29_noforcetorque.pkl \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh index 75af7f27..97974796 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh @@ -3,21 +3,19 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="voxnet only pure 32 16 8" \ + --exp_name="voxnet 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ - --seed 24 \ + --seed 1 \ --max_steps 20000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 2500 \ + --eval_period 1500 \ \ --encoder_type voxnet \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ - --proprio_latent_dim 0 \ - --enable_obs_rotation_wrapper True \ - --enable_obs_rotation_augmentation False \ + --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh new file mode 100644 index 00000000..766e6b01 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh @@ -0,0 +1,18 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env_tests \ + --exp_name="voxnet 1quat" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet only pure 32 16 8 noFT (else all) 0820-12:50"\ + --eval_checkpoint_step 10000 \ + --eval_n_trajs 10 \ + \ + --encoder_type voxnet \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ + --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh index 61ba8218..da310f6a 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh @@ -3,22 +3,21 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="voxnet only pure 32 16 8" \ + --exp_name="voxnet 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ - --seed 24 \ + --seed 1 \ --max_steps 25000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug13_all_1quad.pkl \ + --checkpoint_period 1000 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ \ --encoder_type voxnet \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ - --proprio_latent_dim 0 \ - --enable_obs_rotation_wrapper True \ - --enable_obs_rotation_augmentation False \ + --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh new file mode 100755 index 00000000..c9242daf --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="voxnet" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type voxnet-pretrained \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh new file mode 100755 index 00000000..c3f12a03 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="voxnet" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + \ + --encoder_type voxnet-pretrained \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh new file mode 100755 index 00000000..ec3ee3e8 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh @@ -0,0 +1,21 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="voxnet pretrained only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 1500 \ + \ + --encoder_type voxnet-pretrained \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh new file mode 100755 index 00000000..de220cde --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh @@ -0,0 +1,23 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="voxnet pretrained only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 2500 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + \ + --encoder_type voxnet-pretrained \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ +# --debug From 219b08d22c29b39b6c6b0a54cf5448e12883c914 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:11:12 +0200 Subject: [PATCH 303/338] deactivate evaluation if period==0 --- examples/robotiq_drq/drq_policy_robotiq.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 89421259..e4aab913 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -303,7 +303,7 @@ def update_params(params): timer.tock("total") - if step % FLAGS.eval_period == 0 and step: + if FLAGS.eval_period and step % FLAGS.eval_period == 0 and step: with timer.context("eval"): evaluate_info = evaluate( policy_fn=partial(agent.sample_actions, argmax=True), From db3cdfd5c59545a5c9571626f416eb9ed5b7139b Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:47:16 +0200 Subject: [PATCH 304/338] created demos for the experiment (rgb, depth and pointcloud) --- .../robotiq_drq/experiment_setup/Depth Image/run_learner.sh | 2 +- .../experiment_setup/ResNet18 greyscale/run_learner.sh | 2 +- examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh | 2 +- examples/robotiq_drq/experiment_setup/SAC/run_learner.sh | 2 +- examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh | 2 +- .../experiment_setup/VoxNet_1quat/run_evaluation.sh | 2 +- .../robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh | 2 +- .../experiment_setup/VoxNet_pretrained/run_learner.sh | 2 +- .../experiment_setup/VoxNet_pretrained_1quat/run_learner.sh | 2 +- serl_robot_infra/robotiq_env/envs/camera_env/config.py | 2 +- serl_robot_infra/robotiq_env/envs/wrappers.py | 4 ++-- 11 files changed, 12 insertions(+), 12 deletions(-) diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh index 593ea7b4..3340e611 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth\ Image/checkpoints \ - --demo_path TODO \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh index cd8c8176..0582123a 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ - --demo_path TODO \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh index afe8fee9..8601f09c 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints \ - --demo_path TODO \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh index c199b2bc..a75777a2 100755 --- a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 2048 \ --checkpoint_period 10000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type none \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh index 5baa554c..5770a724 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_jul29_noforcetorque.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet \ --state_mask none \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh index 766e6b01..2c53aef3 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh @@ -7,7 +7,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet only pure 32 16 8 noFT (else all) 0820-12:50"\ + --checkpoint_path ""\ --eval_checkpoint_step 10000 \ --eval_n_trajs 10 \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh index da310f6a..f21c5604 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh index c3f12a03..1ce7f2d9 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet-pretrained \ --state_mask none \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh index de220cde..471b20e3 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh @@ -14,7 +14,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug15_1quat_action7.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet-pretrained \ --state_mask none \ diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index c6254dd0..07466b72 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -69,7 +69,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes [0.4391, - 1.5926, 2.3356, - 2.3129, - 1.5668, - 1.1115], [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) - RANDOM_RESET = False + RANDOM_RESET = True RANDOM_XY_RANGE = (0.0,) RANDOM_ROT_RANGE = (0.04,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 0.2]) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 99946ffa..65d63cc8 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -23,7 +23,7 @@ def __init__(self, env, gripper_action_span=3): self.left = np.array([False] * gripper_action_span, dtype=np.bool_) self.right = self.left.copy() - self.invert_axes = [-1, -1, 1, 1, 1, -1] + self.invert_axes = [-1, -1, 1, -1, -1, 1] self.deadspace = 0.15 def action(self, action: np.ndarray) -> np.ndarray: @@ -78,7 +78,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: action[:3] = z_rot.apply(action[:3]) # z rotation invariant translation # TODO add tcp orientation to the equation (extract z rotation from tcp pose) - action[3:6] = z_rot.inv().apply(action[3:6]) # z rotation invariant rotation + action[3:6] = z_rot.apply(action[3:6]) # z rotation invariant rotation return action From 75d9466f3d8669e2f71327b1600da271b353b038 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:55:01 +0200 Subject: [PATCH 305/338] cleaned some inconsistencies and created policy with only VoxNet --- .../experiment_setup/Depth Image/run_actor.sh | 4 ++-- .../Depth Image/run_learner.sh | 2 +- .../ResNet18 greyscale/run_actor.sh | 4 ++-- .../ResNet18 greyscale/run_learner.sh | 2 +- .../experiment_setup/ResNet18/run_actor.sh | 2 +- .../experiment_setup/ResNet18/run_learner.sh | 2 +- .../experiment_setup/SAC/run_actor.sh | 2 +- .../experiment_setup/VoxNet/run_actor.sh | 8 +++---- .../experiment_setup/VoxNet/run_learner.sh | 8 +++---- .../VoxNet_1quat/run_actor.sh | 2 +- .../VoxNet_only_1quat/run_actor.sh | 21 +++++++++++++++++ .../VoxNet_only_1quat/run_learner.sh | 23 +++++++++++++++++++ .../VoxNet_pretrained/run_actor.sh | 4 ++-- .../VoxNet_pretrained/run_learner.sh | 2 +- .../VoxNet_pretrained_1quat/run_actor.sh | 4 ++-- .../VoxNet_pretrained_1quat/run_learner.sh | 2 +- 16 files changed, 68 insertions(+), 24 deletions(-) create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh index b1608aa5..60c1b217 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh @@ -4,7 +4,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --actor \ --env robotiq_camera_env \ --exp_name="ResNet18" \ - --camera_mode rgb \ + --camera_mode depth \ --max_traj_length 100 \ --seed 1 \ --max_steps 20000 \ @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh index 3340e611..e9c01193 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh @@ -7,7 +7,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --camera_mode depth \ --max_traj_length 100 \ --seed 1 \ - --max_steps 20000 \ + --max_steps 25000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh index 6ffef1a2..6fd6d4ba 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh @@ -4,7 +4,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --actor \ --env robotiq_camera_env \ --exp_name="Depth image" \ - --camera_mode depth \ + --camera_mode grey \ --max_traj_length 100 \ --seed 1 \ --max_steps 20000 \ @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh index 0582123a..d6f61d8a 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh @@ -7,7 +7,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --camera_mode grey \ --max_traj_length 100 \ --seed 1 \ - --max_steps 20000 \ + --max_steps 25000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh index b1608aa5..0589e17c 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh index 8601f09c..2f2ff28c 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh @@ -7,7 +7,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ - --max_steps 20000 \ + --max_steps 25000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh b/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh index 0cca7e0a..ad7b8de2 100755 --- a/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 2048 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type none \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh index 45969e1e..88f1f5ae 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh @@ -2,19 +2,19 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env_tests \ + --env robotiq_camera_env \ --exp_name="voxnet only" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ --max_steps 20000 \ --random_steps 0 \ - --training_starts 200 \ + --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type voxnet \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh index 5770a724..451fb7dc 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh @@ -2,14 +2,14 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ - --env robotiq_camera_env_tests \ + --env robotiq_camera_env \ --exp_name="voxnet only" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ - --max_steps 25000 \ + --max_steps 20000 \ --random_steps 0 \ - --training_starts 200 \ + --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 2500 \ @@ -17,6 +17,6 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh index 97974796..ace5e042 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type voxnet \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh new file mode 100755 index 00000000..9065adeb --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh @@ -0,0 +1,21 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="voxnet only 1quat" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 0 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh new file mode 100755 index 00000000..6384240c --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh @@ -0,0 +1,23 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="voxnet only 1quat" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 1000 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh index c9242daf..a1ec48fc 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh @@ -12,9 +12,9 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type voxnet-pretrained \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh index 1ce7f2d9..fa3229b4 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -17,6 +17,6 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet-pretrained \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh index ec3ee3e8..330f0d7b 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh @@ -12,10 +12,10 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 1500 \ + --eval_period 0 \ \ --encoder_type voxnet-pretrained \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh index 471b20e3..e6f53610 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh @@ -17,7 +17,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet-pretrained \ - --state_mask none \ + --state_mask all \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ # --debug From b17855d679d2f5d63294c9ae827e823f16449bef Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:55:58 +0200 Subject: [PATCH 306/338] name change --- examples/robotiq_drq/record_demo.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/robotiq_drq/record_demo.py b/examples/robotiq_drq/record_demo.py index 2dc1a9a6..de73dc99 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/robotiq_drq/record_demo.py @@ -61,7 +61,7 @@ def on_esc(key): listener_2.start() uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") - file_name = f"pcb_insert_{success_needed}_demos_{uuid}.pkl" + file_name = f"box_picking_{success_needed}_demos_{uuid}.pkl" file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script file_path = os.path.join(file_dir, file_name) From b6f1dfb389a0034ff14e7b2ac92c49879ad4628f Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 20 Aug 2024 16:58:00 +0200 Subject: [PATCH 307/338] change costs to be positive (better plots) --- .../envs/camera_env/robotiq_camera_env.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index da18959e..136f41f5 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -32,14 +32,14 @@ def compute_reward(self, obs, action) -> float: ) cost_info = dict( - action_cost=-action_cost, - step_cost=-step_cost, + action_cost=action_cost, + step_cost=step_cost, suction_reward=suction_reward, - suction_cost=-suction_cost, - orientation_cost=-orientation_cost, - position_cost=-position_cost, + suction_cost=suction_cost, + orientation_cost=orientation_cost, + position_cost=position_cost, action_diff_cost=action_diff_cost, - total_cost=-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost - action_diff_cost + total_cost=-(-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost - action_diff_cost) ) for key, info in cost_info.items(): self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) From 52b10884d224e89659c55ff1d81957bcfccd044c Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 22 Aug 2024 17:03:04 +0200 Subject: [PATCH 308/338] implemented behavior tree and behavioral cloning --- examples/robotiq_bc/bc_policy_robotiq.py | 18 ++-- .../experiment_setup/BC/run_rbc_actor.sh | 13 +++ .../experiment_setup/BC/run_rbc_learner.sh | 13 +++ .../experiment_setup/BT/BehaviorTree.py | 87 ++++++++++++++++++ .../experiment_setup/BT/bt_policy.py | 91 +++++++++++++++++++ .../experiment_setup/BT/run_bt_actor.sh | 8 ++ 6 files changed, 221 insertions(+), 9 deletions(-) create mode 100644 examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh create mode 100644 examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh create mode 100644 examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py create mode 100644 examples/robotiq_drq/experiment_setup/BT/bt_policy.py create mode 100644 examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index 4cb12442..bd346a11 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -27,9 +27,7 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.networks.reward_classifier import load_classifier_func -# from franka_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper - +from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from robotiq_env.envs.relative_env import RelativeFrame import robotiq_env @@ -49,6 +47,7 @@ flags.DEFINE_multi_string("demo_paths", None, "paths to demos") flags.DEFINE_string("checkpoint_path", None, "Path to save checkpoints.") +flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") flags.DEFINE_integer( "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" @@ -74,14 +73,15 @@ def main(_): rng = jax.random.PRNGKey(FLAGS.seed) # create env and load dataset - print(FLAGS.env) env = gym.make( FLAGS.env, fake_env=not FLAGS.eval_checkpoint_step, + camera_mode="none", + max_episode_length=100, ) - env = SpacemouseIntervention(env) + # env = SpacemouseIntervention(env) env = RelativeFrame(env) - env = Quat2EulerWrapper(env) + env = Quat2MrpWrapper(env) env = SerlObsWrapperNoImages(env) # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) env = RecordEpisodeStatistics(env) @@ -94,7 +94,7 @@ def main(_): ) wandb_logger = make_wandb_logger( - project="real-world-rl", + project="paper_experiments", # TODO only temporary description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) @@ -128,11 +128,11 @@ def main(_): agent, info = agent.update(batch) wandb_logger.log(info, step=step) - if (step + 1) % 10000 == 0 and FLAGS.save_model: + if step and step % FLAGS.checkpoint_period == 0 and FLAGS.save_model: checkpoints.save_checkpoint( FLAGS.checkpoint_path, agent.state, - step=step + 1, + step=step, keep=100, overwrite=True, ) diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh new file mode 100644 index 00000000..69ddbd07 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +which python && \ +python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ + --env robotiq_camera_env \ + --exp_name=bc_robotiq_policy \ + --seed 1 \ + --max_traj_length 100 \ + --batch_size 2048 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ + --eval_checkpoint_step 20000 \ + --eval_n_trajs 20 \ + --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh b/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh new file mode 100644 index 00000000..e986e783 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ + --env robotiq_camera_env \ + --exp_name=bc_robotiq_policy \ + --seed 1 \ + --batch_size 2048 \ + --max_steps 25000 \ + --demo_paths /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_state_only.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ + --checkpoint_period 1000 \ + --eval_checkpoint_step 0 \ +# --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py b/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py new file mode 100644 index 00000000..bec70681 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py @@ -0,0 +1,87 @@ +import numpy as np +from queue import Queue + + +class TreeState(): + def __init__(self): + self.down = np.array([0., 0., 1., 0., 0., 0., 0.]) + self.up = -self.down + self.suck = np.array([0., 0., 1., 0., 0., 0., 1.]) + self.random_direction = np.zeros_like(self.down) + self.random_orientation = np.zeros_like(self.down) + self.re_sample() + + self.current = np.zeros_like(self.down) + + def re_sample(self): + rand = np.random.rand(2, 2) - 0.5 + self.random_direction[1:3] = rand[0] / np.linalg.norm(rand[0]) + self.random_orientation[4:6] = rand[1] / np.linalg.norm(rand[1]) + + def reset(self): + self.current = self.down + + def __call__(self, *args, **kwargs): + return self.current.copy() + + +class BehaviorTree(): + """ + simple behavior tree for picking boxes + + start: move down + if force in z: suck + if not successful: + maybe orientation rot before? (test) + move up, random direction xy, goto start + if successful: + move up, wait for end + """ + + def __init__(self): + self.tree_state: TreeState = TreeState() + self.queue = Queue() + + def reset(self): + self.tree_state.reset() + print("down") + return self.tree_state() + + def sample_actions(self, observations): + obs = observations["state"].reshape(-1) + if not self.queue.empty(): + return self.queue.get() + + if obs[8] > 0.5: + if np.all(self.tree_state.current == self.tree_state.up): + pass + else: + print("go up") + self.tree_state.current = self.tree_state.up + + elif obs[11] < -3.: # force check + if obs[8] < -0.5: # if sucking + print("do random direction") + return self._fill_random_xy_queue() + else: + print("suck") + self.tree_state.current = self.tree_state.suck + return self._fill_suck_queue() + else: + self.tree_state.reset() + + return self.tree_state() + + def _fill_random_xy_queue(self): + for _ in range(4): + self.queue.put(self.tree_state.up) + self.tree_state.re_sample() + for _ in range(6): + self.queue.put(self.tree_state.random_direction) + + return self.queue.get() + + def _fill_suck_queue(self): + for _ in range(3): + self.queue.put(self.tree_state.suck) + return self.queue.get() diff --git a/examples/robotiq_drq/experiment_setup/BT/bt_policy.py b/examples/robotiq_drq/experiment_setup/BT/bt_policy.py new file mode 100644 index 00000000..ec2901c2 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/BT/bt_policy.py @@ -0,0 +1,91 @@ +import numpy as np +from BehaviorTree import BehaviorTree + +import copy +import time +from functools import partial +import jax +import jax.numpy as jnp +import numpy as np +import pynput +import threading +import tqdm +from absl import app, flags +from flax.training import checkpoints +from datetime import datetime + +import gymnasium as gym +from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics + +from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper +from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper +from robotiq_env.envs.relative_env import RelativeFrame +from robotiq_env.envs.wrappers import Quat2MrpWrapper, ObservationRotationWrapper + +import robotiq_env + +FLAGS = flags.FLAGS + +flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("exp_name", "BT agent", "Name of the experiment for wandb logging.") +flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") +flags.DEFINE_integer("eval_n_trajs", 10, "Number of trajectories for evaluation.") + + +def main(_): + env = gym.make( + FLAGS.env, + camera_mode="none", + fake_env=False, + max_episode_length=FLAGS.max_traj_length, + ) + env = RelativeFrame(env) + env = Quat2MrpWrapper(env) + env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) + env = ObservationStatisticsWrapper(env) + env = SERLObsWrapper(env) + env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) + env = RecordEpisodeStatistics(env) + + agent = BehaviorTree() + + success_counter = 0 + time_list = [] + trajectories = [] + for episode in range(FLAGS.eval_n_trajs): + trajectory = [] + obs, _ = env.reset() + agent.reset() + done = False + start_time = time.time() + while not done: + actions = agent.sample_actions( + observations=obs + ) + + next_obs, reward, done, truncated, info = env.step(actions) + transition = dict( + observations={"state": obs["state"].copy()}, # do not save voxel grid or images + actions=actions, + next_observations={"state": next_obs["state"].copy()}, + rewards=reward, + masks=1.0 - done, + dones=done, + ) + trajectory.append(transition) + obs = next_obs + + if done: + dt = time.time() - start_time + if reward > 50.: + time_list.append(dt) + print(f"time: {dt}") + + success_counter += (reward > 50.) + print(f"{success_counter}/{episode + 1}") + trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) + + +if __name__ == "__main__": + app.run(main) \ No newline at end of file diff --git a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh new file mode 100644 index 00000000..bcaee42f --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh @@ -0,0 +1,8 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +which python && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BT/bt_policy.py "$@" \ + --env robotiq_camera_env \ + --exp_name=bt_robotiq_policy \ + --max_traj_length 100 \ + --eval_n_trajs 20 \ From b41fb04aa1529585f85e3d1cd547e20c419e77a5 Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 22 Aug 2024 17:03:33 +0200 Subject: [PATCH 309/338] new runfiles for the experiment --- .../experiment_setup/Depth Image/run_actor.sh | 7 +++--- .../Depth Image/run_learner.sh | 7 +++--- .../experiment_setup/ResNet10/run_actor.sh | 23 +++++++++++++++++ .../experiment_setup/ResNet10/run_learner.sh | 25 +++++++++++++++++++ .../ResNet18 greyscale/run_actor.sh | 7 ++++-- .../ResNet18 greyscale/run_learner.sh | 9 ++++--- .../experiment_setup/ResNet18/run_actor.sh | 7 +++--- .../ResNet18/run_evaluation.sh | 20 +++++++++++++++ .../experiment_setup/ResNet18/run_learner.sh | 9 ++++--- .../experiment_setup/SAC/run_learner.sh | 2 +- .../experiment_setup/VoxNet/run_actor.sh | 2 +- .../experiment_setup/VoxNet/run_learner.sh | 4 +-- .../experiment_setup/VoxNet_only/run_actor.sh | 20 +++++++++++++++ .../VoxNet_only/run_learner.sh | 22 ++++++++++++++++ .../VoxNet_pretrained/run_actor.sh | 2 +- .../VoxNet_pretrained/run_learner.sh | 4 +-- 16 files changed, 145 insertions(+), 25 deletions(-) create mode 100755 examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh create mode 100644 examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh create mode 100755 examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh index 60c1b217..78a4cd8d 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="ResNet18" \ + --exp_name="Depth Image" \ --camera_mode depth \ --max_traj_length 100 \ --seed 1 \ @@ -16,7 +16,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_learned_embeddings \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh index e9c01193..d0dced3f 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh @@ -12,13 +12,14 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth\ Image/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_learned_embeddings \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh new file mode 100755 index 00000000..76f1d6fb --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh @@ -0,0 +1,23 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="ResNet10 one cam" \ + --camera_mode rgb \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 0 \ + \ + --encoder_type resnet-pretrained \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh new file mode 100755 index 00000000..3a91346b --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh @@ -0,0 +1,25 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="ResNet10 one cam" \ + --camera_mode rgb \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 1000 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet10/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + \ + --encoder_type resnet-pretrained \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh index 6fd6d4ba..f167612e 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="Depth image" \ + --exp_name="ResNet18 greyscale" \ --camera_mode grey \ --max_traj_length 100 \ --seed 1 \ @@ -16,5 +16,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh index d6f61d8a..9a92bce1 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="ResNet18 grayscale" \ + --exp_name="ResNet18 greyscale" \ --camera_mode grey \ --max_traj_length 100 \ --seed 1 \ @@ -12,11 +12,14 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh index 0589e17c..8fb78a5f 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="ResNet18" \ + --exp_name="ResNet18 SSAM128" \ --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ @@ -16,7 +16,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_learned_embeddings \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh new file mode 100644 index 00000000..741c25ea --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env_tests \ + --exp_name="ResNet18" \ + --camera_mode rgb \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints ResNet18 ssam 128 0820-19:23"\ + --eval_checkpoint_step 12000 \ + --eval_n_trajs 10 \ + \ + --encoder_type resnet-pretrained \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ + --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh index 2f2ff28c..edd863d7 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="ResNet18" \ + --exp_name="ResNet18 SSAM128" \ --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ @@ -12,13 +12,14 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ - --encoder_bottleneck_dim 128 \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_learned_embeddings \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh index a75777a2..3f882456 100755 --- a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 2048 \ - --checkpoint_period 10000 \ + --checkpoint_period 2500 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh index 88f1f5ae..3c45787c 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="voxnet only" \ + --exp_name="Voxnet" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh index 451fb7dc..b692dfac 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="voxnet only" \ + --exp_name="Voxnet" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh new file mode 100755 index 00000000..4ab5e4d1 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="voxnet only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 20000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --eval_period 0 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh new file mode 100755 index 00000000..a9ad8f49 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh @@ -0,0 +1,22 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --learner \ + --env robotiq_camera_env \ + --exp_name="voxnet only" \ + --camera_mode pointcloud \ + --max_traj_length 100 \ + --seed 1 \ + --max_steps 25000 \ + --random_steps 0 \ + --training_starts 500 \ + --utd_ratio 8 \ + --batch_size 128 \ + --checkpoint_period 1000 \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh index a1ec48fc..5e9c3ce6 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="voxnet" \ + --exp_name="voxnet pretrained" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh index fa3229b4..7d04a7b3 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="voxnet" \ + --exp_name="voxnet pretrained" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ From 9e95f4c7acd9a3d5bdf798e18835df11657c383b Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 22 Aug 2024 17:03:47 +0200 Subject: [PATCH 310/338] encoder kwargs bugfix --- examples/robotiq_drq/drq_policy_robotiq.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index e4aab913..db523a70 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -493,6 +493,8 @@ def main(_): "bottleneck_dim": FLAGS.encoder_bottleneck_dim, **(dict(zip(*[iter(FLAGS.encoder_kwargs)] * 2)) if FLAGS.encoder_kwargs else {}), } + encoder_kwargs = {k: (int(v) if str(v).isdigit() else v) for k, v in encoder_kwargs.items()} + agent: DrQAgent = make_drq_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), @@ -511,7 +513,7 @@ def main(_): ) # print useful info - # print_agent_params(agent, image_keys) + print_agent_params(agent, image_keys) parameter_overview(agent) # plot_conv3d_kernels(agent.state.params) From 12fead729b2e61bf805df08fd14e80f77779eccf Mon Sep 17 00:00:00 2001 From: nisutte Date: Thu, 22 Aug 2024 19:25:33 +0200 Subject: [PATCH 311/338] wrong name in config file --- .../experiment_setup/VoxNet_pretrained_1quat/run_actor.sh | 2 +- .../experiment_setup/VoxNet_pretrained_1quat/run_learner.sh | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh index 330f0d7b..7b3db828 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="voxnet pretrained only" \ + --exp_name="voxnet pretrained 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh index e6f53610..4de78e24 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="voxnet pretrained only" \ + --exp_name="voxnet pretrained 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ @@ -12,7 +12,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --checkpoint_period 2500 \ + --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ From b1c4dbc9ee9c5449ec55a94d9dd5a3368eb595d7 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 11:31:32 +0200 Subject: [PATCH 312/338] cleanup --- .../serl_launcher/utils/numpy_utils.py | 33 ------------------- 1 file changed, 33 deletions(-) delete mode 100644 serl_launcher/serl_launcher/utils/numpy_utils.py diff --git a/serl_launcher/serl_launcher/utils/numpy_utils.py b/serl_launcher/serl_launcher/utils/numpy_utils.py deleted file mode 100644 index 15a79094..00000000 --- a/serl_launcher/serl_launcher/utils/numpy_utils.py +++ /dev/null @@ -1,33 +0,0 @@ -import numpy as np -import jax.numpy as jnp - -""" -numpy uses uint8 to save a boolean array, so it is really inefficient. -with this simple conversion, we increase the efficiency by 8 fold. -""" - - -def bool_2_int8(array: np.ndarray) -> np.ndarray: - # from bool (x, y, z) to uint8 (x, y, z/8) - assert array.shape[-1] % 8 == 0 - return np.dot(array.reshape((*array.shape[:-1], array.shape[-1] // 8, 8)), 2 ** np.arange(8)).astype(np.uint8) - - -def int8_2_bool(array: np.ndarray) -> np.ndarray: - bool_arr = np.zeros((*array.shape[:], 8)).astype(np.bool_) - for i in range(8): - bool_arr[..., i] = np.bitwise_and(np.right_shift(array, i), 0x1) - return bool_arr.reshape(*array.shape[:-1], array.shape[-1] * 8) - - -def int8_2_bool_jnp(array: jnp.ndarray) -> jnp.ndarray: - bool_arr = [] - for i in range(8): - bool_arr.append(jnp.bitwise_and(jnp.right_shift(array, i), 0x1)) - bool_arr = jnp.stack(bool_arr, axis=-1) - return bool_arr.reshape(*array.shape[:-1], array.shape[-1] * 8) - - -def bool_2_int8_jnp(array: jnp.ndarray) -> jnp.ndarray: - assert array.shape[-1] % 8 == 0 - return jnp.dot(array.reshape((*array.shape[:-1], array.shape[-1] // 8, 8)), 2 ** np.arange(8)).astype(np.uint8) From 0c08a19bcb4f7110ffac3e8f241f2c4ec729e4cc Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 11:32:28 +0200 Subject: [PATCH 313/338] implemented Temporal Action Ensemble for smoother action sequences in the evaluation --- examples/robotiq_drq/drq_policy_robotiq.py | 15 +++++++---- .../serl_launcher/utils/sampling_utils.py | 27 +++++++++++++++++++ 2 files changed, 37 insertions(+), 5 deletions(-) create mode 100644 serl_launcher/serl_launcher/utils/sampling_utils.py diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index db523a70..54887bab 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -19,6 +19,7 @@ from serl_launcher.common.evaluation import evaluate from serl_launcher.utils.timer_utils import Timer from serl_launcher.wrappers.chunking import ChunkingWrapper +from serl_launcher.utils.sampling_utils import TemporalActionEnsemble from serl_launcher.utils.train_utils import ( print_agent_params, parameter_overview, @@ -76,6 +77,8 @@ "Whether to enable observation rotation wrapper (train in one quaternion)") flags.DEFINE_bool("enable_obs_rotation_augmentation", False, "Whether to enable observation rotation augmentation (90 deg)") +flags.DEFINE_bool("enable_temporal_ensemble_sampling", False, + "Whether to enable sampling the action from a temporal ensemble: action = 0.5*a0 + 0.3*a-1 + 0.2*a-2 + 0.1*a-3") flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") flags.DEFINE_integer("replay_buffer_capacity", 10000, @@ -156,6 +159,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): ) agent = agent.replace(state=ckpt) find_zero_weights(agent.state.params, print_all=False) + action_ensemble = TemporalActionEnsemble(activated=FLAGS.enable_temporal_ensemble_sampling) # examine model parameters if trajs==0 if FLAGS.eval_n_trajs == 0: @@ -169,17 +173,18 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): obs, _ = env.reset() done = False start_time = time.time() + action_ensemble.reset() while not done: actions = agent.sample_actions( observations=jax.device_put(obs), argmax=True, ) - actions = np.asarray(jax.device_get(actions)) - next_obs, reward, done, truncated, info = env.step(actions) + ensembled_action = action_ensemble.sample(actions) + next_obs, reward, done, truncated, info = env.step(ensembled_action) transition = dict( - observations={"state": obs["state"].copy()}, # do not save voxel grid or images - actions=actions, + observations={"state": obs["state"].copy()}, # do not save voxel grid or images + actions=ensembled_action, next_observations={"state": next_obs["state"].copy()}, rewards=reward, masks=1.0 - done, @@ -449,7 +454,7 @@ def stats_callback(type: str, payload: dict) -> dict: break server.stop() - parameter_overview(agent) # print end state + parameter_overview(agent) # print end state ############################################################################## diff --git a/serl_launcher/serl_launcher/utils/sampling_utils.py b/serl_launcher/serl_launcher/utils/sampling_utils.py new file mode 100644 index 00000000..7ce0f16a --- /dev/null +++ b/serl_launcher/serl_launcher/utils/sampling_utils.py @@ -0,0 +1,27 @@ +import numpy as np + + +class TemporalActionEnsemble: + def __init__(self, activated=True, action_shape=(7,), ensemble=None): + if ensemble is None: + ensemble = [0.5, 0.3, 0.2, 0.1] + self.activated = activated + self.ensemble = np.asarray(ensemble) + self.buffer = np.zeros((len(ensemble), action_shape)) + + if activated: + print(f"Temporal Action Ensemble enabled: {self.ensemble}") + + def reset(self): + self.buffer[...] = 0. + + def sample(self, curr_action: np.ndarray): + if not self.activated: + return curr_action + + curr_action = curr_action.reshape(-1) + assert curr_action == self.buffer.shape[1] + + self.buffer = np.roll(self.buffer, axis=0, shift=1) + self.buffer[0, :] = curr_action + return np.dot(self.ensemble, self.buffer) From 8dab130a4710c292b5696a7c2191020e99dd0048 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 15:26:52 +0200 Subject: [PATCH 314/338] added evaluation bash files --- .../Depth Image/run_evaluation.sh | 20 +++++++++++++++++++ .../ResNet10/run_evaluation.sh | 20 +++++++++++++++++++ .../ResNet18 greyscale/run_evaluation.sh | 20 +++++++++++++++++++ .../ResNet18/run_evaluation.sh | 10 +++++----- .../experiment_setup/SAC/run_evaluation.sh | 16 +++++++++++++++ .../experiment_setup/VoxNet/run_evaluation.sh | 17 ++++++++++++++++ .../VoxNet_1quat/run_evaluation.sh | 12 +++++------ .../VoxNet_only/run_evaluation.sh | 17 ++++++++++++++++ .../VoxNet_only/run_learner.sh | 2 +- .../VoxNet_only_1quat/run_evaluation.sh | 17 ++++++++++++++++ .../VoxNet_pretrained/run_evaluation.sh | 17 ++++++++++++++++ .../VoxNet_pretrained_1quat/run_evaluation.sh | 18 +++++++++++++++++ 12 files changed, 174 insertions(+), 12 deletions(-) create mode 100644 examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh new file mode 100644 index 00000000..33c1788c --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Depth Image Evaluation" \ + --camera_mode depth \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth Image/checkpoints Depth image 0821-15:14"\ + --eval_checkpoint_step 8000 \ + --eval_n_trajs 30 \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh new file mode 100644 index 00000000..27321d73 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="ResNet10 Evaluation" \ + --camera_mode rgb \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet10/checkpoints ResNet10 one cam 0821-11:18"\ + --eval_checkpoint_step 15000 \ + --eval_n_trajs 30 \ + \ + --encoder_type resnet-pretrained \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh new file mode 100644 index 00000000..597fddea --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh @@ -0,0 +1,20 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="ResNet18 greyscale Evaluation" \ + --camera_mode grey \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/checkpoints ResNet18 greyscale 0821-14:23"\ + --eval_checkpoint_step 11000 \ + --eval_n_trajs 30 \ + \ + --encoder_type resnet-pretrained-18 \ + --state_mask all \ + --encoder_kwargs pooling_method \ + --encoder_kwargs spatial_softmax \ + --encoder_kwargs num_kp \ + --encoder_kwargs 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh index 741c25ea..68fe8a16 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh @@ -2,19 +2,19 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env_tests \ - --exp_name="ResNet18" \ + --env robotiq_camera_env \ + --exp_name="ResNet18 Evaluation" \ --camera_mode rgb \ --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints ResNet18 ssam 128 0820-19:23"\ --eval_checkpoint_step 12000 \ - --eval_n_trajs 10 \ + --eval_n_trajs 30 \ \ - --encoder_type resnet-pretrained \ + --encoder_type resnet-pretrained-18 \ --state_mask all \ --encoder_kwargs pooling_method \ --encoder_kwargs spatial_softmax \ --encoder_kwargs num_kp \ --encoder_kwargs 128 \ - --debug +# --debug diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh new file mode 100644 index 00000000..44ba1cd4 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh @@ -0,0 +1,16 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="SAC no images Evaluation" \ + --camera_mode none \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints SAC no images 0820-17:01"\ + --eval_checkpoint_step 40000 \ + --eval_n_trajs 30 \ + \ + --encoder_type none \ + --state_mask all \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh new file mode 100644 index 00000000..d16cbe34 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh @@ -0,0 +1,17 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Voxnet Evaluation" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints Voxnet 0821-16:06"\ + --eval_checkpoint_step 11000 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh index 2c53aef3..84620543 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh @@ -2,17 +2,17 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env_tests \ - --exp_name="voxnet 1quat" \ + --env robotiq_camera_env \ + --exp_name="Voxnet 1quat Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path ""\ - --eval_checkpoint_step 10000 \ - --eval_n_trajs 10 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet 1quat 0822-17:54"\ + --eval_checkpoint_step 19000 \ + --eval_n_trajs 30 \ \ --encoder_type voxnet \ --state_mask all \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ - --debug +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh new file mode 100644 index 00000000..7ba08857 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh @@ -0,0 +1,17 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Voxnet only Evaluation" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only/checkpoints voxnet only 0822-13:43"\ + --eval_checkpoint_step 14000 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh index a9ad8f49..f8e62940 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh @@ -13,7 +13,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/checkpoints \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh new file mode 100644 index 00000000..a9b1dd3f --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh @@ -0,0 +1,17 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Voxnet only 1quat Evaluation" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path ""\ + --eval_checkpoint_step 0 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet \ + --state_mask none \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh new file mode 100644 index 00000000..e039be34 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh @@ -0,0 +1,17 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Voxnet Pretrained Evaluation" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ + --eval_checkpoint_step 10000 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet-pretrained \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh new file mode 100644 index 00000000..6aeb5194 --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh @@ -0,0 +1,18 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env \ + --exp_name="Voxnet Pretrained 1quat Evaluation" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ + --eval_checkpoint_step 10000 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet-pretrained \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ +# --debug From 87ec54120a0b985ec2c365324cf1f26f192b9384 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 15:27:41 +0200 Subject: [PATCH 315/338] added wandb evaluation logger for convenience --- examples/robotiq_drq/drq_policy_robotiq.py | 33 ++++++++++++++++------ 1 file changed, 25 insertions(+), 8 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 54887bab..7187ef59 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -149,6 +149,11 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): global PAUSE_EVENT_FLAG if FLAGS.eval_checkpoint_step: + wandb_logger = make_wandb_logger( + project="paper_evaluation", + description=FLAGS.exp_name or FLAGS.env, + debug=FLAGS.debug, + ) success_counter = 0 time_list = [] @@ -163,7 +168,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): # examine model parameters if trajs==0 if FLAGS.eval_n_trajs == 0: - # parameter_overview(agent) + parameter_overview(agent) # plot_feature_kernel_histogram(agent) plot_conv3d_kernels(agent.state.params) @@ -172,36 +177,48 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): trajectory = [] obs, _ = env.reset() done = False - start_time = time.time() action_ensemble.reset() + start_time = time.time() + + running_reward = 0. while not done: actions = agent.sample_actions( observations=jax.device_put(obs), argmax=True, ) - ensembled_action = action_ensemble.sample(actions) + ensembled_action = action_ensemble.sample(actions) # will return actions if not activated next_obs, reward, done, truncated, info = env.step(ensembled_action) transition = dict( - observations={"state": obs["state"].copy()}, # do not save voxel grid or images + observations=obs["state"].copy(), # do not save voxel grid or images actions=ensembled_action, - next_observations={"state": next_obs["state"].copy()}, + next_observations=next_obs["state"].copy(), rewards=reward, masks=1.0 - done, dones=done, ) trajectory.append(transition) obs = next_obs + running_reward += reward if done: + print(f"{success_counter}/{episode + 1} ", end=' ') dt = time.time() - start_time if reward > 50.: time_list.append(dt) - print(f"time: {dt}") + print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") + else: + print("failed!") success_counter += (reward > 50.) - print(f"{success_counter}/{episode + 1}") trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) + infos = { + "running_reward": running_reward, + "time": dt, + "success": float(reward > 50.), + "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() + } + wandb_logger.log(infos, step=episode) # if pause event is requested, pause the actor if PAUSE_EVENT_FLAG.is_set(): @@ -217,7 +234,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): print(f"success rate: {success_counter / FLAGS.eval_n_trajs if FLAGS.eval_n_trajs else 0.}") print(f"average time: {np.mean(time_list)}") - with open("trajectories.pkl", "wb") as f: + with open(f"trajectories {datetime.now().strftime('%d-%m %H%M')}.pkl", "wb") as f: import pickle pickle.dump(trajectories, f) return # after done eval, return and exit From 6d8c167bece5fbf8676c3e9b495e0fd244b367ee Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 15:28:22 +0200 Subject: [PATCH 316/338] bugfixes --- serl_launcher/serl_launcher/utils/sampling_utils.py | 4 ++-- serl_launcher/serl_launcher/utils/train_utils.py | 6 +++++- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 +---- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/sampling_utils.py b/serl_launcher/serl_launcher/utils/sampling_utils.py index 7ce0f16a..ae97e58d 100644 --- a/serl_launcher/serl_launcher/utils/sampling_utils.py +++ b/serl_launcher/serl_launcher/utils/sampling_utils.py @@ -7,7 +7,7 @@ def __init__(self, activated=True, action_shape=(7,), ensemble=None): ensemble = [0.5, 0.3, 0.2, 0.1] self.activated = activated self.ensemble = np.asarray(ensemble) - self.buffer = np.zeros((len(ensemble), action_shape)) + self.buffer = np.zeros((len(ensemble), action_shape[0])) if activated: print(f"Temporal Action Ensemble enabled: {self.ensemble}") @@ -20,7 +20,7 @@ def sample(self, curr_action: np.ndarray): return curr_action curr_action = curr_action.reshape(-1) - assert curr_action == self.buffer.shape[1] + assert curr_action.shape[0] == self.buffer.shape[1] self.buffer = np.roll(self.buffer, axis=0, shift=1) self.buffer[0, :] = curr_action diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 70d83d4b..60a45be5 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -187,7 +187,11 @@ def get_size(params): pretrained_encoder_count = get_size(actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"]) except Exception as e: pretrained_encoder_count = 0 - encoder_count = get_size(actor["encoder"]) + + try: + encoder_count = get_size(actor["encoder"]) + except Exception as e: + encoder_count = 0 actor_count = get_size(actor) critic_count = get_size(critic) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index c394cf65..82d8db50 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -22,8 +22,6 @@ from robotiq_env.utils.real_time_plotter import DataClient from robot_controllers.robotiq_controller import RobotiqImpedanceController -from serl_launcher.utils.numpy_utils import bool_2_int8 - class ImageDisplayer(threading.Thread): def __init__(self, queue): @@ -493,10 +491,9 @@ def get_image(self) -> Dict[str, np.ndarray]: if self.camera_mode in ["pointcloud"]: voxel_grid, voxel_indices = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) - # images["wrist_pointcloud"] = bool_2_int8(voxel_grid) - vs = self.observation_space["images"]["wrist_pointcloud"].shape # downsample on 2x2x2 grid with sum of points (8 as max) + # vs = self.observation_space["images"]["wrist_pointcloud"].shape # voxel_grid = np.sum(np.reshape(voxel_grid, (vs[0], 2, vs[1], 2, vs[2], 2)), axis=(1, 3, 5)) images["wrist_pointcloud"] = voxel_grid.astype(np.uint8) self.displayer.display(voxel_indices) From e1c50a869258bcc02557cf5334f812a715ea6887 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 23 Aug 2024 15:43:31 +0200 Subject: [PATCH 317/338] fix the seed for the evaluation --- serl_robot_infra/robot_controllers/robotiq_controller.py | 9 ++++----- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 3 ++- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/robotiq_controller.py index 5c203f7c..bde06bc7 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/robotiq_controller.py @@ -90,11 +90,10 @@ def start(self): if self.verbose: print(f"[RIC] Controller process spawned at {self.native_id}") - def print(self, msg, probability=1., both=False): - if np.random.random() < probability: - self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') - if both: - print(msg) + def print(self, msg, both=False): + self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') + if both: + print(msg) async def start_robotiq_interfaces(self, gripper=True): self.robotiq_control = RTDEControlInterface(self.robot_ip) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 82d8db50..65699e88 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -116,7 +116,7 @@ def __init__( max_episode_length: int = 100, save_video: bool = False, realtime_plot: bool = False, - camera_mode: str = "rgb", # one of (rgb, grey, depth, both, pointcloud, none) + camera_mode: str = "rgb", # one of (rgb, grey, depth, both(rgb depth), pointcloud, none) ): self.max_episode_length = max_episode_length self.curr_path_length = 0 @@ -139,6 +139,7 @@ def __init__( self.random_xy_range = config.RANDOM_XY_RANGE self.random_rot_range = config.RANDOM_ROT_RANGE self.hz = hz + np.random.seed(1) # fix seed for random initial rotations camera_mode = None if camera_mode.lower() == "none" else camera_mode if camera_mode is not None and save_video: From 82a6c567a6909cef95b3b83a51d402ceb2f1d95b Mon Sep 17 00:00:00 2001 From: nisutte Date: Sat, 24 Aug 2024 15:27:41 +0200 Subject: [PATCH 318/338] preolad bias as well --- serl_launcher/serl_launcher/utils/train_utils.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 60a45be5..cacc0894 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -142,16 +142,18 @@ def load_pretrained_VoxNet_params(agent, image_keys=("pointcloud",)): f"encoder_{image_key}" ] to_replace = { - "conv_5x5x5": "voxnet/conv1/conv3d/kernel:0", - "conv_3x3x3": "voxnet/conv2/conv3d/kernel:0", - "conv_2x2x2": "voxnet/conv3/conv3d/kernel:0" + "conv_5x5x5": "voxnet/conv1/conv3d/", + "conv_3x3x3": "voxnet/conv2/conv3d/", + "conv_2x2x2": "voxnet/conv3/conv3d/" } replaced = [] for key, weights in to_replace.items(): if key in new_encoder_params: shape = new_encoder_params[key]["kernel"].shape new_encoder_params[key]["kernel"] = new_encoder_params[key]["kernel"].at[:].set( - ckpt[weights][..., :shape[-1]]) + ckpt[weights + "kernel:0"][..., :shape[-1]]) + new_encoder_params[key]["bias"] = new_encoder_params[key]["bias"].at[:].set( + ckpt[weights + "bias:0"][:shape[-1]]) replaced.append(f"{key}:{shape}") print(f"replaced {replaced} in {image_key}") From e43788ffce5229c4c208160ff744374bcc20cf96 Mon Sep 17 00:00:00 2001 From: nisutte Date: Sat, 24 Aug 2024 15:28:34 +0200 Subject: [PATCH 319/338] slight changes and bugfixes --- examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh | 4 ++-- examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh | 2 +- .../experiment_setup/VoxNet_only/run_evaluation.sh | 2 +- .../experiment_setup/VoxNet_pretrained/run_evaluation.sh | 2 +- .../VoxNet_pretrained_1quat/run_evaluation.sh | 4 ++-- 5 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh index 69ddbd07..debf80f5 100644 --- a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh +++ b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh @@ -8,6 +8,6 @@ python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$ --max_traj_length 100 \ --batch_size 2048 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ - --eval_checkpoint_step 20000 \ - --eval_n_trajs 20 \ + --eval_checkpoint_step 8000 \ + --eval_n_trajs 30 \ --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh index bcaee42f..cdfb1dc3 100644 --- a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh +++ b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh @@ -5,4 +5,4 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BT/bt --env robotiq_camera_env \ --exp_name=bt_robotiq_policy \ --max_traj_length 100 \ - --eval_n_trajs 20 \ + --eval_n_trajs 30 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh index 7ba08857..90fe4420 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh @@ -8,7 +8,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only/checkpoints voxnet only 0822-13:43"\ - --eval_checkpoint_step 14000 \ + --eval_checkpoint_step 13000 \ --eval_n_trajs 30 \ \ --encoder_type voxnet \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh index e039be34..d1fbd6f7 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh @@ -8,7 +8,7 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ - --eval_checkpoint_step 10000 \ + --eval_checkpoint_step 9000 \ --eval_n_trajs 30 \ \ --encoder_type voxnet-pretrained \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh index 6aeb5194..293440d3 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh @@ -7,8 +7,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ - --eval_checkpoint_step 10000 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints voxnet pretrained 1quat 0823-10:45"\ + --eval_checkpoint_step 13000 \ --eval_n_trajs 30 \ \ --encoder_type voxnet-pretrained \ From 5a2ffdfa18bb38ceb13aa3b08ab267b89f09ba87 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 28 Aug 2024 16:29:51 +0200 Subject: [PATCH 320/338] bugfix --- examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py b/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py index bec70681..fef9c586 100644 --- a/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py +++ b/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py @@ -15,8 +15,8 @@ def __init__(self): def re_sample(self): rand = np.random.rand(2, 2) - 0.5 - self.random_direction[1:3] = rand[0] / np.linalg.norm(rand[0]) - self.random_orientation[4:6] = rand[1] / np.linalg.norm(rand[1]) + self.random_direction[0:2] = rand[0] / np.linalg.norm(rand[0]) + self.random_orientation[3:5] = rand[1] / np.linalg.norm(rand[1]) def reset(self): self.current = self.down From cf851e8613e3e2d4b46338c1f4d6b52381a6d711 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 28 Aug 2024 16:30:35 +0200 Subject: [PATCH 321/338] new config for evaluation on unseen boxes --- serl_robot_infra/robotiq_env/__init__.py | 6 +++++ .../robotiq_env/envs/camera_env/__init__.py | 2 +- .../robotiq_env/envs/camera_env/config.py | 23 ++++++++++++++++--- .../envs/camera_env/robotiq_camera_env.py | 7 +++++- 4 files changed, 33 insertions(+), 5 deletions(-) diff --git a/serl_robot_infra/robotiq_env/__init__.py b/serl_robot_infra/robotiq_env/__init__.py index 7205bc95..1ea4df31 100644 --- a/serl_robot_infra/robotiq_env/__init__.py +++ b/serl_robot_infra/robotiq_env/__init__.py @@ -18,3 +18,9 @@ entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnvTest", max_episode_steps=100, ) + +register( + id="robotiq_camera_env_eval", + entry_point="robotiq_env.envs.camera_env:RobotiqCameraEnvEval", + max_episode_steps=100, +) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py index b29e3c64..771fa11e 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/__init__.py @@ -1 +1 @@ -from robotiq_env.envs.camera_env.robotiq_camera_env import RobotiqCameraEnv, RobotiqCameraEnvTest \ No newline at end of file +from robotiq_env.envs.camera_env.robotiq_camera_env import RobotiqCameraEnv, RobotiqCameraEnvTest, RobotiqCameraEnvEval \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index 07466b72..f5908f89 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -65,7 +65,7 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes [1.472, -0.8583, 1.2817, -1.9934, -1.5655, -0.0869], [1.1117, -0.7666, 1.0792, -1.8871, -1.5639, -0.443], [1.0242, - 1.3104, 2.0986, - 2.358, - 1.5664, - 2.0496], - [0.8757, -1.1028, 1.6058, -2.2458, -1.8081, -0.7877], + [0.8757, -1.1028, 1.6058, -2.2458, -1.8081, -0.7877], [0.4391, - 1.5926, 2.3356, - 2.3129, - 1.5668, - 1.1115], [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) @@ -98,7 +98,24 @@ class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RANDOM_ROT_RANGE = (0.05,) RESET_Q = np.array([ - [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position - # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos + # [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position + [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos # [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box ]) + + +class RobotiqCameraConfigFinalEvaluation(RobotiqCameraConfigFinal): + # config for the evaluation on 5 boxes the policy has never seen + RANDOM_RESET = False + RANDOM_XY_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.05,) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.1, 0.1, 0.3]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.1, -0.1, -0.3]) + + RESET_Q = np.array([ + # [0.4102, -1.304, 1.9315, -2.1707, -1.5583, 2.0127], + # [0.9212, - 0.8757, 1.3325, - 2.0209, - 1.5508, 2.5185], + # [1.2869, - 0.9778, 1.476, - 2.0783, - 1.5458, 2.9585], + # [1.717, -1.1379, 1.7179, -2.4872, -1.4362, 2.5804], + [2.2614, - 1.4378, 2.145, - 2.5039, - 1.7649, 2.2541], + ]) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py index 136f41f5..f49b7e78 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py @@ -2,7 +2,7 @@ from typing import Tuple from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.camera_env.config import RobotiqCameraConfigFinal, RobotiqCameraConfigFinalTests +from robotiq_env.envs.camera_env.config import RobotiqCameraConfigFinal, RobotiqCameraConfigFinalTests, RobotiqCameraConfigFinalEvaluation class RobotiqCameraEnv(RobotiqEnv): @@ -63,3 +63,8 @@ def close(self): class RobotiqCameraEnvTest(RobotiqCameraEnv): def __init__(self, **kwargs): super().__init__(**kwargs, load_config=False, config=RobotiqCameraConfigFinalTests) + + +class RobotiqCameraEnvEval(RobotiqCameraEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, load_config=False, config=RobotiqCameraConfigFinalEvaluation) From ab7fb8c655de7cbbfdd98c96ed3142fa72e95eaa Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 28 Aug 2024 16:30:48 +0200 Subject: [PATCH 322/338] new scale for depth images --- serl_robot_infra/robotiq_env/camera/rs_capture.py | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/serl_robot_infra/robotiq_env/camera/rs_capture.py b/serl_robot_infra/robotiq_env/camera/rs_capture.py index 071463a7..8a60abe7 100644 --- a/serl_robot_infra/robotiq_env/camera/rs_capture.py +++ b/serl_robot_infra/robotiq_env/camera/rs_capture.py @@ -34,14 +34,14 @@ def __init__(self, name, serial_number, dim=(640, 480), fps=15, rgb=True, depth= if self.depth: depth_sensor = self.profile.get_device().first_depth_sensor() depth_scale = depth_sensor.get_depth_scale() - self.max_clipping_distance = 1. / depth_scale # 1m max clipping distance - self.min_clipping_distance = 0.0 / depth_scale # might mess things up + self.max_clipping_distance = 0.2 / depth_scale # 0.15m max clipping distance if self.pointcloud: self.pc = rs.pointcloud() self.threshold_filter = rs.threshold_filter(min_dist=0., max_dist=0.25) - self.decimation_filter = rs.decimation_filter(magnitude=2.) # 2 or 4 - self.temporal_filter = rs.temporal_filter(smooth_alpha=0.53, smooth_delta=24., persistence_control=2) # standard values + self.decimation_filter = rs.decimation_filter(magnitude=2.) # 2 or 4 + self.temporal_filter = rs.temporal_filter(smooth_alpha=0.53, smooth_delta=24., + persistence_control=2) # standard values # for some weird reason, these values have to be set in order for the image to appear with good lightning # for firmware >5.13, auto_exposure False & auto_white_balance True, below only auto_exposure True @@ -77,10 +77,7 @@ def read(self): if depth_frame.is_depth_frame(): depth = np.asanyarray(depth_frame.get_data()) # clip max - depth = np.where((depth > self.max_clipping_distance) | (depth < self.min_clipping_distance), 0., self.max_clipping_distance - depth) - # clip min - # scale = self.max_clipping_distance / (self.max_clipping_distance - self.min_clipping_distance) - # depth *= scale + depth = np.where((depth > self.max_clipping_distance), 0., self.max_clipping_distance - depth) depth = (depth * (256. / self.max_clipping_distance)).astype(np.uint8) depth = depth[..., None] From 64310fd30bf07156db77633168d6b22d5728269a Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 28 Aug 2024 16:32:05 +0200 Subject: [PATCH 323/338] use small encoder for depth images --- .../serl_launcher/agents/continuous/drq.py | 17 +++++++++-------- .../serl_launcher/vision/small_encoders.py | 13 +++++++++++-- 2 files changed, 20 insertions(+), 10 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 1db0d766..983c4b3d 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -153,18 +153,19 @@ def create_drq( if encoder_type == "small": from serl_launcher.vision.small_encoders import SmallEncoder - - encoders = { - image_key: SmallEncoder( - features=(32, 64, 128, 256), + small_encoder = SmallEncoder( + features=(64, 64, 32, 32), kernel_sizes=(3, 3, 3, 3), - strides=(2, 2, 2, 2), + strides=(2, 2, 1, 1), padding="VALID", - pool_method="avg", - bottleneck_dim=256, + pool_method="spatial_learned_embeddings", + bottleneck_dim=128, spatial_block_size=8, - name=f"encoder_{image_key}", + name=f"small_encoder", ) + # use the same encoder + encoders = { + image_key: small_encoder for image_key in image_keys } elif encoder_type == "resnet": diff --git a/serl_launcher/serl_launcher/vision/small_encoders.py b/serl_launcher/serl_launcher/vision/small_encoders.py index 630c7b9a..b120d451 100644 --- a/serl_launcher/serl_launcher/vision/small_encoders.py +++ b/serl_launcher/serl_launcher/vision/small_encoders.py @@ -7,16 +7,17 @@ class SmallEncoder(nn.Module): - features: Sequence[int] = (16, 16, 16) + features: Sequence[int] = (32, 32, 32) kernel_sizes: Sequence[int] = (3, 3, 3) strides: Sequence[int] = (1, 1, 1) padding: Union[Sequence[int], str] = (1, 1, 1) pool_method: str = "spatial_learned_embeddings" bottleneck_dim: Optional[int] = None spatial_block_size: Optional[int] = 8 + num_kp: Optional[int] = 32 @nn.compact - def __call__(self, observations: jnp.ndarray, train=False) -> jnp.ndarray: + def __call__(self, observations: jnp.ndarray, train=False, encode=True) -> jnp.ndarray: assert len(self.features) == len(self.strides) x = observations.astype(jnp.float32) / 255.0 @@ -44,6 +45,14 @@ def __call__(self, observations: jnp.ndarray, train=False) -> jnp.ndarray: raise ValueError( "spatial_block_size must be set when using spatial_learned_embeddings" ) + x = nn.Conv( # 512 to num_kp features (less complexity) + features=self.num_kp, + kernel_size=1, + use_bias=False, + dtype=jnp.float32, + kernel_init=nn.initializers.kaiming_normal(), + name="SLE_1xconv", + )(x) x = SpatialLearnedEmbeddings(*(x.shape[-3:]), self.spatial_block_size)(x) x = nn.Dropout(0.1, deterministic=not train)(x) From fd972a8b2486c214c5d5464305ad5697ff50385a Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:08:12 +0200 Subject: [PATCH 324/338] random without numpy to not mess with seeded run --- serl_robot_infra/robotiq_env/envs/wrappers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/robotiq_env/envs/wrappers.py index 65d63cc8..cb8b3d98 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/robotiq_env/envs/wrappers.py @@ -168,7 +168,7 @@ def rotate_observation(self, observation, random=False): x, y = (observation["state"]["tcp_pose"][:2]) self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info else: - self.num_rot_quadrant = np.random.randint(low=0, high=4) + self.num_rot_quadrant = int(time.time_ns()) % 4 # do not mess with seeded np.random for state in observation["state"].keys(): if state == "gripper_state": From ced305fe82ce3db775cde3154cc2031f6cdc8a0c Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:08:39 +0200 Subject: [PATCH 325/338] final experiment files --- .../experiment_setup/BC/run_rbc_actor.sh | 4 ++-- .../experiment_setup/BT/run_bt_actor.sh | 2 +- .../experiment_setup/Depth Image/run_actor.sh | 8 ++------ .../Depth Image/run_evaluation.sh | 12 ++++-------- .../Depth Image/run_learner.sh | 12 ++++-------- .../ResNet10/run_evaluation.sh | 2 +- .../ResNet18 greyscale/run_evaluation.sh | 2 +- .../experiment_setup/ResNet18/run_actor.sh | 9 +++++---- .../ResNet18/run_evaluation.sh | 2 +- .../experiment_setup/ResNet18/run_learner.sh | 9 +++++---- .../experiment_setup/SAC/run_evaluation.sh | 2 +- .../experiment_setup/VoxNet/run_evaluation.sh | 4 ++-- .../VoxNet_1quat/run_evaluation.sh | 4 ++-- .../VoxNet_only/run_evaluation.sh | 2 +- .../VoxNet_only_1quat/run_evaluation.sh | 17 ----------------- .../VoxNet_pretrained/run_evaluation.sh | 4 ++-- .../VoxNet_pretrained/run_learner.sh | 2 +- .../VoxNet_pretrained_1quat/run_evaluation.sh | 5 +++-- .../run_actor.sh | 6 +++--- .../run_evaluation.sh | 19 +++++++++++++++++++ .../run_learner.sh | 8 ++++---- examples/robotiq_drq/run_evaluation.sh | 11 +++++++---- 22 files changed, 71 insertions(+), 75 deletions(-) delete mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh rename examples/robotiq_drq/experiment_setup/{VoxNet_only_1quat => VoxNet_pretrained_gripper_1quat}/run_actor.sh (81%) create mode 100644 examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh rename examples/robotiq_drq/experiment_setup/{VoxNet_only_1quat => VoxNet_pretrained_gripper_1quat}/run_learner.sh (79%) diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh index debf80f5..1ec2053d 100644 --- a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh +++ b/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh @@ -2,12 +2,12 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ which python && \ python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name=bc_robotiq_policy \ --seed 1 \ --max_traj_length 100 \ --batch_size 2048 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ - --eval_checkpoint_step 8000 \ + --eval_checkpoint_step 5000 \ --eval_n_trajs 30 \ --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh index cdfb1dc3..05e760cb 100644 --- a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh +++ b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ which python && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BT/bt_policy.py "$@" \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name=bt_robotiq_policy \ --max_traj_length 100 \ --eval_n_trajs 30 \ diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh index 78a4cd8d..d01e7c74 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="Depth Image" \ + --exp_name="Depth Image small encoder" \ --camera_mode depth \ --max_traj_length 100 \ --seed 1 \ @@ -14,10 +14,6 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --eval_period 0 \ \ - --encoder_type resnet-pretrained-18 \ + --encoder_type small \ --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh index 33c1788c..c7ebd7d0 100644 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh @@ -2,19 +2,15 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="Depth Image Evaluation" \ --camera_mode depth \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth Image/checkpoints Depth image 0821-15:14"\ - --eval_checkpoint_step 8000 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth Image/checkpoints Depth image small encoder 0827-16:55"\ + --eval_checkpoint_step 22000 \ --eval_n_trajs 30 \ \ - --encoder_type resnet-pretrained-18 \ + --encoder_type small \ --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh index d0dced3f..7143fc74 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh @@ -3,23 +3,19 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="Depth image" \ + --exp_name="Depth image small encoder" \ --camera_mode depth \ --max_traj_length 100 \ --seed 1 \ - --max_steps 25000 \ + --max_steps 50000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth\ Image/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_08-24_15-40-34_depth_20cm.pkl \ \ - --encoder_type resnet-pretrained-18 \ + --encoder_type small \ --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh index 27321d73..9575b8a5 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="ResNet10 Evaluation" \ --camera_mode rgb \ --batch_size 128 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh index 597fddea..ea1caf2c 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="ResNet18 greyscale Evaluation" \ --camera_mode grey \ --batch_size 128 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh index 8fb78a5f..a222da14 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="ResNet18 SSAM128" \ + --exp_name="ResNet18 feat red 32 128" \ --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ @@ -11,13 +11,14 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ - --batch_size 128 \ + --batch_size 96 \ --eval_period 0 \ \ --encoder_type resnet-pretrained-18 \ + --encoder_bottleneck_dim 128 \ --state_mask all \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ + --encoder_kwargs feature_reduction \ --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ + --encoder_kwargs 32 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh index 68fe8a16..56a9235d 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="ResNet18 Evaluation" \ --camera_mode rgb \ --batch_size 128 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh index edd863d7..c3989a48 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="ResNet18 SSAM128" \ + --exp_name="ResNet18 feat red 32 128" \ --camera_mode rgb \ --max_traj_length 100 \ --seed 1 \ @@ -11,15 +11,16 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ - --batch_size 128 \ + --batch_size 96 \ --checkpoint_period 1000 \ --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ + --encoder_bottleneck_dim 128 \ --state_mask all \ --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ + --encoder_kwargs feature_reduction \ --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ + --encoder_kwargs 32 \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh index 44ba1cd4..baf9433d 100644 --- a/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="SAC no images Evaluation" \ --camera_mode none \ --batch_size 128 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh index d16cbe34..d602298f 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh @@ -2,8 +2,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ - --exp_name="Voxnet Evaluation" \ + --env robotiq_camera_env_eval \ + --exp_name="Voxnet Evaluation unseen" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh index 84620543..ce825099 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh @@ -2,13 +2,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="Voxnet 1quat Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet 1quat 0822-17:54"\ - --eval_checkpoint_step 19000 \ + --eval_checkpoint_step 18000 \ --eval_n_trajs 30 \ \ --encoder_type voxnet \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh index 90fe4420..8ede2665 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh @@ -2,7 +2,7 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="Voxnet only Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh deleted file mode 100644 index a9b1dd3f..00000000 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_evaluation.sh +++ /dev/null @@ -1,17 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ - --actor \ - --env robotiq_camera_env \ - --exp_name="Voxnet only 1quat Evaluation" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path ""\ - --eval_checkpoint_step 0 \ - --eval_n_trajs 30 \ - \ - --encoder_type voxnet \ - --state_mask none \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh index d1fbd6f7..fa5c1615 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh @@ -2,13 +2,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env robotiq_camera_env_eval \ --exp_name="Voxnet Pretrained Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ - --eval_checkpoint_step 9000 \ + --eval_checkpoint_step 10000 \ --eval_n_trajs 30 \ \ --encoder_type voxnet-pretrained \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh index 7d04a7b3..e0795850 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -19,4 +19,4 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --encoder_type voxnet-pretrained \ --state_mask all \ --encoder_bottleneck_dim 128 \ -# --debug + --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh index 293440d3..16f0e9bf 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh @@ -2,8 +2,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ - --env robotiq_camera_env \ - --exp_name="Voxnet Pretrained 1quat Evaluation" \ + --env robotiq_camera_env_eval \ + --exp_name="Voxnet pq temp ens" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ @@ -15,4 +15,5 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --state_mask all \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ + --enable_temporal_ensemble_sampling \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh similarity index 81% rename from examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh rename to examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh index 9065adeb..715913bf 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_actor.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --actor \ --env robotiq_camera_env \ - --exp_name="voxnet only 1quat" \ + --exp_name="voxnet pretrained gripper_only 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ @@ -14,8 +14,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --batch_size 128 \ --eval_period 0 \ \ - --encoder_type voxnet \ - --state_mask none \ + --encoder_type voxnet-pretrained \ + --state_mask gripper \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh new file mode 100644 index 00000000..68f14ffe --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh @@ -0,0 +1,19 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ +python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ + --actor \ + --env robotiq_camera_env_eval \ + --exp_name="voxnet [pqg] temp ens" \ + --camera_mode pointcloud \ + --batch_size 128 \ + --max_traj_length 100 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints voxnet pretrained gripper_only 1quat 0829-14:08"\ + --eval_checkpoint_step 12000 \ + --eval_n_trajs 30 \ + \ + --encoder_type voxnet-pretrained \ + --state_mask gripper \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ + --enable_temporal_ensemble_sampling \ +# --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh similarity index 79% rename from examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh rename to examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh index 6384240c..1355cb4e 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/run_learner.sh +++ b/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh @@ -3,7 +3,7 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ --learner \ --env robotiq_camera_env \ - --exp_name="voxnet only 1quat" \ + --exp_name="voxnet pretrained gripper_only 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ --seed 1 \ @@ -13,11 +13,11 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only_1quat/checkpoints \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints \ --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ - --encoder_type voxnet \ - --state_mask none \ + --encoder_type voxnet-pretrained \ + --state_mask gripper \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/robotiq_drq/run_evaluation.sh index 9d763053..200a5d64 100644 --- a/examples/robotiq_drq/run_evaluation.sh +++ b/examples/robotiq_drq/run_evaluation.sh @@ -7,9 +7,12 @@ python drq_policy_robotiq.py "$@" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --encoder_type voxnet-pretrained \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints 0809-15:53 pVoxNetOnly 1quat"\ - --eval_checkpoint_step 10000 \ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints voxnet only pure 32 16 8 noFT (else all) 0816-17:14"\ + --eval_checkpoint_step 12500 \ --eval_n_trajs 20 \ - --state_mask none \ + \ + --encoder_type voxnet \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --enable_obs_rotation_wrapper \ --debug From 7ce13360a51158f39ff4c8a8e57099b0826bbb98 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:10:21 +0200 Subject: [PATCH 326/338] send eval metrics to wandb --- examples/robotiq_drq/drq_policy_robotiq.py | 37 ++++++++++++---------- 1 file changed, 21 insertions(+), 16 deletions(-) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/robotiq_drq/drq_policy_robotiq.py index 7187ef59..5ea79810 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/robotiq_drq/drq_policy_robotiq.py @@ -150,7 +150,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): if FLAGS.eval_checkpoint_step: wandb_logger = make_wandb_logger( - project="paper_evaluation", + project="paper_evaluation_unseen" if "eval" in FLAGS.env else "paper_evaluation", description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) @@ -173,6 +173,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): plot_conv3d_kernels(agent.state.params) trajectories = [] + traj_infos = [] for episode in range(FLAGS.eval_n_trajs): trajectory = [] obs, _ = env.reset() @@ -180,12 +181,12 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): action_ensemble.reset() start_time = time.time() - running_reward = 0. while not done: actions = agent.sample_actions( observations=jax.device_put(obs), argmax=True, ) + actions = np.asarray(jax.device_get(actions)) ensembled_action = action_ensemble.sample(actions) # will return actions if not activated next_obs, reward, done, truncated, info = env.step(ensembled_action) @@ -199,25 +200,24 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): ) trajectory.append(transition) obs = next_obs - running_reward += reward - if done: - print(f"{success_counter}/{episode + 1} ", end=' ') + if done or truncated: + success_counter += (reward > 50.) dt = time.time() - start_time - if reward > 50.: - time_list.append(dt) - print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - else: - print("failed!") + running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) + running_reward = max(running_reward, -100.) # -100 min value + + print(f"{success_counter}/{episode + 1} ", end=' ') + print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - success_counter += (reward > 50.) trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) infos = { "running_reward": running_reward, "time": dt, - "success": float(reward > 50.), + "success_rate": float(reward > 50.), "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() } + traj_infos.append(infos) wandb_logger.log(infos, step=episode) # if pause event is requested, pause the actor @@ -232,9 +232,14 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): print("Stopping actor eval") break - print(f"success rate: {success_counter / FLAGS.eval_n_trajs if FLAGS.eval_n_trajs else 0.}") - print(f"average time: {np.mean(time_list)}") - with open(f"trajectories {datetime.now().strftime('%d-%m %H%M')}.pkl", "wb") as f: + traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists + mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} + wandb_logger.log(mean_infos) + for key, value in mean_infos.items(): + print(f"{key}: {value:.3f}") + + filename = f"trajectories {'temp_ens' if action_ensemble.is_activated() else ''} {datetime.now().strftime('%m-%d %H%M')}.pkl" + with open(filename, "wb") as f: import pickle pickle.dump(trajectories, f) return # after done eval, return and exit @@ -510,7 +515,7 @@ def main(_): rng, sampling_rng = jax.random.split(rng) - assert FLAGS.encoder_kwargs is None or len(FLAGS.encoder_kwargs) % 2 == 0 + # assert FLAGS.encoder_kwargs is None or len(FLAGS.encoder_kwargs) % 2 == 0 encoder_kwargs = { "bottleneck_dim": FLAGS.encoder_bottleneck_dim, **(dict(zip(*[iter(FLAGS.encoder_kwargs)] * 2)) if FLAGS.encoder_kwargs else {}), From 5f175456fbad984ca3ed6d60ecb926e3e046d9c6 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:11:11 +0200 Subject: [PATCH 327/338] seed change --- serl_robot_infra/robotiq_env/envs/robotiq_env.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/robotiq_env/envs/robotiq_env.py index 65699e88..e665815c 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/robotiq_env/envs/robotiq_env.py @@ -139,7 +139,7 @@ def __init__( self.random_xy_range = config.RANDOM_XY_RANGE self.random_rot_range = config.RANDOM_ROT_RANGE self.hz = hz - np.random.seed(1) # fix seed for random initial rotations + np.random.seed(0) # fix seed for random initial rotations camera_mode = None if camera_mode.lower() == "none" else camera_mode if camera_mode is not None and save_video: @@ -400,7 +400,7 @@ def save_video_recording(self): try: if len(self.recording_frames): video_writer = cv2.VideoWriter( - f'/home/nico/real-world-rl/spacemouse_tests/videos/{datetime.now().strftime("%Y-%m-%d_%H-%M-%S")}.mp4', + f'/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/videos/{datetime.now().strftime("%m-%d_%H-%M")}.mp4', cv2.VideoWriter_fourcc(*"mp4v"), 10, self.recording_frames[0].shape[:2][::-1], @@ -497,6 +497,7 @@ def get_image(self) -> Dict[str, np.ndarray]: # vs = self.observation_space["images"]["wrist_pointcloud"].shape # voxel_grid = np.sum(np.reshape(voxel_grid, (vs[0], 2, vs[1], 2, vs[2], 2)), axis=(1, 3, 5)) images["wrist_pointcloud"] = voxel_grid.astype(np.uint8) + self.displayer.display(voxel_indices) # self.recording_frames.append( From 1a244c857a6c45ec9a1d154df2c03285af73a844 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:11:28 +0200 Subject: [PATCH 328/338] final config --- .../robotiq_env/envs/camera_env/config.py | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/robotiq_env/envs/camera_env/config.py index f5908f89..e455e411 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/robotiq_env/envs/camera_env/config.py @@ -99,23 +99,24 @@ class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RESET_Q = np.array([ # [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position - [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos + # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos # [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box + [1.46, -1.38, 2.01, -2.193, -1.566, 1.426] ]) class RobotiqCameraConfigFinalEvaluation(RobotiqCameraConfigFinal): # config for the evaluation on 5 boxes the policy has never seen - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.0,) + RANDOM_RESET = True + RANDOM_XY_RANGE = (0.01,) RANDOM_ROT_RANGE = (0.05,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.1, 0.1, 0.3]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.1, -0.1, -0.3]) RESET_Q = np.array([ - # [0.4102, -1.304, 1.9315, -2.1707, -1.5583, 2.0127], - # [0.9212, - 0.8757, 1.3325, - 2.0209, - 1.5508, 2.5185], - # [1.2869, - 0.9778, 1.476, - 2.0783, - 1.5458, 2.9585], - # [1.717, -1.1379, 1.7179, -2.4872, -1.4362, 2.5804], + [0.4102, -1.304, 1.9315, -2.1707, -1.5583, 2.0127], + [0.9212, - 0.8757, 1.3325, - 2.0209, - 1.5508, 2.5185], + [1.2869, - 0.9778, 1.476, - 2.0783, - 1.5458, 2.9585], + [1.717, -1.1379, 1.7179, -2.4872, -1.4362, 2.5804], [2.2614, - 1.4378, 2.145, - 2.5039, - 1.7649, 2.2541], ]) From 33ab188a1d0447211ddf46a8a108e8b48ff33225 Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:11:45 +0200 Subject: [PATCH 329/338] bt and bc changes to evaluate --- examples/robotiq_bc/bc_policy_robotiq.py | 122 ++++++++++-------- .../experiment_setup/BT/bt_policy.py | 65 ++++++++-- 2 files changed, 122 insertions(+), 65 deletions(-) diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/robotiq_bc/bc_policy_robotiq.py index bd346a11..ddb1babc 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/robotiq_bc/bc_policy_robotiq.py @@ -7,6 +7,7 @@ import numpy as np from copy import deepcopy import time +from datetime import datetime import gymnasium as gym from gymnasium.wrappers import RecordEpisodeStatistics @@ -29,6 +30,8 @@ from serl_launcher.networks.reward_classifier import load_classifier_func from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from robotiq_env.envs.relative_env import RelativeFrame +from serl_launcher.utils.sampling_utils import TemporalActionEnsemble + import robotiq_env @@ -170,59 +173,76 @@ def space_on_press(key): ) agent = agent.replace(state=ckpt) + wandb_logger = make_wandb_logger( + project="paper_evaluation_unseen", + description=FLAGS.exp_name or FLAGS.env, + debug=False, + ) + action_ensemble = TemporalActionEnsemble(activated=False) success_counter = 0 - time_list = [] - - try: - for episode in range(FLAGS.eval_n_trajs): - obs, _ = env.reset() - done = False - is_failure = False - is_success = False - start_time = time.time() - while not done: - actions = agent.sample_actions( - observations=jax.device_put(obs), - argmax=True, - # seed=rng, - ) - actions = np.asarray(jax.device_get(actions)) - print(f"sampled actions: {actions}") - - next_obs, reward, done, truncated, info = env.step(actions) - obs = next_obs - - if is_failure: - done = True - print("terminated by user") - - if is_success: - reward = 1 - done = True - print("success, reset now") - - if truncated: - reward = 0 - done = True - print("truncated, reset now") - - if done: - if not is_failure: - dt = time.time() - start_time - time_list.append(dt) - print(dt) - - success_counter += reward - print(reward) - print(f"{success_counter}/{episode + 1}") - - wandb_logger.log(info, step=episode) - - except KeyboardInterrupt: - print("interrupted by user, exiting...") - print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") - print(f"average time: {np.mean(time_list)}") + trajectories = [] + traj_infos = [] + for episode in range(FLAGS.eval_n_trajs): + trajectory = [] + obs, _ = env.reset() + done = False + action_ensemble.reset() + + if len(trajectories) == 0: + input("ready? record robot view as well!") + + start_time = time.time() + + while not done: + actions = agent.sample_actions( + observations=jax.device_put(obs), + argmax=True, + # seed=rng, + ) + actions = np.asarray(actions) + + ensembled_action = action_ensemble.sample(actions) # will return actions if not activated + next_obs, reward, done, truncated, info = env.step(ensembled_action) + transition = dict( + observations=obs.copy(), # do not save voxel grid or images + actions=ensembled_action, + next_observations=next_obs.copy(), + rewards=reward, + masks=1.0 - done, + dones=done, + ) + trajectory.append(transition) + obs = next_obs + + if done or truncated: + success_counter += (reward > 50.) + dt = time.time() - start_time + running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) + running_reward = max(running_reward, -100.) + + print(f"{success_counter}/{episode + 1} ", end=' ') + print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") + + trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) + infos = { + "running_reward": running_reward, + "time": dt, + "success_rate": float(reward > 50.), + "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() + } + traj_infos.append(infos) + wandb_logger.log(infos, step=episode) + + traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists + mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} + wandb_logger.log(mean_infos) + for key, value in mean_infos.items(): + print(f"{key}: {value:.3f}") + + with open(f"trajectories {datetime.now().strftime('%m-%d %H%M')}.pkl", "wb") as f: + import pickle + pickle.dump(trajectories, f) env.close() diff --git a/examples/robotiq_drq/experiment_setup/BT/bt_policy.py b/examples/robotiq_drq/experiment_setup/BT/bt_policy.py index ec2901c2..e15bc9b6 100644 --- a/examples/robotiq_drq/experiment_setup/BT/bt_policy.py +++ b/examples/robotiq_drq/experiment_setup/BT/bt_policy.py @@ -25,6 +25,9 @@ import robotiq_env +from serl_launcher.utils.launcher import make_wandb_logger +from serl_launcher.utils.sampling_utils import TemporalActionEnsemble + FLAGS = flags.FLAGS flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") @@ -50,25 +53,38 @@ def main(_): agent = BehaviorTree() + wandb_logger = make_wandb_logger( + project="paper_evaluation_unseen", + description=FLAGS.exp_name or FLAGS.env, + debug=False, + ) + action_ensemble = TemporalActionEnsemble(activated=False) success_counter = 0 - time_list = [] + trajectories = [] + traj_infos = [] for episode in range(FLAGS.eval_n_trajs): trajectory = [] obs, _ = env.reset() - agent.reset() done = False + action_ensemble.reset() + + if len(trajectories) == 0: + input("ready? record robot view as well!") + start_time = time.time() + while not done: actions = agent.sample_actions( - observations=obs + observations=obs, ) - next_obs, reward, done, truncated, info = env.step(actions) + ensembled_action = action_ensemble.sample(actions) # will return actions if not activated + next_obs, reward, done, truncated, info = env.step(ensembled_action) transition = dict( - observations={"state": obs["state"].copy()}, # do not save voxel grid or images - actions=actions, - next_observations={"state": next_obs["state"].copy()}, + observations=obs.copy(), # do not save voxel grid or images + actions=ensembled_action, + next_observations=next_obs.copy(), rewards=reward, masks=1.0 - done, dones=done, @@ -76,16 +92,37 @@ def main(_): trajectory.append(transition) obs = next_obs - if done: + if done or truncated: + success_counter += (reward > 50.) dt = time.time() - start_time - if reward > 50.: - time_list.append(dt) - print(f"time: {dt}") + running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) + running_reward = max(running_reward, -100.) + + print(f"{success_counter}/{episode + 1} ", end=' ') + print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - success_counter += (reward > 50.) - print(f"{success_counter}/{episode + 1}") trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) + infos = { + "running_reward": running_reward, + "time": dt, + "success_rate": float(reward > 50.), + "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() + } + traj_infos.append(infos) + wandb_logger.log(infos, step=episode) + + traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists + mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} + wandb_logger.log(mean_infos) + for key, value in mean_infos.items(): + print(f"{key}: {value:.3f}") + + with open(f"trajectories {datetime.now().strftime('%m-%d %H%M')}.pkl", "wb") as f: + import pickle + pickle.dump(trajectories, f) + + env.close() if __name__ == "__main__": - app.run(main) \ No newline at end of file + app.run(main) From 25f35a3275d8c814c526518ca474e27ef2c2887e Mon Sep 17 00:00:00 2001 From: nisutte Date: Mon, 9 Sep 2024 15:12:37 +0200 Subject: [PATCH 330/338] results calculation to latex table from experiments --- .../experiment_setup/results_calculation.py | 157 ++++++++++++++++++ 1 file changed, 157 insertions(+) create mode 100644 examples/robotiq_drq/experiment_setup/results_calculation.py diff --git a/examples/robotiq_drq/experiment_setup/results_calculation.py b/examples/robotiq_drq/experiment_setup/results_calculation.py new file mode 100644 index 00000000..eae0049f --- /dev/null +++ b/examples/robotiq_drq/experiment_setup/results_calculation.py @@ -0,0 +1,157 @@ +from os.path import join, exists, abspath +import numpy as np +import pandas as pd +import pathlib +import pickle as pkl + +np.set_printoptions(precision=3, suppress=True) +pd.set_option('display.max_columns', 12, 'display.max_rows', 11) + +wdir = pathlib.Path().resolve() + +eval10_files = { + '1 BT': 'BT/trajectories 08-23 1834.pkl', + '2 BC': 'BC/trajectories 08-23 1853.pkl', + '3 SAC': 'SAC/trajectories 08-27 1833.pkl', + # '4 DRQ RGB': 'ResNet10/trajectories 08-23 1821.pkl', + '5 DRQ RGB': 'ResNet18/trajectories 08-23 1807.pkl', + '6 DRQ Depth': 'Depth Image/trajectories 08-27 1825.pkl', + '7 DRQ Voxel': 'VoxNet/trajectories 08-24 1423.pkl', + '8 DRQ Voxel': 'VoxNet_pretrained/trajectories 08-24 1451.pkl', + '9 DRQ Voxel': 'VoxNet_1quat/trajectories 08-24 1442.pkl', + '10 DRQ Voxel': 'VoxNet_pretrained_1quat/trajectories 08-24 1504.pkl', + # '11 DRQ Voxel': 'VoxNet_pretrained_gripper_1quat/trajectories 08-29 1536.pkl', +} + +eval5_files = { + '1 BT': 'BT/trajectories 08-28 1734.pkl', + '2 BC': 'BC/trajectories 08-28 1744.pkl', + '3 SAC': 'SAC/trajectories 08-28 1756.pkl', + # '4 DRQ RGB': 'ResNet10/trajectories 08-28 1815.pkl', + '5 DRQ RGB': 'ResNet18/trajectories 08-28 1805.pkl', + '6 DRQ Depth': 'Depth Image/trajectories 08-28 1823.pkl', + '7 DRQ Voxel': 'VoxNet/trajectories 08-28 1830.pkl', + '8 DRQ Voxel': 'VoxNet_pretrained/trajectories 08-29 1037.pkl', + '9 DRQ Voxel': 'VoxNet_1quat/trajectories 08-29 1024.pkl', + '10 DRQ Voxel': 'VoxNet_pretrained_1quat/trajectories 08-29 1048.pkl', + # '11 DRQ Voxel': 'VoxNet_pretrained_gripper_1quat/trajectories 08-29 1544.pkl', + '12 DRQ Voxel pqt': 'VoxNet_pretrained_1quat/trajectories temp_ens 08-30 1037.pkl', + '13 DRQ Voxel pqgt': 'VoxNet_pretrained_gripper_1quat/trajectories temp_ens 08-30 1028.pkl', +} + + +def create_df(files): + infos = {"Policy": [' '.join(name.split(' ')[1:]) for name in files.keys()], + "Success": np.zeros((len(files.keys()))), + "Reward": np.zeros((len(files.keys()))), + "Rd": np.zeros((len(files.keys()))), + # "A": np.zeros((len(files.keys()))), + "Time": np.zeros((len(files.keys()))), + "Td": np.zeros((len(files.keys()))), + } + + for i, (name, file) in enumerate(files.items()): + assert exists(file) + with open(file, 'rb') as f: + trajectories = pkl.load(f) + + # print(f"\n---{name} ({file.split('/')[0]}):") + # print(f"{len(trajectories)} trajectories --> {[len(t['traj']) for t in trajectories]}") + + success = np.asarray([traj['success'] for traj in trajectories]) + time = np.asarray([traj['time'] for traj in trajectories]) + running_reward = np.asarray([np.sum(np.asarray([t["rewards"] for t in traj['traj']])) for traj in trajectories]) + # print(f"success rate {np.mean(success) * 100:.1f} time: {np.mean(time):.2f}") + # print( + # f"reward: {np.mean(running_reward):.2f} where successful: {np.nanmean(np.where(success, running_reward, np.nan)):.2f}") + + actions = [np.asarray([t['actions'][:6] for t in traj["traj"]]) for traj in + trajectories] # 30 x shape (step, action_dim) + action_diff = np.asarray( + [np.linalg.norm(np.diff(a, axis=0), ord=2, axis=0) for a in actions]) # shape (traj, action_dim) + print(f"{name} action diff: {np.mean(action_diff, axis=0)} {np.mean(action_diff):.2f}") + if type(trajectories[0]["traj"][0]["observations"]) == dict: + velocities = [[t["observations"]["state"].reshape(-1)[21:] for t in traj["traj"]] for traj in + trajectories] + pos = [[t["observations"]["state"].reshape(-1)[12:18] for t in traj["traj"]] for traj in + trajectories] + else: + velocities = [[t["observations"].reshape(-1)[21:] for t in traj["traj"]] for traj in + trajectories] + pos = [[t["observations"].reshape(-1)[12:18] for t in traj["traj"]] for traj in + trajectories] + + # plen = np.asarray([np.sum(np.abs(np.diff(p, axis=0))) for p in pos]) + # vel_p = np.asarray([np.linalg.norm(np.diff(p, axis=0), ord=2, axis=0) for p in pos]) + # vel = np.asarray([np.linalg.norm(vel, ord=2, axis=0) for vel in velocities]) + # accel = np.asarray([np.linalg.norm(np.diff(vel, axis=0), ord=2, axis=0) for vel in velocities]) + # print(f"plen {np.mean(plen):.3f}") + # print(f"{name} accel diff: {np.mean(accel, axis=0)} {np.mean(accel):.2f} {np.mean(vel):.2f} {np.mean(vel_p)*10:.2f}") + + infos['Success'][i] = success.mean() * 100. + infos['Reward'][i] = running_reward.mean() + infos['Rd'][i] = np.nanstd(np.where(success, running_reward, np.nan)) + infos['Time'][i] = time.mean() + infos['Td'][i] = np.nanstd(np.where(success, time, np.nan)) + # infos['A'][i] = action_diff.mean() + + return pd.DataFrame(infos) + + +def f2s(x, precision=1): + # return string of a float with given precision, without zeros + return f"{float(x):.{precision}f}".rstrip('0').rstrip('.') + + +def highlight_extremes(df, max_subset, min_subset): + # Highlight maximum in max_subset + for column in max_subset: + max_value = df[column].max() + df[column] = df[column].apply(lambda x: f"\\bfseries {f2s(x)}" if x == max_value else f2s(x)) + + # Highlight minimum in min_subset + for column in min_subset: + min_value = df[column].min() + df[column] = df[column].apply(lambda x: f"\\bfseries {f2s(x, 2)}" if x == min_value else f2s(x, 2)) + + for column in df.columns: + if column in ["Rd", "Td", "Rd5", "Td5"]: + df[column] = df[column].apply(lambda x: f"$\\pm{f2s(x)}$") + + return df + + +def same_strlen(df): # TODO does not work (textbf...) + for column in df.columns[1:]: + max_len = np.max([len(s) for s in df[column]]) + print(max_len) + df[column] = df[column].apply(lambda x: " "*(max_len-len(x)) + x) + return df + + +if __name__ == '__main__': + box_10_df = create_df(eval10_files) + box_5_df = create_df(eval5_files) + + box_5_df.rename(columns={"Success": "Success5", "Reward": "Reward5", "Time": "Time5", "Rd": "Rd5", "Td": "Td5"}, + inplace=True) + box_5_df = box_5_df.drop(columns=box_5_df.columns[0]) + + combined = box_10_df.merge(box_5_df, how='inner', left_index=True, right_index=True) + + print("\nEvaluation on seen boxes\n", box_10_df) + print("\nEvaluation on unseen boxes\n", box_5_df) + print("\nboth:\n", combined) + + max = np.array([1, 2, 6, 7]) + min = np.array([4, 9, ]) + df = highlight_extremes(combined, max_subset=combined.columns[max], min_subset=combined.columns[min]) + df = df.rename(index={i: f"({i + 1})" for i in list(df.index)}) + + styled = ( + df.style + # .hide(axis="index") + .format(decimal='.', thousands='\'', precision=2) + ) + latex = styled.to_latex(hrules=True) + print("\n\t", latex.replace("\n", "\n\t\t")) From 8101b61040ac455797b917b72417a7113320295d Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 4 Oct 2024 18:57:59 +0200 Subject: [PATCH 331/338] Readme update --- README.md | 125 ++++------------------------ README_original.md | 116 ++++++++++++++++++++++++++ docs/images/trajectory timeline.png | Bin 0 -> 1470368 bytes 3 files changed, 131 insertions(+), 110 deletions(-) create mode 100644 README_original.md create mode 100644 docs/images/trajectory timeline.png diff --git a/README.md b/README.md index 509aade5..20185470 100644 --- a/README.md +++ b/README.md @@ -1,116 +1,21 @@ -# SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning +# Voxel SERL -![](https://github.com/rail-berkeley/serl/workflows/pre-commit/badge.svg) -[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) -[![Static Badge](https://img.shields.io/badge/Project-Page-a)](https://serl-robot.github.io/) +## Contributions -![](./docs/images/tasks-banner.gif) +| Code Directory | Description | +|------------------------------------------------------------------------------------------------------------|--------------------------------------------| +| [robot_controllers](https://github.com/nisutte/voxel-serl/tree/develop/serl_robot_infra/robot_controllers) | Impedance controller for the UR5 robot arm | +| [robotiq_env](https://github.com/nisutte/voxel-serl/tree/develop/serl_robot_infra/robotiq_env) | Environment setup for the box picking task | +| [vision](https://github.com/nisutte/voxel-serl/tree/develop/serl_launcher/serl_launcher/vision) | Point-Cloud based encoders | +| [utils](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/robotiq_env/camera/utils.py) | Point-Cloud fusion and voxelization | -**Webpage: [https://serl-robot.github.io/](https://serl-robot.github.io/)** - -SERL provides a set of libraries, env wrappers, and examples to train RL policies for robotic manipulation tasks. The following sections describe how to use SERL. We will illustrate the usage with examples. - -🎬: [SERL video](https://www.youtube.com/watch?v=Um4CjBmHdcw), [additional video](https://www.youtube.com/watch?v=17NrtKHdPDw) on sample efficient RL. - -**Table of Contents** -- [SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning](#serl-a-software-suite-for-sample-efficient-robotic-reinforcement-learning) - - [Installation](#installation) - - [Overview and Code Structure](#overview-and-code-structure) - - [Quick Start with SERL in Sim](#quick-start-with-serl-in-sim) - - [Run with Franka Arm on Real Robot](#run-with-franka-arm-on-real-robot) - - [Contribution](#contribution) - - [Citation](#citation) - -## Major bug fix -We fixed a major issue in the intervention action frame. See release [v0.1.1](https://github.com/rail-berkeley/serl/releases/tag/v0.1.1) Please update your code with the main branch. - -## Installation -1. **Setup Conda Environment:** - create an environment with - ```bash - conda create -n serl python=3.10 - ``` - -2. **Install Jax as follows:** - - For CPU (not recommended): - ```bash - pip install --upgrade "jax[cpu]" - ``` - - - For GPU: (change cuda12 to cuda11 if you are using older driver versions) - ```bash - pip install --upgrade "jax[cuda12_pip]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html - ``` - - - For TPU - ```bash - pip install --upgrade "jax[tpu]" -f https://storage.googleapis.com/jax-releases/libtpu_releases.html - ``` - - See the [Jax Github page](https://github.com/google/jax) for more details on installing Jax. - -3. **Install the serl_launcher** - ```bash - cd serl_launcher - pip install -e . - pip install -r requirements.txt - ``` - -## Overview and Code Structure - -SERL provides a set of common libraries for users to train RL policies for robotic manipulation tasks. The main structure of running the RL experiments involves having an actor node and a learner node, both of which interact with the robot gym environment. Both nodes run asynchronously, with data being sent from the actor to the learner node via the network using [agentlace](https://github.com/youliangtan/agentlace). The learner will periodically synchronize the policy with the actor. This design provides flexibility for parallel training and inference. - -

- +## Modaliy examples +

+

-**Table for code structure** - -| Code Directory | Description | -| --- | --- | -| [serl_launcher](https://github.com/rail-berkeley/serl/blob/main/serl_launcher) | Main code for SERL | -| [serl_launcher.agents](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/agents/) | Agent Policies (e.g. DRQ, SAC, BC) | -| [serl_launcher.wrappers](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/wrappers) | Gym env wrappers | -| [serl_launcher.data](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/data) | Replay buffer and data store | -| [serl_launcher.vision](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/vision) | Vision related models and utils | -| [franka_sim](./franka_sim) | Franka mujoco simulation gym environment | -| [serl_robot_infra](./serl_robot_infra/) | Robot infra for running with real robots | -| [serl_robot_infra.robot_servers](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/robot_servers/) | Flask server for sending commands to robot via ROS | -| [serl_robot_infra.franka_env](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/franka_env/) | Gym env for real franka robot | - -## Quick Start with SERL in Sim - -We provide a simulated environment for trying out SERL with a franka robot. - -Check out the [Quick Start with SERL in Sim](/docs/sim_quick_start.md) - - [Training from state observation example](/docs/sim_quick_start.md#1-training-from-state-observation-example) - - [Training from image observation example](/docs/sim_quick_start.md#2-training-from-image-observation-example) - - [Training from image observation with 20 demo trajectories example](/docs/sim_quick_start.md#3-training-from-image-observation-with-20-demo-trajectories-example) - -## Run with Franka Arm on Real Robot - -We provide a step-by-step guide to run RL policies with SERL on the real Franka robot. - -Check out the [Run with Franka Arm on Real Robot](/docs/real_franka.md) - - [Peg Insertion 📍](/docs/real_franka.md#1-peg-insertion-📍) - - [PCB Component Insertion 🖥️](/docs/real_franka.md#2-pcb-component-insertion-🖥️) - - [Cable Routing 🔌](/docs/real_franka.md#3-cable-routing-🔌) - - [Object Relocation 🗑️](/docs/real_franka.md#4-object-relocation-🗑️) - -## Contribution - -We welcome contributions to this repository! Fork and submit a PR if you have any improvements to the codebase. Before submitting a PR, please run `pre-commit run --all-files` to ensure that the codebase is formatted correctly. - -## Citation - -If you use this code for your research, please cite our paper: +## TODO's +- [ ] improve readme +- [ ] add paper link +- [ ] rename "Robotiq" occurencies (is confusing) -```bibtex -@misc{luo2024serl, - title={SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning}, - author={Jianlan Luo and Zheyuan Hu and Charles Xu and You Liang Tan and Jacob Berg and Archit Sharma and Stefan Schaal and Chelsea Finn and Abhishek Gupta and Sergey Levine}, - year={2024}, - eprint={2401.16013}, - archivePrefix={arXiv}, - primaryClass={cs.RO} -} -``` diff --git a/README_original.md b/README_original.md new file mode 100644 index 00000000..509aade5 --- /dev/null +++ b/README_original.md @@ -0,0 +1,116 @@ +# SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning + +![](https://github.com/rail-berkeley/serl/workflows/pre-commit/badge.svg) +[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) +[![Static Badge](https://img.shields.io/badge/Project-Page-a)](https://serl-robot.github.io/) + +![](./docs/images/tasks-banner.gif) + +**Webpage: [https://serl-robot.github.io/](https://serl-robot.github.io/)** + +SERL provides a set of libraries, env wrappers, and examples to train RL policies for robotic manipulation tasks. The following sections describe how to use SERL. We will illustrate the usage with examples. + +🎬: [SERL video](https://www.youtube.com/watch?v=Um4CjBmHdcw), [additional video](https://www.youtube.com/watch?v=17NrtKHdPDw) on sample efficient RL. + +**Table of Contents** +- [SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning](#serl-a-software-suite-for-sample-efficient-robotic-reinforcement-learning) + - [Installation](#installation) + - [Overview and Code Structure](#overview-and-code-structure) + - [Quick Start with SERL in Sim](#quick-start-with-serl-in-sim) + - [Run with Franka Arm on Real Robot](#run-with-franka-arm-on-real-robot) + - [Contribution](#contribution) + - [Citation](#citation) + +## Major bug fix +We fixed a major issue in the intervention action frame. See release [v0.1.1](https://github.com/rail-berkeley/serl/releases/tag/v0.1.1) Please update your code with the main branch. + +## Installation +1. **Setup Conda Environment:** + create an environment with + ```bash + conda create -n serl python=3.10 + ``` + +2. **Install Jax as follows:** + - For CPU (not recommended): + ```bash + pip install --upgrade "jax[cpu]" + ``` + + - For GPU: (change cuda12 to cuda11 if you are using older driver versions) + ```bash + pip install --upgrade "jax[cuda12_pip]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html + ``` + + - For TPU + ```bash + pip install --upgrade "jax[tpu]" -f https://storage.googleapis.com/jax-releases/libtpu_releases.html + ``` + - See the [Jax Github page](https://github.com/google/jax) for more details on installing Jax. + +3. **Install the serl_launcher** + ```bash + cd serl_launcher + pip install -e . + pip install -r requirements.txt + ``` + +## Overview and Code Structure + +SERL provides a set of common libraries for users to train RL policies for robotic manipulation tasks. The main structure of running the RL experiments involves having an actor node and a learner node, both of which interact with the robot gym environment. Both nodes run asynchronously, with data being sent from the actor to the learner node via the network using [agentlace](https://github.com/youliangtan/agentlace). The learner will periodically synchronize the policy with the actor. This design provides flexibility for parallel training and inference. + +

+ +

+ +**Table for code structure** + +| Code Directory | Description | +| --- | --- | +| [serl_launcher](https://github.com/rail-berkeley/serl/blob/main/serl_launcher) | Main code for SERL | +| [serl_launcher.agents](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/agents/) | Agent Policies (e.g. DRQ, SAC, BC) | +| [serl_launcher.wrappers](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/wrappers) | Gym env wrappers | +| [serl_launcher.data](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/data) | Replay buffer and data store | +| [serl_launcher.vision](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/vision) | Vision related models and utils | +| [franka_sim](./franka_sim) | Franka mujoco simulation gym environment | +| [serl_robot_infra](./serl_robot_infra/) | Robot infra for running with real robots | +| [serl_robot_infra.robot_servers](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/robot_servers/) | Flask server for sending commands to robot via ROS | +| [serl_robot_infra.franka_env](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/franka_env/) | Gym env for real franka robot | + +## Quick Start with SERL in Sim + +We provide a simulated environment for trying out SERL with a franka robot. + +Check out the [Quick Start with SERL in Sim](/docs/sim_quick_start.md) + - [Training from state observation example](/docs/sim_quick_start.md#1-training-from-state-observation-example) + - [Training from image observation example](/docs/sim_quick_start.md#2-training-from-image-observation-example) + - [Training from image observation with 20 demo trajectories example](/docs/sim_quick_start.md#3-training-from-image-observation-with-20-demo-trajectories-example) + +## Run with Franka Arm on Real Robot + +We provide a step-by-step guide to run RL policies with SERL on the real Franka robot. + +Check out the [Run with Franka Arm on Real Robot](/docs/real_franka.md) + - [Peg Insertion 📍](/docs/real_franka.md#1-peg-insertion-📍) + - [PCB Component Insertion 🖥️](/docs/real_franka.md#2-pcb-component-insertion-🖥️) + - [Cable Routing 🔌](/docs/real_franka.md#3-cable-routing-🔌) + - [Object Relocation 🗑️](/docs/real_franka.md#4-object-relocation-🗑️) + +## Contribution + +We welcome contributions to this repository! Fork and submit a PR if you have any improvements to the codebase. Before submitting a PR, please run `pre-commit run --all-files` to ensure that the codebase is formatted correctly. + +## Citation + +If you use this code for your research, please cite our paper: + +```bibtex +@misc{luo2024serl, + title={SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning}, + author={Jianlan Luo and Zheyuan Hu and Charles Xu and You Liang Tan and Jacob Berg and Archit Sharma and Stefan Schaal and Chelsea Finn and Abhishek Gupta and Sergey Levine}, + year={2024}, + eprint={2401.16013}, + archivePrefix={arXiv}, + primaryClass={cs.RO} +} +``` diff --git a/docs/images/trajectory timeline.png b/docs/images/trajectory timeline.png new file mode 100644 index 0000000000000000000000000000000000000000..bdba7c2acb542ad48033b4aa3d26191015c5d399 GIT binary patch literal 1470368 zcmce-bzD>bA3r)kQV;}`E*YgmdUQ!n1Oz0dVRR|dAtgw|z@fBAcSyIy27M^*oWUHB`t*=t)2z5E)EWQ5yuphXFq(LfnWFBU%=iF0bl+^)}Mj@={_hKe9&>V`QT;o9uBf~adn3Cx?8=6!(H6%Tt8s( z+GT))IQ~0G;XT~qgT1Q@>l=G#I7rc+Re+yW2kyoy$S)|&Dj*;sBqG5tn44=-9nc)RyygG zU_bbOZI-mE?pg`?|M!DQua1^1yo~<; ze~}zFSm_|xZ98wkk`SphLDw?Dfq6_PEgr$a^2SH+4tl(xGiFELML!=F{;vmVDDz)* zQp1BOu_6Xmbbo>b2>4hy)hVSiEfUaW>TX>ig3?;jP(19`B{N2fHk7n0?D$-a6D#eL zm}sDe_OKuguiH6bMhJg#3iJX?9!%pyZGZ4JlU|UBQ{4TsdB>b&K0Q!H(4fKS-WhMmsGoi1bet8*WhZT@SI+&?S}{!K)@Lvb z#5cm1kWaiAeXA9))=J(UUn97EkD)?AX6KiW|24xav6M|x>H1qn*P`p^Xp!O2IC)eB z=KXMDKF@HY81qe>DMoC6LOdXlcbM$mJMWR2L$WRkER!4p{L`7C!lc)VUsN?Y z!9DkQ!GmeqsI=B%SZA&-w%re#6>#>U%)rrp9x1HO6SZ1j+U}ZSLA%+k@fQ_wG1e$% zGHCj-kDkG|@p)U-qRQ3k^|9Z9`j_i#wl7zLf1^H@lt*4(T+AYb#kD?%CD({wq?U(L z1*~V?oc~zA`_dF|d*|tQf*NSp_X#vUjx}owFb{M$ ze&|G6LE87|%c=~nB;Op=$L~9~OUZVir!KKpS(#-#CRW?}H_UiR@o{%|(_3MhrLF`Wj(C>*>Y%S8ZG{%5fkPUFgS!yJ!`b&T@;w zY_@;o+f&AII5ycEjSI7lz>R&?KA3tejtj@GX|)!v>AlSk44#W>DlaM~apd(dNy7Mi z##_IF8}|Ak;fCp=(u@40K{0vU*3yM0V^t>sEPK8Dq=z$xNa`qICKk0m-+ zZ)Hv-)qCnCTH907AFMSh-=z|eopDwXN7jmoCcx_=e zlrxZ0ejLWQ`&Tmb%4sE!ef+n$7S7h4mvh!#@3!vq5Zk(KH04(S9cg5{oIAR{6w??> zgPp&+{QbE27JceQe-~5VEfuXWsb}DrV1Tl4rabYY*~9Y}Du0Op&(-H}|MFfCYW6Gc z5?LIpD%yOfxfTtE74D?waH~$7d{ftw1lKJoG894O%Tc{+bLJHuQWB4EOtN6o&*d^P zAAhO`19gABovr<{NA^JU4&BbB<_@~F=x7ekfox#QxklU{MBu5Fyagyi5Sy5y8-;?A9~P zwP7{}Q+7QiUH11cM(z&crS|BZQZ1a75jNI_PlprSPfimBKe6~9Jv@D<79h493-<`@ zU%EL$U$17}K3lq5(QNd+5HK|Q`~(_F+XoU{=@~n+iFq_G%%NFBH2FXw{+OAD`b$s) zfmKgO^!wwPZu3L=A`bRtM(TD^=JYN}n$j<{Y^Y6&w;rRv?ih*W=**&+zxzWkS(&jL zB93GR3YL^|K@Leq{J5D>??q=6WtPY_7}e5(yu8s?EqRs9p6#8|0rK#;$t$jb7V}!; zNJI^Bv&}Nv6+0u6d9|0>v0j+`ZF@hpj!fL01 zn$|iP`eVm8&SR+OLR@{qt<>>v4PCGA0~B5t|7#=%8m(W7PNTK+!HUbu+Sbe};_akc z$z)9klLagR*Ht$``=1|VYRX)MMMMy$yBnLeo7c}Dt@emq-30G>Mx4dXI`vLWP|?s} zPFmRqN#^SEifw*6E9mMDka5`PxF%PEb zo{*cskwfoX$RMp$f&DLivw(ifDxwEbY$HN-^JFkYX3$qk(!DdkzsLCT@eIg8`~cb4 zx~uD?T^$=6A|_~HnavAvVAwAoZD^Xx<7j*(t;z+L&>B5ADdwUbc3WE-YNh_bcH1h0 zQIFM12Y&y6fT6A~1yaf*DckyaE#!s}p=bM&yQinJu5OFZad_66ynL`5}i*KKA6vS%QhggN713+jp z+)5uS{uO_M1C0|X8&QqksV=Tqi>5M2mR9s;1poDTxYb%Hl?%~u5eG~V0by6CLI_86 z5BM8Y>AWYmX8yr+B>3Q0`UjJEugsR;FsEOm^~t@5JMC9z>9b59kBYOUUF_%oE2|l1 zq2GVs-|jqUzsveKqOYwJv%6y!f2joDqkpVllEZzjf45yx={<&>iV;?CY;L!z zHG1diIehEJs!o;KWYfN+gM2jQ^cbWGM3l9RS%R&2*J#rJoi_z2u4)LXF?i$sqtMbe z>}FHkPKjgO>BAt%$Sl@t*#erSvV6L-AGhJa!RioT4V?GmT~KYcOGSD4)>Y=!mE`yn z%=S?fIm_aNhcrvOPgk=S*86Z3-+4Yr6iCqHhQJ(q2asu-|4?9ie6T|%X3|3)34a$j zy(7}a?-mfCK40g5I;Ecs?;lLz+iD6&p$HdSe7byFd;LZ%tAGkS4;5BdLvm0nMb;7< zBCBVe#F*p#@2;}k+>hA^7Mla(=5<@(9S8Q(tui7$~`VCA$7*p{Js*i{@n; zfB%M``VRH<;M>~T0?DVetWV{R!C<6hWR&LtocG_KQd0bBLxnpMoTt>r-v0hEa==Q* z!nw_hmv@16H8wOX1Eu_WQ$_YNba#O7<01L=-rWrgM-VwEqL*!0yvckbwduR_+asxh z)X1C65sbC{fK5#gEq6(j!YH4~l2FOhM$R<1!ua=Q$HsE6tn7`dP;jmH@7`&k&w$kq z>)8TZ0?~ujOZ=UoaEbH#k?LZM|9;!Jk55+5@AVzD&Df(|}@YD7(`Ig!?4(*3*>eps|in$&bFzRL6zfx`bn(zu=i|Fx3#2=lz zN$$@!F*EVm*z~ib%qlIKe#|bhs@L|X_ICy@0);4nGh3ye-ma=UQ#9gyXLsq9IjywfA=Aw_yRLs?0Do3^>NsxCVwXm(QuI2hUM=S^o~#$LPq2Jm`1hh z>;73FZ z)sSyPit%gGFeHMrD9E>$KaBNFaJAH6|NY3?vt~Rq|3il9G_vJyLyzCAT=@9=Th`Bi z^5fG_;l%ajD%ymm&1{C=M&E6j9fV>(hQOp;Wdggd&akkg82t(}Ewno8GQO#j>An)oAP{H4XHg;H;ZnTPG+3G>weUw8gx2 z@nC!ES(D51?QLfHj`zh8M|^zz8(pQPGi$@gYuRln=hn>&y)#zOw8IO`-6N~zU8hfH znR}jtKybql$!mwITI;mz?#)XqKNhJZ4abEE_xD{cR>(hgcXb8ab9~ex&G?V4QTM&a zX-Gjq0fm=Sj=EMWdH3m`I^LaA_L3>V-Vbu=gA4n8PS7qtJ_-Io{$2!z7_|nJ6&Tus zF<#{|&|D^~$^hbhcZ;X1n~)EnedT7Jtfa76pdqit%i7c$9bTU9$j;<<01CkoZw_5l z_ni4}uVlEA;a?}*uis}Q+8n8+^CHIj=5Q0{<0!*z559xLhe)>0@+!exTaekjq|ITb%&zcCe4 z3WZ9rdSxs55~+N_**OS&Nnveo<3suy4jDL)g;eoF@fQ$moeZ=sREstZ(8t)iYo#;(TNj{0@l_j)MOSaz_uq#VoG9BF>@>ZPp)AvmWklQ4AJIGniW_LJXh zxMJ24=`!w(b_$s%-Q(hi5s5vrt0#J3+4VWLvak$4sc)QQ*unCX$?Cgv;JMIGpkkwE zanXXDCz%e@lwlTQ_b6UxRI*$z6JD>$-m=%%d#(Endp5)Mba7Y3M&7sOu=oP8dUf-h zb|cn$KPnk$pg0;P3M4IMXvY=?{(Jz402pY-r5;l(_#(ZafNP*SyO;!cL`=5bQYPzgrHfGJa+CczAK%6G@rXe0 z!O00V<4$tdid<^G|H+sNV?1he7f4$q-2dOK?SHUKzryrp18%_4s@lT27LqN4E%XBzmnb+)?TKrI-Uvsvdqg%fDnEZU_*dVq?ABVU(@gO%uvWN z5MZ{N;)W%Qt8?~pEx~DKRer|qg^tEL6Cz}%@(7l48m9iy(Wdk@m#+O~x&dbRgKc{L zMWKq9POEgrd{!vMtM46~=nd*Z8IS5u>aql1*8+Tpqarcno(8jL1D^3H;d^NT+kGYK zH4g(5Lg=dIdp|qBsx*HDW}@=r{G;C~c&{bCWC#Q$mTR0_a;w0#tB7p0ZBsa~O@_Vy z_;DmY@PG$qd2uvY-{N~3C9G~(fnN9N_iVLj`)U!x0n^^cV!yFCjzi$Iie60r{PyF$ zsFmamk+?{VI1qmeE~tr#AEjjwjuCfe78b+jDPY(Wn1odyCGjK{yD#=O;~nDzAZGQ@ z237zYU|0X7rA>`Hy|4%X7m&#feS2t~gNV4U zl@2FP^HqPDwd?D2V2L)zic4o7Oi=F|N!wjCL2CKy$ll{Chb*hlLA}1#Y@~%@8 zUok5)^T}p2`K=$oQKpMbZjT1}*t=Br1}v+Vk4I$VW7yzd%F&M1khQ52eE{f92n!gv z&Li9JuG%pu*;|2{+1)hqmHN+fkKoln-UDf(q}AP>C!o9<4FOu4Wz0F1x(-m3;yu)v zDXTn8WRD#Y35tJQ>W$6Jgi4BOKZn}Nn7K(kFg7u*UU2cbyOjo-Uxy@WZ*LPdd721O zpV_a^?WbFwaS;_BN-Qo`O$zG@94Wh_*!>KreWjY<>zPL8;{k>V=?&tOpPf-h;L#3l z^xzvJ0W5sxbyh0+w#gzWw}auZ0%hIa`Ig}{L^K#_j#^LHjvsqILt!r#b4Z&T^{d-I zar4Qc*Axcoz4l@iD}2ETV}h-+LWzCI_=uljnWm$$@jKs!UY0)}@p zzXnY7h+nmEK_AujTCl~Y9X-x=hL^C3N+J#89D982xswU{@DSyCPJXu{3!uIyLi^a; zeeC)95JT$Upfl+deIe)$+3AWL5{~fS^F0#YsFVasW`NiIaKf1J@Va#yjI zEA{K<-1Bp(RT}WL_G1ov93ZLj`N=IJoQhSQxOY}Q0FO>;l|68A~*>6E-+gydQ zY7@yQ6sj+5@_4Eiy!G!&T37d-j}H&Xf1=8W7pU}`GTy#MI!KObqu~)gyLl*X!@x;< zOUwH0ZQSW)V)@SIRUG8)d#U{{>3_l90+q&@O7q$OWf-%3HqN+7+iD0*v6?edQp{vHxoud}v)ygfh zd7hl{feOzTho0|RDlWA~RkKd7rx9ecC*@SA2c*#(lvbqkdwLYNayk{oB&;%p>I(^A z*zfdB+P}v>{;ax1Pe=16_cpd;A|kk$v!-$Xu5^ND6lchxxdLbNKz|O8E^#a`H+}uZ zUFPaqE%4^zZE8N|`Y83d1Xwm@27Y3~RE$$1Cg|^|Byp3|lRT~A2v&XZ0Q!K7%}CWC zx{$(zEvCT{h2?u%_5;LB=2jP9$O&j)90btkKGY~-H5CgdbLFN*^^5T<8}KV zzyg*88e}TDa4@RDPejhw*t;g)lF$>N$7)rg1i79ay?&f{^wZVA)iHf&^H0#uClLoq z29Pzbx4mjja!#MthY!~5pYGo$r8TVhH;XO!=+{BUX3!gpQzEkRb=CZBlK-AazuO!? z*O3sv%VeY!ahRsO?%~^AnE3Iz$!{@Ji*4@aNrI+Af=Ysr<01%aCyFXY{Ry5q=|NUS z{{bN|W?BD6`EMim!XFSqoS0fP6AC&_X z*{^I;%nSelCHgbhS9h`)`iP)dBH73x7t*)!o^DVQ?4G8?8CCvHS`z^lD3M4TdNPVh zk0#Z}N_&|6*pQ{KG<0leYqO-y6}E_h_Vy_k4_@_&-uEhG$Kcctnp{i7hBuAowAeBANIlntkU@roK-rmdsE9v$2CF1^;YCfnf$&iY8A+YC|+R zIX{3uyRB5|1w8zPq;gZIva&kbZOk0A{x;?#a?i$?J44+`wR(og;lk~Kqcg}+1*8SZ zjfMV7=iHXZ`lUv1^j zyqPYgl_hsP$kM2KtLTC+Sb@=9)`+;IWI<89v9a-Tx>d~r;?ww1zP%Xqmw{lfwysc| z3M^spDksIZ#t`(R*-nSr4QPLf_WJ}Xy1H6te|?5+Y9e7*<=Cpo%GZ-gK^iTPniUQ5>^kfKC+9L6h~)7-)EZ{HSS&G&V5-rU{mo zTR%^PM)CyJ_H+=cu$7C8Mo@1szxk_Q{3liEAKI6IfQxHhct8_mjUO15Lt57oe`bKA zU7OXs@O-#P?;|5F)y~NoWboea%;++QdFb5Pkj?RLg6*AYqy7E;kQ>=>@J1p4f$QeW z5?D0kj2wAsXlMW?$RkOfmojY>co53szeacMoP(8JTsqn>sb`G$0NYb5(V<$6pZ|yX z4<(|jl;=GeLtXi^Mqr4rAsdAWVQ(oPBr53bpxC2q3csvgBwlpSlj=9MQ^CaU1;<)Q zj(E*qr5Pg_TC01njx(js>3#2Ve+^d|m34TBYwWgxc6d-td01c4%$(of^zmtI@7w4q zqe&))$(ec^68?~os$;cgsIUUcNw!>24ocxSztR>TLSBE4#7z=#(~tG?7BX+a!@js) z0ryzFI*(Jxo*hkn7SrW-5xDJF>Yi-)>vSVZ_F}96QXF#QsgC3@SlgUSl~UtaX<8hG z^0KZ+0JzIv#ul12;VBL0S-w5=2E#VmD)elxCu9R22m7_w%ii|K^9+R4Ir0ofLCz7= zM&W_10^j$N4;je`?H8u&t_#|4MgW@dRpF%L|9Anibr=DW`Fb|%#_%Vd$$A>a!zE8%b+mRp+5AFW!5(s9rQ_CZ-K|udF>X@5>+oI> zfkmf{k47d9wGT||O)@}UHWK^AvqruR*;JjFCiVAb&hRnM`IR5UQ`5Ce(_21m!8R~&JdlP`^vjH#$dU@V=3`y{b`uchv`=5U2*=z#( zex*7NL}^XUF|EF*3C&tD%k4o#dy2aFm;Yu>^-&U|EQ{@HxBJQi%hxmQu2lxgp&-N% z2uFCJ8q7yRfZ3cwLP6XBt`=7ReSM}t^Rnp0T?;r?qrxUD9%c1`;?XPh7ve!k1|WrO zj>Ua4kM|b{Q_Fj-=zjiG2-SGj`J4abLxxrB?9usocZykH&&@3#A2{r!i0cxAlA!atYvnhU|Y_uPzL za&LGIOa9>(Bx*etV;r^{k+qpZyI zkCGsc+{|KIQhP#xl*xG>NL|ZzE>&*>76UAUlj%x^1YJ=O@%MC1Iy3txXZqf6*bYb^ z09eBsq{6vH^dg2e^{Kh67y%Z%7I}R#Z1oBh%)Ykc!>OOHh+i*1$lUn@TyyBdCXq;D zpmqv(yQdKp^{|f-`w9I_c5I26>~}4yB%U=vpnJNaU^jmvQ#s5-M9jk5#KZ&<0oenj z??&T$1;)5MduP@2E@OdEl9Q*+FM{RZNh}Wtp$s_CN8Hq}_bKkC$B!U`{L=}!P?=}+ z_kgC~@jSr1%HZBK#$X!LQs7KqEfvlB_s~1$K{WEKBXJV})C3LG7+^m8AKnZyfjkzt zDh;ZtR!qx}EM;a*zET?zaOTt2)%_qmi8FpAul`qc39^;+YBT*m_Oql7Ar0nXl=>E}<>NJmlz<0l;@5fr6Mkek? zb-1>68i9GXZTk`+te{4tkxU`S!;unY*ytHv= z$it5ZX&}SH;-0Pi;PE$K5i!KPI1lqoB98AZ{K(t+A%D=TN(B-XRG1p(?iv#xlYA`x zxR;QD68H5Fj^tnGQnmLJXX&T&V=Q*h$~IyjY*Fz_aLtevTspk!4#?QEOmJkK;iVb* z9`vq(02{)~Or;%JO^^3%oKRAl6wie3H$9J`Cz#YaKachSEgx%9vO#2-?&w(3L61Jm z%(V1yF;&GQCfv#)+b=&2XkUy-kh&y{_y`S0s?4+BJAfL8#_5!+VQgDmXiVe#)3fJ^ zp*(TAr?>s-y=%(+$!;H|yy;40eN3>lIEB6awx`zv_(}EtpgR?it`T9+ZzdTT$!(#n zmdqHTYaPxrfbRC3ir8CPxpoMG0&*k=zlu=?6~ttN&JC1KPCZJRjHtwlZKu$0MqyWl z_P=tmS7PFTAarW<^*g{;Fhgmg-dMcoyskO$d8o;~(lC%4sV+S*qoBf@?eTx!-;v+z z2Nb#w3lwy+4hjJ0&T*MqntJR2D$IH`DjW@&lu8*l#-G#Z6u-Gj?n%PnXGcnGIkqnB z!zdX>J_4rO6PltpO*wFm^+ZX{rG6klp7bg>%Dht<=>%w|I4b5bpdGRAN@2l3` zq!j;_l;`DeKcOx4d|RRkCjOI{M+ZOy@X-J*-j*zHgs$I3tU-@aR7aflGL#%%=qvj( zzNi+-_A^B*W4>0J*?vI>`DrE%46mQn*5fFtaYwu=-b8?V&X@>Lr>7jz7o?&mfa*no z4&TT5?kw#;`tCu&m&XqdbwlG{Rel;K=I5lp7Y2U%<-Ipwd$WAp+Nqh{{WW4~vrre0 zoTSKqvug{WazeC@H4@EN;eB(Ix)aSY2=6I{*lkOn2SXB}Jk6&+k`WP5rUK{?YgsIR z_{}ZFGhe+yUGF;hP;0;yv|PYm`cR-`>d7LDBS)3i7ewXW<#Wy!LJW6wNR!KXTKmmg z&*lJC?+@u&8HctXZ!sgjdTjw$9B1E?4K1nKI-lG~Y_YX)N2(;-vE6<`4x_?K>J-P8 z6c&YGR8Fbg9$&$Rta;!uug_tzqv47O3AV;PFv7KT7Zx3TADX7l-R!c}6kPn2y+)gg#V1q6OeInm&`=^q zV9li_F+$0TRU}_XdTHZ2&vZEp$lPgf2r-t`@J6He0A1GA1*E0vG!f^CUW}PX7UyYN zJ`P_8#)V6lFjZA6q24~sU{x9zVkiZadcHbM0Qdb7O3S&dEgm33Jbjl38Jux{;~PWi z9DL&Nsm?j4J>Q*2@!r^d`ukttJ)X_ckN|vRvlefhnCyx*4znXdg+bI z4h{}zgC~xUg|;s{dU`lKOsvWxZ@NSRsg#Ri!y<=lP|tsUfD9r4akaGeKV>x6{?ZTi zwBSEWo_`6gRl~(WaK&OEUB+wYpi;<_Az@(5As;TRemJaTt6*5r)WOmGrsq?cxf;^; zA){`1k_3M-gt}q0w_}?YKYEi)JnsO{v*b;{F%`-<-z=MNFEW% z8Td&ur2)LQFumm?31XmK0Hh0=zT!`jAmoBDO=S)AGR=ywX;Bj$Di4Zi%F^tAujTsv z3}4`9%5ooAaD~>_B|36A)}O1iaryU*;${E0*MfO*o#;pH0_>Y5;ro}DslrTY?)Qa0 zT*TC}Z}3}jJtq5|D_j{fl1|_NH_W6R6-@Sy&qn@xA<0a>?xU>x1rT-Kdj>KGxAa)b zQ!z#Y6xTpb+z_dpQMKT-)$};@dml%~H{D0-AT1HQ0Ld#X@#7(QE?V{e2U zx+?LJyHeKq4#o6G>t_%V7*{w`UXh<{%zUiY2HpeSy*=N zB8?cEKutq_^@(nfwg(b-i=Of0Q9l>g&YoAaK=^zbx&P^gtK~(s3rH8q0ZSc+I`8t; z&hJ^;yhRyO4`LY9w_31o4f;qO^u-w{C#nX zNU#ptqtsVy_Y7dDFt=%s(&1c_Bp3byiE?a&cYEEuv-JtaM+0e_{OKPJL@n0~09m+L&xf}Hcq^nCu`@HPjKv{HQlq7`RV|z_4r-sob z7)E)uP{hK<+Vi|R&b(Al>v1x{B?$@3gNO#xWMY~C3rQEtLYV@D==SK}m6KCp82jfm z3?M|0AK7ifg#;L`lOTh+8&mwF!Xoxs{Ap@g@3DXo8-e7krh94-B}G#?rskLGqx+J) z-3JyRrC4cuFdm^jr%ysr+_bn1&%$|upBZA(P-rWxEWSa`Eh#MZ^vB+Tc{-{A=Q`*N zZ(6c+M_@6@I|AMzhALHUlrTHILGxXlPl-eqThr1vUCLz^7)aSWz$PHSOTe|58gY*a zK{H5BS=ml%onw)W&}CqPM^>Kq=KxGv{z}b=Omx4|R-<2UK~~@|OM!x&pVZ8kqtEED z+=EYh3!AEbFWsfw{j#ay7^G|}#{dAg{XDuo;T(FdW7c{Vl{OmkeJ3pJebdEIO~Y%C zQpiCeI#O;cGJ~ko1ngob_)5P203TcXt0ze0M_FQXF=1@Gir?d|(FCGNSGy_Fu$Lsx z&whB0sYvqe;gY^=8l&`pkH%#egO?D(D-p8SI2C5?IW7)O8rRmmHTr+#vs41wsIMn; z`@WX)D2!O+{Iezx5rG>jE&Ld{wD(Iy6^N8f(b*#iaQnnf7>v>(-SrxjYDkimXCp^J zpZa>ud`8P^W+8&l^F;JwYhMVC`Aom#dtCB4&o1Y+M+Mlcx=>PN#emvpvM80}U@;Ni zSQ#BJ65W&DMiYSeq$dhD1ZdHd>@Dd;IzHZB!MVEckU?{uVKGU`cnQkSel(#BY&((jSeKHDA3)Sx&2Ix6|^gt5w6$asE>KKYa{ z?&S1Tcem%?YR~=D{5W|8l5gOcQ={9rHI6`8^vh_r$1dMf4L=h!P|l>Sx_>%%In;vH zIfVYyRY$M;J`0FV8H8KA7E+m$8k?Fb=NH--)d=Td*JravY^46ksw%&0TwhsX`$wl8 z;GX&wCkKzCa}QC@@WSxEg~AWKY0i@X8nwA#BF>i}pWD(C9lYY|WOaq8C+s7@fKNJY zNP<5W9Qs_+(ATC$eE1^aFmp`U`Geq3ue6XbO-;@84A>pZ77bV4H;H(-;lY8MW~MC| z_86K;fw7S>JNj=fjc;gsd=Uap%s&RY?FpdGm`l_>8YKy?QgL`F@6>u{l&_=vNcQ$H zK5MIUiKCa+MYaV4#2WK#+(n8u zNH&SPaJR=x&N4 zpT3!*t$lhOYNK|U$qXjmoH%4gFa10BW}#vxC(l7WYS3YDiHU?C=zh6XIV#iN?zjcl1_RDs)FGSV{d0zB}0D`#B{GhiJ? zdXH{KCp?`?b6=a3WFrMlrXqADzkxXka!t4bCiF`1H8tZ;TGw`WLr#rwJ$bWu2Mu@I z^XueAothdNR^7x97^TvG50#7l6aanIghib3Uo!mRtOQ&fFHGGBaB2Y3$=SdaMv`D@ zX-Va($h@AC@h3WyAg2KG=h%I#z928bLH}pW9pnUgdns)OdE7_9MmSJ?-8$c}X)Dum z6}9Al=yPwjX4&jzku%HHN5>_}S`H(<5>Vl7xmA+2^JA*=RQ@-0Gxnu9$AykN)SsoD zLnolT&3nj_!DnNGu#o#ZlIl8_@}7qpp=|AVUc+1>f#$(=0Xc)s~OpjAy#`g ztaaUF-j}aEzQg~0UzY(ll3FC`i<2WYT96J?nbKJZN z@AjU%WVI4TcDbme=29z#tL&BotNU*27ALHR%dUM1dpTuMnBRdic-NS$?kID$i>}gE zE=H1O`5y(uu<;*R3$ev_l2;pkUsQ|Lyllgyw4ZYT-ZAJ{tUBL$%H5IK_$d>ug*(7a zkri#1Fa1fm1QvPteT%RBE9nH7`E5!mh_E|<1L?6_alZs?NP1revXnqIgwl`vXYE2i zS7A3<(m4f)Jzwm_h*)7wlN3L^G1UbBt&6PGL9IDV4~^ED#3+D@i`P$g(AT?~AA8e8 z`L-@I2TRoE^o)vf?FUx8KbyCJN1|um@9geEdU=~xO8!YWzpbJ&K_9R7sJ+@mr(r_W z?2c5joPpWpP-Yv0!E?PyRJfrCFzp8zkU*bupffweE{~tkVD-6_zHZOL9y64*_lHtDwN&I-?s-srII|Tc`kZ%PKm7|7m;RC>#99df zj@{5S%E{RX**@TQ*BIf-ekG60Gd48_uaz6T?gARI?n(zLmM%+FXus8V?8!FLV&T`sQ&T~ls|+zbN)cRdPs{o{zh51 z5{SB@!qvv#j}0Oh;E!GY8HwpMauRfDdRW0ON1JZ^<97s0g(yEhfv6i`cbS@+!F$En z0zE;|sd4WZy;KrDA2ZkeMm2}0;UzNpDpMwHKyU2*dwf_r6@^?4qJRUF>NA;XIWVn- z)YR3bZsfNPd-QbJMK>H|DHD$Y{5c~pg#jnn5B4YKd;&#ytKMRm7wrF>Aqqa;-sZb$ zoN?cfD|W1Tai{kEw)8J6MS*eR6v;wvw!OpO(DAQxhpKK8%_nWyie4Rg*&M5eDQe zW5l==CBI8nqdIo1TPO?T&_Tb0oGw+(=nAd+z zG0L}?R+g(e2lFD#8{{TBE4Gh-32%((b0+6%jv@J3XM}n=?Ov?l3%InD=Fvq1h}3GV z-;P09i^6z#1DCZtKw~H}c8sq$ZgQGiX_GAfrg-X3=QYe@SSq=+Yd~gEp5( zn-^bhlL%&J0FsJ}RqZF2gYS@X9fFd}$BS1TxklFyJvYMByv(X*U4R=qjxU~6_rHSGr?FC3UHD9Zq+Sfjp1(I=K{nPXCAEZPeDOV|;g8O5h#b zP`lovySh|ejM<^CIRpGYBDl`pE%Ze4gNCo?eLL_Y4)p-=V9lniiJ6JE4INrPrRDbg z(KNkHjW(sY>irapP0fGWZa89JGIQqix|Mr3DPI0%dQ2D?)baRBU@o2u?ZHiuJCn;M ze{T{8viNu5K=Rc4-m}G))zgyr^Udv$>OMf4HC%;Fgw=^_Kf;F+kJy67)AAok6mmU# z`DfWKEnF%Y>L;2IHk5De%yGC#7Qpw8^cQO&;3&o}wnkSa3LH#i-4g5S_AbXv1EW*8?mGMdHLMVE7Xa|X-{=nY@tBj>i%IcO8Th=z@N%SWS7rfEq`FkZ{#*P>w2B5rJ*fqDldm2 zWJEL#CPhUXI)3|%=1z8#H2_-sYl^nZvMLvw=jx8G?R3?gak0kJTF8ELl^z`c3oYM< zAp~GgMruwDsB!z`&|X#Jdf&F@ux7jH#99Ad&w99kS+`$dMg|OW zN8Bh)Trb_*mwGT)TU*3iD4rmT`M9fw!uIEv{Vy3vKHo}tdp1i0l$W0~D6IQEsV=!p z@6&v)L+E#?NG8ISO7|y@`BKJx3+z+-j9c5= z<2`>ka}?#BCk?;N#FXll$oA#`KRgt`pZl(cvWr$Ru>qGyQt{H#)DYbWl`o%>m~Gq1 zt?{*|=I=?kpFVT0GEhYM?&`nz?SN)`mdzobT2%g&2MbJtTUy%ko#TX2cmZ6>0%X#o z<6yFlh1Jc!aGvmKwI%V$gj&S|ALYHU=TxY?4oriWpa5PWT!xwIQedt_Zd7W{Tb1lY z14q9Th5{KIil)N5<1sXHUn_Z3Ko9VKko3OFu7x5W&%GuXn-&mwCDM14q<*Yl?PXE0x$0hds9Gs=Vtoz?xgF%a?3aAxnmfqu}|;Un(m)-wmmG zBCG3yS@ntsMFih*B4g4TvpcN&=28z$KbrgzN?`MCTJk2ClocSrDNyH5`UxW)EmP+Z zBWFoIdI>Kqo_y*5f4l%&9#VvW$eC-DS|Yy;uv1cryyT{6oOOUPIQq8BzK(eRWY6Ax z&Orf>9slp7cUE=K&q;NpmQNQ zb3_6$4%oW;rQvP$DcmDd;G$^Dx5)QGHtS1d^1?`#Hk-m{4h#p z=KWASy>8|Lef<=`;^sW>?&AZvvDa$e(+%A^*u25$%D*}o>(r7n#M_uSq9ofNe{=Hf zAI}u!6kxJ8pe#(Yv@6O(mf7{IA;1r*fxB}E$_IYFM#k*>OJ$ARnfH#Y-7sm!laD>5 zA}|_$0y-l3%5(6J1gXLqpQL?OT;3sff@uA3o&LOB0M7FtkztoNF zPoS}_A;p}VPZx+ZKh$=DgYjA9$FtF^{&pSDOLL#7e}d8ZCV8IXG~u;XboQ0ElO+45 z9j4WbI>k$K4s~5`(cdyjA+pE-)YwOUQ(Y z82g(wyi!A+{u_VVQsjQ2moAE8I1B7cYJU}UHkRr0f^zy`_qM0jH5o?VOF0W`^5LK@ z>7RMnqPye>SnrK^8^zkq-2$xBclI};dtPL=n^Ot%x+sjk3s-s7T)sE@&PrVUd^3#D{wo@_|slh7M-d8?n0It5og|M=wGqF|9>%cRzY!f(Y9{f-Q6Vwg1b8e z*8l;6yIXK~Yuw%4CAfR=1b6EM3GR0Gf2vO1`@&PRyBcP%HD!!%rUMsgGBR`H_Cm3v zLY9TI?9-+L0glDYtur&STnGjptO4q1Yq$CY{L&htTQKcTORz#_X{WsWA{Wp(ftCX4 z23c%s>3(fz6x3S#Lu%?C?9fs~*+9?cKK*h5bpOH~9(mYDoxZycE$$1C>K%6$BC%L- zshz7Fso58dGU+9j*~@d4)#cCA2C@ZDB`e95)EFis%<6;;ERREv zFWiwSebor9>Y|l5!_i0RI>U#+R|#P}xlm52ch=EOl`73!G!GCdg9BizvM_S5>bUCb+zUQ~HFB4$@{zsdM5gRI!>sIa=cft}uJ**eW9L>~Ld&$l5 zwaUrh@-c+Jg6HtqANyNKXy@0$xOqb#G|$_iH$@(Xnln@M1MXJq_n$-o1Krg`IdBz; zS`dy-mYkf}wyi5w95n%6f_wzbQ-Z!1z(~tGZ^<;3^q=jMnII-3qw0isACMF?UoK@h z{Gls63#a<`qwek0id}{u&Yc^cqu48&GUrL4Xl(2k@zYxK7Lq9+%|3Dq6)Q{nQ@^&h zgw!(1iXbY~1=?jZ_riJ0IEuEVWw+;L(sI4wCD1tstBAg)N49Vt5Cl#TvvGx9#P)#WCiM7|t!|NKI9E^A?~ z#XT1Xj~ET2GGSEHn`Y*cy)JIeFLvcZaR6b{f}l683OYHOIXJhl-rg*XJ*I_`LnD{8 z&-lV-s$zjL=9s0$^1q(ZLT@`vv}@H-T-`B^YNbGbEAF7p-b%z+8Jw=so5Zp`)Ik4s z(bLO|IEl5oXxx}-%`&ge*@AJ8p=sCVn$N)sUNa(;mxwyI zetDa5>WJYM!;4_{x7b2oG!jWxR@N`AlP2s45rj#Bs#@H~oeQJOB^3Q-%jwe^BIOZ7 z^L4yPG%tDY9~BoKw*4pC*Wb6kHqb_&)&oXmKqU^tWL+>t3+l&fjs?L{EG%AzPPn;@ zxR@AOuP+Hu-?R{mL^_kwP{e`Y$kyvxhm&Fw6sMIhzXv>PY>0~N=KJ50kj~lz$VVqL<&hWnW{=C1%6Li-zI0vrPxDYY&gUfQOTr;Zfk_!BC zuFfSptX$zp>z96Q!}=zS@&ZO9(W&R*>~S@)C}`eHqW~8(#DT)N-EZ_u-y?T?HiKX5 zm=(w9-W`7OBk`(Lup$a~dHB^99Btyz^*&7W5Q@XHshfS=96y(RL|se*JxxokB!SQx z{f?%l+%@VHGr}Hhy@SJL{@Zl`pt>GCGPmtD|K@j#*ZXjV5-Vex;v7}PeEGLLe{Xv8 zqm&`7oNm(I+b$H~0StQ*xmC}i(y1uFuVN&{zZ0&4C8kLr#L+L+2Q{gka_W>|tY)sY_Py+#v1``McVlyN)d`cHOYK({f!3nj zz|F%$0)rv}(jn(v)tfB{izWG|7R#{5+q~YOe)-Ou9?$Guksb%e3#gMX@6NuG z_>a)W_P39Vxx$otovV7x`aI1l3H=z2iVXWM+- ziU_;IfqUKQLf>CR&}xgNoRk+) z7qZ-1g1|9yvL?F~*idKf-mek51gY=~UXk|j4~EePBQgyofy^loq|*Mm{Yec$;iww^ z$jDfQVfi!f#AnH1d%G}Xu3O@rVWpCy=2h5Jz%E)q7(p_@=Ye^3?8nw~_H}_le?MbN zelc&;Q^u5~KnoS&pLnRnREVUGs2S4z5|WcysW)8c(5?ITfvd(gdo}!0IgMgM7TWqk zn@BVU<;+8YL3hSkSJFG52S$l9eiPj^`fbzhlA7!jnB~4{i{cKW2&qhVK-x1^>Zu&? za3M~V76;|sLTs#9z)G5#j(zeJbIXC8U{X(z;;2n=wBqL~<; z=`WA25&u5PyqGw=@@E&TZ9ASX7lmz>;*J)&56j#$uEH5 zfhlDW&<8#YEv0g$K;TD-5#Cj3TJkxj@)H3eVNqkl*;)^xIM|=$TV1ds%%b!34B}qO zN@XVD1t02Vi3!*R-bmv~g2i1skigv)M^T!a|2 zin{+7)qZ)I*}?XZX+!_m|-g$)}rj`2+)Y21H& z)Xl#}*ZNJlI3S^$whMR@mjBhF6Wi2c$u)rEsOn6I#On>6VXLSk!I&ihuTMb44w|qa zY_i~^(3Jdc<(jkLd^EKCF@I#nl|`td2#vUZ=G)5#&-|MtVral7?A0F(NZLHlmFCmT zD-&(3I$VUvrx^s}O#$D3#zKY%E|1%H5WMToDd5p@a&-;4evG~Ku4S)l)7kjY1}OGZ zjBs|}-nQVMFLTgS@o5_y;7yZlEnE?Mb!(x0QIh<-UP-i~ zZt9_!Y`4Fo@SUXS5g#W-ayZ!nM+lM)gV_M;OL#I}7!jcX(Yrdj4Fvs*D0|ZFPzQ*@l+Lr+;&kx<9o)zj{lw~f3t`~`eU_&$K+^m0+ zUB80xezvWqZ*5UiCT;KYgymqOv<=+YWZNW&_2~>E2T?5reYf!<( zS;I&d4#gnmfKN}}0L&!5I_y+< zl@E2p)qAL=|4}BBsg&b5I68`N=NDiL&}X$A8Kv_^Qv>2S;DB{oQ-U?(=;Mp8HSz~e zJO4feN>DW$6%ALaV&!=!y1AOo{1TPC^dw+z2eLsUTLiyl#9`pZ$%ll)Z~Z zL_`Lk1NoHU{fpHZC*4L%gQCp*qcwX1T?aa6)j^XWq;pf#)L0oBCB?h(CRpcF7B!#^ zoyOejeLI%F82F@k5(L$hA9eF`&^#px_uW^=crEB|K?ZaY+ z{a4@fW|iHI_ptZN_g4%dQPJW#C{;!H3BvT&mS)TB*%n;n5KDaMAMV~1@pz1NC-5T5 z-gH5|@jnIMX!xU-9>nqsh*ti9+Jw8W|2%X=m))MosCpDEh9}g~LFsvpZ;udg>&*X> zU`BurbtbYlvQDi{LPfqdzFKLs2h#?)Z3xQ=fi_MNbni>p+@0(ZAjFq$cjyKLnfVMs zykqb=I8pv6g!|R@rG?lEj>vH_fqarDCe{`nXw(?6%RU)bZ7ra%RnG6vf(HlqE9@^h}UeMrAx^iWE1DqWA?ez@Hlo|)T(0tLLoZ~pteEz&n z-XlBJ`%IF??2Nm3h7!6^!xmPG&$uSlE-;j@34+uzDT5tPr{iiGS94> zIph?%;G~2K%FEBk`nZo7IPrJ<%4`N0@!0(s1+GQ_KQLJ(QFYHAqs4Pi5CaEz8v&p2 zv(F5_eLr`b%25UEY4`UG#W1>?w^tw2Q9#rmJ7x+v34pu@q)%f^Nk|#1=ARCMFnF?p z=z=tfUetGeKQ-#t)leSY(>F{AS#S{TdkRs_$~t|LSRN3u<;gCrVgh&&u`-!ZwAs_} zz+KA(j=*b)<%~s=JOZdME%0yNJu=JgMBpirYX$t9{;a#AM^oY`ItOj-6PFMF)O7+1A&pfr_J^h5_h8NK`M*`f5BZ=YqipHKODHxbr+2A$gh#psBl?yvNsVVl-ri>{Dsa(Pl3mpzz2J+goqKMLn( zxht$^OKt_hxD)dfw7o_QvW&(Ct@2KRP-J2TKx{xUQD)qCnDZ(T^N8edUTt zX!}j0R>Q$KGfy+@vB;i?7@@m}9v)?CMS5371`V@S#M#-|ifZhA?@&){-TfzDkzyu= zSO%Pe+wm*d+B!IN^oV`&9{)p;&GS2*PiZ>aHPhLf{1M;JdjYUhGPm^}UkCAw`+_*9 znPGCz`Z5{0`({xc+y(s)xm7;lfqgy++&C_WDY30JJ2}#-GEPk0e_wTSs1j)7{CWO% z`ukz@U^g?kRB-w4U>xU4{^5gFKMGZ4=OK<`&x~cyRAkFluB8(DD&!Te{*^Ts3(_)!NIOzn!&NhG*;5SOcw*-SR`0~k;XgQMf@*qF-X8_A} zhN6W9hGb5d|7z?&w@MSU^!g+lJ9G|hn_WA}fmb+fqJVSrDrLNeEol#MvSme;FHXpz z`5HDc5AE+4|E6kDGh_bHl9oJ6!b9}6#oqk!)r_N!9ib1d) z$b~`u#x(9ME~#pH`%Xf8ZbDSk>YxFESuMKF{{-&!Wp>m7jmoGs!}#(%oi7)~ z_x8E|^6d@FfWc*4nW3Lo`vz4=%z!ll{m)#ho+he*n>H6Th;D`|WA+aor{=dQ`Nfp2 zUs@qECpk~?fd=PPmT(Y|C)(s^lN~d)jpxh>Sr4+)b8NQXlAoe5B_i&>^+|pqc*v%B zhx@0ELreZ}>XX0kW_>yPeg)?t+mR=q7L2DyDtl2kMDXneKYPrlMK@;T06*ZF;tjp= zJL4z1s!k4VOVW{Xz`W}z}Ydpl}0d9^X zjgze@nc_>bS!Eg17Vstwn0yAGGX8Sue*Tt3J8*VZ%kF74k41{v{sXxLTI_S-Jx~Ui zY9@Kf;G+QUR7eqHO|ef$P9lUxfr+tRloWlb7ASc~^Ge_K zOO^=}DhJ2*v4A(Is6zhc|5!>V4ose!P0gV>6kFal4vLu-niY2ZbyOE&5{#g;?NVx! z)Fz=brUjqM{O>l;DdXN%goH%)fc{!)@R>e_6;S9B+UbBJXnfdim;%xNl>S4HOva^h z`Lm|Y(7I;D?KOjYay3)v3NM|TG!z7Y*gBY^{JV>DHmHFl^Qutw>_?q3-&y(WjvRra~ve9j;IL550(Ur8s z+3y?`Mew{w2|K+E3lkGc1VJKnMfxIv-qJ~I$`x1k59tmJxXW@6p*&Vm82pkqbnZEF zfC_WO3P47_UTgW~v3Uvyede&V&sSB^GhD9bgS&+#1?45w47*}|7jp_RRu!_a7r`KL z$n&rA2=UtdnjjNM-P3c53mA4&Wx(H3^_!@7WH=#Cro*;0xObB>nZ?ue4o@9-c}OKjBJEll>eck<0=!Rsp!X71H8%PS>cqlZ)JQ-?6)i2Oe^iE{%R^ zUBPQ1S*>M0dvK(OAiz?(?Z*#;8)#Xz3y+A9RixLToj|_s@Z3TZF0;mv=zD3y6BU_6 zOP`{ffj|S2IQRz#9ufc?W6wjL0HJ}yhvmaBJ3@q9kNiSNF^yin)m#(OH9=LyP12;YMnS;fejRVna+bT0}166rUdOtC>SIqw~zSg644-T!UZ1o@zef1V%HgZ2S;aBkr+P2staC8qX@~y z(&;ZV#!M5bHMX%pueh$hlSqr$x^bPzwHhsK0^>07=C&To?xxJABPQ|B_p+I4YWI)7 z-FSuoaAqkptq0>njyX}%S1!ZES=79O<;DVb65fk55gwYaB&CdYD3tz5s+YIc@ z@ggA77MaiT9%nnCq^BZ~8vREG9${@}{y0R7AJf6T!gnE?Rc-QJOPg*_jxd(vpkjD) zGq*Ms)Uf#v;1V}6^ZH;PRl0BPTs%bb$?wc5oc!H1(82@a1)u|kVv^#=l=>;F;R2nO zjw|W3glz~bZN$dLMu9cZ9_i7k?RS>}jl|Td*)fr$BLLlIuDD^{M(WDc-`)dzh6bTwfuuI0|ujzJ@JB+5nljnL}=HUJmk#yLydat$r+n_ie(xbU|ZwT`*WV z@J2nOlToH<;NY!#+gN1!;>ja^n457%HV573<;L+1ACX*Touw=W&-dW$xl}$jqJDcf z{r!PcbBv{p6)d+$_CK~A*I$;;CBJ%nvt(rTDYside=!Dl1_d)<>rnth^4G}qI zoLZZgdx3U@)&CL&Xf9ArtG5`$OqfN#zvRE;6fw$ZEXyVN>kQQgyxN|CNEBe%;QuA~ zo#uqpG((4a*NgptnS;BYg_-mDYi(=~!;V|&B+j6ULN{5*IfuYpe?OyzbvnK^pI?ZC zE;XsLF%+#^j>>&24h`#s_@YCe4e1SOoYkqokvr=|2XY~s0v4BM+9+qfQ#?HjX`Q0{;AZeAIetz{!;rs4%qR*uMo-M~a3x8H|>qoXaz6-wH9 zz*htYlX;$!4`8PL_ZwqKztjhHaQAX$Rl1m`E`T9YdVt3sK%w%u4jzlB9|)3!b?1MG zcA?{l@lr{;g%#^slD#I(nYO?$Hth2XVT^9@@&~>-@XW6af#o;@A#AW@!=1tPoag+q zfm4OnL4Qrc>^Sg{bdso|;ky3?uV{Nx3{?}0GwiH1w0*=(j5=d$^Q;fCj))^7Cy0$Z z-sn#ny6sB1Z`QEs)kcC zOB6gt6G;#>6tlzd;s3M%7hf^boYupg4~n}Uj~y+%hCJWZsH_?@!y0n;sm9Tu_&Sy_ z&anuB7Gu~w>k;f;k4Xew3|4*uT$%}iGH@jf$vH-0X!ZR>Fyn;NDP?Dxf~6M&abyE+xmjsoNKWAq?MAa4lZYJTjZhK@-2%l>|_ zCX}gIV@3Tj6?;ZO&4?=r{>7tRI;(W$UmIcEC}CU}+VcbBNzVg8G#)OLHWU@FUO(7f zxcANqh02OkR;Q8FNevgMTbMY4*>#Cv9=fBsgns+EPuArUX2_0W?1u+7WCn#4t2tao z#xC#vf&jij;3fy$`x*(DzId%G`pZwSxC$)zu6)ZF2DFlPt$Mnj`hYgd98)SHsW+XG zt_45vPwz;wiI<`IZ)DuvIs0yz?TXIIs^aPI3mXWPfa$Fe3B^cRQ}pI#e{xr)O#~jp z3|qqv44l-Q3&X67q!7BJ;+wMAyY!SoEUf>An^0MW9WyfMtHx;_mn0|goSXfd*bpKf zdqwK5OTB1)rln@Wf#-DNiHnkNRS<}!A`1q{;NO0#;?f;erwW-GgzUM9{}Istm1ozX zQ(+($#CNrz2tL%)GKboZ3O@Nk-~oAblgKK8F8dzWAWEgyQu*-*qr`eE-yh1!HhWCE z#6y7@FEfD*2%tvt;3C>}6B&@jR#>DR`0J~luv+M#$EA0VCmmE~&qf>vRn8QOnQ&a< zYRryI=q5y#XxZT{Ex=_TvPXR%!o~FI;di~iIod&I-R0|f0LAz3^|5wC&!s1N`k&No z5n{&ZcDZ-GE%)w*=kVPL!>rxBzM(Df{Zc@`sckY&X!$7@hf=P zr-Hjs9CK$xaoJZP04t`BBfJ`1lfoYh(e9Td107!#hVG`a-f7%nogpHFkby7eY!-@$d5LX25D)F?zCzqaZoOg;V}Z0d7K=BS)rD^J+%N^CNRCK=;HLzs{3U zsqX=F?~KvAIkdZ{zn~k2JzMoM`{eQ@sEJyoB%v_5QdEgSa%jgPOe z=c!tIDf$D@W2@BuBTz`ABppn0g9VI-d#51BBBJOo zn_f+*GhQe=3Csh)>V)b_M>vRLGx3NZ6L~%5{E3f};?80ys1?UGVb{6q#uRm1T7lUu zyY8k_x8z|X+u`Q#|8|{k+Pq4wr0zBC688Sk{w^K^(VosN#eCk2VFj3Ks5#K^Ff9^4 zOq`)PYPWPsh9tI-9<0PkP+uC5ieb^7-mx`*L%Sp}dqU12R1N*{tU-#2t5TzeshgE7 z!RH7$k>S>=njum}dA}!3&9H1Kd-HZMp@9Z76v*9xNr!L5rnO}-7HQa{t64@aiIxz2 z=!Ivb6>PlhF6UNsncycg%jE%0bc1MAW*x0>4l&m?>Cn&mlB;N*zJC;mfFF3nXrHQe z^K@&QX@(4#mPZMl&4!1aW3#hKvPtDLqj7`wLYNk&ahjO9@gp9h@=kvsa>%)mT&!B= z@49s8Saw+hU)?5*#G+yNf+nLw{-W{^5r`Lk2FpxejcrCmbX#CS=jZ2Gl@Nl=&#+h% zZT4Au;wy>~EaKbeP8~T~hHilm8OZ(YH_FK3FKQpY6k;%;@EekN^e`k(@a9XrJOn~8 zz~jG017l69u&m_!Z*$qh?sf9@$z!d7Q3u=d1%+v6}2@1!A8MhAAE5j;o2YazaB;)QQy39m&U&^z9=t z%7wjw52Qjc@MPr>{p0^|-sEw|u0cq;snslQfyEy>N9{q@IfY-iK_$Tu>w|C^r|cqR zAMfcaLit%{@>c|#T95ucZ4^5Z_^EY!$&u`W7dAr_npV_7`3{2ohp2j4X%d{-G$cyV z{3XKq^?3W{x+ZGW&v=JF+Sr$v{9QIAi!EV+)1Q6GdE3QuwRxBF-j={tK21R zjX#8}iE9L)U%LsgxA7fLFzZ!U4VpA!f+Xp}B|iZ8-WI1lz07Jdgk^+D!qp!DWT$Ow zdt*aK?So-nBYQt0(c+a5Z$Ef(zI2ybskW93Z2{qsUsnV0QYL-NoZN>{Qb$@JN=r}!8HxkHQ&6;peEGPiQ znVN?z2{=`Xm5BJ4FCqc5cP%Xd8%3l`U%;+K$y`Ne!KbNZytBRA5OJ@(AJNX|$445g zGyzY(Pq;tn-NQqP9VjoF*_S(Oxv{nN#yXNZcK>bv@Db_J3Ye`Li4+UT(i){mN6{*= z5rId>w4ok49oWdh0G`Nhj!^ht-Zw)x&;8-DkI71?{ekAerutoWKjd_&HKcJP{4PaG zyrYwRmUKoAse5!lp z(4PyK$=l$RmtM|MN7J||#eF8J2RhK6Trvh<4a#*Pn(cYQy&1y=uJO}>QXB(tM89Ejqv`N)-v znr1IZHCOXRp#@nke$-S-gu}Y+K2fBZ6kT(OKXL2*X}OQ*sDrKK+b)9WLoZK;;7m4saOsPxq6YlAO|YMaLxw)F?S!1L>cAMq2o~+D!%US?iK&1fnd60nI6&KRRdlT z%k|$vU^1o5#i>IuB|z3`?Av+DX!jC#YKr&0E>^>)g??d$m) zIj%nf-qFDr_mM^8(1@iPC7jL8;;c0I_cys&vk(hLKy7*n)Z#(}{Af559>#~RJ?KuW zYZ80zg?Azxb78q(K6z7D%hlTcM8^OnTY#@frw*ZK1W(a@G~H>Ecc>Pu(Gw7J2`w>{ z;dk6@gjynx_yKv3W;i?>y|5Vk$DBno4(EHL$n{&$>=?RQ-i8j=;$vP&PuI zcz^ngIJ?|OXgeTo1#UP|QZ0orZtS6&;+1elwqhM$`gcJXOc9~^;*O_)DbKfp8j{mH zSw#yCQWb`uWt;$A(%=^~AiDd;Xe#;g4lt18`rc0ZWRg5jY_1Hw?*EYiPJC8DCljfe z6TF)>G@>>ru?uASizjEy@asrF+Vf`U-o82IZ#3$vmi<*mFay|;1rd}m`cII`K873v z)>+eA7mACF)H+nt(vG}cdM*CbwJVklK1F)QEaJIB6poGyfM28+h{xj_xK&`L7P+C+ zAN}g@I7BrZVPDf{t9EjI*2C+RI8a+hLL22dsHW%Ap|8qIU6~wwVnn76&2Z|8onU^c zSc&vn0?Jrk0m{}`yv1i;e%q~vuTv7%D|iG;i}=8d4Df{W%yyl5pnygL3FytOd#!V1 zHr#7J*W;CZxx=1bpK5BFrDdF?4Voxm^J=>g;V{Y=c?6y|_uMjJ*$^{j5~m@gQl8wD zYLaa1qV$hJ?(_ZaIOCkG!oFRUOV$MM-_W2Q_uUXdt%c%c;9>9Bibc+k~1{) z{Qco+lj4`?Uz1sjG;_H{R3(jUaQ235>!wCG0?;w6sv31@=Uh_H8K!UF3$^A*QYnvN z!-1DZ5|_QE(k^ImY#Lu<8d@`{G29%Gj>2`Zwy^8#XIS+T%T^C%i#UnL(9i$9yo$sM zMhT5@d#ptx@D@r5q+4d~{USmWew{eX9QLK-PI8&#L&1To9)7d34q(jFX^|^jMFRK_puU%oko@%ha;jV^m6QN(PY)6m@43?^e9>xMd1BO&af)gh05pmP{_6hW;fPsT zY^@sZu9|KhP%YL0+hO2y@|79*7;yT5PBZX+&7zN}e%<^Kr}x|ChoSQT%bzAkp@YOE zB*m#-sF_m{Lr{;5vbBKSLJOcNZ}kNLWhADp-=M8qhrZ%2uBU7qY9E6Iqm6VWod}=PKF8a3kM!OhwYdOd^C6?X)Ie8E}f*-;c18r~CG1#+!8(rtDkY9#wOB4?wLBEyl}!~+y|~_J2Lf-v zh5|Nu*Y!3X<}_e2MW5x8nx-IT6wP#lgh2FCU{oXzAKDXu7)#bXwIQ}g9Fyu`gFGWY-!>axqsi;+68uqK5winh7 zTLbgp);V_A$4ow!D=KmLY8wznF+}}K7inQn;==~T*v%KfkmO3@PF?qVE^*az_elOh zP;}3Is7GIJ;fuz^jMWi?52(H;a7N6F*}segCXP<%$n2oYX$MW+!^Z7%=MKb`nTLHp zv)*c2_k={{YSyPr?3Ban8SgNB&IzMPmgT8lZ7(TZ{2yIi&6ebWBXCteLZP zRDj7pAo!}*0%SBiB$ZkZev*jcL8{gx+`{tSzv*;OhE_&5vf1O6c&Qe+fH5twLWL)? zi&1$rsoWj8UVa(LT4sqKN_rK9n>sWursh4T@o)AB;?VxZwi!vLxbb%h6)aHs4)I%Z z6HSPiP_S{-+c91KZ*X?~zY5dCGT=EofZeFYGHD=qz=}&fpD;0)gNS}VvWeI`BZ)=2 zAn=si!-1t*IiKnGl{Ot3>Yl zPi$t1$!Yb@ghzdd2X3ySe_b@n-8zBPOtCE!sj@7f4<<8_l8+xb#=k(4_(~%Y@<==K zeS6E8XY%sU@eR%%sLbga@>K|4c3AyE6kb4o!;Q*FDAPzN7Z@5(xn1#%dJ2hea%Hd_ zc^gp2%9@_(LA_sKycf7+BAV;&+}+`ezW&_?{GiuaiP9Y-0E^KJE(uxn0;^da3Yzx^ z{LtXdF$M@Dpf&PNaRa;^F#UPo=YZMg*25Kkf!K=u!579V1UlP;+3=o=@i3RuEADzr z3=hAr@FYgJ{yWq=D=bl!G>>dv`Q+AL-8Iw;b)6EMVs=SgTmT^m4DRuT&bquEuRcMf zBzVc?=FPUD+zpId^@{687HiZ#5Wn_h$j!M%8YT-lnwdAKQYJjyE`QrkRuO?R&oCow z9HNi_x)&`$>VdRG%o`IRV=QU#0uZXW(#9vFW*p*(xoEeZ_y2O`TZhY;B}ro_FoPyK z>)42uPzl)_*>0(lkR};SS94~=R&gT(3}OyltfMyO@{^Sq(W8oTp>RHZW}i4f@Wy|$ z;%eHJQ(Dv&2fPUE+0!+MG;I8til?sphkO9T&gOz3;F933=JhMkf&*4MJY2Q+H4Z1D zG1Gg*egHDL>ffIaJVc1u{B6t~W9=`NfIUHvE@?8*q`*8J=3&GH3L=!p%Zg9oeN@y8 z@$rlu&AUc7K=8~rdOXI5!op_tpMZj8$)#&;DEwS!sj=3P=n_iF@NKDi{F(bBEZksD zlLV2^&65Cvn_G+ z)LZO528q<_12_fNfB|QYVc$8R*FNsFuNrEB0;)tfqf#3NmgS5TGqCSdu&6)$TdP!V z{`t+b{ww-|rg@?rWHQ>)u`&F9VN6NSQLN(#3P$Y9`KONUnh)joY%#X}WM>HGy77#Y zYAHZ(i#=_M=t@XB&0;CgRNp9Zgj*+?0!oM>841vppL#cJC4cx<*`22D2X$GpYYYRG zIwEIr?9vf>zh#0-RLU&nYpK2PmYXhAn z1MiP_lad!5Ek@XzL=h8Vl~d2jj^(>zju7SlGqU}ES+iN+lo<9P>+kTf{`v-K)G&|Y* z3c{vL8rfuU&e5WlX^4Vb){RBd;i-G%bTu%2&s($$Z~XrZO!*k<%tEEd9CYjrY=WG$ z`>zele?vt$tI-W?L_p}KI9hT8;~p8?pQ3G*)wBpJr*%l3-HG;Z#rez4Vc|6F+$#)?j_lSHOfPTW>!{2?zbP5N*~|h-b&3hKzopfmMNQYpLjO z3KG#6VlL`aY_g6{yL;IB`WK)at*C~Nf?fc037m6b)&Ic$H(&H(;!kz+70Z^`%E121 zQ8ag=Z~LNp_Ul||K*|94Qz?oWKl}Yd0rGw~gOIxYexXWst5vtn@g8{fT6i_|u=^TT z5TsCvbNBmjV)|&wTJXejXPq$(gQU46X23#c<%mc%vuYYa$_P>UBG%X|)Yv|G`9AOy zE8=y4S#svsfK(bf$(wcZN5Q6i{T;*BMCXdTo%Wym3*kp;u}+z9%LCHr$rEztAOBqA z0n+~z=^#uaGiJjWK!y9;#(X7sSfp~XLK)hKzXWs$rA1d?+UKfuq>YD}x+EafyZ!!l|M2g7Ukm^Pe0Z>$750lqx=P~1lup!3OG&d$01ocfC8iJB z)pXH&CMTJJd3f<-G(Z6eWKNw9Ke1`2U=O&p>ymi+tg=sdOsTc#Y-l(w=#SQFSf3%yFvCBMy1qUjsC zUz5~vd;Ux;bWDmm9piJ)(TXq}B$G}3b|SI|!guQ|S#@xw@t-M@1{EmEW@eCJaY@h@ z8YR@lCyeh|BWJC|RCyF|*sP$3$>Y9;Zg6)isgkn4`4UN+&MW}Bd9w#3=^ROWgA`y3cf z8<880?IUeJZ{1%2y-2`dr9j_d<$m0b%fPOG;M|+Tp3geRQ~P8me}4}VeMczXUUrWI z?vj`1fcNC;14%J=Fl*lnHlX97m4eNh=-=c1Ga%#L^!gF5hW=x4BI@6cCkOA=zgp=# zB8vJ?Cm3SkNKgV9l?cX!HO`vg+?dB*%zD^1I7Vj@w{dU5L#7gQ)AtF|qV8}c`mX6y!hl7SyP}zGxq$7lJvOK5OBKgHAP?l$MQ#6po5X z=1>HeUd8^=)Hk?B#C|)86DQx`&Yma1WD=DXIe!0V98N@CoTI7Q-LW;oG@uhOp;$-}+n@vp<05LV1lj-ThZF^YZ}L!cHPRnHDO|^fe;#ynh(#beXjx znpij@k+|LDvb(*D=#E}xzkBiyUVE8!f<F)=PR@rTRhj%A1FyCf*FON;`gScBx@8xis%chz0R7Bs; zJ^J#Dzz_@gaN}RyYj$5eVvT&Y@PLkW?B;=Wma+(7Ph*Yo(ZiYZ4z9Ok zrtnW!P@|-ji>E+pZesil;s~_p6V#jiIIWJGj?(#wa*EURII2}53K-m%u^Srl>}{@i zEV-pn@uJw47Rl7EB34)gy-R?{ph{ zq-x5EZA9pwL5rX__(brt45!(HSVgAd7+KI>kq=Ur1*}6g?!c{%;-dIKqX()42u722 zi;up8ko*9QliRiMbc0VV646cqWJ*_?ZDd!zp#e{j0G>)-U2h-_SNYw?1yDf&tDE#< z%OCSw)M?@3tNkC7rr7x|^U>qmg_M<&xbxm)m9*bnNdvP;USs_qcJb*Qx|V;6)P+#g?RlI1s+v7&YY6Wlap2 z{fHhF#+f^~=K~9DEefYYh0y_ZGe!?|%2y|N@uXqVLwltE(*npXdd|U~rtCnUdXQ9a zX3)6CnfYNuqZXLq$jrz_1JDrI@I@rGU(4op!Qq(9Y1rN7#mQqFcA!T1U45cV!#?i8 z4e4bjY#u8~nFVs9<{Dx7141V1Cgx|ER^;~oRpN?v0EgeY(Ei_{Vt0*9D-Q$P7?7h| z(L1O{P<(&}^zlE&+6Fv&UqKddzSk-_uquV z2o#=Suo=E3+}-Vv-D#q6&@jv}#dng4BjZ4`-Q!m6JQd4~S%SzUSTZ5v;c-hqNdH@Bg&e7xcZsSWmIe_LeLbzA5y2 zH?(qc3Xu?4z9>5O*H;3Yf&LkYvVdr1qBf9X)@|4Jt>QwR{d}~w9)>`blq$d>Gp(DQ z4|Ei;GmZ|+&59*Dps3^+`rsQZ5(X2&8wh5yf9yu z2&rH0#YnG6kZVA3OK3pQu-R*+QFZS@ZPc-9r?#AmwnZ3cMto|~+z30)A93bk3u1g# zm?$EC62L&)%ya`5gDdcK-#=XJhBSUz;CdaU1Xe%|EbfQ6&v*DIR}TARA`uLj^JUmW zk-YP^|rYs^ZJ zS{AG52g1uvio0wF*D|ivqD_M~NtY{SSJSSGvQFmCGlDcOrkN4A4ks7o&m6TfwkJX1 z3F0po;gtIm(e=mUSnoB8LpFc;pBHT#H_nQ0Gp5F_m0-!e)Qxjn%w#vGWN?b#)UBfF zmKF*->@TH|xwg@bI7yfkA2*0)iHOd|X(uSXWF;55+s8Ku+#GP2hZ@5h!Nj)|8e;~ zbN24{m^iWfT8*jl-r<^?rUD-&Yy|TJmPBlo4X`wmMWz@Rsune%g4jNI##tyj-7jhQ z$qUMoY;+J_z6wr5Ee&}_@S`_kOLTy92rwfCye2Fgu!Oq_!fR~KsugV4_wYH`h__ob z@g{s2T(w;Avin$9%)CUDu3Dhc15^D%(ST)lKvB(OA#D2l(N}GBeUvumCZ7IJ8tvfI zs@?EWC{Ai|1%e-uPsD=C+Sr9K;7_Mqj92{15dvBf0gj~Lw!t6XfS9|@2yxO3dIl2n zRPJ!Paen{R7Jt(0Pvg<5N#l@7Y611K`;$F(#X(~z=1+vQkmw@DrXPd!`@HcVvk8R! zJR8pY^+xy`8>smtMwbs=8W94W!@~GenIyky84k5svk^sYUp8nPGgDXWW_wI}o9kR`$=K1APmY{zh!xZr4|a^<Wpc^L5!_OSu z!pgI7mO@J=gPfc^)?{3rqmMt#UBqt1*w@>XhZ+P#!Mx6bep@?vKO+Id%)TV4^sG3| zkZH7J3nyOTAfXa1Kzi^G0oK%QaO>XxnK&f4abvQ)yuBGLCD*O9!4l|R`v5Mdu&4<; zUwQ_Mf~16k=Xpq?54_17b&rD;A%A8sqt`5=Qd3C`IEk{9EY+<)aQsd;b@;5xt|A*C2F|*$j%N zkTw@yXyiWm9-lATgRSAyIkg|PJ8mX0xGpqk;{vO`AJ>&AH+3B{pL#zH`EU zt9MlKH`ImH(mGD&&+5{|nnn?A7aX1%Pzfzv1n~XjqS4Gdu$^Qn{kD0GM3DGpDWKbfU94` z;v(~vFq1IZP##!jl0Dfll5SK{4y>-G7Jz&aJy(-5CJU1Ja*hm5D=)T+dJdJ#OsDcv>V~W|L3geEr znA7U&^Xp1FKZm+|{sc%Jq5!h*RT!b&f^mbk5nH-0r7{;s@hm{eWCa?UQ^K?R{|R#K zg^~xT!_Rl0{H~I^G$HKx_&}`XdRG^hq+|&Q$`r82hOWQ=a82wik~mgQsH) z;xOpy6f1_!orSytf2vqU;eU7~4s+_8XDp>dk6aFqj69IB#~eDHZ)F_}`52lnZD#f< zo|559H3w~-8KR3Ff>&1C+TnXlCLqp}XG4_+ zSxiq}ufC0mN2yupV559O81|?vQ|-!ZV*akLH3%VrYCXOslu%i=bY7!!>7-}It;sBA z3%a>}3}&C0i<7r+zVrx0*KK*zl^<|&HCI3DK>oCRexEiqFlnN#$2zid>i(oJ)vSk9 zXk~KcQ|Dx8U;xa@W+9XWt1#%p*w4k$xu<&sX!qxp9>vME^hn)2$DC@iLnh%yY~=F5 z7KDU0fyvc!mZ6;_`hy7bNn#D^t~l&!V{gdD z&Q2vfZ(I4on@uKb5UbhJ(fu*6jWh4J>m(5CJs*8EG*~sqfzP0KSHKiOtE*%eT%AP5 zQo1&Gzjy4ZH0vHJOE9K|%%Y_H0|l`3I9>U=3atDb7t^zpkZ>GOxB=3c^WY9fS=kQ@ zg$$z#l;5rP$ovI=RU#!WS)<`0c>s`!$Cp|6mM?({-hD(M&im&Z4A4II z_wm>jZ1O5xre8|flv80T!h}d%xiOY>)RllE8h3a7UwNWfDz6WfO1Fl#0cIwR7G{Xn z&+$KS06X=3zou-!#CW2MKC*In>RONHwS{Bt;Cj?Wj1PKwc{(GMNj)$c2uUUKP81Xn z*aq^#P1=6$M|G|#bE=SO_0N|O_Tw0sKK;b{yXh;PS6s&U+Zv077!|r3n*~M;rhUxL zP<^WQE}x4G-frZTO_ErO`^3B2;9MX>Q+NtJu#Uw|*?uKGaNC2IV#--uP*hC|uAjs1 z156lD`lw}88gZ`v;0s17fBTYW$H({Hwx+m;OMj6_%Mkl4kcE1(Y|r^^1z6N!TP1c6 zZ7TrlLnva#iF1-HOjQ$@eMe?lAbjgko)Ajo6J+Ajqu-1l;F{LD2+z}o>7ZQ04$^Wq zCQ*a2PvU+eNa!s3s%Ule##3jsR{d$9{OG=34!9@+E`7NT5yS;nx&U_Dy__Bp|E*}C0<@&$z>|GNW7#KLV=+&&*r(9qpOE6TM@)Hk! zcpKk%>}eIOxTKWI(~`z!p4pIC_YpnTZ4W_vhGq__DK63>SW#wuOIIvOo3u!?`C`gy z2&CZ{cg7pLtC_=IeLtQ<0uBM-bJQbo{UI_y8a3$oJK_;ZeVBW{wF=@4f~Bs+2n3bt zqrZxta^*_Dh0LM;)y}s z+kLyvDiS498nu&UAnt3)z3=*!n)G9`@GqW!8_?~uP_2?4DDMlAJqZiStVwh;b?QUS z;5pq7aF}i6%P-sNX~|wI81^mKrf7*q$Yu}6361uzA4h|H>X$YjA0Hz}80Yb^yx0E! z>Q}w-3XZ!!|AfH7Sg_UC4S)C3dF0Z=7Lkd-)<>Wyw@~L=lCF80y^=-^6m2mfVY4`4 z$rb+r+3Ju#C%-)~AX)|}4q@|w0}^|hc5>@wxhBNe8r>naZ8#Lv6HxRt6N zybnm1} za{JZ>B9l0Pa{OhjH;Uw@L+(bhzB+k1vW8i(N~J)O(I}chLm!DX0}!5F`_KK~Q*ewW zRJPB~P#re>ezHFiBcNM3S0=*10uki`KgNn=d^JC&tKQe=z7h`&UI_`#=h3&4FP7#sv!u*3lef#QI z{c*F$#+cygC!XK8-fmGf!FshE1}tsvl)P`-FgN3HEjOf&M~7Gt6~W$#C)`}W`!DUj z&m_>Pv+R9<@l{tJ5TFprt?20g4l#VYN`2@fTi?3e0`JelI;^)3p!q+Dx$2vClLXuX zkUTq>2=R&OZRGUBSz49SBbai2etYbfek>j>D zIiUQKhmy7^v#0QdYkJ_5$7-Ir<;k@xTwaa4ng6<^*iwxOw%j2vMcyzj+j4rH^ipOk z(rLvIdtD-!()V3o*R%3@A1Zth#^jYXD^|M{B#E&=!vCG7xc@B!*PKBWZ=GzC=US7h zEqTq>t3y+x2s*<;dKMedS<@=e?KImFU2B;DoiMBUquKm4bh6D6fYjf2z57Ptz0dDu z^*vX=L#qAXaei`#UZXb9IyeyrwVLBf>a7GA)bSHWoUl)^b@N~!;YbS?&3H$UI6kfO z>;tF^z(4;EkU$pCodk0W1GZl`@lWYMU^~z@eV=WM_yy~XICa1$eJx5@;sWV;u-)K| z0;;(SujNLM&7YGSzqTjw{aaSV`Mjjcdlu+Q4dha__{Jc5EcPXA7AE8_>;tDGI21w7 zX^*Vrt|S>sSna9S-yGP`pOqvoLWR#Re2~1A_{RcKT#f=}8tvThT0`M#6Ra}fDmhK2 z!5F;3+pt?N(M-KK(#t$?a%)@1VR*(`lCMUL5%nb7^Z=;Z=(4$X+p$tFmZD-s@u15l zGa8s^U$D2?a{js zPllj`S#+N_^dmZXgB~oHLK@j76H_!};VUo%iCDGkX z(e`7C_gsGvf0Qg63-J)(O90xuBKr7mmjmqy&PKQyFMx+)1!BL2mi|Io^bkEWY^&x8 z{}mHp8YNyFBw1X~KuISUYL-wZgD1*Dgk|7>`#vu6tA7)scy6l43=8PYMIGtK2z5An zof#(DcP@hu)#1-!!1?sM)X*tEG>DA=jr(}ll_R&&;xyjW<$G=imtErycOtAn{d~Q{ zcQCUs6m@fW;a`*LSvvv$uH2=}&ko~WgMYCZ0%62K-+7*OZ6?E{=_4ch5ppUrf7p$a+&hiBL`5%N?sRLU%$mImO5j&wt8_pr^H4JW{*#khg z2T1iW0mF4GoSduQ5t$lyA3(o7%*B$BFrkb96T+!np#|>)|9hj#tGkKZhF__8A$n4| z@QDnPn%Jhq_Y`Gv!}z;y#R~W?*z-8!WQ&DV#}PcC>>^5|7c|ci8|j{KA{K#c{6cy* z>Z-v3t61~e|0Jq#O<*W18XVnX_{ZXDBR2Lw@pj~}grd~wR{tSGMGrQqGztPq=unOg z*dHgGJF-Y8#Wv}pE6s4r0N;P!0k0XLS(SvX&2tr(6RHpwtQ;56+ho-dx4nX8vH%(@ z|M)%v)uXQl-#>{E@@RB%4B6$XqU{gq?ydB`eM~WG<`*NcaQ_|=tr%_6jgSJ=LEPp9 z(O^s=d;oe^mvAd~{rQsxL6o>2%h@mq3iY$0U)=MvH=0ir*E?`91-|-)8B`bSX9Yo-!ys0Ajv(NHkU7DUsgU5# zTMC9T4rYnO2&O2WWspolY+e5%sGwHp6v!=uK2UrAJtl#+b|VSOs=rWxU>=sjux8TA zB>g%#YIT3>Y7N>Zz8_a0}9=4lghQZfP@{S-Io^;%}o^Mv7+pR|JgWEXSRR|gRbej zUHRekLQdV|>Z&%4G$!d;{&~ZuT=ymA?NT8#MY{wm>{^k-9f4UEYQz~n+wvyvJNM~s ztQaQUJvTx$NW{0>U8gb3ZUYt~dc5?tWW{zZ_sn-`KEk37QC+nQ+dAth@p|0-!vs6q zHrdE9@gW|`c9TGRz5>>dbSa0L8Zjegf%{Xrhvc+`^9yb?S5YiCMzbmkjp-+I4Sikj z&+k#MPI2_eD#{r;PW{U_P4A~qW942|x8?wIYG`;=RMb*O;jIF{nl{h;JGDZ&6w^N(=!khC5%dLTRGh3GJJu1zxeJS7bonOYiHez}xG_JK0P1`>p>@7@40ksB%^&ffms|M{vNFQzB7((~-hUE@x~(uA|z_ z>r{q_oP9dg#43&@dJbyGb@X>UxlIHF2L!u%H$;Uz`O1UnC(EYdxydz8A?B0o9{5vG zyYpGWaRR>p7B!4vx;iNlSr$R6;7|G#$p<|)*nTha9-lW*cj^1D8vbmk%9G@}(iFvO zfV6kWLq(;LMgu32kS~+i(X@COTvwrsAa&aIaKiH}5Fz9CZLdgm+R=XdHp5d5pihYGH6T^WqF z8zxEaG+0QTHx!v#Ao(<6>W$WJ0ZEV%vNPJx|01uG%@LpR^=QzVz@nbfl zB`~QWwe&n5JzliG$Q1u|2gpGgw9{|cvzp&hF9n$LO9;u55A;t{jG0*t-kZSKvG^*-+(i~6lDW_3N@ZD)!k zP9(i1QM{XHmL=o$v1y)bS-n;mP6@hjw50}8->XN9Z%qufzaVwo)<+<&5=b7d+(y`^ z0tBxjs9@&}o4qH6#$6+0agND;s-xH1H|Xz;@b+#an0ie)=^H+mgON=WO8lghYkOw3 zN;jfiQuyrq%M94Cktj(gsl$sPV5u)!{q{AX7=C9SQxy_Jn(IKlq{2rSzD$r2-hW1(|v%4EMpg1 z1@`38MGK)huWxKXLvSz5GC1A2HBGIFnhR(?bO;_stZ62pgo)WPTI6`no!|SjN_#!; zp>)2#@u7*|I9V^%ToCf?v!u%_FR)S9kQhQjrG*Fdh=+i4?#cJtbwB(F84PhW>#`Az zaIao45~d)+-Yjp}zTzhYTL=p(h9{icP*5u<8Dm6}X5r3}JrL|uznpjB>8T^9H+4;X zJcqfnrJPByrU;L-R2neg*M!A^Zgx?|3a8^PTD>BHA8zP?S%TTePvl&`@@Tb>!PfCc z;FXP9w;fzo@#oY{MbnSIGDU!K%7r=~S)C13rxwaCgAqajB;9kuhVbD1vW~cS&!kVH zM!aGgviKOS6}YK_&JaHCEn=Z@1N-uU((&P_?YqO}tddaAva-vI|J(jMw1^SF=>%qT zW$Zdlgvs!G^N_Mcx4YA(4Qte+EDz;QkIP!i5?l|DW+{ynKReEDEHXP5q;Iwc-!d`3 zwV3$sgiqO+NTS0W$t|C|Cloq&EXq^hPd)vZ-N?q;v=cPk1Ttis{r@xH1KgWX0X@T@ z{deIE>TnY<{n$_OT|(uBd(f^yVA9bLob)X7Pi;aYsOCRInNE#hnO#CI9?3*;uXm>m zfqVS*lGXRaC7DLLIdjn*ZjX3&LDR@$E2#x+BBq~N9~*E%dE$ZGxD9wc0?VcGcAs;G z!6yE()eBk3ebe(t>8InJu6yI?o|i4s=QTKh z)Gw3K>siB!00l5&wQYdB1eN5NU*1HeLz?aM9{-dv7FLq6|s?;4~5bTrRXIW#h1)bhZQ-% zYWPd{TmPoj*Oiye3_|oBTY_aCEg|s(v<-A&Hgjkn#?veK324*$Fa~!JpMt<%You^N z0Gs&oJ`O({P0IAIc?e)m$K~MHTdq~@^nL*WB-p^J#=rYN=L5XA(~UP2e_)hNt_7m+ z<}$-Do7olq$f)6)UT(pY8SxY3(>ntOXv%lw5st<8$m9kPs~LF=v_9bv8g)KdE{msx zQ?-qj^h$^Y{2>e zXN5{a83hv`7$3x?Sdzr{X+_Y?Y%ob>)I#xV?CKri&tO#HhCY(N}jD$ecISA`bjo-W{Y>%%2l-*($h*)HNyri|gMM{1Q>*@+|m@oATlG(Oa9D zl%0q9eW{ziLMTRAAPp2_wZ&o)>>dzrvhcmHyQVIv#OVsIjA=91La(xm)a@F0#cv!M z11yVMLvNfL68|q3;PBgelnUXj<0QWw*XK-0tec=o{N~DgDwG6gQCa9+j(|Z!gAe8t z$A~tx&X89~7f-G57CKP=itP_r0`vpdpThy6so*mIBliHSR|13n_I0BU5FETvuf z?ZX?UMN;9Tfx?*TTRJ(zl(0+e2pm6j?uu{?sT&m^Ki>k&Q~Ovmxw_Fk$Dfg(~-iHy56~47|!^>#{IB2H{P3XRlhgQ zNG1LM0f)eeK%I0t*R)&)IWD|Ap!VmUA}l$Hf9CB$N42v?vaCHlyni+b_2@NY8@%*T zUoxd~bC`q=8{^p=FJVUzCHWy`fqeg87}=}Ai^`!Iqr&rKx^pBsrNHx}L9ea=<*k@` z^ALvX4i6P%KX2p3KM5UEr-ej1_KdfOusB z^Y~UWy&f18Km0yFbmJ>C*jzUD>&}|iz3j28R`QB$`~+!MiePWPJhMQiVd-{LK!FSaKYAZUY8<3Bz^W)b{cpso$LvXI<98$xEjjWh{ z4RgT)R7{u2`Sb&ALdXN|M}Sq&!{rd!t1m^x(3H?SGLWf;4A_*kN-oDh_@`Ji^^Kaa zLhr{?KVM#4%=Q2rpI8=TM_zNFPQq9AEe699Y8G+IeqG42Sp^K>7p2dv>bHrk z8wtp5VnmiPp6QnpG=3j3%Kh^rl{PRNjzR`hixf>w=kcC1G4iFcH(ihU?m4^a49TUL3^r@T~@DbFiBSmC?L7ry>bVBt@@(WVHMfKo+)3AU4KXo%s$R}>@ z1>B&NHmX`2?R;&V%Fbt=LEp%*ge<>`a5XMx@d~%(hh`e>F7Dy7q=|tG6Hqs>EI-FT zB~V`j)<;YPDc3;9GZTHF>3)d)i2h{8j||1%+A7|Zlt=Fjq-^I^eT_z)qHjPMQ=i0{ z{=q|V47hYROQ_b=Xj>OvR=GoLMjl9#RZNYH7OjH+;iVQrpf~`WbsWyvQl@W>J zRA>pj$)?Jnj)?oH`)7wz({7;Bc*RaWVU4n-iV{!KDWG~9JZ!<(yxhzZby183UyqH+ z@%z8&y>=6N7N{_G$cK=ab_tOqGng`7OmO-0UzcYomOQ*%E6si9{! zJdg3C=eu4`*V<`~fkUkjaqS9OjS#UDca9@>7GNV#vut}&qrJUl9Q)rh=l6;QXemRq zsttgt&~Rr6_}GmT+RSw5>>=xXMDw{{`|k04h8wnn@!Us>cFnWi?i&T5{Qp|yB}-CZ zz+X8@n>i1x+&tYP00SbJmD4?@Ki@W@+6_m4CZI-!sa76mU$KCsXJc`je)o{aFDYKo zrKpTF*DN?&Z=7UL^Bl80LueJC=Y&8VXONnw#8Mg_IT~e>E%`!+0m;g5%jIq7Zj=>$d@U^4yfFB(ZQ+X zh3X4O|B{UkCOKfia`PNx$trNFIFwX3hLGlH_l3eVDVp@F&+if&He43geQz3>K&b_- z((FFx2Jyos;YzAd5eRwoAF|jjTVOGyydbPmzhsUM0|#_9ADtXH;T)lqbw4neFu`+h z_>BZK7#y73yV3w6CqZHqweYJ}5yH$ZNFPvp^H%Fkj{ro|}HBOCj+KN^=IwZZrG zAWosKDmQ(x;*Vn)YIg;eGn_-G;LUE%AcSldxqrWGrDa+B25C3ZxuJsyZ@0jEzr_jD zBn6D2vm!A=>OH)>#5LK~oTlbWTn^k|ky+jv_PO`GD|EY%JSLaBxZo^>a+^M9-hadE zs`S4BJw0BB+Y`>#SltG9;XOO;DJ;B=bE4bxkCpPk8K)+K$Mzr^-5LwAeuDhd22=?A z2N+0>$-4wq%q401(X6>sDk&P}Jqnrzb62s|Q-wS2`z=~d4(9nQq=h1G!o)+{ZU<2< z#nYHeOhkq-w`px`7PaIPbxBYmFmKJD6Vmhix>$U(1Aq0IxnvW9kNF{<}0}X45a_sT1F|FVOb0F zXD^rP)Mh$XUv|P*lj>tKKaYsVSCT9jKwe^v*5@&xEeWaYIP*}%FIZvvSSL@whoF6q z=1t;Eb*z79l0z5xH2y^gEBi$rW={a7syQqX79Qa^dn0#~;hM~b2`(sL4;#j0xm#CX zqh^piLKIskw3RV|Ho+sqtL6&=6t-VSb1R&D%rF+=T^q?2lho8oF^N08HW4K<&5z-W zFHxgh&&{!3q<KbG7`I??HEjXccQRgb$*Q0BU1E1J9~zK^X{nP4CM}jOu^?(pc~+w$;GsS zTjOd}{v5i-d&e2GNy8$im?pe_o`WOp>2U93LKfR#$NEaB8`dBc#DO~p%-xQ?d^TwF zn7!Snpc=n(;F8j~w{>{ErkdwBAi=|8)+eOVq=zr|++h0~7sTF^fhG=hf_~fJ45DzN zN4);-QTdg5_w)jocj;9DG}_CPB^R2Go9EXr$LV*rP&r>vvy09TKLff*g!d!Mx2K2q z!#<;0?Yw^d4&B=_lAVygH?2r49~!adevC>XuYlRXpF1ohReEI~NX_l){Rg^-7Qc1M z41t;rhP(yh2PI)`g+cFP9<+4^ygBGX5pr;3W(IMRe8~4w79v+i){~tbORixwH0@8E zm1Zq)bSF+nq~x?`N;#_#RqsGsptm9nCj1ddeE|&J%SA|m3?O65@CvIUBAO%tFHJWe zsoxvtR0z=HWa3b?e!4Rh$^GP_wnVgv@~Z#5RYgDUhsw}^{&_Mi)Z(rH_0?4Zw+a+p zE-rhtdu`^y!1A-g$nf7hWus;7x4>(AR)5;GQb?1X&;GEUG2UFGpA=%OO(m@7xhAWf znQ%HaH3cyQsLWGO+CMi^&**5DRpl*?vT1%GsC}-CQ+NO4VS}?Ava1~S=u;(u*3n!h z3+03@5k3Rs?GW$p?HzULQL(pWjDPgh(%Gr`&P7`cL@t)V-T}%#DKY`Ayf|A;INfFD znr72_qZU2uT6vxi6TKra#wu<=_{f%HDap>vxxN{ghmP$jEG+CElQV%O`}?>}E?Z z*H|8i9@@yct3}a%5TEeYeYLn2&Q&1W6Kg z&#N|rgf$i})K>qw*aR*AE&Tvi*x|kkA?t`+8Nk2CI_EGLN&X7&V!f%g$)ic;1JgZ>0( zv4gd2vH!aVIp}&L7kXeleHriO#d*~bk)2aX$RF+Ph*;XrGnqFGDN^Vt$;N+8|JZA+ zq4o%6)Hs%fe}Qz)UGcSv$lVr&9JDl;;h#rvpuT`Q&yChPb{h~_hSJP5mGa%%9pJ>J?IWF!%@&GVwfBMD{1fK`O3E*I}Dk~GspavR*OGgL?ikkYO zYXkfv6hM)GJnSL(4=QM_asnPBa)gV6KUAD*+UpK zG`W~}0A2(lKY>T;b1g6}dV2ms{(DC%UlWx$0{rSt5B}|=Bcw^5*VoUU_`;ts5qxgE ze2L@WQ~u6~ssAOuW3n{iH=cFoCN`xfuZKI|&FEqI*dW3j!49zi`)()`semqHBI2^PYpdKX)5Ya*S zmB;wO)!R4gg;isatKS#7_CmI$OcFa-djc;_p`^LJz2Cay>RI&P)IMVV6iVGmFn}c5 zH-*`2y{O9QA@+e*Di_I>*OI9b=QBA*+xtDZ=Y3N*zcSw~g~XEAu3`72!KunUAKxy{kjpgu##mQXQ4**3Cm{wm9g zdu{}CkN|J{rO?}{KRF-i2j@z4;`pJ>z!aUc zuUj7M=P=$LvS##m$nSHlL#_7qQoW_uyWE-udn1qywh_;0Y*)w%sfXgui)Z|Rx<*BD z>dI?etNp-hT+qUggH-1L82_8DZV2U7ec14b_(LiqL6fhLPnKZCVIl+ z7xF377`AtUi2v6CXYHZknkCV&+60gY$c;DKnuI3k923B9F*={mXaGhGsg#DsI@&`a z=#x##pKrmy0Ar?8OjAK8;b88^t*gK)3-&Bv6KR?ZzeyLf=&^OdA+%0R)!0{4rQ2Jp9%L!4mhE!H_Os? z&e=U`zbtZY&{Yb`nDBeK#uzjOm5nE4qt=k3n^OR6Iy{_jf$5j?VzI)E!4y=m(PVJO z)byqO(|G)Bd5t(Qur1d{*_PfOjVR`cW|>dW=y$5q8I;I|(?R5A$foqy$O*85Zx@Jy zeoqL+lYits@ydkHUed!>rHFg7r9YrHil9fPQY?{d_*|256K5c;Aok?qbK^nrA_STCB(m}@Vqu0?Xd!YqFwgzjTm&+l1 zQzT1BglCMbyD}AI+W6 zZwiMpVKxvTe||>Jh`2K%)?u-x*OYI#<%cW!x=jDsBLe)&T@W zzeNpbLUEOF>WHtnQ29#J=6NGVEZw`iMT(7pM^rx$FK8*i8K`GAj~XUMGT3kLrt_n@ zwN+JUrL4^L0Y=1u2lw*T_vz+WRaX~tamB@5iO@$tR}|!$h4$7)_=!86US%0BkHffy z_v`WMHNkhlfmD!;<>0=}k+hIwaP#U)wR&N;LtkRfPYPRcHTyk>XX{@>6*!iv8hD>eqePyHCwxZU!pR#)5=(h+kHr?4w zTPJ%c{R>T>AFlT)oiT+8oS%yMPMiDwc8f#Sg6lZ;6P|SQ3(5x-x(1^2DW>7_vs~0^ z3(b|uz~k!SFZl2=gE7^W1wWsVidD0azz!9R{+$ zmBZ9uU;Z#J5_2<+@zg2pZmcXkw0FCartu3o_{6e??tlfLm)VVMk3IR7wj*r=UMpNW9I^WfJs>f>Qx zTsUsP&Hhi7r}uN?{J4Luj-EZ0LGE$|px287CIDxRpK4aE6=mGOo9tY%Kc~mqcZpdX z7$Y&;*5>6{&_>s*k5!}8N2z9$p)E~pIc=zAq*4e@J*bgK2a_^4LGT}ExDu$rxHT}$ z5@pQ`aNp3iD;9`oSZp~Hs})MV0BaQ89waY`xgZhIN_ob??_Nmr8mC2tF6M23LWw3B@Hr5`MfKV~9>Fd^CV)I~uqm+?U!J-`*p#zf z5c=Rsal5GkSZ5v%+|TC}CstBOcePK}YTjYT~622e+Bj2~eWHOBu&R?>E|q|By*T zLl2U(=RYCNLTk?JK^}bq*cDtI7$QYa%jpUHo^BXA-=1uMYiO6Jyi3coE7J3uT>)4; zT>?1c5ifEdx>BwmBu>yP^e4R|aLg`5qrrp6GPrjqb4&}h1Dq7$IA8}2sXX9*Sy^{z zt~&^~b3M;|@=3}0v48RfAn;+0!M zt%U{rSjp1S<&P54oX63K)2Fu>!I&=PvV?{0LIK4xB5nLRI22~;2d=6#5;e^KI4Diy zAGfw@?i+QC%XyL?CHd4Rx_uIa)EWkg!&m8I3Nu+P*wVjEj_OKe82+r&;LxX=<8}Wh zLw@>*U^}Tmt0t~eh#%p?_U{LeU<7Ei8}4_y7#!_AvaY*I<)A5ZenHTfw862DIn2=QADDVvRE9rY-w%hPv>(5lxUYB+QSazR5{tAK{Q zovdcgH{D4j?U9NEB%K)Ug1WGM8;rsGd31kl>F$2IUBUuG<4C|($DZW4ReT+^mC@>r+fZ`;2J8yr7&@Q){qDwrTFvf>ff>!rP%jSfxhv)8j#} zNyRIfN4&-&>pZt%*pq3g9JgWc&#KKUWacTBlahy<9kj~>>riyqt3E={Mk!1wz~CtW z2Tja|3Ca{BgtB7~y$CSj2ReZNdeVu^Cc^Hc*1>wqso&+P`vf!UwCbwP;=24;fA~K; z@}FJq#8qEhuxK&N7_s!9``v#w!P@DgIw5 zE;Ebl^hHc1IH4Gb=Z=SJ5cb>x^|(xlER>Gdt?I*W&=APk;~NFha-2dWDW|pw?FPm8 zDC$J$D;99e#RCIX9%avueB}%yf&f+!yE#%bz3Aoh9STVhH1Sam;)G|>T zjI$C&2Pi25T zE`tjGz+_I~8sm$#%YF&YZ`W#C8T!WFH1HcpM6iPq zs}wkU5E?z+4V=JGmBxY9`oxjs(}Kk0k>UP%;nP_+pf_pF2Lmqlg{BllV8 zoAA1)9s r{DMdOe^g!KA(XrUq|qbv(#D<>H0ul>5D32TJ0OQ+x5s$3dTL>_m&!1 z{J4Y8q%?^>7h;VllR?{LQfC=h-u(U7IlCT~qvUmM_$DCLp7)*4Z=}Q z5w^Gvlr(dgDp}@Qh&H0H=1Yz2;xs$;;zTng{$RInB|LbYc%)m{xMqMS9CPRzIN}jr z#`x#_7FcL^$ZaedHO4m)%%zf1O@Y)K6%|%*oSW8a ze|!5SM&g@f4|Lb4nfpA}TBhuz#sCo5sb|ENO+NJ@<&^dpvbtXN!f+i{=uQG7CPHG8 zh9NeNdmA)d5C-7Q5<7&9hnI@bhj4t0l&uJ56VO@=n~1DYNM`~K!{N?ZqE;Nk4niWP zk%?|{*dQM(Os5-gILr)@4Cs<%W+q3VdE>ulqFmBW>}WnVkE0V$z+T$^B?#nei4fCy zygUGG3Easo$7FAOMceA@Kxu`QA1*s`ZyQat+0TnEr~Wa#j^-ezLJ=vtNG@EG zM2R5Ajh}2DqW0qhXfLzKT!Z4Y(9v=6>3Laqho~12s7mSJY_fcgSeUF{gBt9X`xj7N z{_)nFj*1X6c+V-;_SiDL8f4qWf_&2on)xP|gk4nzwo&E@+qr}xg2P7+4NP}cJdii))mbt#gxgsm5qt#%ewl!0BLJ!DOIDpq!`BAjEk$pDsiLM)W`u_d7 zKC~o2r96)lf8JmNj%_685=-ztUVsl$8*s7kz@Hnjt9Y)9jGKI!&f#@v6k$$kjufiEBd|W=fL-+8X9Bs)(OTAgp zyHcyAjBlT%K*$4;AA6mx**YqFF)IX2C($Y9gwymxg9Y=cnZqp35O=V`LIART?S5J| zwIJXF<}eS;wB>V{Iyp9_c+o!{%=0AML-3w;v&9c!v{;{S31?!PaCsFngipU$^> zj1J}kDSBD1+)`?i3+M+;Sfz;R(k6--T`cQEd6+UsZINkYD!i{Qo9~~i*_k6LweIMq zgg`gX`VM^!w_i9#HO65A1k?;h8)|{MsBC_ll;T+d*+vYQOo0ZjQXl9d`Y|QXDtnCb z?!4ki*NocCP3iB)Pf-CeVhN+^8N3}Vl2DR@`&rSA*WS|;O~e0NVpp2jSQE32M#a`Y zW19u)esLmzc*&}4_nJWv3DRL=kg5NOm#rKc)vxt>DFhZ!vRuc!}|}U?5*2Jp;2cf!a_$aE|quqE~KI3*MScL|K6eP}}6uDo}-8aB$> z%&GrD=|B=Bb#n@bUinRhjR&IT7vaK=&Z6lXCcS-r)87QeJuc-SP;D5lvbBfr1W%^) zhq*oI+xl#(?mvtcuY{D)DS{p-VhxWv9g83Z{1GVZ5zoC$LJa$y)lG-4H^Q#xqmMUm zzKh-4uDst=Xw|sJez=8FXAkYjB=KDSw0f}w8i8-@y@#&7eSJY^h%j9|@gqDX(c(Et z_DxYiO_K-r-lLFBfuT*Q4NkU+C5}#@QRm_C^&!+Wi2*jjXpOjDFE?SPKPlgARoPWT zCxzwEwdaed<7RFJfaQEQenEtD^#Z)Y14EFp7FVQ+AvS)rq}aKY+e~k=Ewk*1m0aR} zx-RT+gB=o&CmI7a4Em&R549M<(el>TRu7uZQ5G2Mrl{aW4YGy_Bz7GoP$T*(Da;*; z5r$F>?$mabSU0c}#7K5|IL^MlelmEyP)(PA^+S90Gpwe-vJ5P>{Q;g1jvrtTfEmoF zW2!Z%W+g_|pp=*c>nNP4C;2M>2=Tgy6@eTd1L&pic&c1h9aaU35juIeiR%n$G>S4G zSZ3rU$@|O2iJO({$ht|UZ|fZQ3+SQ zA9|L}%dZfQ&DTD^P6duy7`wezOOZwpqhNIzqj}sCH$shd`b2*Z)Y^<`-Y?LBsr~lo#U}W91)%*Jna% zV?#WfRy2$vA1M|DHQ*#vj5ynXbc5-@TBeW0adg$c%O>xb6>EineI>KjGD7l>LcI4y z08$uWcR%^VeCz&Sg8!O!DuEsk{H)?3l|G{$J@kxm%x1dGT5b%;Dv+ zD3>h7mK-_G(&E`)d*lED2jAM(BIO6sB<6D3Mu~AxoV3h;mPrKU zFdQz-6*!>zeUOI6_FTCTP^&}&=E}-0w!)PDoVs6}t$j^4FM9rvnHmjkS6+MfWFhvq z45{xY>pf=IHApeVE&v5xJBVARJ72cJg+3C~Tmw;9Z$Y%4A(*v!uEyn9^IPe z(<8pkv<%5Da_eF-&SAWFNNB~!bx@^b6iQVJTH_N#H8s4_f)xm)5q17=O_iuVj^qEL>a2q5>Y^lk zad(2dySo#d;10pv9fG^NyL)h#1Sfc~;O_43Fz27Dd6+5+9(bUNI`{0gdwt#Q7Kh3i zwvL?Vdj(4@;2Scnwp4>HqDK-%Nn)q*ZEoy^-^-zt=vP;*eS1!hb{b{tD&ennWPn%w z-m@%reEZ)=Eyv~P@%6}^pHFX2CmN6%0oJ5v(dG)+roBDwqC^x8gB zc%T>f)gej{EivT&JFum9+fiIE9avpJf{?_MNL-B&lNqamTX|aYppc`5Hkcu8cX%X+ ze|US=X7HS$c)vSfnKMv%#H)7q2O^()w{}edpaVdNZAu^S0*&ToVXyBB(QrYQ3_Cyz z=KOprUcmSZi%>@$N8qlj2`f~*l6t>i;TNz)4SW$YmT@4x7|M{N&zQs^I~8KuxO(w) z7l6qEZ7%9|pmI+=4V`;!7EkXv0yody=@Jh)x7yk{`ZFDMqOHlACBPzMkt2?|4`Bm|DxuX>WIn{q4+!0sN+Mu z;5RPG&tjU9Mw-@bs`m!JB2H00;w!-Kw*ZZBKk=V?tvha1)bLWk6dS|% z=$)wp((Z|*&2PFAzcMg;b1>hcDdz7n;s-WbOcHJe7)KC;BLfA z;_jf+KP`I?L|T->>KmIUEkU&+{-F&1Q^*V^x#{O^4>6B*{GVx(t`PO=>igmQh$;6f zi>Ymptbo`Bm?~_$_MIb-T`Q}HB#Ve>mHOM!!$`vh3fW{l5M`32<@g9ty;4CgQbCn> zLT0)~#TIRw#~@Lieo%kRntfZPE-*p^t1g{_Mo%gAK7bbm#w-tkK0_AqJPVvy$qybv z;H=8?=L&~~y(KDAM>46ZfZt)KLd1`7jsf?9Us_Z*jDICtWHL(=;5zsdv%Y2mC*1%x zDwvGO$TeyCQ{qw+Ys55JA28$qS^GeWPY^}`Nrj|&@m|9BF7qKAT?2#NmzNjj3&Bfa z;MK%<2)vrS2-MX{W5`m}OREoip)FeArzpWPfaT_;l%c4WGE#9SXuy%f@p=8f5vHsM<2 zu;G4T_~#W^p22H&ZcX4jo6wL4`hsgo7Th*+oBW7^bnoc|_{epQc?hh<;#vq65kXzp z9$iZe_D%g+<}velfgRN4N!+aO0s3{(e*OUr{GOxEwH*K?Ad*CJh9?Gj;3@@~vU=p8dv)2=m9`|Q~lyOL5v$W*>_bW?c;|GpYc2jbd z=D*yi;FNeOlhx7Bb&po%o#d(gTY?w?9`HBbmvyGf#*_+lNMmB`2yy<1ub{#ORtwhp z)Z1BqY*cR$Pk0y16>WMMe2OR8q8_lVnL7NHo}@R?72(NO$9+3-fX6kFRh*xs|67Mq z8)R9-Mu6-cEy1C}DX~R%RllTiPawfo z^eyZa=2GxEkAjt>i5oUT$oB;ku%*vPlB$1MBL=H*1MTwo>US&(0f%2ak>Jb!7fJ`; zz#iK!eGZ>0qVw4B4#i(&I|O_k+IfNV@_ZWI2bjBHgHb(6Lk0P7<*xoIMD2=Zn5Rh0 zO^EQ(5y18$m7o6{W*+^0^WU#qPeU+di-DN2Q z3h>)t38Y=R0w$nI_vCKyRRh>D7y>GSQecma4hA{WMz{e8{ zN+!uFd+`zV2J&>-!@T=pODG%vUhnPDNsa?#$IFg6IeBW6fJhO{K^*~L;U1zKk_kf$ zR`A!w)H5#fvY8D{&DsHwRPg{fBn`(|mpFz(U_R5Y3!k?xMO16VTJiph z8Zvff$R<*DX526x5)iz-l$s}3hU)UD!k^q(o8-eG2d(X`LXt2ceu{<#Zj1QeSY^{{ zmJFIJB8wse7X1piN(^f>rzSy|65!ydY6l;ZSkRd|jf6bYJ&{oKQ-WrmKrgR)?Z17aXJx`{)!kzIzc(iwd;a)Q4u`!6 zj!`#bSrTfvSLcvs=GeV;^6;zwuFfXH!lw3g&y}wd@xnvExJ$oH>sN!U@~yxy@JDKE ziMGr0H+DRDNEK9EfB9yR+zhN{`I6o-fESa{>PW|f zzMWMP{n@&`vBH5-Ao9~fdO-nfYXy6RWk+2nmGUbn5lZPIv2KIJU8=+i^3W6&Ys-<} zU?*dKDOWaS19`iX1cN`TRw1pH!tX`O*FEpP@$JkaPYeuqsxETK7BuvnI1uLiLxfRB zfPMt`MyaMTbY-HI3zqH>E7t8NbKZW(hee)?^z7aHt4iI>@*{`El*rby%+Sd-7*cjd zU1}jm61{-u4UW^_p?RzY=x)a|;FWFIwn`tI50cJ;H-U1D*!`nel_sg)v-udRbKxua zqkh2>Bf?woa(xNq#PF@af7!VM5Gqv+lf`btIn|0P;B^7EMZv?#sc`esmG7skV$`&_ zXx0NS1uE8X!LEF)pia zYpo;u{2s^Ho6Rk3BtS$SXF?IVr<*;2H-w`OtEB(851XMAS93|4Z0YZlq9oO=sVvRq z#l_?fJW0nVAa(#!QWy$?PNUFsCb9op!-mc0@9;UgN00X35^0B7+6R~WhEj6Rv#XWHdIWj zamxAeH0-cVx0~tl6~3cA!$_z{6J_2Va1qgbvUAY}PE+OJw5T^p;@L3>9_tZ8FD&jG zGpa5kOK2C|CA~D(Dgz6VU9@FdDX8$VQODtG8YPWX2N$+gC-j9rQssZsEkircO%_Lw zzbeMRW)*1Q6%0W}%wig0Myn@6@T})G#2MNt@9Aekz4ObM^%w`|75rMtBuFikNr;=B z&L6^8!8c2g#LfX40SWg|V^AA5+5BDyGS!c5Uf#Q3 zKH9<+nbW^@T}qdbJdJNkDMzf^122MZ`h2l3jNzNg*Mqp&c4fTT0;Ua(+w&Yn`2AqZ zH=Pz*VpqNuG~Ga{GG-(c?xg`8ACySzi%-&8g>7^ZRayN*5?(BXZT3oB-rl<(@#Ev; zFJ=Q>-6K}T^4TWR_)a3*S{A>LB%RQB1JQp5#QxWSIc#T}sA~UfvY<%}I9-xsLj)t| z2*915?>Nqa3iST@^~Cpk3pLpEF_pV0I1oU0^TZ9_4*d9Kl{A$dnBqibnlgVgWR4x7 zrv#!CF3nM;YI478K^!~lbmb#NgoZfp21jom8bD)WW}d#zb(;m}9#xv*VhriC+|Kg9 z*&gQo0vTmT>#sqg_My7Os{zsk_et;%w_pL|)Kv#}i{*%PV#VK{xrbsZH<6Qs0B(_5 znkGGZ#S93DFTQeNgR3L+7~(GEEqdO1$+ltgaH z%8Tx)DnMn6)t>a%gDY;wjZ*h!pOXzx*}UGLQYI)^JvQbz0_6Rz8{?=^)0p9S;@#_A zDUXLUT%nIAsQ-=zpX+Sq>p_R^|DuDu-*$yR$Up84J{8|idp_ttj`Kfo4gBAMcAh(S z;58>+tD5ik8|on(0(m%?+wu{SgU8e}Oo4jl>j-aoup^Bb*xprU##J}%7T!yU`W==MPstC~D0(Npj&tjz7*F zO3*Nm%v9Te!Bt(oYE+m%{jC-~M)BwoCZb5otcW3E17s6)9-I z2@AZuewI_$ApYY3YAXLxgjUme@jrSA3VcGLW0@eP-Fn+ixfkkbj@@gGs=T;PEat5 ztYNVhg>{^qA8iukRWez?62|axizv4lXvMq&9Jh$Tcn?HaB(~t0txhJ-xx1W)RSy=# zlCZShXhQ0DW>Lht)4U+#o4g}sV6$1+?W`gSK(VW z2Ae6)Aj8bp-iY{|TltzsIy77o4&;kw(S|MwV_8@JNLYp-P_27=eqCaE?}JuB#pD#& zn;Q!Vc)D=lx5V9Ga5FCREsnTtn`HJkCl>|k5_>jkuRkFz!DpZ9IS(g`6Hd%tH@Zr; z__ku^B`XEOLmNmXD~BnEJtyU?yT3JY(|sHD=ROqv7a(DO%9jsz-ojNnz#^U{38a^2RsX)}}Ea!}dY74IAore5u9M{Ka3Lrqhf>#+L z_OTJcASfLy-n9r3Wd{nbEe^0uAKw9fe?sBG9HIOed7mDNNcFI;RXb%&UcOvR31z@m zt|1D=1%7zj(MSUnAI}L*+0|D}`0RVDtCwOywY9YYS^$9D$c*RnHaj(FZJnIRo}&xB z92GZlJ{kzdux4xu8+PeDxy;R>$NXT((0&7K45Ow+1#T|CXUK&$f5YgLn`CXr{)L0x zxE3-LOSF-y{d_{itY7dzAJOkaMCPeE!ShD>fS6tjXY&VVGJOS~E-Q3FmdQE+Ab;FO zso`B#s@(=I_>MSOI`J z+~fU)69_W!7R>j|+XYU>e4iU|02LlXKH#gVT$ySbQPOa(th(j z|FXO{FQ>)#&5_!&_H!&iMi~Fsu1J{6+{UtxWlHfd#k?Mio*?V+S>>L)CSsUe$>2 z8Vw`G!&you^Tt}M8NWHE>d7OFg;)XZB95xZ=PXxDFy8EcZKn(E5Fnt`XZO>P$6=uzMV_UB5gRQn(WvxIKO8#)=y| zeNGY44+67RGebVL=6Px3A>Q(7FhkrbN3`0G$zs5SIR%~WL-!-5js_0FJwa>swc|mj z!tB#Q4v{t@7mLEg*P7!zsQNg%#Ac5pq&%aQ&k|K2+yU7(DgkPmsS(An!Fd$Y)XW_X zLq$wBYr<>fQRIvqUhhJUol5m`o!up;w>SGJzrcW!H#fIXAfb6rBJL0VHiQytaJKm_ zr|J$cyRJI)NGPXl-QC9L2@W(_5cliQRP=_}|6T_wsZRcgA8v7Pfs`=;L%JaVgbNTE z^AYYEa}C&X0aoL|!9f5cz;5qszxw3r8yv*Mo~5NqMx)wAV;Um=TV?`8?(51?|Ho+O zOgOqZ1y+p%B4~I2zHL-hG=i>y{?5$(7keT-;Mqqb67C*Krsf7tN-=;vm3lfVK76`s z0#wv=gPk@5zrfA+hqkBe%}=C{hts<2*Ufh%zsJ?hopI*wUd^6&_@3tpY`}Rrbv<*7 z{j?Q~;^gTWIcj>6>1v!~pn+Vj8a5yb{v{9}i%vqh|7Wul;zKcwnntvAqqErz*!0iD z-3CNKlcL@-@MT2cVR-~&lcjMox!O2)KOvQSg@oDiNIJx@+`VR#DQja91gb$urd-TQ zRD>u)Wq^|KAnT!~=_Crl-}%~C4G|^WdG&hSj02(zWEg!-wEZdC&IlTi}?&EtqbuOw-s?`e%Fz(@xqMq1qrhm`1nT0|wN z2vdGem^ZQKlPhG|{)o5g>E#r)qEGG{A0IbhX!|_Aw|To7czp2*`mOs-z#hwkp}Spy zM?2$GYy^=LFsU_iwF~{yyH2-bZ(Fg+g!(=9;gbXGkmw*T%kK@m&t{Qa)Q76jep=h`JKeI zDep@J;V@u=73EMxpBHBOAh*~Na3j3}J|?A0q6A6Ke-DoFMStFXqE)RLresl)zE0WP z{)pv}-}8A6j64tq!`QS~pu0Nvw`8X~{#<;j;XKT9ET+cvCiw-ncrS3}wTy+4!W<;b z9Yt2`cCqILtdB)eHh&wHW<5@NHZ5!gYC`OS^J2p%(Mi5Gz5cGH^ix{cICT>YKqa|j zn3%DQuy3<+pK%|?@z5xn`I;_*u)JrsjJUtG3B*nAYBQxQwU+xP|D1ZwI?Wm+(xzLt zhtWVaz|5?43O?IMMYl6NU#mre)M>KIPrqE=OX7@Cqn zH5kaU+pb2PD+kepBdbdJ*H{aXZmqP(cK(|Y?VtfZAc?kj_2Z*D^{Km4$PSt{UrJ>6 z)8uj@ZSPmDsp#gb9BVu;DOd!_piHGro9z7J%7tB%-wE5P!DYDL&!i|a=>$wTQ?kPh z^2yFuBRhjbNLsf@v-^mGQZ#APA;&PzC+A1X=q$E79TEOZiv`vgb|>`LL#BG&n#AT8 zArTPLh6|n5V+npY*L20?lizAEnDzP|EEH8W=tbS(7W zWj#HZ<|{$;{7PZV+qc`iI?C#6c-#o;V{9ODV0M-_<|k?hmNEgk%r9v^-=CNLIN(WH z3)9cZHdzFU6ZT2;?$#zA}O_a2rw63>8-eXroZ3=7(N;y z^)#ze59lujNRDGn(HE#1J(hl+OY@hbRvB#$nM@K46%xWx$3V;;-wn9GqQrl$gtL;h z^}HNQ^-SpQVQA;kzlP6(@Zi{=(R*##*=1rk?b`s5JEC~ECh5*{hstZ?2@({Oj)iV$ zC@O|UlOH~7OJxnx5lLE6=z#yZ0jWR2WSn&J^wT!0Ohx=TNE(lw_A6ZLkW+~MKhd7e zK_9-M3T9^?8-gua95qLE=`(cH;5mE;IS=@74TpXm9k$?9y zaVI)fBJaO?KESiaqESmc1_o!_5^ae^0h+^)PI3cR&G8E}0%CN)^MI7;mH-CUrF5hV z7=V+$dxeN)w-wK_at-BCNV)DO3mfFphO!ls=!bw5jrisMD?}vVEl`VCZHJd8fPB*> z;9Wn8kd>C3M^I2XU+aYs&Bqi&0p!-DZ^A=BWak941=ii|Pzm)!952N~pb{HyDgpLS zi81{f;SMUp!GiRL4J14q9-H5dkm;<%5XSUV3z|^PD}8|Gz*$|4bMQyOINJ#F~8)V8?&nV{C4fCi#B|539D(At}6TlCSY$qpV`40Xo1nJ1(w2= zAe$919FwhTQ0)ytjg6=xHa1XEnSHVS_BOX!Oj#)#*XP$0%Bpc%$r95mza&z#rSCn! z9hk|Z;2KbaRKQv(@J}lXn@`OmdH8m^d-K(gcJln3F{S~>lM?E!qbz*clnpHXRO#zP zStFy#p5QkLC=kk%n-k9&nnZ&Gi&)nK5DPTqKbGrB*y2lPH482h4HXE8U`0eQJofc{qv3(#0{7FC${w{gW2=C z(|gV)HHfzFzPQ7Q$j33%30GdXj+_SuA+UGiAd+!sNREN}1ruQ0m$ zIRnrl|ISGODwSGqi6sb*p&H3ZuHaoeyJ6I(odID^9je!WI#3jo^P|bm->34xT9K{j zvhtp|dBo+clQMO$s0$tEDE{x_JMXKIJjx16#7k`?3PCLh$y_wd$-5jbKY8kv~Y(21QKI?Oz(%B!@Zc3LWNEzf3EgdjO1KaNGnNJGCPkBGL$iE5`#jalyr zHcAq#=o+BQxeHSCB~FZc#V#OZPe@M5Yo}Ezy^*wiUOh4U0>Ja_2Ojt3rd1G(BPQe$ zk4xhie#GpXdxAsnpvcdSoRb#nAh{ewRCRS3LlnG#W*XVtp*NqPWn`f{QcArX(I~h) z3{tift?EXQgJNY2D?HVpQ%R_L66|c%oywlTIKcm~WXG}KA+zA3ux7_ipAJcXg;1kR z>Lr0k)CIP7-wK$vPv9lH#J{yyf^;bvROVnIf>}Vnlq2-1hg=2z0LM&IGOfa}n9tn~ z`0O=E##Z?NH%eg8gF{4p4{+}&po6uD9raOwGoa56(Y&G8R5B>PP9#H@89jq*dD8}5 zi)bcdN9^FdcFAq)1Egp6M8l6WYy%%KnDRrI0IU~=+Evwhpg$9U#Yp7Y9S7clH36WE zrdoW3kAU{?YDm}*26dEr&3Xj%`u9lw1ckalvgM5Jc8rwN(xb3&#nxRjFezc4(s_83 z@M!j_myUFdo6}R*@hcpTH-1%rHreijOpJ64gijYAP4mv!m4CEjra45ID;}-3Fd4Nu zRJv3}A;I>9euARkVf`w5drw%#}rsi(JSti5ga2ssI;Pu>ZtiaI8a z8C%u{cnkk>4!W%X!K;@Rmr=LCNG^azc8kD~$24!0V$c$&F~Rb!3bx;Q<=6TJORj=z z1O77EMDya2xlXSqOFBdDP(uYwNxOg**+40MM|Bo7KNO2XI`xkcX@PUW;g&D{P#j zlzTG+8EHc|Et%s2^cOf|-a}Nap3c!>^iN1xs6DDR^KG$jLJlLkfB=6lj;{1i+$pbytBn%NrHnU$8{f^~XRvfu5lck52GN$^QodRR z+2XLf(n9H}NCQ8{k&r1JM-Zae<`5Q$Q9&Ygv!Yvppi`YOWR6~H1cx3C*|=C6ACo{6 zrDn$Dluf9ZpZ5gXHt*Y4(KT{Sv3bL*TBq}OWrekLO><9W?e|a~TiSk8p208>r!#JB zvav!i9vU5cGX|=YecveXQ8hkx?tV;rAqfGRGw}^9D$SM}ptN5brikfr+uAn>{d{}0 zA#}tDNhzeC^9ywcfC8A%sdCdXlyI@L2Y#qC9ucyuv6X49=y#*|ZOaG+>b~`NL3m~i zbGeFB9qa)Xe`Se20#TA=B=-He*sc^{*#NENZTM~H+;Dof5M>GqH^=sERK$3eI!1GO zjDevTvQdQm4*f}_?Zvrb(T~~G2i+2*{@cy0al_p18X{bFSxNyFzAMw^o|0A5GR+7T ziCi@Z9NYDZ{U!(FY$sSh7f=$jG{+kM0K=j`JVjTBU-;_kV?Z((556-vD^PDZe!;Kv z2r<#>tS>A;WtR|T&7DW>hjs9!(s1N$Po&OQ-?gFCKew`Sjz7Cjbb(HW%x)aFo60-2 zvihw+SlLQ|(c6Q_>a^FNdSDD1?AJ%BbE zN5aX_*HYKx7yG^)z=F!cDPvq0M;C8>gt|jdFR0$IfDS}SAY7lJZBYn3%y7SOD+qSSRz=^}i1&bD(Hplyv+ z!u$-XZA z{^5PepD0Ar8-($Qu#;eS;XYgxvF+Z2S?YoZs;rWHcocP zu^w3*2Js?U9ha%_;vVJ#bmzwseFE6(Q0h|EbW}_*iE@e88Td%M>rykMBsmP!#U>eZqXY5sE8P5U|i; zkTBODx$*PxXYTH}#yz`+T-S$N02a3$kQ3!`(k zLF2c)`ucghJElQ?)PJI*RdezuS&t}=9{C*A;dbf%`0*<0rAp62n9tIJ+tjaKsI5>W z^My+bo6KOES|*)4cg&e^62+H#A~953VBEuyIhD$toSfiYZuTr1PwGSiF@pqvWz#B) zE?HB1)USVPkN$9Ao7w*v0V^75M>;F1ufC3iHd+xb0BYehl?^kFvRW<;wR%GS^@CZJlBBvjH65*7*kIshXxdXvhkFtRg@LEG81u{A?R4hQi-B_Yhq z?$qV!R1I$jG=U{!Sx5lcNHfG+a7RL0XMvUG#u$xo@(bJt&A3KXJ@tr!H71Z)4sxrJ zOaa3GLYZ83k_kGvZ>H7A-aJ>KoNm!v*D_|B{>&X*7G3(t6+KsO@_>DA^5-EC{V*RE z#`gUFQJ|lc1Nx5d@%fV)XV>Rijm+W8c}|#YOr>%f6g0%ME;o0Z$Mw!L+N`)S0wrha zXHKB~4dsaRattPpiX)IFBKRXfGz%Ulw+seKW;GV4RR7LDxy&0Ok$oI{SuMtCVvl#G zth{y*CW3?vY!Q$^W8qX83<#Ed|jyjcXxCIrp8bRTv-a@xE~-&(-_W1mdWmQ`xN_2C?E#Q6>BlZfN& z_D)2FT1WYh4Yuseo&Sv61|aB-gz$~qv`NPwmTWagnlQUQP>oRgaS==)?oW4u1FBd& zUm?&>cc3Pn6O!CAiwz51I$CkIdJEkF8MB~!i( z(TqsNa|Q+a5DmE$`%@iR12r;k#lz!VAP)pYYMZ4*-^!_t9DXnz(x&QW^_|)|p zIDarz;yauhzXh@maCv8!5mV#k?RqOWFKu>*HU;_lXWv?MnPwh^;s8^?Zd$3#Hf}&Q z!fFirLLdlpdiyG@T3QwZ?5MHm-Ya-~{E#L}H`{-xj4K&7fbGu1t~FJ`*$(XeL!_nz zmSW^^?WayTQUze3Z0&h^xJ;xV94Sz)Ha@bVMf5Y;Y*B|c)82W1eT0{6y4Xpg(xGf1 zvV7f@FIP1aVUuht&5m(f&;h*7T|_{?oXGre9h6L6-NtrVs^*FYJKz>{V(3oo|8-_v zy<51?H;rdi6rlloBlH*L~-Bb#pGc!Vq9pTPNQO z?ApjD{uT56WaMpGC|W(GWBJ-jaf#clscoqPw1u4t>U79@)3SZnW>1(Od?k${Q~O{? zkJtwPf_yT{L{-JD#2~yQzr~zjxL&9XScrAi z;ybLXOu@x}*INYEf-P*&W{Jy?KoM1k)|Zr0Vgaz<>l&{MczN1*IFu0p-WLym(h@il zELebr^Y$4tKy}dg70+CkM>9sviL8otx0h3!W7%54%983;vA}3^jssMfRNzM z!GVUc@NF)}VE=~0k55V^o2(oPJ~Tjt0V)q3+kGB%Z>Sh#g^0-@MPo?rI8_<%6}&CN zgF(v@w0R{h#bou8ZS=B(MI+hzl<5+qX0(TLI4O-3EK>;T0ZG1cT>E}K*arH{i&V;F z<0`SYcZz9&;i5@TovcJAK$kefw?USp_ixcK=xsQ=6>*RS`W-&PX4bVYLhpC8J-;=#cOj%-wy(K?)2>>RUbpLACh?t% zJXt6>I^g z*3Lqs-U=o{eW8qL#Fa}rk!3f}5C^jC8{Zr1XN9e{aCF*BOi~_a`!YQIq zwSatull#=e%rR$>p-?{YXu&Sc*ZtrppazLle%?PcFd;uW?8a_67VUVO-X_=uXm~$1<<@BXF-_CV z6lq67NK72$SH4p6BWXpcM%KYiWq7B{rj(;#N{E1ii#_iiJo~B&X-9t1A~|Z z9=%P$p7{-drFB5}`F;NSQHg=E=o!KZA&sJm6CHjSJ);lrwb{)vjdZW}a&V3wnhR7>6m%~TgSw)C=djqh*g zE2_-3^$n5w>7W+49gp#9d8Ffz$c*$?K+%JEr@mn<$HffRB^~t_S?zS!h;br7mYA)c z_kuaZLu;KGuMcu+l`?;?cB0O&O0cy3D&BNZ+u~{JCLeO^H43GrRdpVDlC&q`$o0eV zA8j-D)(bk%sfFU~1kz3BODRu#C~QNJ$+p~pT;s+t=F270?HsOE#A^4iJ4!-in2afl zF?hQSLNv+ZhDt&YqO7UCgu~DSiAuOehT-k$KY0V&0lnPjYLrSkBl`j=y|V*20We*% z83l>1&W`=R;)TC05Z>ZzKS2@}S46IN!oVI}dH-)m0J!O6y(gu|d>WgJq~=%k1%-LHw5;9s!*+F;02!jOJzAyB{98jwH=Md*HIzJd~gYZgAUbO?s;=#`x13 z&`F?EbN4j85c-_Ez*W7dy?VU~_kb2rB$o{t@+qgU&5Ygd^{AoFrBjr2UU{PeKnUz>>!0)X-#XcRuZ^UuEgwDR*EOB zCxvs-)vYx3JKMed_)WM&F*G_F>9y7(Ge_L+FpdDk^T~Mu@U)SNY zz*hE+kQuRG<@LIJSc>4Enz7%65k9DHVWs6vWQC-*44PVOiUl*_Zf6HKsu5E6+q)rn zh!mF~V@p1V@-T^&-ZMa&2#AJ>=a3+7gAj+wTiy`fITz=cCC?dLNr)h&a74XfhuWty z{&)xaiVY9{zlDCO2Pg^%10onTU*$XdOW_q_vX2>u5s<#lyh5A+gK=U9aIy$dI0 ztn~#U28sAqkH8Dq(`1d_0;JzpX0+srqW@z7#-0B}DxLh!MYf(>Ixo4>t<@N5l-r+i z*zl>E@X${60PHJ%x7nKk_`R!j>^O)@i!BQ8o1(Bkv1NNs=XkIG8O7EK`qCHgSrPtkO8YQ>~)B z+yR_y$%l}!GnEpZgnuke)OOArvK=c`GHWA4_=w$~*%X9)EsmLgfk?=Lm!@pIGq+z` zOV=>?yUL%1mOzalvS47a^4%ye52bQ!!~?_}4*~JE)!9gPklC7&&c?B8J>ck#60a|qFfNp8(h8*DE3}8GjM+ZV7_$kBWyux~s{6f;3_QWR47*!EXwJvQ zaW(6X%lmA+KUkY%s|i2#oB(l*laIe{+{}Fd57@ST-6pvC*RBs99xVo}ZYPX=G%Nxk6r7hFM8JD6cgRBmT?JXSWNQuGd;l zKqIkZ{|2cg04)Jk>$V297s&I>{ss0X2Yh;7NW<%zXKO!RT^-hC2IORD)W~@<&#Buj zre1RN=yl_>(BHRnZ56AhQN*29L_>e}_}vVAmVQ!)*PgKFdKI@k@jL4GM(OOST|!viB0)}KgS5X) zB?-uK(m2loX}uN-mM?zTWP;vwFUd`&Dg_8<+I&0UuF1Ih`~)%?J3Ri(|88sam|NTt zuvpNc#HcsNg2v=vPEn^62lq#Q;#~!y1!DL)bm)>Hn@lJ}s$}qc)WZGa;SrSVT!=;E z`f&o|+)1=l#qxP>z+u?u$}`b%eCT7 z;vY9$?Yn|>KF^@?$WPUZhz|N4W<~?JjKb*sWXt>xQqnChW;`kr7A zCSoB*kQgHgHMN9voAEsQpOb(_trmJmUtx3k%mj(MFy+J$o!BHWU`R5?7;ZjOId=;K z^}1vLn)aaV8W5jq%ZdJ4H{SZMxtflLr^U1AS4xLin03FjxdKH)R2RGqZuRr%9YtcH zo#&tl!~2}tW%{UTl)zM+@scCYoPMY{HkiB#Wnc>&b+xCWg2MG(GssSGj}z$0V8KK3 zpCP}>uoE1uT0KAMA{++(eKqJ~8JbJvEW$Tl=5_tMQakuAn5q6Tqkl6gm>iEryn_!j z5M7V6UwV$zN5VdjisL^n^h4uONRGpYH+_J8m-j7E_B?tE3JHUGRpZyT#d%|H8FX3} z0T0=q5X&lT6ZU0g$V$C^IKiSlC@+6NN~i_1$GsjW!of1DJ&}WOqFh{&UHaG!`3cVG zQ*e9;f?iCiW`)TJAjZ*Dj#Y*Wo*E<4{vC(_=pnzJI>`?o|C~Px<*G>fD$Q_Lvb}+Q zGE{n`8v5q+wvCtolPsYRc!g}PhedE8NsDNv2MG|T?~<$))p$GsJ>yoTIv5-XF4(%h zzNV?T{gFbew3m^e17z6!=MOM%Qtv7E|9q?~>3|heE0yc-e%e7$lASc|TDIl5LPskl1=%rsjl2?_ZVo zUWuky#}oiPY(=(lj%P4N6NUQxngf@#dHMLtN3rb5%W=8AZeNam%Q0?fJ1gDbm_U29 z5$v9ruLBJ`5H={9fQ1?f75;@F3ssALJgjuYI51gt2$?I*G+vegRk5(uGzs*RrEE*I z3k;Z6?d$hm$y^c_kzmBt)qgUA?ZODA0-a8Id1=6jE0s3_oI=s{t^O|AU1H0){)gAs z%Hd)RH#kieO_^SSGh87EbFk>s@o|@li@iQVi???+6bwT+Yn$uFzjf$#^FtHHc6}h; zUHHG~3wx#&yEkqpp^Q>qRLpE!9JnzpM$Uwib`oU>d(^N`HeGS$$@sBl8#OH(cIbOU zdkpY24}sLfULPHt{MZJcmvR5O#=pCV0|`&PR2h>8^~x|@m}wZe!DLM7hlbUar+9&> zZ-tE79=dVEdd8`p)L>e<<)KR~SJhWs{Ed;x^6XT-cEN#odd-mciZ&u#CL;uP zy}<0Qk8<(J(3|zvqs_AyT-V998EvtqW=0Ci+T6;{z?(lH;_?>HwNqB-4GS)W`3{j% zI-`jskR0wyx$P2gC%z$nNv}iLB3n`@pr)(Jvsny&E1yRF>J%)5IPS`O&ojbhALkYW1|Vp<#z2 z{yjE&blJ2VlKhAZP=T4Yh-K(`aI6+ICC3ljGJL&sW9;w{$m_*fww~O_2DdHEn$i|V zGvo)9Mf0QqQ*ad&6h*wnr9FGW*BVCJ!v+)mZO8O9Rba1GsRnX{T*%GI0Y1$}e7RAZ z?G{M9ha8K}5yOv)59F!lqNs0lpFAdr7xwn`x&l`E%eGwb(&&f|D5063o*$z^#cCLq zIK6I^X#{U?ZtG73Y3iOS4kK~6=lTrclJd>=2MkO^rLN?35pG}Nmjl$RyD zA6e8#GWIdb1w_yh{YRD=%dKi8*|CPCue9CVE3*l_V|-$@v*5W3&aNL78rz)g0P;I1 znNZnUwnn!pTS zl#9H1E1-&6!9X9Y{rOV&d6HR@7%vL(cJXKc-XfOt2QR+lvVt{FLD|dGRe5j3W%+-Y zI?J#syQo`lHr?GwcSuS}cS(v8(jYC3lypdUcSuWzbT>$cAl)V1b=Lb`*LTkO3qRPv z^Q^h%oMYTWmy-ys`cuW(zvZ{zp{)IVeW}s#@K)21JcO~+&@~FDaEat30O%CE=+Us- zmB3WLO{0rRmy~A-hMoOf!6f#>JQLwV!8L}MKAx6maNXADJ+K8;FvX4){3&N1r~kzd<$cZ^BEyFB z+n_prLKwA+&?`Ur5#5EIpJ63vo!b_6N%!MgI6{033&ZMR_Au1WymDS+cFwzFR!~*Q zrse*jsHi9{zxWxi-<+asRtH92#}w;gt($J;rIlexfG&(0nBIhhge*SU4wPJZL|$At z9TV>-D*X`+sT^e*r4v$NU|d?s08$25v za}3g8q;Hc$)Vx&$hhqo;<2M(O`NJ+a8aJ}XwQ-iTWGNoGukwVB8yfnG(`kB9{CdUZDTlId(Brq2@1T(PHNm&XiG*~^n4@vOgKq7LEA2Wd~Pskhd zk7GteB|7;S_Sqrqjd(57RM=k?FDhg~1&7Hh*(P``-|sbyRjU+LI&1(r7UiqPm8GFS$tq1P3fOWWL6h*eug{yp z^Tam3#Sg+!AN-08Rc{opL18A?9qLNr#~(Q<-LRhpP;%FZ5NkP{R8p(#;5vSVsrJ)f}&=$b6W3 z`+Dvt`-i@NR1?O-MEP6}ylkdFWYhwur!^8Au^Epy9q1+Tj;J*W6fgI8kwmuGFS9YGzfb1l`^ z3Ir}>0~`>E7ZO$|vQ?uKN@~jEUo||i2{vh20XRWe-qUxAzFgx~+H6=MoqhkK1_cfU zFna0Ow5%5|;_ExQL^GNRK$nD(njGx$EmY(3<L^ClJT8`WG*&u?1ooxbR%iwrs(M z+ve__M6hH%EOvFjWF5>QiE89~Waqlp zoFwRKNzxb3Kev2%%PiCG7u5-VgH6L2jjaHKD2+k-nVpDemp#7>UY|ZTlr_05|E5!> zeJrIQa7yRDC@!!90t+mlZ?H{E4Y3&L?qUz|EdLpa{RTEW`VE67CLE~&An2EEUxT-k zWYzo0e5M{)aID#&;rPXJ8$>1MOATf@?>p;+jV%f1_MHvCJ&lO?de@bk{fWW7h0776 zxZs(9bi?H#lQfFEKo)VakQPo{PkV(x;2wMhVAeg8hxC?mEFE)_L|+ocxS)$^YXx*c z+VoWj|6(Q3wWJ86wtaQa=neQ))QMY3e60Yqk$!a7pB^JXi6=6wU16*arer#)Y_3QU zA90&p*%@0*%hA%C_4o&77S7B{t(^leAcybzAiudn*iGl2JgL1x9rnN3U^@YJ{gxY7 z_shM(3t|JQ8uL4P+%sczNgF=Wqiav+2ff6PwW}G*eRg-N&&SdBzjNmgLGm40KSX+H z`yGGH%f=N%w$dtpUdix}Cr9$FXaFo5GluD}LD6s=WdcV2&8ND|fHLOy#hUKw)4EGA z+8+$t{^XXY-3(fX?4}8f>0ri*cm@w+#`1jqBX)vX=ID7Jlb*klRW6%l@NxFp>3i>E z)#?zWqqIurHIOIZf1>3Ka78~_9y~BRq8AV8rEJy7(Qo&Kfh`rBOCv3Sdzxw7`_WLaT!YoV;KrLM%7&C9Q|M17*n$FrW61^&Ob3?!t5 z+{~ZMbbJqj3&8OMNaK(iMtgp;sI;+OZt}9yZhM|7iCACcu8J;0`>hg5`y5uq+~s-Y z(X?-zW8Gor>LQHC=4aA6!eTO?3;XE918QQ>k283tH56%?OYRdOs!8HWW@$5j3NG&W ze8|sE!o%-#MH&I@hCCD+z&l+^>@OllWj@=`*A@^ zHU*0^?iJ=QM?7K!-X1W|W7@e8P*xdt;1cZ{8Y14g&=~#fq*SP($HPN}21XhH$?V|B z)#K&uzwgX!_*Hg+Jpb(d4=HB7E_PHPp@bLv2~$l1A+x%?{|5L@eZQ25HP{S?aPX;0}`YJOm8?DU;;YhNIl>9i;+YO%j0UzqKiqV3T{Fx z*>=~&zrxV0wt-k0EZ4)$P2qDPkT}5}Teu(VwJcBs8{NQ1@JGtjI_A%?JWo;kZ$;I9 z6Qj5I(td!R$u|1ySKj=g5lHqtJA>)T9c=tDxbJ?K-*b1DdXG~7NBMG(8ka9hn#2*L z-so2btlO`N!yh)9?m!}j^%tia!QHB@h#?-iqM`y1%cAz<9=nvKnrAh%s4F85FcH`g zhP<}13YRCIN$B^%C#zU#>+|lImWU9L{w*7?QCg}lPicZYj!oLsKT@yFFH=ZpB8vsL zV8gdYuZ_Wa+ea02yTnWCn3*ihJEa@GOSmgni*}gli%o6xwKxolfS{SW8MFPXy{#wu zq{4pC?`#Y2BAz=XMx@+^w;;7xXl*9~mtz|8dl<^krQ~Mt0DBj{x#(+0u6h*-knH`K zF}}R~^on65u6vx4y^FzS3i55Offr*bLO=S+kn12Bh;K=+^SCbFC2|n6ckS`Bxq%;yvQTBoodA*B1=$mZJ}oJO_rL?Rnt#= zT&VEN81fA|$E6$Zi|N&>`Ff#p0&%%=A} z_OvlvNUX0x`tpY#!=@rou2BK41v)lfo+&*=&{$U3r0Zv1DEU{ z-*{ru;Mgq8*P7HO79!aXCPp0TW4+eyg3?9tV4{K?KSU%gjxYuR%EQ{J*I@rur2-K{t3n)q{v_1-GK!?)~ShehNe1$|t`7g+_^Ffc3! zh`-J-C9it@d}hT_<(^|c5^;0H}0`vaFc8HCmYZ@3*@) zm&G6CtDhNsxMQgDEO#AfCIxf&O2)aV`)+Q6>$^AV#wJjIzY+MElqPwtAn;r$;*R!97*k$Q^HvMaY-(pqP>N_fR|lHkcHC;)7c z?{<^oB@j5HR?l`G_&_Ej#p%_d-RbdHyZ=a`YfF5q>xc6On<@t1f^JUiK>SK0c_7}l zoM#g@BEgZ9o65Pc;?Gy55*+U|M879J1c;^=mb``|iIiC^tE+r@@{R^va)0l1Qw4o} zedg1_Tq;NhUa9&lrjvfh>P5teSmH_^61xkb`4r70x-4PO!ZwAaMJ28D8*d2B zaA#Le(MbA#Uxk$~g;+Gn+Naz&Cz-7j$~dx!%lE%-r*Bi!M$E{}T;Jc9Keh#j*`=3i zeHTebrbfy@C{w*HsvJ}?4h|&Kn_b(o?#*8^dwKnjK5_@7Hr&jA)DjZ5SeH7X<8rk~ z&?N|BZzc(N>{*9cN6@?ZW20#SeWx8Q0gEr(?U$l5b=MlSHBxo1Mt*TK6BUU6Q6)$a zvHt0g#p()B8K9lmOxDp{crXr|RwroBkf_~TEawyCv{H;f=C7h8LqiyjF~;tO^!R?5 ze}m>*THz%&T(umA#wu_8j_7Y;+UL}?%>P8nUrFC5@|^UnPmBcaRYDVQ)bqMSr%bsf z4f}nScc7~*$#2iRKsJeUi(dIhYc>qb6^iZseQXD^_3e?>oKgkgF*dOO_U&hA570h} zJdAqc{#YUX9Nl9So;OI9{+MQll0al&&@nJJ#+Ju8^LZ~`#T#|k3ed-l?8Fvux!e(? zrdHv)3bAkW3);mXYjoG9!Muu+&fEn*{*rTu=k&>T%zq44FN!zhCkG=P0FN~WzJDQd zBOziV9ugBFauX1FY$`HfI1%y&<~*;{JG(~!W}$Fepn197yodIgWsZsL&kr@)zK=xG zdpChUj|>xjc+lov-Mm{DmS5L`Xaa4~(6Kxdh4(fc&H$^coq;4`Sz?= zfsX^+cTKOONWgyqVVkEB#xIiq(^Qrtb(%dI)^EskgP6y2aN`FNP@w_gC}Oe}zI5)i zQmjRv+;o7Qa?9Wauyqmu8B4KniWjh~H&@L1B+QXQcz98`MKua#vqmm7u7_^K{-AG8 zdUp(f?LD;5^t0pC@MdQ&4xeM3fKnN}e|&df3|k)HCwQwBPSuHMlwxJLx%npWj)=z@&x=#rG>6qLUzuqQNwZrTB)7f zi_W4e!!%riT+YZ{Q_U{I?nw3;DM5>~->pL?Hj~C#IHOPquA6{Bn+oz`$>9z=WQyKf zVJ4wbv(YR2yAm3 z`39r7CNZ9LP!E-?+U(wCFcF6A?d>d!*Imo%dfx@eXZ8*SH4o$_!X%WUn5n^F+@6QC zpDnFE6O3nz4wQY&UITj4zM^dJFj{QLxcfxom+CWj)kuN%9a4@IrB7~V0XJds6z3h* zZE27(r-l?!+fH2=v*{}TB{6QlkGnrfBk<*)&K_#-%@W!cy~bZ@!|-cK)(2@6M$;sY z`FQW9O8lPLb8Y4q5Wqg!IL5HApEDZS)-f9%wQPOyCs@)7u5P;NILcW~h7k-AG@YAl z4lc)r+S>GLhT5%Tu1K_CZIEAdP+1Djf%d0-s{33$zgZ5mO^Mb!v78{o7iJaAH8 z!pDFxeT&$H3+YjIGS?g+bIR<*Bot=Dm?-q}3Ml~y7fk+IbYd#Zm9yg`KMq4W#FV8twm;}O~(hBZh;Cy~JM z3-IrpCMmu4uN9ixoCIomI0%m&uFZCn{4|~#5jZ~%4HIk(uT_N*K$^WMQC{$+Q2ZYy z);B^HI6C3fVCjW%cFAZOF=9R*<8+2c=FcJZZ-{da0ZeB2+;qyl##o;IQaqoI51ymd z4ueiUow+Zy-E&qdYgfybmyrd=G1K8#-~e0f zAfxBM=QEkz;J{@cGQLNs%T?x*F|AYgjY9sL{$5N?IrCA2u8`1*CyqiWu$#)X%|30K0Y6Wi8?)%c?QL;&yf0&-TKNdL04b}eoLyeRS^s?PYP*CKm(iyc zXO`NJWKB0OXT$ES&1UvMTO_R(xNiR)&_y7T2B$#8;velmcK1XXbWK90>d3CBhW8); z3P^y!x1c|~j$A$29Zqset;**mh)iC(#VLmH&fmVJ>rj0so|7{20xABXoeq)h#;!&q z*YL0;lm^FW-W&2+{3FeU`KPpu?g7M@%bra;kqB&+sq~u@)ucpvx2Ycjsl;dqAey2d z;l716SWw@i$8=C4KUX${airhk(-ZVifiNTnU!EQTk{DfeYo>-G=KwCK93+u&gN%V} zHA^G!1j#VyV(v;zx4SfyP2^X1J?UB4{kyf!1n@l^d|tuAZ%= z#Fjqe@+<1&)hlUiK|M>jJPw(?_zwE}<{6n*#;pZ50#s1cG2OnpL>Bd-jBMk4{P^*9 z#NavaJd!`kOFg$B9z-%?u#7U9OdMWoqNpcyz{#(NSLQLQdh+tBK0w=JC5~KmXI$1J zhjI-C5aCTFf$Bhr-4HDSTSK!ZbK1=nGaTvudh|0lq|>TiLM=h|+?MypCq^-LrbWpr zMtY=vV?T7II9i}Dy@+)C@Aq|=k+i+Q z6kn-m+JIH~z*Smjfn4Zxbt!1Xf=5C-iFpj5hZ4TlYHvP1N;K;8K6@#r7Cw3Rd@;=z zbLT{qGB-D0%)zoL$OuwG$EeL?R38#1O#}mUFg^h<#g(P84TGc)SL&lx%;obl0pI+` z4vTXlMR!&=3~ino?9H1}g)J-Xxr|N5Fg!7{E~WsYAx&V@>Hp4d>B)qQXiP0kVwF31 z`|HzdFgEYAwr!NflGE2=|2PT|^kB{V&1NUr5KWQ%dbVH-SUKjysem5lrbe06uDQWN z4`?iUK2p11kax$om(xe)5?O6Ip_84xZ{%+lu9JNTc9_!qavXBReZ6Gv+;_EAvb30U z8mo&Bp&;CNbBM@+ESHr9h_0Pmgs*H1p3qO;K*-(x9(dB`6j0VgtH7x+*5}hr8dvi- zf8GQG)ezYTDyWC4wj-8tgxW+<7;()O2$uUjK3>;ks!ydgLPq6cSU!*}MgUU`N*qW; zlTs^gw}g@_WNcb1D76mEl*xOvWqG^ymu@@mJH6*#qnx;Te)0@7DsF!;eZiKaE2Dp> zk&%&M^=e?VpX57vxmTqN8@boW53~Xp7*uw4_Gm5P{_oImeJ7y~(|t!R*_s}!`u{xG zfaAg>LRmjx!z-zc(sQ~QE&BZD>Y))R%7y-}tY7bt{N~<3TATP?#^$qoSWU3gl*>mc zt`D<^qcy&=E!3elHdn2lb-5#y47YU= z5s~4m!zbcC4+e?K)f;Bw5W9{i3>B4Vk9Yq)7Jy{6pCw&t8i$Bq}`(PfVG=QFh@MWJW4cOC7nJ| zS*>xys5&O;B3 ziVAA$w;KY{r%PONimZu!S|U$UR1CyDyN*x8ViGg?Tob69at6_`D2o|bm-*Y|$fRU= zSS*0n-2)tsZtsM0gq_#hq%`3-Wm_;>T3a9g%-w7ZddIXqgCtUbJmm?Vkcg-*n?F2M z9b4>2iDV81bBsuH%~{rJn%9*2%OI$aG$T{5cq;rG!Hd!Z*N*Aj4QK|eV8J=!0D!b` zgv=lX{-+KQ>%6Y>)cyH^@j5NMQgOVDSXdG8bxrB!So#C)=H*HMpgN&)bHQNr3~b*b z0Gb2v?v-ZZ8mXIrb7)OD7#Q3LCXUtMP4Awnt#_ix2+s}=Kq%jou z*N(7aU6>uhp2qL>d{;WGo1TruW|)gv>K;a)u+- z7zotwG$Bj=G4^qC%0CH3^CaNzC%UqtJ~RXI4FKFN5l8EGcW!prei!XD48r>UeOWz} zV61U~>{W$V=X}F(9B(%g{~XZ;X4w2uk5j)Y`oDQRs}U#;F^SvkP*p3G)RznnTq>9sKhPy7Tzu zxn#Qk)}vOX#yrD0`|pET$n4*19*6vn)j`7UU7tw4VZ0#NgtbO7iRecu^(e;T=(kwz zUq?LDta*s6Cc;2$7Q*!Hw}zxKApPQ0{tn&ILG%LJt4dnPD;{-!tt2{trQ}VI#K9k1`@4ZIS3x@xBk~VU4N#!_8`=@Sf!VuQTzD~nSK>!}dwE8f-dDPSJ@MqddSo4C zflEa$7T8VbTd0T!Z2>T7ITOcoL^mJc{{B1U)S$%*um@-0hHw@0;7<0S3k2%m0ovSo z!k>~n(6&i5=M#9ZSuzh#$k~8z^k|GLl0L>0-53ovqBa%r0iVA5+3l4quDOiCFc5|} z9QPJ?YmB$?2VcF&B%*c^v@>uCBRAkA>^51ktZ5lwKQ7;GbB{Wx;UTAg?HK6l;DfRr zEftF}jo@S!_5%=wxgtHDdVvWb4glOb!@%~)X(qNI z)x+vDYQJRW4pj4%^iZu)$TG__nt3k5PJ5JY*@uBwks(PG$k{_&Ii<%o6yRL?^Y?=f(7Z z40q^MJgL96$L17~yvE(QAfvZNnFf)UlwtTX2b=N!8~^V1l_v80H>Hb~6lx#vOBZv? zU!B)zNT6$yB9I+l!@K0OHIl^|}TZn=lCD&o7@-ALA{12?JU5$v*)2=R@`L!H1D|U+bneZtHw9p3^fO$ z&;!x(V~V+ZwBv2pUxj+omsj@9cu{RAY$Yig3+bm$anFlz>Ws%EGP`Dl{{l-yP_S}xYFUQBMz>vQNU`c zi0OUwcqgz&8|656U5)CGCHi;@`=RUyd98OxNVKSTP`S&i*pi{n-Glz{nUu~E*}&ZW z!89&(++bhUXohIN`tAv2C`*=T77Sj{7_YW+x!W=4Bsb?QXy%IGF&^;5@r>I37&mE| z_zbEh&{+*`xwidTyT2#VPV&qVnha%xEQ?qgu9b`P?f;hu)|FeFi6>+shL4!T41~(a zyMEXn!ZK>bM-Ws)!AuLkVYZ-zx2F%S&pjNyfDh-d@LK@vEZ~W6J<&>M}kh*9~T zF-+i-IjjFrOD5Q;DI6|}h#aqDhvTog?IZjte)3i!j$AsH(MEt@u=7r?dyi?M!7j;u8zfHh&vfhGEf7qaqNClxkGjle2m@dy(q zIt~uWn23}*?Csv={r9)8IxGf8(w>CJ%;0dUeqjvc$GH5o`MQlw!mHGsWcX!kEuaS? za*z$1iQer#vsV{AU|{mPZoJINHkieSfO0w$!kn5Akq`HLyIXixW@z|$S|g#Y$tA>% zF(=?0PZZsFa%T5(@)B@m=#|xw>&pQaIb+gie3Y z1n7PpAC~tsi4%V4a$i-4E}i$|X`w@h{Mx)JfaorVga++J^m?W2T@=j-j?fNsx1=mH zqd%Nn4C{yR{p8G!iI-*r*DTkEr3&VnVk!;D;ON9~{c%sd(=v``2Gei8=@0k-$fjF(~W@n!r&V5{p4pZZ@3)k5|F}Vd#L2a^i3@N@Zn^2>5GqxL)5nMKi{ZN zPbj*t-B;-_lD~C528zTx8p91(nl~jsM)6sBW9U`%2rJwX?nwOQgX0Yl6GXnfcOc6z z*6~e(u=sfze4!uVnti6JT|~qXKvRd%WZ$`}Qpladnnc&I){}nkeDjUrt>CZ9T2@Iz z=&}#oEBEL}{s2m$8+fM-#;^%R&oqjlTr`P|UBcCge^gNVR#`a1{o3Ivd7)pov|-fF zt=(Rl2}BqITMbjS*l-cY%+4)L4e75u^oAnaU(RH~pNfzj<=53J@RbJfe=$dYuNm2A z90aNl$O(fcC)=G(tB3;78`*evM=y{SoIc&GZmRg)<5pAz!gY=Rweo2YX=XDWzR~8f z-SQcJEYPzPz$Fnbc1}T#kP9UKxRxi#d)&c&@=hRY-z%el-7CT)!y2p&^X7OKP_tA%jktnau1(n@*5cm%ESw-eQJ)4OZ%SHurz3r ze^*wl5J`|ffB;Y@e4MUFBimkA$ST>+4At0+_y1I(0?Aw1~K5 zhD6_Mn(A^*(k)oRM6?|+V-~e0mBSDt@(9}G7hP1Ax^B=hEMg)^+H=uB%zkBNW-^6` zubR*LG<~u{71eG1MLuI|l_pc@#5H)i@XiK34|}&0AES->B6oe{e71Dmf7nXSflSiL#fMG!X8D_>p%z`W~<+BKH^DNobZ7Q;nlo>2^X;uNX7u* z8lf-ZAN)T-@GN*`v?@+k+NOJvIKb^ddhwl+QN3P@Ca-l6de6|L5s|nK{Hp*In>UKS&+a%R8QvGPm1 zmKslhcf!HL)xR#;>g`XZuH-?jhJfZSTj@$oi&iZ&9#;cW@agb`!~dB6er>5-Y{Gp8Dt)L?aLNy zTI+-~)8={e-X{W{$|M58aXd?S+Vd{@HsPxs``P2X!Gt{Rcb(VC!}q40=wigrzKV4L zSo9ps6k?se5u6C#amDjoQUeW(8Q$kECo96}x2BW|h2FjFIzuNUdX>DX;e8A;$o`Do zR<((T+%Ps+lt?sMusjV2w<+>2Q_HXTxoGs$zIE&(@(+r{ME;#eYV|p>4 zE<$zYhyrE8*t{JjJlU-;MLWJeKisZ{v34tbQZ!|>n2sJxyF9NOf*`?Vi?Ij+n-t- z!n9m=340IM+D7MDGJm*!yQLNXclq6-eR##Jb*iHVbl9*9u#NX2}5rXwmt8+P2;rq2E>Pt>` zlO-!c06Dp+cSLwNYOB{3iqGAM!6|6TUe-IF4?9jT*gMw7()rxJJtLf~whgr0oSa@S zzx~wK)(sk@u$ly;PZcyOVx43z(~yR%NZYd*kMyWJ`IibMRW1(QwHciq-rxE?EUpq^ zx+rmiUezUfLhnB^mXT=6cgqGe$NqI{)210gJ#M~ekxhtMUwN6#m;EZH-rwj8B75}T zwvZm^h)8bLPtLmp-FZa;HQnR+$T*m*1eI&B!J0}(Fxqjd{^Cj7al-oB#LP()TQqFZpsI^ z2OhUZdN>&JTH%+LpQ3pG;SvZj)_32|Ca+WT0@pN8^5!GVz1lt2BJ6NzRZhR~5H(sT z^;A&e0UGiFH}0Sr8UWjXRfWs4yt+wjyhu>HpCR{lR~^eQ%aBHZ#s;F3u`Ykg&i(z8 z9fi^T+j}FT=Za53(b1Iq0|Q|7#;G-G4i-m#KVcaLKg-8OHKf!Yd(`Vt?bCkGzg2EQ z)YX)OVHisvVq+QLQTD=M0wcE-%K_?zo)1dxgaJfTOMXfHDkjp$!pa6^ha^BnBOUOR zRMBHpnda<#{d~w>yzeZiqir4omBZ=mQAS9DBX2?|LDK>n`G#s7Ez=*_N-zl2YDC6| zfuT=u0TIkK2t-vlS{wIMVi#AY#SuhrDnudheRoZ7Go$K;XWn=`0cQi68eV>SA^$Ha zxR|i}i{1ay&@Y>T#oavnTUeKB@JFx@0}~;bIUbg`1II@NOt+cVJ;35s5 zx54lF(EQHV6iY0(i#Ju=h{!58#IS}F!Q4FW=U1Q)8p1w?|Dym!v8_XC)nc{x@F-P6 zLlB&aN0m(78&bFei*1kH@+bCh!$$-s6;=-&o&T!^c&+(1+B2~s>?T&nOypvSU5Int zw2VbOsz)5fM31j6!;glz81BPRV4kq4x?C#qhdpF5`)q`$JGpe)hy|2~Wn~1)6f9}I zd@H0F1y3?@j;hzNM$T{+T`U#YT@4MkQOIE~p)w;_X!##@Cy9)Bf+?qa-F!cI`lJjh zQZco{LVy50Sp2R_GBxkn)4h`Ih`?NS`AsN+CHjHIhcCl+IIRSc^~ZKni^an+WR#A+nx)}Lm5(4(O6Ql)?K2|SeEf|) zzuiffsd_?PABzm@9c%pa`J%lL~*hGJ|Bo$0J9s&U>j zF)9^$EnkunsG6Q?{&67biH{3H$YjJ+te0~b`M!rf1bIdv7m7m;!+g)Viv$qs#;Xw` z9qeotg=Ji8IKQNP#sisIisARJ;a?blcJpU#3HDT7(GY=O{mscL6QlHpI=qsNw~}+s z%N2{?VIxDgA#??`0DVPUU^~nv{@^tld#32(EHH?Rf)SUXp zMlK=-#g!)AMAEs3d6tNQQx#J?4hA@6KQKR4&VQvvK>A$$oe0j4ei)LFDY=FTiHeR^ zO~Q|(4OUuNvGB_h!`2Ql({8?1dZeBYgl}LBvv+k32Gi}OC0%&r4K0M%HGQ#SbmJs0 zHN3#C9>4G}#s*AtBzifQoq;Py&gED{8! zq_nxK(dP*R04B*ubn)n3zkYo>-{Bo%0MHgEm8$?OMuh|`?d2Z9`%Uh`Rr?qbsL z!iK3G{gKtfLUGLxjHNi5n)$5E37SE9<*IWtVartGOMb!>`ZOIM=iiVEx%mR9;inU} z3sxgU*VsZmb6M#7caeF64*aHoQ4N9wJ8xEfqD5csQ~>)A9)L1qTk=qsst@0ePVmkX zV<5Uc-r@om%ij(k3N^fa4!Re?rr$M%T+;2O)~!A-hTFVpi?=PPZ_9a7eXn4iN}K$&zv==Rzj9S$3YvCAKxg{w_I z!O+j5Wx4bSVbeg=Add$>b=UL{f*;xjOBhsER@RUY-5}l#PFz1bQiW|zxhUVA@S8SK zFp52pHui-t!~%~2(Bsc|zt{XB`c_!DjV4jzlWCiNSsl$q;%a=^=^6HaP1qQ){}B?} z0rUC_U0|$L;{-MrOyW>%J=f5}=ZaYoF_vC5EN%4q4}s&Umq7gjqKbpf8kd+fV%8YS z*vfU{Bk@~+fWBAE_ej&=ZD}d96gju=s0I|deI?QVt29-!Y{8RTyJ#t%v^)LAt zKUgU`qc2PNG|784%bBw(9p_~vl4z=*a8h4!mGkP(0E-t3+4)~hHC_7|y%;!gh}8hE z_vH{xL@$m%kzDg-l$?#RR%WCK@6Td$SOUPjjFpzUzT&hQF1B z&vu)GSd7s6d}J=@R``2zQ@Z{+ViGzEl0u@QqBw|Dt!UzdejPNz+zVT$u?_Zwfo zML4x~qbb_-7dnSL+Zb8p;6U7$Ee3jzzw#M z36TzzOp2t?BA8s?kAAT2{5jv}D8)t~Mh=KE6?F$-W(S=`uFo(X4zI!!f&* z&E5p(W*MxKpXrwhpFsqlANj=JTW9_*#q4i(saio5c&ouj;1GwjR9|9rh%>NBMNmuH z>V5@{Ew0Ticl_Jp<1d@-MUDLH!V(hW+`Q-d*5Ux+sSDE51LH7iIZmy2-h;^|H=MGW zZr83xvCG~6p{(Aw;0LMU{Cf*kR7t+IwoT(-?0#s*IEHV<D<*N={@Q8lxK z=qJ9c710mGKDdLXw&6956JPsitRwv+r*N`ch^ntR&9vXPiJVQEzN)rImCOBpxN(TK zt8es$D>IK-k?h(tqDaH}(`52Fqmqa=BzH&frny~Z!fF{7x^ZV7@W3zvr?fFX__*%9 zp`VYAkmL9cPW2n<+f=1G-0$V&S=|20tiL&a)AxkHGJCypuW=v<2i_hPBeuGHuyx-A zKoFQU${5~b+E}TKYL>T@TNb)cqo#V*zoh%)D11;kTIYS@nR*wJ^#~IxsGYdw<5t-= z9UaaP8s|?=7U*!{zJ3O(KqT$9G{j#}N`nzZ8biM?i<)!nPWTY!Xw`ZAsAv^ai&YPF z$fEy9TW2c>3_*q^`-#A(T?Tj1^zrFhtKSU76<|piNaqAKAxyY#W6#hzCCvA{vGAMx z^uw(wZ02O zo1LLtbl#LN=esYq*lcSuIr9dJyB1?cRa$({;x_u#g#Z4Hp_w#S;i??W7uU7{p*a zmw>6MDOH_y9JihR6~#3`;^MiY10(#ip6jxzx;P!hg>LH28<;7D=l7aHHTI&FR_`^z z)MPzocPcYBd2j^9U3>W9WBv3KE02sx#^sIJl;_RAb)XTmQc2C`jYLZpCc^;w*I%uz zy+ADx2Gl7m?GOLndOaKiRbuq&Cg=*4b?-FOJfL@?6aSO1aQSwc1UQC zCU$OFeHPImi%k+QVoTi@z19Vy8#?D`@GI^{e&Ly=YBR2hanb_WBNNP>dxy6LxJE$@ z3+N%k#3l(+lAiIq#Gs5iI69(PlO_(gG^GOR`@tIxg}xKV?T`JsHv2bDZ&w2Nqh>|! zd#YSpGVe)#Tjy5(K!b)djG~Kh$%~3SM~g6gSpC;UA#x0Dqz>c8&Q$!2|s z9!JR&H^li(fG(&=o(GB)B_p2?*+>lKro{yh*-SVM>P!y)sTt*Pn0=C2aXNyZ;vid2 zk0BB-63y|y7~<3~uQkfk3n#}1#AVCZ9y)0$`<+^r^U4+A=qCbxEAT+j|7!gR&69K1 zB^z<>SSmw^qfkLj8HfFhOb1ClNG73EdeSxu`_?4#E7(FZ~P;{u}^Z>?AH1@CdDIy>u2 zp}8Nw#m`|QGn%r`Eq*r8q`USc=IAGgX^ru`zY#<5r#OEi85m&T7Z8c%C8di;-is}S zEm+R7O1tl*G-xr43$x%8PvplAmTa7sCPKg%wOiVBFML!G32^mUwm>W`ZP%b(8^4=P zo-TeB-e76pn0ra1dA`OA}8F z3;NA>uT$V|r*ZG@+}o5Ch`m6b;7^-c<`F;izqL@55h)dVB{W_}bg@Fz__NYD7$qCq z@H`|S@h$!HHht_9wK3K}=m$^tw({GlIWfi`@6+IX$c)RtnriOTJ)T!$glsv$p3ZNRSdQh@_8ov z58Peg$xpTs?emzwD6q(Z+}#MIv|nElbRSf|gXOWURv<2rxJsy>1iPwOE)Qhi<_|Yw z^C|6b*T(#5{F({Aei!8ye;Y9=YTc0NuqHgwrAj_AJa3MTb?b|7>WqsLb0X%6D@I(D zR(B!zN_FYv=4^-|8jC0=y|B1cLf2)J|Lmx2b|VCD5);K+j`Pig5uX>9@4CJzOkxhz zCPlxr=}>hFHLpwlkwT3=BcbHm?mz)KAmtNTzr=WqH6s0|GsUPp@AH;Zn)G) zhWTQSF#bs zO1cq{?vhfvySwvS-kI;-J9FmDnK|bV5A40xdY|`seowe_gT`0s)>?JO+i}MFQ^|ko z4K^=KvcsG+CEJ2*Xv^_U`cU?S9Ih0HiJQV&vTM$Sf=6!|9X5|CBXNN+qg;-`D@b!v zdX)lij;K{kKpFV#4E1s=de`eWfck)Xjil@v><1A@?b9!>0l~4v54!;+%vEXTEU2i5 zAMXmXiZv}MgK?QieXgca5;ep3F7C>xR%;;#~U-iZyo`GxTBK;{g!T^ zZ3j_#UE{Uh-?FeR>4A;C`6EI_+-P%Daj(`KlSHx<+pKelFqve`wxWpVH7?Hc`CbF| zu75TP=F{EZyJ6;x2r=7VE;m4>$VYC)(#M#sqhNa{m(kTRE0-`Y{YxgDY5uD=lJEWm zzL8!i1Wmo>Ebe6y9J>WfwQs4!1iQBggz~X+N@IR$E(V>FT9;L+D+G%49XVL0N~5r$ z{m51(e|sm(t|>so%Px(q2bdyV_P#Uwm%r_pZe?x-H@RV{4K{Q(?7y!zFr~l8c&Tsl zgFV+)@2H3@Mrd3dXYaX)WbzJ)f~ z*Mh%nA*&=P1ssWuxhA#Rg35Uv8yiG=&0q4UrL+>=PS?>QL5M5m`K znmX*yOR>-4YPdwvl4^9c(DH66Xiol*F-<)2kt)Q~lIY8XqPJ>1An5RC4Z$;!q!#wk z&X@%ZT0&mus0@VdjsuW3nCyhexD&(@>t*k+hhrLX$8XDps@#H&j7y`A%8LxSCeY`<|2DB>zQ^C*OxK{}zV2QznPc;LUFuu^ zbJDIF4mo_5HaAbt60|%eQ)jt2NPtJKg+@w&*B}Q5j)GI4+llxaG~BwEh^u=M<7}tR z)3Xjh)Bza5i!Y^r-R7v79ZaWF0 zN8+F$T1PBUIauK!k;%8owNW9^kZbItCOg!W9{YcwWWimoaolraoU3id(7yem(-G{- z0+CTyJI1!#iAM}Zi@v31_7OHM*}l_8lEXU04m>>)URh#7Hz<*6S$Z*o!&HSBdJk`8 zTX32qQ`Blt7R$uIFlNaf7?X#lKaXH1y*xR?Su$)+{Wc-@XHvxd6!vv@YLe3+r_53{ z4|64SEs`^ruZsl}5!_x-kj+5%1T@iqmPF-1r~0|SZ&gS@Na+@BM+CoZ1EZoWDkwzgA5m0y~srGl<1z%Y( zi6g9n3aAO-f(nbM?Y(0FlB!e`Zb-h*{1?$-+NkO=F^+e-%>h{s{hzn+8bDP7!e z?c$Rt4(SwEE3+*-`q{TV#Vt4nK`>+Wme(lgc=5DNldr{M@MI&DI4^fzFf&U0NEI46 z*(t~>S|fZ@GfED639}H#RQawalD(_!wWTKe`5z_0&zE=#%g-;uDy$w%_myxno)~U&4_a^= z=myB?BMs*dTvUhyc2&>j@vNwqWtr)Boj5gCwv4GfzBisePbc0_IRDJ; zUaf3n+_kgv7zGDAp~>u-OF{>uKUC$6KJh=0`C=U-zZzAJj)_HGfeF5}3> z!>V2on3`{@7Y(Xs467H68gxOF8xYfs!C$SS2Gw)Mu6-4P6csc36>|qb) zE-PMInS^KjyFDAKD+}0cuV51K%>hpDS=gEQ)#W*VSl&he>)8ub%*`{>RZY7PAo5<# zsym`>b}M#1JkKfm?0K?Js-*Ovm^wXVSZ#YRhv{w1Gw>zd?m`=Q|GS#d*QYU7_#?kT zW*Z~pEEkI5Ab*$y9ZJPrf|bXi51m}PHQV2oV+wZH?AG%Gf-tHfwfj}12ezh{$$Pf- zIzpb;qjI^d?X+zAQFW=ENp6ud9Ae(X9`6<`Z|OFzYG}^$YLMv6M!l-m3@bGY6<3?r zovZhfku=Nb&q{Kbyz2j3S$iRSdvfv*yu7IQ(a6Q4l%X2!{8G0o=_*G>v4CE>>-&nONpg;>YS0~v9G-whCJp`4xgsWtQOp=YZZx)cp}G_-{vrY&i!1{MG4jcm8i}GwF{safFg<~MRVzakfvy${Fg_s#cgMjQ*y;= z5Ug4Eef!=qdY;kTeup~L5$XMC)Mmj>US`T-)bAHbFyRCdgcYdDAzCJ4i;Y%d;X6|Q zznU@B;G<-?K=NaI!0X5P?Bk+)oTSF$(c{CN+wt)?bzXXRo(j~_J)D^Qjzeo6Ih~4H zQ_(~?`EPnTOFt!<Pz}Ntp{y-ogD8*(^9qo3sOQDR-#^-9Zn>Rr<3T`t;GO7edLaOHP_M9vD(v5vM?1bv*|+8;f8(F4 z{8h;JyTUJl3~cZdKE6I#b9s716xmpqW0_z4HMJaR77|kYTJ-cy_Zu+`8HKuj8x~#8 zev}l0pa%r^vD??gNld~WVxgC6mvI0C-3b6q>dnPPAa?U%fk6zu+xZ9~2$G_K9$cW?T z?;IQiRCpW+i1@gqk!c#>DZD?Lu`9pZljIC=>FWJz-+MN4a=A-!Hg`2`I~iH}GP}H1 zj0BI)7M|acO<>F|Yq*OaXNXf@52nZyWP4WDnWD0j<90+K*hwCG0?V`##djvh6RZrj z#KC~;qQDO-9@pR)2Nm>rZHoUqice>vFBCmWb;A(*J(`~{{&J51jYC^mm0>0=rEHA0 z(PM)1oR%A(Zuj3)i)FXUu>TdMLRLpMg|jLn3?cfinZO0SDmWml4-$8d+Zru0#X-d* zC=_nx>1N!MIYpMLdg&@tJXW{{0?*gBw`D_RYrCv%7k`P91iIa8a?_m&^?J2R>@rA& zc~?gAJNj3#Rwj?sW~8GfFX45GiT$6Pxv){shCykBTko2ZMyEK^Ub_uz~WLOMu zAi0b7S@R2?)YjG2-Trz?`l=>_B5>u|jCs^eX1t(bmAr>chAhKqO}_%QPQ=gWAV^|2 z%{lv^gfJ^#S02}9P^#t&3DW^#{i&HGiat&RZz>@-h}b>)T*Z!#X8iXN;|?H`9Ab`s z!^yKQ@Djps+*dUiQk?Vl^t^B4kz3OHxO};(P2ZC2f2I)j`p}?Nbekt;7*@Zv^Lzy5pEed?C}oH@k=?v*9c-J`Lo%7@ImE4#i~-EQ9Lqf68dh@52Bi;r{* zHbsq8FQvEGUU!1sq#lXZaSPp!t|R zI5%w&p|B3m9bbf7+ukGWcKrOM(IcfttIa&!7sH}NHTqasK*?W2@95vP2iTxYAno9{ zB9^{kt(I}EwsG?!K)wPWyitp$L5sFwGoZ)L8M^ZERh+{YXgUq+9bt%u?YGqISG-{e zum^Xldz38l2JtxjsOyi8*55ReI^92fuH zoz5q}Oulx^l-bHAmdKa7%Z{%N7(2#oo&i?i2w6du>ja@aq2WfGb5Equks?^wV$l6g z%C-2ysIhX?b`S&HA*LTW%g^bN_@fgPT#3b}vG96NGQKInX5;8?$SL0&p^Ah}WEr>V z0zyisZos1kvU&ek5=>-lmOeWNhrkD~a<9=N5*l_7-~)hImvsnrp!j_CZWFgRd5k;X z$g=#cK^@p-18e;&8fgpyjQ4C=9lbKq=WA>KT5W!Ldjt%Iy>Z3=BwBGYBjuEn#hu#oG5sW(G1}I(;T7xn-4YdFK7Q4hPzl z?%%Tq%Wf-PIyEhIwl47Ck;Keoz8xWEAR|I9RcJHN&Mqx_Su&N=KC|Nz-4&v4Pr?Kp zrOp(`@Z-Z~n>o4~(7SNf*g9)K{V8w!zg~c11Jlpu{WcdmzHT_++}lmg0EC^0_XTq* zfkCfbY@y#@iK-CNqUJU8jmU#$=@NAo@J7~+F!`wAc6|&iWjC0nS^`@yxNnC)AsUB| zA9nZ4Sq{()M!S4SZ*7Q1b1_5>Lv~hM0p^|5K3#qNCUPWAQzl0$L_*=DN#{Lnd>TYP zZHiT;@&6ckkhGadc_K7O8gPU5I@r9A0Ed@idqeSYk`ckIEW9_LsZ~U z4wUJnxeO9M?OYHSH_?ul+PTyy%ceTQn=9B(*W#dm5m%x#mat!ZjxrTeg*88?AR@{d z2q6Yb|DZk=)h~(n)LHvIU?z*x=f@4%O38{Uan(baYr2`)Yn*iKQh!Lfb{jIV#w7JG~fjRNhZZ5NcoM1|3yY&ROc7?Ig;9I<0SLzwJuiwy$>5!ttof z?5V*^=iuzTSVbov@}m|Sc^ZM%rS;~OhR@t3*}A+XRfNUdOb5H9*YwKGh^PTiYtL9= zP}~k~ZyZ9XXAq!1)8UhoNz%mfi5sw{()RvLTE@}$3N``?V2AYycLxnH4jh z!>G$;Z^$KM2&)UF02gb~5`w-R-Cd?2x>cQQP$||;BXREPRUbo@b(88zu`k}#qb}AH z37|#d;(CY}S0>n1AKo@Pt4~`^?pDLh%ao@|FKd<}``43Pgi-zJdB`HT6LaET_qRCu+Ub<*d9po?;7k+so%L_onHkvjh0kQ$#Prn%{e zCO7>cmy5xZSF6laZQDeBo<&i(${5_1r<<8kTsiJ!02pQtOE(DZV%*lN*1h1_XOyKY-*5e@n>r-@(Ou5HP%0FoW zx4Qr)VnmE5^2I_2b4}da-7vbcHVfS);Z9abnD}z?&x0Wp1X-jZ!hE;6Nj8Xw-+@a+ zRSCdg9A6#?;#BaI-I)giROHHDd8@Pv;k!UoUtFM?gD*9PhF#jrxHw8#K#8!DVU#C? zS986p++8*~)Ep|1WzCi~ zXm4!$2zJM50CK)r7}Q?Wm=~npmVP(!d9T41N;~zAWZRNJ%+ykJF7w*+NvyJ? z<3~KZSj@98l-vSNP%A11(=1E^ujf@AOybKLk^ni`UW<0+(E%}8mN@nqLZ^b4y(}2s z-F{rK(TJEc=WhJIu~jdVWV!?2z?MWQ2|ICfGK(fIme6u(b6~!@SZwzAd`~*fPQqxe zfSXLs8YgK<4iopM+cBurTu##W8uJHg=06BEF!9=37eR|`>IH$SOISwsvPVQ(3q&>o z`v&I`_)v5|Hmjj%6CwfFcPFqf=35iZ)~(L!W?Mt8!!RhTIm8T1N0A{5_36rk4^%K{ zEdD$(g!VjLBG1~@`IVnA8OHuq3Zg!y0ts*w&Df}@)iTsPYP}Fdm4+`?Pki{tW!=tW z&S94X$Mf9IH^A*pyTtA0U=2^RnNfF75LS`fsQn?S5%T4S;zvX7=k1!*Av0boYun~U zA85Kk&hFvzKqt4EEw&6(R#1e0(os-2^{4uwY6kw5Xn8;?=e%oxWr`U@zF_ev+bF23*6xpU-m9R_6=kic`R}G$FD)|=6AQhinhlktH)by8w#=hEFQre@Uv~#zIUoO_fh$fe1_&FZRRu0vP3&*6z&WT-=RK65i>kA(P@BK zxC){D=}s=FK66nNg7HUPY>5y5!0<8HWeA!IS4R2$-zaL0R;}F7RAJEUJGyN~4l%-z z|9}KYWV5KZTs-o8B}!kU+iAX2^y?Xs$k%(c0U;UCaC`TabdnI6z3wez#r5h$5MKsn zrMi(bs)_=Tc1*0>bROPJ-R2=4wY6He)aKM2`D>leQ zUs^S^1L>zUJ53ae2m;17KYg#8?wL#J(2w@vWrE+uw`;gTGq7*wL8;|Iqe$<yD)jK$mKZWOyxQTr@k~@PPq^1_PjZ!SZ%88+|MH1fn3~lID zQq^P>mFT1mnRn{33yYNsr{#>Pn8ChXG_ULp1q*jXw-xWiRgU#{(UQGHi~sJvJUu=L za)_>-Fonhs*MmN|82M!num&6InOYZCij^#vKt&Zy&m0i@U0q$hbfB?Wtuz12yTBtO zR%9~NMUSw1+o>^;%Nyk26GugmY|D1H=mzwo433VDC|!kN zPr68BZs+fqI#l;2o??@x0FzJrtQ~hjCZjA9k(hD){!P&yN)4r()yF7G$RL#dD_eQY zI-X0lWEor}Md9#TdGonRd5l8mb(lcYe$fldcn5NV9yd(87AXSH@14YpPw2(PB4kv^Vpi3*NOL{Ot93{lrgU>KJS((|Dv zbQ*R)RsOu(S?e|OE5^5H6|ry7Mx3l^W7766F6*di(IZVeZj=jGd!j{B*xu8;y4(F8 z@$`IAtgY>aQeq~-CAqXEu!*e|F)DnJPwAJ-5pNWC{;R%}y2+O#AM^uUgfAKoeZN1t zzkw%JW0l9;pJ2yHUQQLz!M`A^?U`S*#169%GDj%1c7YZ z^8GMB0Kp6tjj6}8O`4Up3(M?Of&ZP-J!xYaNrwd8HEV22+LL{W2!mBj7*c=m`podz z+XMU)?Agz&9P+(R8_}AZFHQUg;3b&gzEc$ymm?lhj3kV|;ZM!)`CKdh zaVY_brtYnfZ-58{NJ%lVRkEKARk}vhWP5TRXo?db!`#WVO2KJ^Aq1KyLB=w8jRcs` z!DO?NA$%Dn^uLR=p5@bfXt};f5E3xX<}bhSfjuWykBYzu9H<&Us{Uf{==kC`7Yq|+ zz7lpLwpaoJ0`DtEQIzKrCzKJPRiTA~T`sHw76M&=)ZT#nZFU58NiC!Fj+omYcCmGo$G|VZcpc#G8h8ArkXV~VFAeKaLjKjs{O9E zOC7uilD2g}*`uFF^)|8r>>!r$#2>cnSE?wX@z;qKqkgrcbR8t$zetsQ!9qq%&&=G_ zKH?QTzsmBshm;p{#}uCs0Dw6a*ZZ$($J=6cyTuM2Uku?+SF*>XVLt z$+5qhx&Y$UYS!aUR3zz)c>SEr_`$acMZDe+;|wS*x;{&FsCZ({hAJmL{$%Ygs-32K zED4=`IQKz=p=5*l8~WvPPywhig#`c|fowDzU(n)gQBx!_d)x4`BOy&3`KC7m*5a*G zGAj(9$RLKeMokOZNte--*r++UlNnbRpMd=*9;wfu^(c@E*f~&eo);Q3n!n@anIQu< zkVtF8n$vz>Z)6>-W;19zFJYAepfdoJSjg}vKj8SmRLE8osoIBwGfqttib%*{mTg;# z38k^D1?eWxs7$8m+$8MO^kX);y4phtJ$nyd*xW$^*NHccMh^e)i+o9FiWn^NQ*{b* zq$k@P|4eE}b)P}Fl{d6vAM<+2@LpF>_g}0iI7c?l$h(R?4+0)?U4ec%<~TFzXW(@L zxb~Pq5(yp#MheG#BaTSJgH@)GAVZMXFXc^8NK-06B=H+pYr1I$T&-WGZ@bW4wG!FC ziEB;%M!7WDBfINtm$QMfNBam*nxf?}?pWbNhP~qLQLlu)*J1SZ;b!1Ws%aG|dBi`) z$T9fc_xOCbR@t=iy;x};=lvkk+ce_k`@%zc-Ql->)^`FPH_s=M?|R|)72Ph?T^b{q z2%s}f)6mJupFMO`l}O>^avVx8s&xRL6+7vb;lC>4)%|l=*bPOwe)C(xzzTMzLG=H! zynOndLK};4duej$q)A`{^Tr)w>K|jBK-1F6*@)=g7eETIZMl)=L6Z57x2eQZKM~_* z+Ccbe;LEG!>o3*PDv5A3Wx_~PyMUJ?vB6%zMFnB4Lp!-?cD7Hz`vr#ZJIogg_@-y1KgIr z_d~*V$Q!IxO?;Bw24{hfrpaT8Y)SGF0VDuuTxl=_MS%#p9k&sQqsN>2fJcuVu6}Ch zM>=^9ObGZUt!r)eC}qDaO?BsGUDN4>khj|q+|bV>Z{;v)2^si|ESa7qy0cn({) zR&+q4mVPTJ$1RV7+;FrhKL8#O6V4Ec4eu-{wN0rv=Kp#T(KX`b;DFxta&K>;$?|V8 z6?UGV%;byiW)Cw>wxptyX>J}DK^KEy!U=HCUdoldATTG+nvQ*U90g~Byb`&7)o}j9 zvlLvm2}A35S1wGtKwf?};vLBGk6N8;Y|*NRZ3PW zc$Y(+Ek{1^O`MUjcUd`u9kY$bwCUkF;?-=Oh0`Mf#MGa2%$7%pTv;$3liQcjMDvU_ zdPBiIi(9e#l6=R-D2c-PmINgxxGjej65b0yS7(ByKY%HnY%eaL-%*P&z@`8C%sLCotSYjVqR{ zD?p^$sWEvZX<665XXC~B)-B3&gJ~NpBnvHty#KQQyDYMbefl}&h`)_(L2uB16SyE<9}%O5^L!OpQUJiS)07pKHNo+5MH zpr_Z((JONJQy6==u9*~y3Wag4-d+ko2l*GUzfE?ROj?3kfyp8itd4G@WZ3~SLW>o)?_s^gg* zx`D?}L5W6G&VJzhG^g<^mspbZc#}4)P3bL@eBy|$HvwwKd{tYQrko8?KpJJ}4?E`H zd~)MIqSZ~uSL=Z73N`JVG4H5O zHBE~xGvkC5>Me(cKQ7A1se|26aCw%8K_)-dc69An4R1MONox9_WRqo^s(o(S2jg*- zF&Y{BD9u{fUuLu(E)B!}nh0q)l_BByPcAJQW6WqsWWp9W|NoM`LuL=rDxWIyt95PV zB8y0;@PPy^c|SGFbDD_to%C~v-0gpWOd>238=5O82JCXs+lLo1<1yl$(n_ew1qdGG z@rjB8whX2r;pe8wwcad4;GhFa4emF$B}mn)JRemra?N(uF(v#u?GR#IxYC?YenqAY zv(FzfL_fXqJ+V}T+lS}*G9QM_FhB;17WGE}VjBsFDhz)Lswz6Bx)K+480@(7?VYdwJLS(;I+OT zQ8Lo-7(PE3$gMjn1Gu1JuB$4k^!l;wG~o4+UNY!WPWH^bblJ345EP zRLFE4*s+tIkk3?ACBpJOB(KVjbz?(J!pCycvnjR8z4lN@)s zWwhFC#FAB|^~&Da-3N3KH4^_onH7cXe&~?(b*<9<*#j%xw95DTNJ}5AB1X5uKB`fswongW;Kc$U4JFJC5Xi^)+!8~31X4tW(8VJhQZPzvh5@+b z>ytH{*5wiJM{K|j4 z^b%++#SzZwogvBU^)=|p)IXqZPs(8e?|VP+$OGdHx1t}|CDF;P8l@(ZcGX?A8!Y!h zpsM4~D%@n3<6V-G%zTZlL`y7{f=0%Ut`5_ATGdirKGkaTCw`L0Hn39228FHPigNov z{Yy-~@KoswBw!W~0TE!UdUC~q9~iIY0Aykv{M79!8feY4A#c8-J&-=URUrf?`UkP( zgMB)UYb)I>3nHnQs-PW>lG@g}a@J>#zdSthqy~1JLi^o(i%JY$aWl|3CX2uyW33Ou zU+oZ(mQO4qDyNO;2HYi8AwZRon5r;8zBwJjarv zJ)~AQ_i8uarYViWPSFUhNu*APCMEh?&jU9FHqWyY$8_K|%*yD(Am)LXE2$>t^-!;! zOcPP)Jcuny^r-x~Gu@YfT!M{oATfWb1MxM4CL3rQl-QlW9JW?R!C~nYT*-jZ2?{DQ z0=~t~&Cn`(OgH>IH5cdxOnbf7FA+sHJT9hLZ*EBws3Aq-as5nr(!1rrlL=ugDCn!E z_=ff`DEC?&Zm;luo-+LU>arfeAcJb_aZ{sn5_`*02Wyv@>%zGh@u7ibT$_Cy&S5xc zjs?APjQaRFkHCkwFN(|GpSB^EMvSF7<2R1H2m`0#;m6zy0xIceR6XRZ?Cm#xvz5kL zm}N!i05kP;Y5Npd-g1kc7U5*ifqkN1Z{N5+4%IKDoAPRP9LM3`tR@=eeyfZIl{5?& zdi_u0{pEQkZ8X%6m)|Q>ScFWBki+-Zd$hNIhZ&T`moN1$g03=49*uALPu<-}CAF@a z<1m$m-l(WNd0TKCiu?aW7996nCB}HEi<8N`#K<8-6HVtzGRzHqS*BiqB>lf`=zI_n1ntG*}hEnU|Z5H6GW~)xjf1f+Ghd?}= zFBzCpe%6k)w?~3U@^EZ$XY|X;ls+yFWewOfaG0EnQQ0|fK*eccx}%vqv7d7tN_9ru zxh?Wftweyw0yAxq3m)PuuvhbtH7zL3r66P<#d<^A!0;WBSzb@Z=xTA^@rW?4SM){8 zlZ~fE^W=Gi^t4R?-T?E7)o@Xowo{~TK$0AEt`+ErpVcTSDSx!D@`PUM6}@WLoudXn z3S}bmptlcznTu_QC*$cP)D3VpDpN$KLK5XkjTZzifgH#Yh?gDgVxZ&i%PYhtlKF?* z!Sd8)VyO^-CYFg30jb>xh|X^n0@O8CGotiXV~SGLI04~$h)qjql`XL~fEn;b{^C`2o?c{{xU!S9-A)R%6)gWFV z-YTCjJU^%5%CPC{T3b>P)2M2dH`yHZAcmwNyk<^3w#)qUo+fjG??X~jQiZyc38|;L zX+XPO@VKI(X&Ubc_EIa;J7=$0ihQPYPvp5q*Sn0*E0qc1Xj3jt1Pu}S?Xzl9KMZ*& zu>ZQCCaTr@T!P2N^5o&EbiHw!a9_XRWJ z%7+*884t>PO)GbALB_;8ME~ zXMlRJz7lQ7PN-j#{JJLkEirD2YP^aeRH`j)8B^Tk&~~;PoDSn0MKY#7LsKUM))!H_gRDOKFA^*$k zjLdd1eeHC&RA_6MA5^PU=$2E9NX;ItNw%f%S zPj?4$QbfRs2~?mlCa)>6J4Pw7gLa>6ZEU!`VE$?Y&hI|Rjm{u-{Kg>O@+$uqtBAVz z{B2xj-wneT67=xgVpdJ-*^`JJdx>cOLX^8Z&dfpEbjpIH!lC9JIj%HcdDx}6{0H(tWtM{w|zD{NumI?Ei8o^SX$`L~5+v^|Fh)o<;T=5Bta#W>cPo zSPWUN@~NjOCNe>i7z2S=^W`J37Owb;9D@&(;4*~CBMYgsDn31PJpl)VKYzBgsApM( zR}7@ARc5~<=5G?vOuhqUOJ0tx50n4Tf66wp1a3r~()<(Zz{BI`RhSD(D27Z2F0csm z5;x76$M)sOzX~?$&;a*Lmcl;j1aVY9L|=SvK9q8Yj+ecFop^}-+|P#LU5O^S@#s-Q zXil^I9ZL58J7kvgPg`EOh?YpfIzFmj}w685ETZHGExhfzQ?FLtv1|(eaMP69O(y<%D zSImQ%LO;BArhOJ6@cH_W47A;fW;>lfsbAGGFsa1i8RiyHlgb8R%iDv zPVR3Ut$1He6ZCRC7x4@Rh3c$EzTs6tv;BddxSZ^DNT_ciqXUIwVsEHr$zZgFwz?Qz zxNtsbdwZui{z4U#O1(-nqSQJ#!=g=ZGPo{RTGm8F1q3?48Y_ZNNm-+|QxZ%elfo04 zV;L{xf0o9QTG!Xt2G?t-g*38_DH>THSy}n9zl)~(2--HmYZ2x%wk#T%cc6!?#3L&Z z)1+TnjTGS(!+d>;R@G1aeHZI3bQ6upZb-UUinhp)v&$$b)5Dkb4 zr$q+Ox(wh$F39*+Xd!Ew>##tHa!n{!2~z+~NUQ?MC%hn>cUlloeBSFMpq3xAH2L4% zM*SdyvVqd?Q2UT+@gpuBInT)lP~AlBCr)sMLy!ri2n0!rUhn~$g!_0Gv`hnC2*7(x zI8_9@LwV!Kk(IoZFE*0&AK7|FZqlZHdR?g_zVTf)B>7hKj?%x2F5D$rB*6OUz6ECW zgLp<^x{9SkcG~;=nFx!2I3Z`}^e&j3TyDs=n0zXhgbu6LoV1kekX|_kGU-j{^`Q$JK zr`sW8Hf?jUw++EKviY-i1AaCo?R#RRst05_k`C^iZc2ZSQvrC$2h1JH}eQpar3Oab<$rps{`Qa=e{^n9{`ti>0fBY^Dn z_e%iyhZ`fG?)PGUhI!+*l88ccz&|01PHTt?~NL39xgFh3lNt<+hS8yze zMJlzTwye&p8bQjMaY7Y}5G(y6`-aOztDM<722{SEFUI*;kXk!|x^MUN=)n{Q1+ev^ zcMDs6=!P+!!t8^bwbzDRtfA{)Q>`RhwwtG9+T{Vr>o>4i!Xf>nxDk4L*tyg~4oRV9v*U~n# zqhozo*@rC=5y8aq6*SaWAM!bSE+T`GflV<9H+_FiDUF>N;Vj)X_Uz36v7w{)i{GW-vL^m`KTxlo+a_v%$ z?lZ8ESiRjP(@2{7`4j&%@Fd)0kK*MP5yh#@5(0YK6WI%n`TLYDezcY)4%BIj&;5yu z5QU|L`mhDHv#Wb4H7#K!V>nYJE;5WJ#q8AMp_&q2<)xU#a&3H0@}uwJWTAEC>bDkx zU-pW6aLU3G`??BSS_+Pq6Sw(jB(}13%uVv?CDr z6-#m$r|WXFyqo}0W=WW)nf=K6JP9;@KCVBLG411OVCTgJ7MPx@9<^{{*gM1%6_Hs; z^XBCd+ycGONtM)fXgG0bcfxboc%km4{n(}-xFd}LP_sxNsTSRGXkuc5GQmKFaKMw1 zKYu4|p!pu4>~D*W(Wyk?xuQaktDudqILr}T?-4GDB*{*}F-!5=a-9*OJ!c9Ovc;c_ zy4L-UB%Wx^C7Tr%zxgUf-se9$9MFb%6`mNz%01*_xBithhrU46oDnXyvV zGL(Jy>_?jcHT(}KphDp}E`J$jQ||{fu`b2}ONhGgYyJ{yObHq-_s#Eg>Bwg{_hBGK|HOd21@wWz`k56Hn$?-^=~ZP zz?dTk%10I1Qe$6>rIJ~& zv>%*LdNf+s+E>)q7x)A(JnEH~E8rp1Y27(^cR=jZ4Gx0RD*0)>`1w!YAO2Ux{u3Fs z4&7i;WfMVM_V7i#45x*G!zgR`j2k2y3BBpN6-9I&pt(CA#GF9H=$REA9b>qZDrT%I zT3d0%#6BGIoFf`({A@@P*dk2cbE0zxpW2rMYwkdcUrIx>;bLC7$TmeGZMq*~_3wx9 zpU369zvh$!D9ziHos}t8FYQudkbk*v4xRb;3A(=w;3Pn0>$QhgQKp8_Al!kGFaq~b zc=+m1@@jT~j=`=;+jCy`E?n>fB)g-LUJ`Ts=g8{4hDRwl~xZQiM4hs4>z2ay4#8g5- z+E##Klju;R zy>!w+5U{}9OL04J!7$V;X8c*kq~>w9i3Rl?QwyN-J_dgrwkm~WG>SyoXy0K8U!%DL zV*Rfd30ZGnLE2VUXflP|po_l)fLen)p2~%+Xz!GS4k}Q zF`MiADutU6QIE=S9OwIWC~8eMIXy;UArjTVzsW1#kc2jz_QWu(Tb&8>g=9;Jx?e5L zpF33_chQZ-Ns-B(CDb0o99qT)>}JVXi6>ML?%eLs)D+E4si))V2eCnuN@I-l$Eoc>~3HT zXYB2%+;I|Q8|&$*5p7mC^ms$aT&LMBtAe$b&)TmCe)+5`mbO?MN8J6ZN4iPPn7Q*_(F>u zlA7SmRQe%7fgo`Xfmxh^ewS}v)fHB2l>12DPvj!5Tpzc``(#@h$7cfVe~s$&cKUk) z;&R_lY}|mD9$c|N4LOQ6ar$vPAG#WRO2RG>t;ma9k(TCMzFi zx&*=!iOy#aoMu~Wq93ZY;_%ql$)fMY{*)B|{am2FGRinxTyZ1)mZTi#$|@F1y_o(> zb4&d^!LLsuS;g;tu$~(cmt@Ii(=d_4+LaDu$q^2l{~6TSuC?b2_|B8=prj>T?k)e7 zcJ$&<@8CqWUW0bU{c}QFy{}>OT=;3@r*w*yCwin}A3Zs?s~vFzY4Ec!A+eZT97f-U z(|DC=6}gj@W05*+=zRnkqQsSPtPI9Mo1FAo41;@oBI0P7pg1Z6(%uDGh6}l+z9-j7 zm?y{EY=3fypD0B5lTySdj^E-cJtPkv12WSqnrs>aHRjM(1+N??^*RbsF2PJ8?5bx> zfBUO2A8e@HV_4vd0s=mR8=v#23AM;!RhO5SE^wxk*F;NP#2`i-w1x-d*JY%btd@i0 zjimpG4D5b`o8#Y8V{!V6AM2c(0fBk#?3ZwHLh2FpSNL7zAD#m&cX4^EIxjUwlv2Uv zHD}$YPcbS+!pH9di3C$t#nJr(F-5LTe7uk11SO;+Ac*Y9h7f;L$$VQ+Vv|?8Qsr#| zT9pY>Dv6q9Q`0v5Lq)S%mThdE4z{-8pamXQ$}P2%qQF`=Q&WM>^y^nRJjllfBRfD{ zEipB|RGnog9}w#ZK$dIe@)E#=TYG>;_0N6yul4NqRvY2RhS86VN4`iyN=CdZ01T}h zuG6+N(E^*AQmX_8_TH5b4)d{01#(4}tdYhrhPF>lz##MiH@d}Hankqt-QR8mgx9H# zT!yWUjpHUs4o*rF^yC@ihntNr3J2Q;9@dYKae?dr_;dSdduih7m~p_&TEWlHKlTt1 zf_{YwEw-m9rr;TL=(5ilx2cjcRaVCVr9KgQ&N1;L_Z>V`NY`dGQCg z3S)4ZDJeEKwo9PX@lP~fV7|c&>O7)15_(TdCr`f?~nd*#@O3;z3X|d`?>=tMAu|Q z-CrbSBZ_>Vs+wpv+j{rrJTfh&Y%uQf70(F1LKXDGvMa(fxQR94uoQoasoRJ%+BfyH z=kX}ShTQ`uCZqx{;#=={RAQcVQ#KSK-r<*#oTW1vo8M?4NXu+vG((=hdK_`1gF$Kg z#gF2hAyd>nX%VY&@tR^)u4O35qMME^meYhef8wCypWKP8v1gX@uns*6~p0t zu28_Ts_8lG+w|5`22GOI4-o(1{t2|1;5w)4JD&D$H)FJa2Q=`fs_x{Tuf@=t{Vv|4 zXYdDHk_ElF-Z6s8sZ?Py0Z=Enm^fp0cADDql6Yp`Vv==={w6J!Rw{r7DQGFaw+6o_4QgR~a zNd@TDNz)@KA-_V=^uKWcdiritQn3hekVL`jNAWUCHEJ z;dJb0m-g*e?Zy7P2#2zgGz8VIcOfi<(pQ6f<|Y-Hisr*STV%txW8+;}sV*=8G6df# zrvW-Qdmwf&Mdtj1Gzi_fwnldU^n4S;tXsarxe~b_bSDYwWvf!AI?o@>5@-;+MMbm> zQK)iD-fwnH9WsrM#8i#YsU5HW5HFC#fVF(z)B2U~Yt%0tEILH5i{`nxKovj%$yqcl z|2*%plC)1~kglGG6M8~w$I#1@t5`p^5N_6c{l>uXgc>zo+$nYMjBf8UjS{;i7dk@T zsAIeBbYQmU8{)J_QZe*8`5t!lU5wLoy3*cT%I=8^E9jBlwR?sYR{}+%81@T!fn^VfZary6k4qUR6#|d>bmf#>=a8jT7RF z{i{OE?j=IFYF6zeGdD0-a`u&%&vvt*`RL`)0==i3e`2DE*WXaLUZEss9K2IJV3!okm=W%=5`y7?Z4O^rtuM*ZUjoK&KlFP%?PnegH_hPtxWZ7G{5SnC9!ce44xIp%1$xV}EGm+gtY*b^WWrJj9u^7LXL-N|eiu2w42d~I9 zl#KG2Zlr!mV2(K>hnO*jxpX>?Wq^IsJN7t0k}0S!X5-}L2h`&(W%Hm!)e&Tz&YA{u zG@Gcfk!moM%6@{R)9QUcvg~(230)%dTa8-uYTv#dxS=gfAQp&?M2XNWuY^*rHyIYs z-9W@PqGNK;>ABx9@WAlzg#Y#%R_(UEXA>iG7qY78D$QR%+BhsuoklXiF-0SGP>l<9 ztXtb60~G?rBc?@1DJboiOY(a$Ys-iR+JZlObA;^$8^oFjg&q(PZh<8({`SCAHj5&{ z@-GW?=(S~KA6{F-LiC|aOZ$WCw;|W^WTx4iIvF=5MHhP{tXIF4>x-fs5J>_BkmsP@ zEQg}xXFT=%AWJ8biTiA;;y&bQ!8$y}lxJEgX~C*l9INCTbCDyR(08)a*bk1$zR0L z?n=TM%TJQQoNVg+l06TaEy2e;5*YBpzvn6x;PqWzBi+^&$}UpP^LFX*pfj9*Eg|0Z zW-(nT-E33*qzfo=5xEmuy+}QT)^^hhOv59W7Jk{BU&K|e0SKp@N>D&CaW6)8{m#9e zt)$Coomv_AIKt~$YCw0Lbvx3@)P5=wBR0CefNo+9W-nti?EN4HrOdr|`qzDPJ7_nM zEuh!Uz2auYL)4z;3|3XDJJ0;(!D;TkUSp+X?^loZqd}g#nz6#siVk4f~ zeMy6bo#$&%Hz#C9cHDmTc#?F%F3bw?#jHU&vvrHs6PGEkej&Br?GespR^ny1>Ena0 zIO-rHo1UH!1)EG2bl#|Kf`6@YpeVjShBxN?_S_`NOz8Yey-s;aHB?~o`Un6kgUh;{ zC%Y#C(-ovpUaC!TlIb$~ovbJlC7{>a6i2s`HkfB2Uiwd2_jb4S?1+LN5E>xeHSvRx zT6l@_x_6tA^mRJmzKVwS_k5#E;y(`@5F@$;^}Y^{URxy==AiFVdLXoB?Vc6|#+s+0 zx7i|GJhs-S1L2%Kw2WYiy9+qRbMXIM!iTNr;(Ym1pJS*+5TcK}ISb_ukHA12E2-18 z+-F=n(J<~68kkI=m6q#ZXg0l_focp9fc=5^+up!V?)jEqVHWp^fzUH;pw3^(FTy&% zATA#y$?iVo)}(p}8O=dB*%R^5T1AE)P1Z(v`>lv2M_9$i_T56f(?7Rl`hX(FC3Kv< zI2`3mR5#3Bwj#oDBZ@2KAkWQn8!XR)*XH%7*1dab#-Mp|%OFvwb5|iG**pq{Zm*yl zzEh!QJjHEdC^%THa@+)Nl_A0Pj-gT-46(e-PUJ52y!dx#mN464`raO?Rftxo$ctx!2Tymzt_|yL##y zi_c~%n#ck9Tz`|GCo9)3f|AVw3`lkLKkY z;ig~;%ZR!P?Rb-i?Y~#s8q6w5s3pZ7WYVMrRWkIiz#p&@{6Hi?Jo|htz<$d@@9exOWweLN3!9#*9ykXO6^L^)Ov1Lp+}TC~vntYRG6ai^oxQ|8|? zar6;XG_^R8%Vy_T9T;U$_vd1IV3){6akFV zbQ=HF=&2-qZt9ahy6JckN*O8ApP$S@v0bv}3F{ujpFq;B#ChA)#DHuhS}{+I0x$7Z zb}KysiHA5IlOx{i{)!PQlHnETD||Pl>w!dqEQ^;IXK0n}H7i)^(HV{eDJ_^G2%?*q zhsrGsF7ii$VH6JZs65lh68(O1HPk?r=)_9#ZIN_lhQ$&os$rQ_(B~2R>Zedr(d-ST z-48@|cs$VqU=~M0t{bGu(Mra7pNv4&BuvQ?p%*D_?oaV5o~{-`l&@sJ5Dt25f3!FE zj?A-x5r~!7!vz3V+ymwO!||e!ytYMmXfK;@GqG@J5~m0PxfN>Mk9RKr#{#TXm?_H} zf`9iQLNkcNd6F?YI>a1tZ zNXSV^8Q-g8#k>NKhhf9il<+8&cM-U}NIe+;+*&MaYimpo{)TMG26CG}e3j{tWVYNu zQ|bV$4CTakVoKzq`9ntL_F2n+y;uD}!T>{>(>2t?a+ZmTGOTy!4pRGILjqU^ZWWlk zx)ea==}Z@5k_mZycZzz^kavIhi>kQZ8p2UZxal5KXH?w@NsuH)-LS~*d@Uq|iez6a zD>cL_LJqAV$Dm{H=t~C^>L`te^(Y*J4Zbr*&ALY0-p^o4&XYlaoy8*fE`V;hJ>84| zHAI`W7%(BceEfc_ax9w6>P3>J6|T3a14@C{ogYLurU+!0qW9kt6n1`_`%H$h3u`8v z;i+(`%eyc5kW|OpqfjHJe8mK<9AO^Z_Xp~SYRt5*J1HBVlYMC!#H>~_#|DEi5}k}} z`(% zX9H^`R)2^wjfpt{uCZ#1i?QwP{N+nDxLdm$Dn=~QE9C$(mvS5#N^wyq!3j}${_qR# z(d5>|I-7<@1k1$!J3&{LAG^)%4C-{B&$5LKx)cc-yeOALUZ${@dG`&fh4Bc+C{e6Z zI9Rd@ODvJh;X1#YF}mxSd0Qt@zMHDBG_ms~cRg9_^91}keJuHQ$I}-6?Xtl$mQs#a z0H|l?p$kGTWg0jISq}b6yb4yzwft{QSql;bA%8B%T4^JC%ax#{wr~1U%xf?RSnb{1 z@~kv=8k>1CwQ-0#>(3xyRet>mhJYfRmhPjT-tBfuA~h5K&_`e(zZcW}ux|zHjMU0r z)$35vp2fnnC}@nG%|db_23qax?Ci|9IJOb#&v+2vRK#=lIR{n!I+4LAO^qnNvZh$G z`iUUAzh=(8*()53$R9AFMspVl3}NKOoO2VgH+FR?r_I64VC5b}EsPlW=D{J6K-0Ck znGeak(%pSth0WvZ1bp0aFD_34*xrF>=6B4$XPZ5z_*(iM-HQjyq)-b>{PdP!aCK`? zJttso4*8>64y!xBj=yNVlf|RqU>!w7uC<_UWNmVpc=KsfNNMqLnfUa$CJlsIHjrRe zTHM&qJsjNdD{DTlE4vAN{h6QnnM|T649TlfLr1;Q_Uxj)C>X}c279K*Ewe!yNAgeZ za9h0mmf$!DFz!esl+U-`aOtz)X|v!nM5^NQn+BcNr|3gVGQS}cAvR>q?TJ_DCyKV_ z+b5}j!8?5OFWmBYa+7PqpGg@-m821VXYGII6<)w#wec02<&_`x`Ps>;3E-coM%Xiz zT5nv!?~EB$uNYBdD}w+g%Qpjk5n#_{b^XD#f z$Z$u64DhYTD8v+E7)Nf_Q?4Bc4l6YBPzkPNq@)Li;^&uNbnO6uc(Ar^S!4;#pg&!Q zpbs2H`s)=M1u}a)aka85AruTIyf@R}tbbYiRY?UW){OA?!8@AKx;I{uS@>)oh($P% zIfoD3Q9pZ;sa!amZ2@6pbie}V!?$@H& zpRM3%PTh2j6X;|T)RF0jKX=^!QA!)fm)U}4@BGYiaZYnSwZ;4Q0-;3R9U5B_o>I~@ zj7GLW)L{(l8=%&`E>VZ;IwvRN?;%)ucLVkclI-R z9?otzHpKUHzpdUwRhs2$Xyh}&(XhU1cCivUf;_Kr_@fvw4P&{-Q;&09UmM+MItwaJ zQBfZe%W5h*xVs~Xw&o>pPmYncc!3_JMT8alv`(j`{PVy9Lln)CB1Hmvn1&&JLX@vz zw8YNbM4JGNP0vV#u;6dR$8Y4vw_ZAM;HHWrAiX>5% zDN4d)c~azyAem?EdJ0k5CGU?@htVLTFo0Shn-TuO2+7ygBrtIvgb^rCDo)gC2Hj|6 zu|}1Brkq`d?8;K8;|Q^_55|e8Fkvg_z=J!+$Lg%jtx%$N%|H|__1mRoy(O)!`DgEl zT`qMDwV4@ww43;bN`;6e4~6%`0>Sn(gZw2~K<8(yfx{81vZ256#adO*)e4O;x#Mo# z)w6Pc&CqtHKZPNL{Yl$W*4%>2qT@(-_xH-BJmq!c6i%Rzk{^j3%r=U;-06m)9+X5M zPu}`_GPa3tS~LE;2o3J=sw5YirZ89I_@Cf$-R##+X9%>l^J}{)CXB~C9x&N%ZVWgV z2D52OEWD5<|fDDr5%S@RVB z+mH-x7bO#3gqYaB=_c6y{7lxrO$qOvZk*GL+0B~-?fb0HPQlm56;vsMKNRK9Rrbj* zA)-~Ova*^M`Q6!m&Glj2q$TTct6#Ys9F`=fg%N~8mg=iT6xf<{8TxhQ#cs+74-5^F zt~5I#kb9j$`&=Xr+%B4n^nfgb)8m!7Z=jO!6OM?-i}y;KE4nAbgUoazgmL+}zutAn zr=d|i;hlChes@7Q)tVv5lriC(1_u60^02I({iKa;xbs9OAD08Mf?fSlo%pe1u>x2H z@7w%6GTsu>{mMinQn?rubO1sw!8HjS$$zvG{F`|}Cy9ov3rW7qw|li<4S`~M2mA}* zQF*XW96RtTjd6$~0-&BaZi!MJ0br+oTeoU!Z*L#eWf;Vs^z90=rPDT^zK%se6SjQp zl6*HD(9H7Qrix3Ly^5V}#kR>3xkfi!2xk`Wmr?2K4KjJ<$bFzD9XV@Y?*+%@o_D3@ z`=Xui9)Da~+|D+-ZX%fHg{v@nHJEctQwllf5^69#PK~fw2c-%Pn7WK05QRg0A7Q3! z#P12Xa5L?LUc%K%^_ob57}>TZwp)CmEBlYo#~fY~AvYAePu52l3+~5=G`!}nN8@!Y z5+p+$X6}vKkt38!SEReO^_rXB%j!FE-Ye=$wSSFP``-){e|MU=q57~4+wca?3Rkz( z-YzcWUiGrBfMMcXf+5qvi#^WB(oAP_w_NLX)b8aiFfbq!)UGdBH>Qp5{XDrMbJF+T zdlzt$#Z4R>pSlI?Rs?7d3=t^y@QDZV+d-Fke}VcO`uX|vg$zVb)}ToX8T!H42sZAT zPvGWd?{Y_4@g{EX>GV(L#|%@kiMViL@5*BD_ZWy1(xN=W)7U&wdDWbUDDpuJ2YQoD}yA6eZ!_e zBK>``D%B1NbWH}Td6Wu_t4WlL2LZ~$$5q=V{``znF~j`ym3nGLcl=$m?^+vD15Rq1 zMMSpJvU*$+TiT}6i|}B*j|);vTQvUlXn|cAQ3*?AZM^^$>L~%5V@n=Xd`3 zk>;6Q{=6#R)k`3=;>aFl&mIFrNBsT=fTYziDJQ{2aE1or zT$@=4Z7>gDQi$p#Y5&6e7f}RnU7H)=sYfiFiM(;2E)QinEN-HUlrlQD zR?#RLuKQ}$(L`N|kmtxIhhJU>N+B!P9yr76PR1P1;L>N3Dq)oAC|gpF^qiC+dHNuY z&e#$si7Mp(_Xa%)bEqI)loy#hfGc4T_Giuz-tN750oCeN%zZKEBvqKbw|8_|*>{5d zhk7e7U}P|4?Lr6`Rlxx#u4SlXkNE!Y--y8Gz%YV!+IB;Bvewp;$orhivHKT3b>CdL zcxGyV0&xaER@O74I8BkB$;1QSdjE}MmFh%dC;X#NmvOA2n_7GCL*jh=emE*^z*7TG zOOBp`3zI)A-FMSlP`o8e)pn{nozm5rzkW&?BeAnMH)1B#vWf)z=gRA6e~13uo`cFZ zraA&u*_v@LK4(qqYqYt*bW^jMtEskuS$%WZkIC9yP2ch6e9;Igc3$WZAJ?@PI3<#+ zF*6{A`o!obq=oaZR6Y?W>BPh!G}bAEG&X5&ESaf}2UN4Xf9DWoTOC+lZq@2`4(Si_ zix_H$vd2sZp?6YiGsU6!88n{)*;cI{TOMB7!Neno4{?$}KPfmU=^@D`k>3k4_ z7bQ>;`TET~{ECAhii0SIoeZ_MsVVgQbJ(PPSlc9Gj~IE6K6#rhdYdi6sv<(RCb0z; zB@%US{%r%jLl{jIsFU4d5Xb71p?Y~>kRp-VI?SQ@Owa19%j*2W2F1f0h^$aDv_t*qqr~ExHfcqa}WE}%wZSbK-LtpKi24)X<+t-wI ze$W}lxdkAeDt|0EXPMmn&I8=BFF!)`9&^S`U}7B-&;8~@2EZj8ZohXw8g&A6l!CVc z&GO(TyY-W!NZ3_gnL-P$PTu~2o8#psC_ivX-U1NIPoI~vACBOecd1q}pGg{5SH{%Q zhzu9!UU`5!T1;exn`hh4adP%-J;yY~9!J$aYg>4A$MtlLio(D8Q`5+6gUGT$SG!V+ z3Bl~LZuOuOYOqdkoOoQsKgAW-1uS#;Be`X->x(VQ{MckstY60^iNSN&AY2Ga69h2~ zi&u6cIwy+t!^4aDK(J{d&V&m%qa_Rr8N{2GRn7uk5Uj>sXt|R4pyquwG=6^<@L+Qo zH*CA861T5k-G~(N@wdwn>9K6XB#ux$2?S1UDz-l|^MfBP^}j-SCIv(iF+rl@Yfj zL~u|Li_Y`s-~Dm=95vtosAmw*)cd$<*z&P(+F~0NQzId*dbNqcy z!*${bUje~f-fFcjeMpGai5NHbi3>mk*=bm?{t2VNcf98TtPTPXue}x5qZw~bRv*f( zaD@vx?$ZHq>3gSL{dVvI#XW^l4Mb~8rS%RH7wcFg=^#fkZ!<)w!v?=bb$vgu>r$jk zl&uT+u~A+&r4ZyuWNQy1jUaaSd&#G)%o$VaM|1o624czQ*O;(V@g!)WAg|Ni*VpHo zV2cFYYBkClxbQuI3>B|)`ehM$gyBT##AVF+h5*Gm5deJa96!ucL+e?gdAyjM7qW#tjX927G94|R;~9z(1dkG_jW3c{WSHfp!BL_ zD>0cyMvyB`?aQXW#D0t1mF3VSNpi5;BwRoGPJHzJ{hwF$eR_H>@}*FOyRO}hGD05^ z_-nNjU?LfeUFR7habVHDfA~!CEtkDS9t!p~7U7SZ0}h^`HxOOzZSLY0D0{pb_9fbD zSZ4Gje%=orcI3YwUiFkN#wQQBwhSt>89=*N)IdF*I#Xu7?+bqbY&?8jctme2od!*Z zJzldf^>Lp#*omT(%)aYa3l+|O(;}FMq6nA7ksMCjh(qCtVSs4{wM+mP1c3PPVdivZ zG$zl<^>su04LDsnnY6>ew}(_Trtc8M4}rVE0eGN~JnG*4kOrFHrzdaVkAM6vEg}xg zZZ0i-*#fTIlmY9wDMVaS>xnvEO=0*w85e40iA&|JXTMj#nvaL_-dO||QjjowH>}2 znKntqkv?{&`BQr#M~5>oje0k-R1~&ZG>+w^j#NiW3=6*4ya+64H8ez>I3ZR-mb*;NCys%*hFwpAUW+ zzWpVXi859!LX{~(BL0pznMT%LpiNRo2i6LD2^}3hnQ&Oj3Vh$N9JahbQzv)bq8R)4 zSxX~3J0+czm2#J3RVJGn0+V-)n_Wg|sT32_)_%B>`B0`fl0eqLFX+^u3s5bo$X%C~ zVB4nH@^WGgWbl<@#aL|JY~Ft7%tOj(K|^qTlBdDRzkJ;2BPA!f`?Q=voG3e3aNiY( zu=I{!SXh$^Zo81f*i51vhvx>V)u9t!toig(+ingdF_O*cbeMBWWD^+J71!nJEWT_t z$G+(&Xqy92t>2_)WDt5CX}VUEfX$B1>zrTDf>^g{mF6;<;XI}US|B)4%mvL01}pYp znE(Zn*X|v$pn?!T<`tdNd2^xqppKJ32j>AlYk3iwGfYl>Cb? zf;|qssB2mgJz&C;`rgJ%S_RhJO5@exYaR-BVI8MQ`nWvD-$RTfXWbysl;l%nZA&j3 zK*h$sMtsP(xde94Ix2aYU;Vz^-Y+@{dj3VVHCGEV3gQi~)vc=4{x#b;()oT`!}wz& zC2x()-$vC;H>KQXq+?CwMkWAJ0#XbwBp%^~?Hs6P{{i6FZ$c$Yrh_@QM&*rzzB5k_ z&blIDRap6d{F07-E_{lY5X~huORa3+Sc}6YY`0IL+xeDjNPm}uSGXyC;EoViY7DMR z!K$*C)hfs>0Ln~OG>Sz7nPP_8r@Bt_&ZtYdf zipscR4j)kUzGe6FH#Ll^d0sU)Qzd*S>vjPs9LQqNU43s{Z$ZxbKY!3jw)Qic*MSsq zg^ekqcea&trg1#g=;5$>)#JG$J2kXZ}7A&2jZAv{0Bj zy#Yr#GSt7mn@{zV@EE`!_3M-Top8geGnhoMxO~|(it3uZBh+uZ$5SCNVkcmLiOTk$ zK+vM|HkDBQ`BRUDeQkM}@!j2$Dec9cnYaWG85C+3>@@`Yvw6y@vWr~-14J-6Q+4Lr z1J(QxsYtIBirXSfp6>U}1JiV#a{v_0qA9n;*dv=92mQ{FhWyxCek3`T?TWSA}y#2D=BH~A`qC={FPn!RPS%4 z{D`Fe)=UiLL>?zSh>KAFb!sU?I0x0be)T+Pzur&tOo891Y4Y_0%O9W?rHa5-FY4Q! z#RXEJaM0(s1q@mP_`n4N3LIaJ=Lq%m-N97>ZI!oo;DK|(O__c@J){(h7{K-5OZgYD8bjd|Og^c@C!W+rdjQjOST3RRtafd_0RLn8!ebnDt z#%BXaXc^1qu5s|LWpn|{j*}?={+uRaAR_Q-4}hs~9jiv2U%Rq0;>J z(VmRZe4MU>Yk8+s#8g)!EzQmT9PkJT2n)7Nf8Gq=)N8gLfS34^gj8_Yw&|}VUJ7b$ z_{n4HA{-qbgN+2jdZa8<-5|bYVdvp6l@KDN!V7EB^hH?%Z0D0|e^v3fjGHRf=9vXX zh&YWM%Ojf6XLt&T(f1?r8~}mp{gaOb8FHJ!!UD|KAJm7X3A#2nP3N!LzZURH+b4_IEO-!u_8C8sUk|aD#Jig<)Wxq6Z z##aV{=)d0$OODDI-oxgzBjyNs##FMs9_5 zVW@`;D{4GgC>`4x^&RfeTYym_@gc;}P%Q%gR;an1ZUq|}G9b)x)5ux}-1|iw{Kt)G z%||W*zi(OyP{7#b9{l+G+Jhh({`Za9hH^`G-n7D`Z3!8HLL3cd0?h?Q>CvX&Wv69P zw4~9Ij(X9xf@m{!M4f1SGJ|*FXd09lj%>V5D;p_nDQXXtf8wEL@|R!GGzM~01c%qd zFjYk_t(2O~=ijY8Cb3xvqeBF&#ru)>JgrTYImg6fQ3ZK;79N57vYb}Yc$FFHiaiC> zkV;!7F6&q3o?mfs2i+`)G&97>+9&Y6-tKL&{#jN=G@APQ=PDXrWD!Jb)VP-Lp|o=& zhwjfY-fslI}MJiHQ0n2C;(lIPi3T)-HCF8{Hc9Z@o zn}U~2^UFVN9gD_nOq7oS!CG!C2c{-t1jrzJWvTv8&|zRCdW zsnt^g2?F!<^@#aAH?!WE@Bd=~lBQ$)n$@ODvLuWM%IjFvK3M>|HoqEV`!YlIoM3MS zj(NI61{iKE0t$^ARK9ulxCz25qdVvSjNySDiVV7Tsyj(`v<{1Rv74xSu5@5hWnDIY-qHv+#yE9H$&!Rguv z@aFG7n^zjkKN<9S5MKxBC1nsEc35hb)bO~IY5Sg0%BwcVe11eVC`3XVZX^As-tmk} z__KdrQCP9-t#5jy8*RjSZU2%S0s-=&RtOpvvEgftW&W!(k>`OI+Up{%C_G7j3Y4}2 znG6SO!7!U}H+F&>zy_CqDrTYU+ z6>LPo=Lqy#fODvf_RDaVDuA?=4P_P2=DU^LI6tx5e&HvLj$O%>2{I<7fcXxmOfy-y zeEfOEW{xR}v?89j!~Yd>+4a=-BHw|>sKB4$K+GQY^z=l^HU-R&sMK-~l?~wK?T72> zn&Od}uwntS6C~%QnC%Iik04U}@<%r~mRxj-oXq!}GHD;_^_U_@wj#9XTf+T6jCl%k zv`>*g{OvigW=zk%c6qCLyqD#xX@Tb0B#0f*zWZkFWrK!m8~|XDNMMKV>5(v_fx3;+ zB43Xk0F6~u;gV{QUj?a|esXM&rjat$KKP~g43eLj1NN3)P~ih(7H({M z8B07(f}q`7;&?5hbBHyB7ot!6wGt=4WZYaQge_ON&#`&RkS>R3NwIRl%PLsdt%+{joXKmEom46xPv0ZvKFt_ z&E~T8*7>*znGr_~}1=j6~SkdS10hL|T!}PweQZ}?cL6R!@3?vb%rhm*- z3hJmj)~%hg2k%~sEDpg0ELfxIuNDPxp1;LDU?XlgJ9$Urv*m2Z z8a!f-0}45HUTdM^Efe8bqSiF17EG< z4?n(Yer2J{_0io+K^6%c?|#F9pRQ#&$%ubH$>v=O%8k4t9UZ~&d?6e{q%EBVEG}aS zN&pnO_toSLM0UTPaZG95m?O6b`d(KsG>YDO1zazWE9wo4iXheG(3;T4)Wf}(LkMbJ1+^9Q<8p1s5 zdp`Wd0mVo*ZfS(AFV7FdpOYcQ(X$@WL&wK425C;+gQhSs^g&I+CV?DTRCbuRmkdzF zH#Dm%u-Z?}UvMjmT04Ro)RlH>8b3qj6s?d)zX)jEyhxNY`~755PKpNKn0eR=?Ns2vlZT~(LX#q zU>GbDv#K7{%I^83*oeI+>4!U^g-tgVS!P;>v;TA2e`BIA-xgx;U znfgKg8V{M(ZD^(>A<&b5Tkdj&o#%~?eC8-T=rJ94)zA=tDMxg~ge6CT|CcE7qFF!| z^_PPXMioXe!_M}upASU8x%Ty`(QFnJ=sPy0qVO!=6{83p^(dUr`Gaz=dvW?rsvs-# zFsJdgwVV@Ms7UCq{Y62zJcnQfl@n(0+hp5H<2nEc-3oVYo<3Gk($49;O zP>zysXCJCHeOO_da|uP07l8SZ9LuGYMWvsXCj-VVypt}tcV>yGa@xYAWi+XaG=vf_ z2X5f8*uA4cmsOj5Ih{-9nbrmK*DgU|Iz8uUsSVv%pG|(*f7*b;I^1^eJFJeEEp!l) zOSCcxdg94etkt)}N#Z6eq9%~bBr1dbimM}{6^0=WTeBv-dA^;yk?Q-EU2nuPnSRI!#4<<)q#=OCL4M>8ecse_4*)_|7EoE77d%? z?3Xt7jDjE>w~DVVdGFPW0+#qCfi?_sS7E-YRfVi@$H4##+xR$T1WtBD%Vo9N)f@pK zmRUB8S7L%gGzSgJAE&;X#D=AROpgV4Z7h|@@H+4dsf~;>sF@Zigwt} zZ1SO@qo1#NqN`tw{+Owt&fNb-H-#aw_vNmtgX#3(^77wpm;}sGz!uE)B#VJLarFK} zu2Y=47>oZtz8?=70sewB%|X=EmuJ??H4omubJ$GmWnj_`iTh(gIrTvG$Lsyet?GB1csB{`J@MszP72bQm%WnLj8@pqcrjy_gDP0Fdn zC+5J=2F;SiOp4C#hr(_G9JBCW50pAqPwM@8MdB;g;N-l4*R={DgXN@c+>K1E+xTjb zuKeE5@7F)j;7cRmKm46KFU`km^;qKj8M`TZjhj1Dm0qyd+r9ipMx0nuoz#m4jeGp2 zw_uKi_&L)^LIvzgC3fHTkd)67MfRz7?E*o@F^^hJv@AO|9FjdWBnT^snJqdr*&;Vt zQsd6(y+-g9m%ZG0_ois!u*avE7k8Cmr;%X~DSQ9cI1|>gSCTsUb+~hftb36n<1{wU zBb`^z52v6K4$26JO5ww>^^uEbMkhdJ0Tvv&4{A?FN|es;_B#eneP8$h&rb|4f5x?X zuMqWdI42i|^CXrZp#U!&)o%LO2E_*BQ;znIf-Sv=-G$!Uw!dy2lk*e0 z<#}u+F+?UaQvMq#i_emj64~9Id8=|0hu`CD-ZEUs?+rsEB5LzTLP1wx4rQ}*A?6LA zx)Pi$?C)~x981%U8JORD=c+aQ?q)(e>RxDtPq;U4zT0iWzm~S{ z_*J$d@)KyV8YQYK!+?k0;+@(fBGhvrF%cv~p5}_iOaq^}Tu({Dq09FC6|m#HW~;{N z`__MnF7l{+S}C|(I)DBAtW8X<0Obj)So$LI{n$c)-UZCGL4Tt%4lsU>|FgI!7gb^B zAh?r@9!W1movDgzcfbc}V4Y>ay(y#7pN86AUy#kIXrt#qZ)|7P{KziK%~lJE_i79&>weoC0iQVIUY<$;HJ6Dy zMROf>vxMxjO{i|oY5$TeH1N$@DWW!bJy1fvgsay9cHa+3I)SCMb+E0QQbH%0AVw-| z3$gwV#alZM#_@|;Wz5mtRt=~WR*B~!8!-#C zVM@=7i|L#J1X{PvLrIzPbi=}CJrSr@a&*n~P9osi30i=3QvL~?-GDh@P@k4vR_Dr| zS6vcXY;VyTK97#P22<7^&yOcco2H&OSDtQRd3o9iC^;KM$$*EtwKb>#?_cZn5Al9< zgUCGQw!X!yuazSpUkG(naoE9AWj&7!D||}7uxQz!j8_CXheZa#!Ge~>y3t4%UR_c(?5MnSMcU) znT@8fzd&H_XOLC!o47!zcEP>gx8o`0w9jV)B3lR3B9u3$wE#cz6zKA54=NpjT?wh% zw%Yh|^IV2dKRh0Mpnd1*GI6>+-|_tBIoJ30jp9ibg{&F~_x#(V0*(;;XVJ}M#d89U zzMu^E8_q2lcS)!0|IB6bFBC)D+WuHv{7eGN2m>eIfbR>Jthk7i$(DOf%LTU_q5vFDCE?2nO>{&;8g%0or% z=Qz;|SQ!hXFo=$BpaqB?GM_N2PbU~Leyu~1?Aqp7^0RI-6KVInsq*kb3zblUCkB1Q zlql3BBw=5ooz%DKme?s7{Tk#jW_m1|UEknhMM+1MU(wPL1A!mI$Q77hm0{5sg~-t? z5nZg*`VV+tfTx!jhF5jk|If`Y+vRR689bNB*&wpWnb!yUbj12}oRA>PFk}-W;*}Rno_}@@nW-x1z58s`Gt_UY%c0{m z_KhShTxPn}y;;w)BvAE>OBDeNqT$4N_57(xyEa2&3Jd(}Pj&p6{rm3vFak+lwbT$3 z`wLi0UX7X-(m53(Q*rhxw?EAbKF z2)C|7ac2a&NVy}T@>wj-zSxR-*tc)zIT;(KyEZ3laT?yfb-Uk9wG{7IwC(d`Q3(D9 zSw>`Pk395Ze>3LkdB3hx-lbYqk7K!f48Lp>L&b)hhqY0sDvSH=fxCRn2|D`yI%$LO zVcgB%U<-;h8>~Bsdd$GKvO29CddBd(TZp?(0SnVkGfi}+O^5=WtcQNe)!McowMxntY>8KgOHDJK76~78pVug()jDkX-CmxgLHwn+t>tFY_6v|kGG0`O zVg&gm=4;z`e*%kSQ)x$5VYf4=tN2ZfOqUk$auL=iJ}3Otk`Xwnot2=`ZzPTK-P*_A zk)tgJkoOsd>uYPqwc2jEUBSakxB6E&)P_T^8Ic+9f3y43wqW>i;z0xdGF1$) zHtkiu=(gqX*OznD#+X`89zxFK`A)QHg`wB{^Cv|41MNRgX`Lho(>pwD|vtd2JgL2O8%;4`5TD9fVJTHgMM`hT$R(BRzejpbPv;4sgPJX zRU!ppRLEe}jvzunFrNCWY?RXg*(?7qGRAq?{R`yLXKSn2N6{V(jm*9N679MuT@LXkuWV$*jUERhFI)%%JTYG;2atJ%8leN+usQLcYHF#5Pb@wcz zFi0^2gaxI~RUx@pt2im(&>*Jv)L7~&Ueu}1&-}6Qw`h>;%3M#elWHfZ- z27gG5y2G>x{oh4WlrCQPyX8%<--sE0#r)iAEyRr&rDn*D=tprS!3^0J(}Y$W+WJDq zf(r4Fde}s&x{9vK*p=?zb75|uYhI^M(|TugluSfP;y0|RZ+nUX|3&_L^7WiUPBiJD z6SHnB)V=HWIii?hoO?sJGyl1}T3Js3a7oW!L01vae6w@8rr;cal2mcGf5q^gkm+-j znD4|*U&i#_qch!Tsv!Nef@xcV$QSlZ1+iF1kEU9Ocb!Qa-fHawL(Nep*^1Jcx=DrD zG<9=Kk%{^x{3`=oVtwZ0zl8_9Biy@y&TkJx1IwBL1g1el^_^Ef#p3n#8({I=!(u5o zU1=_KxCZN{Y()fM4|%0orvs8)SGpM7c{?q9V%aRpC&?>`NRVmdtUg8)!DCon>m<=L za9iXdNjI5x*?78Hf6;f?y)L&qpUurVLAlFh+he#8KTHKrNU(zNe0}M2(x-6BU&dZm zrfQhpEM%jDc$=`>NB24tFKMFQU23C22Ut!@I9{{o>}EW)HqPht2G_u|rUyv`Jg&d---B?Rqk{K(?;msS@D(iSx&rgRRxSp&`wq;Ww5Wo7B&RNZ% zSE;%6?WpT@f_>Ue{EX3)&zx<;#L0KDmTDS>^NVY%$Bvgn-_5NH)yr>S^D|^x+?=r@ zfOUgI5u`mpK>dmn`>2j86NG&+2?7UVMfydaz##`jBlp581XSZ@Z2W*B07EGrAV0+Aetr>*r?@<=z9D|mI{uz< zM)B}qez$`e?q#uP2j2{^f=Y9A7#ahp5 z5#`UxF;U!x!*cnkqnT|@dKU(#_#~p7^w}01?q9Qa+ZbN}9WVio&0O9AtD;`!*{Ww% z?2sm2-cIo@^QVMC%jVqDinrfBev7p^gn<2G&C5*Bs&Hn7ANH*psSLA$Q_DNT$PaMU z?^i^-;#FHCFFgUQF*fyh?>XP|%Bx43B>aiW?|6ZJ?7cN=?k;QdH+c=6@=)er=8roG z19oI%rEc>b=S^UaWi#pN8!@GV2Z0NvR_C#niO{XhJ&wHp{yrYDo_==63aRE}wc_^r z#wQP$F!2|hTl1=APf5#CJQ?_c;1OJw;`~$A_n6U9OWfIe_n!-xV_p$qMPr6aVPqSJ z0zFQHn-ao{+*)0S>RBU4uh$2gBz9>Xhet$qnZn2w@_#(`p*ON2^b?8272eldNJ(r% z;$!uT_!KHFr1DJ|UzihYD$ZN)1j3p{mTjaO_1VDeCTJM+zbO89f0%CmspV}xZ)Ek% z9tfXjx!v7^mJKp#jPUjeLtEWXl2=kV?e%eDDRdLOb6X-2Bxo6(M^@EoN?QUW;OMfC zB}<|op4>uC*&w51qlb^{K7L6O^8^HL18{W4^C6VK_%u8Px)@mCnEaZTonPDOX=T|0 z=(W(OcvolVJMj`+V5dxxRiv_nH=~G9FKt{r)IMS$=P2RE3WWd&3V?Jy_Z9QQs19XQ zKN%=wH3YK$wE?{?h}ZeJDRyD<`+?VU@Y2?{26}<3^rO< z1Mgpx#~e?x=n<2cnN(f^x1g<1(Ef5@S*{lw4yvx+b`@Lm=n1a+*IG>BNQ-{P^tuu% zye@U&4|G|KpFaGQFZIx2Z8og?P_T20(%lRlb|WDk;TE-WeVs!Kb6@sWUbva%E&-%4 zFeczB^N|408{c2dW+V3b|Kcva`TnaRDkMT0O%nTWmDr{{*})IeDH`sAhKMMDDe0nF zf6I!NKN@~3#S%c{_~O>xPBFISgks+Qj3Uq?L^LcO= z235!yuFLFvt=+B#(_|#0v6nfooM*-(a&D|2Re%uh)zRh4q#4p5+goFUzIloW z%auTBg)u4=&Qcof*38>}oD4VSv_niPhBCPbkazmu!tY-WhZH9fulgN}-E_zIk3+s) zi=nKEe9_i$cIRYxFD&y%J<;QD*U_I+Qy5$xa$|6)vWA@iwv+~pUFiZNpbTy`{dWW# zucE^4xiBabh@wG_Mp`<>veQIrbJvD6yh*+kGeV-q__edWA3SR|O)LPsweg_p|Hg@t zZM)F*TD2|VzktmcHXQtu(7-AzH$f!NMNH2Q%oU&emrPxk&3&}>1Z^aIIp5!Xl}+fJ zu`e{Ovk=b%l0}jHX?sk)x;Z!yPyY-;FDfcR(7{CcZ>AG3qJYCE5m^JdZ>dmahuq;S zxH($@`f(VfzJmk=AZ-Kj8ZDG1_I3^W%)ty8YH&EfvKy-VO-oioh}7dHc>H?pTS9kz zp7kDJ(*@e@yJ&a)k#!OeVzI?DV`Lu0Kj0$*=mE$2mSrKBPy)eE=jkx{NdOgi{lN73 zxp?|is6IsK@NLqjXyp6vM4#|9J z?W){?)<_W8*z(2ijC{5?{!z4Uk{{|!tHILAvIJ18QLEZ`VIJ1fKbbyL7R4MQQoKNP z#~Ja%3BE$^oFg#;GmvJz3STHbqz-<)Iz;Fl@Y-0GKxM+!>t<5t zyg+)Nzu>sGV-s_#?@M@Ukkba&sPn@|h@#Rr%~31#7*v>F+uJqQK6ep3scIr{6VDz1 z*D}Ze5oKtTW48sYu`xi35(cKNcu~Q>`jJ*WaM^<*PK?pqwhZXN{#$B$5PJ;}}d zdamu1uaZcTNQ#WMN#<1O=1qom+7|?-;+8E?_h*PykJDYpd3hs?Fz> z@7!7JVB9qFPGG>lq1U||NO}A1TZRFI(w_av#O3R|N@Iw64yE2x0z2>sWFN4HPv!(w zo-RT8T_**z>A0r`$xkb9K{JXwbQ12%HKi6pl!DIjJ9=W+{&s+C8lX&rzqhCBquH#PABcgTM| zUVCZ3OiaeU+H5X3YpfruvJC zeIQx0ri+d|jsA9aX(-@*-gy#O)XK`PxF^nSN?0-p<8hVc9?pD$@%h4zdGRjN`Q#M93n|Ub;satH#U*Zc}ZF#^Z8px&8uN+mXi8D zM^&!oB~8vY*#kK&GEqIwo0Fwqj0kz=EW{Ez&>Lh*QL}mBzacjH?yEp$0g{&%-vXNG zES^s;4Qy~zjj|Lk+qxQ=V$=a0Y8Nr-8(Y$p4YK0rYrUA=qp8tw5XIHKRh>B}so3Gr zh_7oVHH7$)Ye*b(E!vE2vsI>k9UEIVU>nJA4oV^KQ#mkDA%@f)SV|J1;+`bYynh*D zr6EA3(rkF)+H~Y|mVKcwU?iBu{x%4g)mC8}JAIlxUCH{Ij||g#Zlqyw#-^#FP5JXC zOXI;02W@*rpT{_E5v>5R=AeShlRb5d}mG^`#!XAL0PP zo^jgQC@fkPtT1ahDTU~6;DRSwWcV?bH&UaTyF$Ethf{}5IErsOW;o>$2DG4ny`>)U z*IQJ#zaRYbii#&{@6DStcqxO`>(e5t2YHX-)nq-6?`G>~|7JoY3U|kby+Su*UhCL^ z&?dcz9iRfWb~?}zsxM+dw33^VNTq&7YE1v1ylJ9oIKoz+dA{ch3lcCnrS$%}a;PJp z@X`L)Vhod2Y(`6Y#A80T)z{8nK4=J)JQjglV&C4z&wXr*8OPrdvbZT#RHX@)8Gh+U zIBpZmt;n&y!8uFDgR@L^Q!SW{`3r!cVx;O8hwK?(tn6ssCP49e)gdN+KSg|Vp%#>6 z3S)144#%6cStEKkcCKBj-~vY?h=}Jp{kf9<_ia3-{C5V4r?d2)L6^XDa>42fX?|^3>e?Q~$zI zio}S}T4QGX_%)mKEFjxuOcV<+E04XaxzfHf*3qxJd-F12Fms4E7fYiuzYso}x%;wP zc1)GAO14P@1X+=)s;Rm9i}nLi=PB&zpAiLSWTOmQYG&O^xkJo`&+@U=O>QLMsT$V6 zeY|`7#}iW>S7skwvbrv9V!KZ~RJE+A@rDcVetYjycMIvuw7=)HpzPM)UCtbXPw#zq zL2hhn`WKRWNfU)e9}6`oh1j&{EgXIUU-}P2i_2Re;+A|Bjx zLdbT-!s{0o)0nA4blEbPvqRcg39eF668HVALIw<+5TSXf8iU-7eeeT!q%DBayf8L1 zWEf679PfL5N}W_JkF_p#BklYDuh|^{gUgke39?de&=n}uaR1LPT%L@dGFl1J@dR!&-dV92E87u2hE^Cud1*Fdv z4Ut%@LJ#q5Yk2zfo6~dk8Yi<&{j=SDb0hb&9E4|W5VDqa@oR~1t`fNWks}&fb*t>?`~lt;1fGG`B1VqRiQ<+Yk+LSW#LLljEIR-gQv-42MRGIDrz`Qpr@!7i9bO#>dh3XoZ<^ov1xh18hIxs+6@VnUeUidEyN_x8 zrCxutE!jq&%&?Kdp@j@gE`NV@6u?V%&w8~#+U_8|AOPv|^go6&L~&|MlMW;I+O$UQ z7Rw00QuwdeVtEm}`+nv}Mqb0zu@MjpLR3K33JL-A)__1j)uof%JNB6 zI`M6=$~qw_?P@*|*+qv+Hb%$SAkkipo>+^XsN^C_`+|7d*q`>(4WHE#OZ}QNF$o0T z>_Khe1EFZYPI7tWsvXb>=Br!dbaGkmX(o85Db{4ZxTfLCjOCQbMsPmC(wYoLjy~=AsI{ zVuQlH^fj^2|GiYGQ5R-f2Az&duXnuP?hR}7^l?Ub3E?$uxZS{U+O}8Si2z@?msv3y zL>C42i(0llJ8n|!0b$I>8e!zCL>^4XNist~N8-|VvzICJKw+57l$^(4FEWRoJ99D( zYnOCHRzzf)tgXE`>^MX^h=(S+-?GaT{yUv+Z>Hoq+@^PCDKHfL-Gl`dnK6lNG_noY zxBN052&&q_rBq9Glg+ToELDs#5A#1>5d+WM^rDLU_ z;qHCF2ZWZuQ+m=}7)pmB4O|(vrWQf6uU`BPC$-|rf~6G58zHWERX?;Z*B%hMjtqnp z4UXb<7ND#J_N0g8T7@K^X4sJ0YkZ(rd3KL`pRrB#`I0F1$RtIy5H)n<8So}%$iF8; zp)Mf*=RrbEerWYUMR`9IhyVp+t&Yw<=TH78G{4ajK@jmVv zArZ0j#TyAG7g91Ir-Muku?`vR9Z z>wVt)$z=&^6G^3P=?$zpwaeAe{1`z_v+hCr762<`7~XV~ZPV56l)bhm9T0u9Pqcvt zbSj7WG2FG3j_TJtfDADi_&of=Q7b z>I!i&`5ZXc{RdC%x4!IL)`fQXlVo>+-2JQ0OA=j&Vya(NCzoXO0S|X8>DXT7C6iPvGzk7q(X3U_ zcP~3f2L|O2A#Tfo;*JeGp6qfYCu5?tQz;=Sn7$e*i>wAXzkcNYk`EmQ8ytOa4#)`& zeS$KTY@>LaPn@_Mn`(%A!?#%l;}>YS%m8O|cRpBF&$Q;0OXnKRy*DFoCKoCIxwsxy z4V7=}c5JV5z-OFmESky?B9ffzrFKiQTTL!O!$?!eERT5rwxtg(;lI`gdbM_<+}za@ zS$W>4P5d|S*w_$o0-^}F+UzvRK}<%QF~SMoj}>cZT2e~VCf#K+OV*4cx10KB$oKhw z^-Rm0fXQF_i_jvapx&$|owasgKv zT5{pi98OVoe2d~}%aR?;2mA}%U}my&9{y;|Xq<@h1)PK+=O_!vkDfc!iEa4qvZB&>j1tY$vv6-U{bE#6?gOe}Y}*~($Lk;(E&ZXstpG!19=m^U%{7D#Q&p2x zYc$SWOD!$o{kJ=Cg#H=_lQ#@1UnIC6`!ZaqZlA(MqvaH@=5M%X!E}Qi@z3f2$>8Cj zPCP#mSN7;HasdUrXPFb3*5m91N!WhXtLz@%0<%18(qHs_AeI@`eP;i=;i>v1f?1>? zq7+G08-+!SF>AeX)l9;6#`tgHw%YL#lH;lo4!KJcq-*ayZmfDc0GKrVkZi}KQZ#5m zG!LEl;TwkZGAo)3tzq>L7rEd(aS2St!Q@t^Sup3c z<~=`@g{{i9_eBF8Q{?i+C0DO~nlz^ib1it?-8nGKb2TYa5)vIOsKUi!LU0nc%f@TA|U4{J{ zsQ+1u2K`(KQMl^tkuY3W$omPt&kFn~h8ASRK1awoje9H;gV6~}?xDSNBD53kd|9yw zy@uaUzi;PY)aXu$9ShsHwBO^~O)zmEiaEr8^?HWv6S`mJ!G8ijQ+Rmmes~sw8yS>i4f+(*nJIq0xmzzQ z6}>4%VN-`&KDi-(@g6aF;`Xxs-iw1#G?)kcZgG_#eVcskb=l?FVe&FNsisMv?c%!W zXUV_72L19~mUFbMEoZ%md>xo_cX}l;ONQn%1B!A2bb!va-`(5-Yp+@S@EhG1>bUBF zqK|w5u3SeqZCkN0pIDGk%%2ifmrJ1j+TuYrNbQQVdaMFcFoQit+)Qb~X=~A05WI->0(!_~e)XeHT^x}( z1&YVl_ayI$2lT2^%aMW+Zi8-f171G<+HaovQ#fPaf9*dnI&%2#6KBuetH+x$CX(0N z(JiwEv24@$&4_RKeG3sKWdn4Mq`p?^zH)$C5DKjMSQ=cc_(}ZNv>;hS)Q055?`^7J zIhxIm9wjJ6J+V{W0^mw;fQ9+t*1tkYC>A$Egiw#7S^M}LApzfdL9Hcr*N0ho{fra~ zA|G1Fphk$&l>lFO6pzx&tj;0ZMTD`{okZK*A8~I~bQPzsI{Gonxj8FiGc%BVGU;U_WfT z!ro7^xCk)nHnuQ7=hq}J8iC}o)Y^}ZQUdzOf%(d00&!3b*CZ($>lTCM<13tC6^N{6 zi?9Je^0O+Hlp#qC|Lw=l&nD9qv_CJfERe~-LMP(LUK?ba;GuW^kAX6qD4cydI>B9< z=mVmN@MT$NvP4#2y~ypQsMdG(%yD+Exe)cOC|@Fe;7H9H;syRMf{fc_Xd zDUWBvAGly^;u;=s6bKtXY&*Qhk{_oH(@b$sG7>2Jciac9b7xCMm^!YbbZALRq*_la zmt-9Naua7~r$NDof|9&}reF1TI3?UfLo%A}uKjGkXWvWv$)p#GuEa^_6$7~l#I2ug z-x!_h|G4|nG5A4TibM`f@ZW%I3lN~>NFqRMkMjyyT0#u&q6bKV!5AJ7NOwS7LBCT= zyO0Pd-P(q1-^K6|!hW+&Odm(bVlWNHFr_5^w2JISf0~dXj{scQZUiCG)}IYgY)aT9 zdpfAJAv%gp8J%M!8`r3tT#{WY+SFQ|Tv}pv{X}X@1cI9N*R}6K%8*PFJ=!o2mJV^N z8|%1DGSbVu_v2yuB#x~{PL1>Qy6F}zi%vlQE%vta?cSzR8X{=})C70_7I>h09;*Fe z;HCq)Rp6$p7#a9VN8L#90}h~3v|(c+6#bULRB@6o8kiZjE>dvuj#v=ZS(~ zTq*t}$Z+oI`*Zs(iiMTBf|70i+!H+0*@;$1Kx`^H8`E0OFzWYD9ofF0#C88mw6SA+1}xM;Eir;?c+W?Jr0BP>)lLtAu=L{4k@Ifx04)?#-Dh)SU9$kEnQj?wS}oQF=1 z8oj;dt@uH(sbqZNxCLdaS^E~(U2K#|-46B%>b-li2)M7VtSXv(hAMo2&nQ}cvlDy) zjkC^=@ciG)yY?VB?(qQy4Y9$FK03TDq%Dn~3XW7!AkjxJQ!RVVDF?P%1+uY(HY#Dt4FkIQ)69gteMX*LY*r0}o56PZ!zuXd@b zR^8!mtko}aB~dWb#UiXqx)p`->++asl8sReE-4CVf}juCA&F{10Q(*2$-1MA`3pj7?Kzx$n`)>FyrdsGmXMFC5Zk)g*pSJ_qG9AQ3R>fp zuUG(Mx$mZ*HT&p1;fSAgYGdi2>w8H4l>~6T277>B(>lPZ)d;XOs&!w1rR1}`?B+Z@ zs4rTtPMv@VIO4NnDKPwiSrB(0FvU~c-}x)N^-Cq9D2P5@S4;=45R7e zO5)x4d!3mOVC{Z3HwS08>*}HOoWnvZO@q|>=<#wRz|USanG(|rRPoNv&Y&a3)~J#dd54lOoX`b7^VNTL;q9m->13k6+BSQi?MZd25XG31D~g6ReP^I!EY`=P6Dj{493+;w*h_h*>1n~xiZRz`br z_6In!$x_GW2m*s}_8;y%2CCN`CW(UVyXez}WEjD^P2rdB;Q(a|q!G(xD$=HqyIxdt zvR9+KK9&?cAOvuA1Vx#Z=gWrvmrTl+m`by8=WT`1*hxD=_4SMNU*xLYEF<*fNo=&J z*?8IhY6AIX3ZcF=aSye8)n(9ViLfaGvXZH{A7Va;PW

9D+7#ATtcxj%;moqsSoMHL~l)NXRt8mJgNH^Y- zGet}%fC3VxSN9!PmX;ftSX7&S^R`uVr4mDd#c}KNzPIZW-0wpH&({W6Ults}kQ#}v z8OhzqHdNR=c7rS9{8-bLz|dCRG-wo!A7xBsn*FTH)WV!qQ<}(PxL*Ag!F+T0=b8yA zLVN7|16J5v7=xq^=7x1qrH6|iByB};HUQI_b>`ZTygBG4JwQsTG-aQ7@a3)!5yh!SEo z{jhYIouWf=CL=IJ9i3;oLytpL7*~xtmUT-tXFB3z2u;z4zlx^UsLElUkPF~>CH zn%2$zzB!|uXv6@uSy0@ukGu)@_w4^%QyX=7w7vXVgDaQ`aG*4MK9q&(Xy^1RMU>&A zO$2s$bf31w$ImeutZI9APB7{h9Y55h51wGC$HNbHuqQnb9ooEX;gTdEX(q$nSVk6D zF4Cy8=vnTie$%*0qk>4i?BrF*=Bg{OaroQgag@{?gDjRY2^!BuFdRHuHxZ(hiaNCW z-00YiP-bURHC;KK=>SX z?)YgfS~a7YSGVAJgiHXRq;7M6@rO57MceyXa=>H0Y}I1;ii;7`fIm-OGL?Z)ShNnB zkt|hUMP`% z-ItBI*I=pjm+XGolwJNazK}UD@`-=%IfEIY9DP0)vMkN+K>M|c(`*fULP>?GOBS)S zIR#i`6)f%pd_RwIlJhT7P0yu8BkPTGw7+|Hpkm2U=a6|Hdw_@4E zLz(cOB?Xf)y)^U%Wr~zlq~n`TS7vWt-@kt+NqkH}fQ?8+_jHcsA{|D)XGhU)QZXFX z;C36^Iodg`RQBJs>}!;LryU)v82M27B$*78tVuZ-orBwsTHw<0wGNGx0CBnicb$5p z8a4Q1KSy`mNKyX*wZP;|$rVDi1}a6PMlFxLAbCS4P_!m4BHQo&Ct+}x!mEpKUa+mK zGyMJf=izmOVO_l%p1x5pI&{;gNaIb_!mr0LYA7K!(?`|bWJtiJutk8{#HUL5xNAlS zpIJvl{};IlIU~7MXmRz}!LIyScia z;j+AdPj6vnYq!zF-tQmL>Nrf-XBTp3mXdM+T4fY_p{TkoBuPeHTL3=_B_uqp9 z?Eph`q-j?15|NLu5tUPaAlTuHrWD7IBjlg9hc>55)bUKy&D+Oty;cb~m?)8Uw2#?O z9#z&!XmNMck(@oJup-dG*8K{5EsmPe6nw7S`kiA^Bv@nqLE`CFqHs0Y+yCh?V0s_- zOf>9RA;;WUSv3i9e+Dhb(}>{nea%IV5Ax>gq0ew@QLM+FB5q;c7F+`4n5Sx&7+3c% ztHF&DIM--CF5R&#m1!fAJ@4#wvq>e#K5I=d(f=v-Ykpr$ z<^ptRJ*%65%#uoR@Nz2!nAA@AlR?K9vszzIk8mm{!!T72fq%CyaZ3cpuPk_kcyVk*N!6hXR(ZsA_Hc|TsR zIOf5yGoznA%;=c~Nk>1=$m-#F@uiVDU% zWC)?$oj^%LkBOfz^+}$Rn6zGUQ~UR|zr`nb@2dk+XXoJrb}!lrrr;M4yG)DLWCgRa zVo|8p_yp^#kn1_mjsYkST)H)ZE=G4-xiq=PBMVw;WlGbQG<74?;V)e91vL?xcIQMW z-Q!ImMSdZoe2aIv{JI7KGfxJG?=bZR!opSbuYtJZ2afUyt2E3jw(M~)kCRr#pM|^9 z*i!%G!$a)BPA2B&vMwmr?BTB-kWAfdM03^~x+kjr$r`evH7AiR;9ZW($!E&PQZvq$Fw;@CUhw#)=iFYdYsY8l5 z9{@Yir?HD=sLC)RVO=^C)y*#DI|F4f+owX&q}}$v*j=V|@1+?G42yos zTb*K?)N_-ruKnFeRV);`g`HD`P*G3t2E;=jwXoy$)rb=@rR|0$Hwi$F* zb$1X#%S0nv3^5HdUoQC}@>eb{?DIER%(vT28%Fy!g|JQXtt2f#B#&bO{A#eHYjh{a zx8Ja8F*TW93J002E&wK-TT091(yDkJ@6D6sKTR`gVl`biS!#i5>Lk_JT3MtgbTY2Y70ZrZQ(6fLB9g{@-krzNMo(etE4|R|0f3mOR~XkPDOm zL@E6!Yt_>=M=NuGl1+5U@oY8|jC666~x=GA<$SN3cBwh-$+&*UvJ#=qRoKa;*?pE{d%tI_W-=*|dfT3<<1OQoZZ@`7s)>7!ys`SB6fAU7_v9{W1&)+l4c`*}I+No|bIozLjUD0Bv@s%sc#x2_Td? z=G`!;I2<oiRLJFX4j+>dksAk{xJdR~(*y*X8{u3f*VbI) z*ZA0_N%9n^4Qh0KSMk4YN~X_Rx>3CP0n0N(vL#Jd*vglMhgkP$Mkrr#9T(ZNm3#_C zfDfJdbxrc`78W$jlouE}G2uW@dZ>kbILgas)!moX@!)|nZ>WN(D@%NsW|+Dh%abcF?nw*_Dx zXeo+uHSjUo`CDyl>8T~j$k#_XeI$R{gdjW754fpcqlY#mg;PsWt0%Jq-b~%z94G7& zbyG3R8xjyzye_-wA;OD(pYK@P*7rH7O@W8h>c5$*(dz)vV^5+})L!_CA!#mDxpG%> z@2uS{2sY|faI9>qN1DPKJ@Vt8C3$P4w|=H|QorWvjsr-oPW}#gh~Dowv<8pO{o%9b zg;0=xpQ8PM#7OQ-RHIDUWvYgMW7*IV4LBBW(3 z?o3i;W{EcevidFpFZv;NwCJ=iVt}AF^`Snb?k+tEb#%wMXAv$}s%j>pC7j4$(nbs2 zDA$39SZJBiYQ!+wu&We_D9o*f5nm&eg{}GPg65WCYrNZDMGgN~} zB#J*Z2!WNl;&J)*DIY3F7(9N_LWba~|2qXkZCu4%h7tjtK=`$jZSuAcGIB10DK_~o z-bqRr8zlehKxa*G{>~anrD^d|yhBV0T$;xdRp1%bN&M4Iy!Yi_!pCj1MkWFbObJI&q=C z8~;HgvmsvFD7+yQF^PU-ksr%vunWTGJz9M-VGJQAJWHEGfQ&d}lgft7qhFjj2%HccqI5aLnhp%!0A_3D&&&1mQf}&#Hkihks9(Ky>_X23_>wu8tLfcJF(3 zzr)y0Za5c%zoREvEHc>Z?`M$%Qnr&jYD%OMKM_iDRo%D*{hwCS$oQztaZG zL>aCaq!`QFt^*D~(ic8uko67y{F^n4E>k*~J4OUTK+nvo*<~cd$>=sW)R|DW;Pf+u zr;BN5w5Q~(amnOOqxXM$7g~6un?wu#-qh?@qH1}(zMZTj>UNkfJE1x9X)53amSHBrnYqsP2}=Q zJz#8|?r(UEz2_8MywBZD^P*5Z8sL)LL*fee?%c`vXF@>cg3+S;#wIBZxXMFcE(b z)6G>tINi*02x~Otn1&^+oOkApnr@zd_ZW^pXY+Xcs|!~{{er+1n$2|HG+tPc_g2SF zGH(|c4;LIuSFU5_q-zS8pFxp#yn8-M^{FsiLJ>qER35y1I_YFhr?y>isv_HO0=CRW z8!dUfE_MHo3o~8X8u_Nx`^1;4RkL1%RQ@~;e`F`O{i=P&B%v_{2ic~%7aRXXq0gp2HRkPN`aCWvNMPqCPgHQrl zT%vPffqi~~MRsK8ihbWM4M;o`hbJr}2o-}%wMh?m_)M_|j)cipqVGQ9SOYnf#ogg& z`&5;>r5cf4%g#o?panzU;NO!3pYUr!h_%l-Szcb=W_-{M0$9O@@J+1WQvSwXQ?mu}3RzYRjiX}MZEzWTnZ0e4Z^l}TBp zH$D<;HR`+48bt}OPswwGHkT;xqPxcriUaT69Iu2yp5nr%dnk`w(@&YIg~8#FTg2}- zY((L*NokZvvm#uxMDBGy;-U3R2#KXUAGY&5iDrJ5&m}HU+z0rN7&0TOuK@}zAPoI8 zh&+_SSp($rJPAW|(70S79dKss`}pVT&0-BFI#rqn`5gH?P4qemWNqHv5rGfAyPNL& zz0EcuY@m>t!YH6FPc4a{g-i#vVK`zr4t*7Ei1q_22ZqCJeLtlN2%P|J9-tW+KP;&m zhp>Uk_cL{!3xiO}B5>z@(Ir}X4PIDVTjFm=kf{X1;~@kiaIX21Hs7qet(~M!fTQTS zsPL6|{D0HUukD?^(Qnnl6@EF=diLrU{nVD5^B0g#Dg~Di`A9?sksO9;v64%x(M|Vp z8fJ_y*Dih3|bLWvxhd(Y%nY|xlmdN z7DSl`_XRxpTCmFIYvG_I`tq6mkJ$$!=Q5wf0l!;pJkN|H1ofTBH(I4WxYajcN9h?I zvA8jOjUt(4N_35wbkku#t;@9HcqB+}Cus{&vHQq331TI`G|m7E5Cq3IY2$36Y4>I; zSuGou6`yG&(!bj0H%`Li%A+UmmBS{1fG?Xtttc4_fyY?~(_AQVdp(f68EMtJ#P*Yy9|b1L&4OA`=rcF=>Cxp0^Lzm#)&?P$ zo3*T(Cue@il`N0G!OHOXdFFb4eja91ZkV#1DunYHyaIxNqwx5zjfXcr4*BT%KYZTk z%o+O<%tp~7@{!+*d->0Y-}9s8C(zotTa{!d&N)m1pwg*{so`Prm&bsnIzg@<{E;Fk z%+qMgw>i(;|D&;%CcHMkb!VAfVK`s1I4s@2J4O#$eX_(OM{1Sby1G6B;<+}pW)_pH zop`){AAaFrtKi7y8K&_54ySIz4kr@&OX3~+>E#TAsb~XK+b`^Bo1~9me=Lqgd?O%0qFUvxxbn5EN<4{ zUHHiCPbC*Iv97?!DrejvVGj1}2wQNB+l86!J*4akKb!7Ey58P%2rz|Q%b)G^Lv=|5h0%%qVi^gPah3Y3w#!K41o21ePCM;%r zxgp0tpC)hHZ&%>tffA#TOJ?o$J*I<&hhX_Q50ucrEX}Y1r@j$t(XCHArU`8eXRjs? zPn|%Xq93{hfgIHDlnojJ05Yg)$U}TiPGAuqr)1>iIi#*3m%A!2zfn)%qe{o5zbKt?Eh&;*Dq90x9@T2%b(Pujh;IQAtvAJK|?R(t3p4; z?4}4IsB?V`CS0hc<^B$?toK&@k+#r{)|{>6FS4>U7?wN}pLr{D^MNKVV2-(ChnI&0 zqhXclHxO&;bTJD%7BV0^u!rW0?&|DddZ3<@#D`<|t^cPw|vux5kyP7cq`;5qZeW*p=*1jmpspw`M&v&oR`*g48eLlqcZ z4QlybIZt-wIL^**`nW`+Dtpc=)&oJnbOkF6wksve`Tu+?($0(H>~VGX`LEpAT4)qq z6MOO?h&ndfeXgjKkglVWp|E53SmP$=R`jezgne#2wmpRj-@WH|h1g;$HNVNwsjWR& zIQVareRt;4%EmdT_=sN6E!z1IniPS^OxEsS%c!E<`;{(o#Pi!iF#@ai?@vr;seTzz z$d733oos_d%bvTLx|6272jvIzkxlN$lSqktX0)0CN{PT2&_kG6;oY;Y;CGqo88lOT zZ|r_CfYV0EuaRp_@{+0}fYgBmMqN4M>f;j*Y9kHQuMQRF)+K3`@UaJWp9-~y`%=V9 zT#r`>RFhm7)O->;t(3!uKH|AP)XsTT{H_cbTZZkw|4DW0#6^S?@9Y!(EerZ1ZH@~z zH1M>tAO>R8xGHna7S}NQmI&rHYi&ug0Rz19mlxon*QpEhCck7wEdlDw;Acw{C zueU+b;WA9Bi@O&Xjvp`0p2|1`OC)xI!Cyy8l0R$rp5dKZ@brnMF5AX8i@2KJ-w9QJ zbi~tOyBQdgWmBY}4+UFux8s!n2!M=BACiu4r1`!J^Xx!y@JL6Ij-6;R+_D@~bwk}r z5#mUv&{TzOFFbVX@790cX_Of@n|15vl-B+|n{es_NT`zao90>9YBN|dmGPB4QSTY^ zG$55JYirT=C3B01W<8IsVEOhnN7?mt8}95Uhfn&&WOSuV%g)4hX_S2TItxf;xE9P4 zTDEMk;&J%TNE}rE5z(;q&YPe589d~|?0QC!(>p%HVqWS~vBo~6{A3(tqKt?)C;oPZsErT? z-iE)aUSPQU0~HN$tb#;i52*gHcLplIMTM(ha6? z^M_w>#&SVu`?h8Vov55@b`kSnmWy~l;5!3Ti2Ku&9B zj7|aFcEa8iCHJ+l(3HZY3Q_o+@Ot@@9d}1%Emgq*#W!|7_4;h!=lKaRn}8>T{7scLM=T!2T5Bt447tKiVJfrx zwC(;Jtk|-O8*C50utXbD!$~4=-8h%E-u$iVvFFXTCS3{m$Fbsj&wg-igv5U)I&gT% z4!lofu_8p#+fqkq!v@tBpF74j#9qG+JHFMgO>=j#3ryVKXp@z5kLN)3$wmQGYDn-&hOf-u<| zX4#N_=@5&Pd$ZTP$n1!W9c~B*p^PDhoS2(n;XWOp;eWhV%N-zUtK{8UNPb%i4C+8) zHG$Wg24R-sn|*1Q2|t{F6rt+l3~cAn`R?UCcoHnHn+{ZUH~ry#Qe6lw?3@+mUi_Xg zo@N5d%b^3;xjUA!Wq#%CXkjvuH)Je{Q>$B55y`n=6Vn0SnXD-Q^ad79Yv*6Qljow= zYYI6VEWHCmJ{BZ@8~>Xv0s>wLq*x?Gl0MI(@d=py8qwO^a=`l5E6o~=o6wkfuz8&u zoS|4XJA^w?m1Xa0bO%751-wcOe&fxLx%2P8FF^l+a@oK7?Nu^&X{(i^fRPw7{0VgE z+^}Kct)q1=O+B;tANDRUgQt3|^_DWc&;f+i2QdY_>Q`NgcHA0scO|RGbgFpOf)3LZ zF$)06r{VmTSU4$q`Tz-LApysx?4J>Q@T6+ zE%%;1^L_t0^Nz2GH_yG+b)DyN%&w`X8&)BC&1xMGtQ^eh%3E@bF=bJjXtX>{e27YK6vIISk(|Em-UW-4}4H;+fOP4L8{&DE-*Z;XRR<+%iK>_}N z3d|-&4?4jN+_O+$X_VsiYR*_^$ybCpkHFQ@8VgJ-i28#O=jXTMuh@n;!QYJl{|4f% zoaI!k>g&cgpT95f^K796|3J<-`lBPG6s{B5XW&)wPuU&*078s#=_$@4^)$vBEtA7i z);SAkfdE*D*v3-Ge4VlFBsi0_R9rue{D!h)+~>X1{{M&mcdHCH9=Fj<;E!+SkK}?s z5s;t4v3P}+q~z~qO5kO}EA3u1(O%dlvPFv19iqQt{#LrGq#Pog&P>Ap)!^f-!1~Tf zZgkoUXRsjegG6D{(vRKLOPh(kI}Jby9OaF|#lwU*uVog2IEJQ}EuTH;rVk^|wQ@## z2-Q=Na|P8hUwt0pgg5!z=?EE<7Tx+5I`Ui9mV`+!d^a=609K|eQMO)shvVaSLGCOT z8QHct#iA(YVS~C2hPtcAN8IP5RsT5fErmBh*6U!=(DjW%#Y~oCjQ$ssh3hu?w+Vn+ zjayI8v>#%vG5NBudL6Jl9s*D6-X25WW`vo}Z8h)I!*>B4OU`kI(ueIw?<;r5ASN|U zB{7wtO3_|34CPpB3Uft*#?KNRibm~~?Bh~10^TrVHFaz0RkI4=3-4Ba_ojbfvDY&z zmnKcL%~Nv)Z5rL4ZUZ~}PG>WpGh-XcL3EQHv3krv?lgKgOX14(LP)7o0;)&!g^RXsfbO)woVNOZ zSpX>;lCkwNttzbk8VoUls3!U#r!@BDnDdXVSE+^)oQ=R8$k@JUlB&Y9&yb*wJ|`QNIyq#BmfUTG?sd@?^j6RxdfzyEa2hSP6Gjl# z3yVM=g@YQUTXFoYtOHDdPLQk{^?qbTpQW|?AlT7JS?GklA#08BzB&H7vmeE`lD~>? zb7NWqPLnF_PI&jAL-_QJ1$=gZZ8j6e-iUW|BGNIqSL5|f?vNFyh4yzoJwZEx_p;~+ zhr3VQ?;}h?&a&4>I%-cu1wQ@ur=yL^?V9rYwuclWGc?n?KVHzadx^!W2~r zkZaA1K_se-FrSi8rWtdt*ZTkx*1wM`%VCzurN4Q8g*`NHpAhaO&|w_(iqBwty2NbM{wc};*6nLmO25x{~mhnT7i+dA%| zc25oTb*tt;HWXEW(+@;+?PrN`zKd2EI{588n75gK=mdrLx9246ai>u87C=39fry-l zEKB z(nfOf7~GBIc;8WY?p0U0b)k{S6e8650L0)MInR4Jr&AyRk(;x5_4IV&UnK!2+F~Q} zd~23Aj7>TV<{uRg($6599(po7X;Ax#e@$T$K0z(Y6BT>%YPI3fUAjqWE>G-yWVlIAH{JF}}>i#$S*oj}?F>IcD=PskiP#Za4vmsm! z<5YLDyJI8W+R0!oI_9d!XTbCTX*J@HErImt356&^tMC6nxq^&IYRl&~h8-^SQ$_EE zXNPf%V{1HF<&K3g1KH%*lei_nAe#ZGA7EP;v%jmLeak?8cAWLGt?%zG+22xE8x`pf zZwSy;s^*f_0Tt)lSiS4bS18%0O$?K0iJD{XxK|J#B0isPRx?F8GZhof9jE!JkPi3V z{tOe44*Us-e}_7oHj-5yJm^!fJ>t|f3w`g63%O|0_CK>qdG7P3j@Wt&5%@+mphs#u z=@cHdU%JKb$7aT6hK}^Le2*|3tnRzXsEfV`j&-6+Z{tG}8X1|QL(f1Z(?)70KTeoHzpqC;!!Q7V zfa#+-JU#H8#A@wi_Zp+(&sKDRX3`qzvTZ5)#l{eYT+K-@1ZH-&z1CH00}t0>Q&dSTuh+6iRP%JU?@m+^*YUV&l7D)E~Y zHC1k+nA0euM_3T}89M_R){VnMphM?yaG(Vbw0<7Kn%+oS@Hf9*=UZqykh;sRO{Yr) zsMGmCUzeG@gu^sck%^RKxLLoJk!8Jm9f%6?MiQFNF~Fgj-HQ!;!5oz%E=M)j@iQo7 zrHX#Yra?%qAUO)%sH5v-n8Gnh>Z z?Z0jKW0+*Ef5xsxpY?R37Y%T)R150Nf3Qo%KMe%sIJxi!fRq^i1@Ni32yDbj6B1>S z!CFFy%8{HK zl160(aOQOZ>b~5bu)8+6yVe;mI zMUogx?6?&V$k>I-eBQaC4*^>MkJQ$6fSL|F;wu7HVnv$})DJ53 zm#h>d@gmS^blIVwf?0z*9oOdBDQcPLv`5o>wBM6Q#E|EBuBc7zsUuD3ABu);`UubI ziv>(OH!z=gW3ZH#!p+9DotW@unQ;@5PFDipuTCn{Z)k&q#@o)ql$8PVXLh=H1Tsm} zJ5^5PK>EbOxbF-jOy(9BR#U-gwgLNHxeo-x&FCpUaYg2ycb1 zTXQxm8;4XmYr58-UL}6|6PQxzKNmxO-%yFPXo}%6=BIEV_Ox!8yu(+IFL8EG)d>H} zG?{}2(pSwrjr1Gyj5)&-Y}gHWB!X3f@H%G6)NQZF=v8xNxUOTmm%(r0PcV1+yK??~C2EG`)0u20W^=q81CZI6v_J52M=>!@Hw11WK3wS4R5!>EIc)sly`FVleapChNJA1uI zXe(9 zA}ah&eN?hWi0+rVoN09?cCs&0y1(eG)Lx*0jqXxzmD9#2ZGZo{oPGYkm2oG+QSj%; zAx@nvGnwiZI2wb#2-G}%Yk;jKwycAn@U-{vT7Xm~V!SWr?lXsEDk=(g?XvBGuOyxg zG__fs_ctl9>$b8EsbGYpmEk%SA(}n`p5XJ`-}@W~n^!30eKWWT#EXcsUOma?{;a?%cv%}Oj?JNW+Ab$#vQp?k+T3{v55{=jdqG3VaFz!c>X)*X84Yl@|NSL<7be(MQF%V>673868Wp%=g<) zq3p?TZCYcq{i{H+*onIG9hh8%{Nc_T)i@p_0X3pyv5PyB8CzUHyhH7RW@kr`<`0u* zjncBRu{GR@5XFpJbB}}mjGJ57p3BeeO?iBf(epr zY9|LcrAfNEA}KAfz1jj4mlfTkWbnf%G>2)JbJa33jESi%Z}2*3T@7DX>b1zc3Q-9G zFq*?$P*SS@%?TgOJTofQ0gH!piNA3LjE~M8l>>MG=JrQjY~Ky5zG_x=c7d&lg*s2x zi!IMEU{56Szq@54hTqVYpv#^d(~bv zUag!Os|>JTwUV;S#;Ye0;Y3h~X@fLQ?D^tgYx z&K=rF&p4`|V5Fm9-UDnNpyL0V_d5bUVXx`l&&=BI#4(6q*;w7)jOrS{NrP_G;Q^JLK5u7^J>2P z)P%S10vhHHC=?{Wm!Y%SH8{)KD3r~(cxOs9vQtDH>1LLm|dyU!RLWG!Sms=6KL5}oTo%*e8Iuy9n$^%d7-X9kp zJ_}dc|2Q*r{%iIL4u_Y4S#$4`tkhKu@tgYGov{L&Fx`sMWe-?Fi#WZYB3;PO25~ph zsyT_4NDiZs#^hI?sVI7rOofPb`AW*c@-#tH=8=hkim3-cM!86Z<6R-G!$4E;D%e{g ze?s}X8x)0Rox#S0ZHDu6M-cm%GfcEDOE!rdFR#MG`}~BVQe;|3)bFnL5_T-MGnru zWaOW%Ms+AD3;JQS;@aXzme_br$JxWZB;JDFi{)$Vd7R@t9?WCP2v?bh-3Oz(S#+(2 z_<+S`lgY=&T5b zxD(Q9hzU}Nhllck`av=vXsKN__YW$ynOo3xc2;x0_J%0t@#b^mmtE>PH^7ezeV|MM% zny#rcMgT9K%+^1#$C$Bmf++t7#{DaSU%$pqAHb>J=Wg4#Y1S{m^xP)_Y2Smqc9$f} zuR+&@Guv7%X2kw(`Gdx*3rOL#YLU)Tn=e}XZSQ-Jn`L(}w8r^!eB~ve(X3ms4g}={ zbaYDV4}m+c8$Yi0Ex%b2ZPk2_qgk!XQWHB@tYLTh7V{wH(5gO`94&cNcM%673V3BM zoRS5a07bv;NN;@U6+@?_=(5Vd1>gZ~s%ehd#C%Hje5MG>K6`bh^*aH-bM8)@o<3a> zZsb&%X0^Rrq<_+(6|&#G+NMzMmc&V55i-BK}`fji74xSOav&DphZ=!eGh~d_>-5;^BqY zCxQQgYfK|@gRTZ{OAm4CFhU-ENCQ9EV?d(349fL?xYrE6x5F%D0OYFc>uVhUAD=c6 z%NzD1-V&g53%~V$CIPsVvjW+IydR(l*mOKWjZ>{@g7Nsl6xHZIdCiYLAg_72poY%I z=CTPvm7(98JuI$OHt!@1`|8zSBO19mUn8`H^Ib|}-Zem2`jWszOzt#qX~xRRi!-BG z1Sc-xkeX9y(>1ySpB4v3{XX0}VINiA&kbsUY;fK=8WhU0EfLi#o>ZYhVz#j*rGi5- zm+QcuGy3wULS*jQ%F1hyfa^0ep@`>E{}l07DEQ7amd}vssfF2lJ8bs>D*HOa9$Yd0 z32rqlxE{f7ZQb$Dt3LyG_0-7Sk+t8;8>ExobsmF(f^9=&=QhprW6|Hv-5meerR5y% zVUpjLh4Mx#b>{*@=sqP@BLfskZ&Sw)q6Gy`-rW4Wk=CgyPsMb zLj7&;Jgj>Z)%?sN*Ix-C`Vo}}2F7)z8&Z=TJGywJd`*3INq@B^Z6Jo3)O?VdnrNW} zXG_xm!|jOZc~j&W4!E8&r>C+iMm9jB^`C=sx!L_Cd>~WMD+Il&%3!VKq_p{#W4RT$ ze|NvjKMBI_;OqlFwo+tqr}l6J1qJo6{rfj-6g{jsk}L>WSy|)LAfL0dNm;hEb89`t z9E(O?lTUqt+XQz4PJSK7PfF!;2gUDjWkzC{eoW#p^_Sb$69t$p5t=0@yn{sdO9UK% zaSxE>S#Tx`$x_zkhYG+-0nbRTX(4iFLpJP!EMP;Ig1 z&GUONg#IPe{<^r&5(L*xamn|?P20MfV{D;yW1ZQC4j7mj%Jn61I;R^vN#%c)r*k_T zB%-A!tTMBJtBx|TgioP~y9~@$q#GLf#+_~pR|-TbW-y8!ndJrK$i^2W!@aO|uc&5j ze5dyl>n|SZ)3)DQz=2ec89*&n>$G9OhnA*9awY*qT+M%%h}epOrtGM5`%XWu3=#7b=R_`2hSv|KyGoKqx@H9#}<=_EfpR{GwYqV~M$T9f#l&lMd?( zElNwr`?BRe7e)@CmaoD^-)(CD`+Q>%tW5M4z9FnT!R)O$(HI*mb z$~dxnogD&4X+N!b(c-Zj^J$h5$YhF%PLfpf56GOy5Ib25b?p3cS@d|QIO%wU=n3uM z`&dU_-f#Aj&I5O2vomX%bEQh$C& zyT%H~8+kk08c-AONtJb=L)&c$RQBxIinu;`_y!Bl7IiY*Zt)H8H-Rq(s-p+s775;6{oARW%HmDo5y!;lBcbW0z$~C)mmlhUO+(gDAB&7au zjEQM2nbGrXtz;FJz?r=xRW4DVE=v!CEZOR2GI(q=gY0aAjp1Pq)%BTh~BpbN@ zfCLK__77X{MJR1xJlEI$)#4|lL?}u*>VNEfNwV!l1*d5*I6HLAhf3NTfIF9_gu|GiMHG88_O$A@)+=MKPG{T?1x z4}K;~!uL~TX4cc8r}~&EtoAYvjo~&jP;3!zWbd*j(oZvF4Eop^t;_=D!C!6 zL7DugW|@i5>&^DR519A*r(V7%-mBP!%eFKS9r_o%V+6M*0i|X6))tl(x2lmJq@oQQ z;Wi0JionF3h1v#n6;rwF&A5x<8Fv45lvWLQ&k|P#KMjhQLXh7hG!PwQ>n3z8LCv^u zE_f`2W8?i$=4V$ae!~?1)GDVZb;P?$VdpBZs&j8F0wjF}b+3<4bw1GJm6aAxY%m(9 zWi|W)C@CiH?n>%ZB_3(caTPPA_daz^_R+4W^44$>{zDwQpEr4g42^gcYBeR2?W0gv26&WN97nFX@0bfVD&_DK{v`GPIq5d#2F=<1C|n-h>r2rnA>H5Xgr?DFQsFAKId2!PM?i^^+2myTF-UJa4Ih8C1gEq|Lvsr6yusJk z<@(12{ngyln)-*ai*b8ytdNZp*-dZGaqZ8}bx66pZW_OMvVVO?MGcZR-}}Hzyf*>^ z8cE<)^YY)=WW(v-B>*vQFjWry_O1$+PG>3EsOz&VJ4q}%fj*Gxp&cpOn84)|yR@%r zU6*qtR_A;X>fP+8BcGBBK2G7$M-($UjuQx|ysWE&by5*j|KEN8{N+7s)2@x_#UnAi00Ot9mmZsauG)4uTX+5yab+kA8UeaL zC!lp2SZa6SBE7pgPoyRU49LHDdc!hh#V*jHXE;4*-PXfWAtU&B<`VtW zL@?^MF;ZY6*ZAG7$8_rtT8L!#J$`EI9y>@2?ZqrT`&t zpEkx42>&|&lPH;vZStGlCi(82=Y~i#Z6v8vp~sFnF$lQtKyb8a$A4%uk6ZI{I3I$j zXxO@Sh(aRY$qWX7YaOq)#}zO+OmX)%*!BPL+(hKfYPeT{=|Tn_wLdNb#dE};^OWb% z(T?a*UrORGwf{}QQ#ECvm~2z16-(Vk!0z{}qls+bU!$E*l0p6aIL=lhy+^gf&^_JZ zv0*}lNEvMOaaMQh!a239AZjj_XCoZB3%RcM)q#R)53$v=rLlhZuW+ju%ptDN$AUNG z2j8*6U?*qxUEir7=vXG`FhwHk-5L?sz3mBJW2p)Z)##%>8Jw8-x~QCtB+YI`>6~?L z3M(hJX10g;23UBn;J%?ocq3*ZfT0ypT>8UpTjRE?)QJkLrUfrW#^j|Ol`?!sppSyD zL)lDe(0hCBajPVS&;|QaNiak2aS>37kG;cv`#WD+d)oeW{JL7%Omad`E3^h2Pw`Q^ z5^?p)G;jx)hxeOKCM2}gF9RFJ$1N!L<((%lwx9%Q8K-XmauF zF|DIb2P>V$^S1{bs~X= zjbl%MGA=g|m9(;y_vf#uEJR3>N7@IKgaP1^&gSxIzpXTMjU@%$ftuYR|*M-CS3$rf~X z1fOU&1Uq>FLZE*J-fdJ0bxc=j^qV0A;#bJTg?K6i>wr$skuCVK!*cRZviL+-_=vyF zEb;vEa_8}{%EPiVRGCccXx1P6B#+c^sk~Y6K#&Zs<{Sk2rdCB&wwbm(UB>J^Uaft< zehHroO`%*x^Y;;aD3ytA(R34rT(uX%id_@`X&WGkKg()B)d8T~K@yg_wuMvk{G78K zZ;~uI2zMcSY7ODf_Vzg0f*?Wn;})li=l1^=13&t_r1rgjBrNC9X2vJrFa3!xZ6cDP zxPB+BdxWPtmypI#pU911NZwHbM{=Q0Jp=9^FcKI(){Va%>KJH$RspbbZ(ZH$o(ooT zA#t6APT5R#b8{3}WK4;GHujL{E%~G#+ouR&8b(!nt(TG%r40h*qZ}mY#y;)wob!44 zITl^=Dw;~Ig~3TZZn=>f%p=pTEuBscJ)O^O4omXJ)HOy?%-FSqG&Vs}b%8>|?5rQO zXK5_ViByQBlrxt@Ng96yYh{|yERbNrwA%SXZI zmi;77(%CzkOLJ~nQk}%~eB=(Tg{;T+QQA)1hH>vfYTpLk&I^mr;~+yvI~jvW7pn;d z+ktdSuRjhx$f*qC7Gs3CtTI&{v5=?rA3guNnTJ(ezPW7GSKRQFq?_LK&q&irnAQE} z@By2AdB1eAD=z@=rBEtm4OWR&$wzbu<0c!O`1i{@`Qj;Rl@kIH`WAV90!rln!2fSc%Z>m$KModWc`{ipWDndVGw+z7&Y2tKVz zG(H>a7bBa5X*p-gsgk2)(pSth#WZXCvG)P92e2K;WkTSD1vCXzk(9u?42UvmB-GN0 z(=Zis+GybJw_Fx-#)7`*&{(!&0Ony)cj9PsLSq`4l7x;}@Os_ELF65PaDqE9QY*h5 zY2Ko3cXgAo_VO{$Wt1QvfhFVA90xc)z;R2xOalyP*8oTqW*E%atUE^;2H-6g>T72= z{w+IzlDUtdg-@{e!b<6CsYweP+4AM`u}gfD!y7bZuj+}N5N`$xC_M6okXGHb(^sRa zxf%RejsoWQ_?qGqU)H>_aA-Qjcj&VC)ETPh%|DHVB%tHLHbHRo;X^7!@dz@i%*#`f zl<;7p6D%}|iT&Uub}sk?9VXkU~x~UPO+t!8n^wPa43@{+{*xF6l55TnV0wdZ|bpemVYpM2C|rpuhVKjrJ@7DSNa~h6@E3{AChzC#-FKHXo{G2HvJcr+{Z9fb|1idVT`Ms8!k; zXGGhRzwmDPh0su){DQtr;^&VIa0k&GsHu~} zhv(<25tsq&vPDySnp`nG;lN?hKI|bjTR#6~q^7y~fVw_0Ny-EsZSc+Y%?%HJ)Fweu zQ4yc_r^?(A1|AKe&6fu-PjpRjSUn_yWvm|Xp3!YcCu}qi@cy^2s&Q`Df=@R6pQ?-~ z$D*2WRf)G8kUttAIRReCgi<*KQK`Vs zZBH3ZG)x}5_!<%_Nm0h(lnT8!blRF&$p4xo>xu}9G>1+#(XA0!Sj@y-7{6zNDw@nt zmqMulKOg=6c+sYzW0m3QY2R7>*RT=7=hTzInbqb+p`}VB-;z&D$_NPU2Fseio-i>m z9DR-mc6Y5lcVWG8Sm_an<;WSM4lkBMmcVGojZ;LUOLe@O>f-2ZUOtxNm8*Zr)o0wK zZQ82CR7M8*2OIs5krvPpubR>tQti|Z{`|pmKUtX|(j_wCdOZ4=V=9on=Q-s+O`xP6 zP*^RN#HLf#Eco_ui%vu;U-Nw`8rAHDka{WZo7)Kijj(Ag(4w$z5Ukb-Gp9Ouk01Os zDE@-Xr`m>#=tX1tI2dj@{A`5)L^KkJ>D8Z;dkpf)DSL8epqLEZWveRmklZac958;R zQ;B-Pu#;b&AvC6j=UX<@6@_nFA%y_6dL7%_1sibc!j7Z*&29=aFM(+`;zRV6`BmG^ ziuYd^`Sk-H>HGVu7!V|4W&H*6#yM2Ta4y~k%sXgWE|!a)Bod3 zj2p0dRj7nQSYodB7Jv^xfdd7cOuvm^OE7QpNMWlk4%-hOb$F$4c<{{2MmG*{?v1oP z95>&dcIT`=tb%Rs$7ONoHYZ7s2Xa0ZI9G#A8iH|kU0pB;*#c7W=0tutnd#`^QA|!wL!^~dt<}0kln_JX>(bG20o!O< z@Y~yyf4mSujJoz$42Q106IKwqi|r3r`dS>=cP(r(i4-#5iY;m;?0F~lTyUm$>lDYM z4FxS`r;OR-Z$>LPyZGljF@2U-wdc=u$GbBQ#e(3#LaBTGw7{83=`~{R3+h_>QgE%P z22bxI#m<9MR{@7qxPEmmU3GtJi*7~U>Ph~DwU1rX)7m*KX4_B9P0v39b~tW-QU3fB zX373Kz~URmg3HiX%1uS5FrnbBALPtd0NKX401)yv7^J-)wsk6*P0JP>ziiYw(3@x9)G(w_p5OntCfdAUqpBOkRUnX=EUJA zEVfw7#+HRJqx)j!)%fy}8&B-af$NpbH~iNpb~}%)Kk%`7HiSF)-d)24M%4CXlKQU# zSe6U!ZRy;>+L}lZRv!*_16a8;8aAWsGJq_I+S_(e*Y$Au-28E+*Qq9my@?7bo@aco z-sHn^$2aB9*Fhc8aA4mCcIf}%jlV(g7K~RnepURT z$Fgo#N>-CDJOFA;oXtQ1K4Yu&`F0zTbk_J=Q)Un7yc=LJS6w68);)-|@S{yFp`&?H{96h*4MGbCv@VA&6DX&?VeN%;5*r zUdwo_@oeP&00aIH9tofH5OL^|P{7f~&CSiY0-c^(x_@l{%FDVzcU6{%VYCq>vSxf6 z*w%Tdr3b{^NY25Y0&hn@_zS;i1n*6*WnCbBsqx;{nq3-`@==0Ch9Xbg(z7Irh%+ju zRs}ADHAz38kPvfuk3LtJtIQ4}YbSw)^e49DD}n=ju`#FMWP9xuyV|e7_l+U1S2aiE z&p!nT=*x`#ou4&Yh@k-hequQ53w2hvhZkd~Gg_FZeg)VGcpav?-xor_Z{7}? z@oEHA@`4zNPZM!|(d4Hu?=B6c^Gm5vqU6zUx)rclI`x7d8l+8Q#ChU`!h73{D&&H9Kr#Im+9x}uiiCakw`gmK@Q&`09opid|kg&MYl!wLccxnUnL%;Fi^h%WMeK6-eaDyK3B zg+gr=);(XdvW274PyGr`habe=7IS{ZRl{=_*JPC{qtIFCwNML~sSlJFpG@D`pT8k` z0VeFNN<9Yi^^kXGnz0P(ZyZIUDOGZKvPM5@{LcZ=2OJQaXIMpJIVQZ>rv4v|7>-N` zY>V8$KsI{JiYvq+am2JQKfFHJBidEZf%3r+(^QlKJx*%dDp*bxPB zA@%Vrb;b~o_cFn)sxRxQEXT1YMo?gAeB+RxPo1)CRoiYmL!^0zs?v~$@-oi3ZbAB{ zeL`IhMzqBpgn7Iij3ZAT2I|mj;Id0+7-!Fj^4GC!7>zkPwk+W6vg3@vgv8lm`~xp1 zq2@@kmNhSpNm`Ic@Re==<(>oG=S^IQeGMmYfd2as1L>^4j`jCgI+-Q{MxX;hsbEds zPD))>naydfm5K{dT`RDO1Z_T$*fu(y7!&Dg*tBDhe{nO~?5&Wq=#}=0gS%P^- zE=A`})(5bx{OA2?OaOEN`|rsm?8v(X-!?TmzI<9p3o52h&#+jVlipJ0autPbS9IXs z*rxq>z`rp5U4(JYW8vE}h4 z;!X#=DR`6ts5z$&^mJ&rJv0IuH<|JN*bUuSPPFQ?f(O)L`DcN|*XIROH}2Q# zmkVkm*_h;S*OBuc+Ty^zH2a-`l=R_a9!oAqC`UjCdDZBzU$K2S5Y$6mJJ)zDw6$~P z9L}kjn;#tbBprVnhn&cU`OY-xCT6h3^jNw3{BxD|&&1;TQ`*OCCSdPwujF`d7Pjxg!~~QvU-oBh5Hf3Y&Ejzi*@f!d zwVwErfwhKBCWQ3qHncG?=9F`w}n1bvH@g*n#asioTbX;>L2-_!isF2*DU7BJI{UpVb8U)EQ59S`O zj+i@*p7)?(4U6xTF6g9P$ki=jP#$}VW<*=PQ7+@*t~`zE*ThnUZP+pS(B1G}59XH# zx$;>WNVEbXTI5un8hRLb;WgZr7cmGNVU#uyC33r#7JYE!9#t*hzy;7^UI$3FRrEP( z^w-PZ`-VflY4)nToo@l=8R7PBOr!_Q-5usLJyM)cb%Dmtsmal4gH*`p7OVZ~=%ZK} zcI|i2fF%2uEr{xUHQd`WeTkXSoXLtVF_)Vt)T~+7Y{enALF>hJT__X8JUX4|z>xzE z&j+r|&=@PLbj4liIvgEMEJAL#I)^o`Q&mO%fJChWc*7}{)5+FwEm-+GVGHBb)n?tl z$$zUJZ_ZCrJMDP)zflywaesJ{J<&k4;d;OG!}oyp=W^<8f@KNZpImRAo1eA&paBTh zw4(?=L=t9{^kL(@aY86GKShf??J3>n{JkRse+A`?uk}09iS_EkUI1GSf*o&MPDybg zMm}euW-NHjs$)!Hcau3SKKGuis5LqMmoGsgZUd%l26Ze)q<=FUGr@}RIvX`*j%|$8 zO{FY<>LBm;!LZ*6L6)RJ0MkLpoA=3T$&F+rBovXQ1TkUYkC-Jex+dLTp~zutFegA< zEZ=H_>F5Tm=-8k4ZgMiE2yrLF>P z9xi5%#tuEUNNppC`#2*QN4=#*u>6)Ad-8y6fZwiK@>yMYIajxWVpwtrz$J0w$@3$k z5nz^kh^gh&2*$c?N#!V#_z)HH!$?AVf@R1oaBIwpH1&}RRZDUgtjX)}^3MoVBqJ}# zBe6mP0Yk76ZOmgx)tV=>Se=qOLVC$pWIV#FjqC@dD6P!w0m9T6-_#{Ja!p+wNa8et zJ}nC&Rdg+wQg0?HJx7B4Bnt%Zm$gqrUgI~&x7GTI)^>1Q2W8vaZ8rai zn-yOr!U*|fy$U>sl@^8$apqcFxM1c+a0~1Qn^~Z{8QGmm`fmH9l(VkInjqt4>H;_piH#?KI&As_cQDypJYg;e^s*-m~H;Gutcu7Lzyl| z?HY$M$Bg0#!tA7-WkY`Li|NT4I@EgNhfntWDB%&SU;-m!N;;fayXh1hWEX*sop7l+ z^F|?P1r@x#038>M8#<4VF<^}fl`1z1+yp#Zs$iE)(3vyrbPB(NT@p`11D*q9n7?l` zL6%9!!-y326+A@{xp?#P1iaj<)l$4}=+-BX65!j!_Y4|+3V*U`e<^rg2}^5MN=%i6c!u$cC~J%Z!L$+eOI-V znuNxB@hhg;sq|7qDYqp+?d-yrnIssUowbJPQGVE%41&Pn`GmcjF~}+qzNsNAN)@HL zs1Bj@4-1uNavwVZYx+#55v!=SSWnjH5(~2TX3>4s_`AEgMI3)~)~o=ZZ!Oan^sW6n})J_zb0IumT?zaHIvCNZV zVwGv6t+>tOFm_Fno}T~N*-*xS+|*qyaTXWd3)06^EP9Q(b|*Zql)S+#MpBjHid!{z z+S1XBi1C6O9ON}?*kx!mI|o?}685i^wVV1*S|2LQ=cvUpttfRGDr>ZfzECSfP-1vN zzkJBF09nDVKc9jN&e3HuMZ@HJ=c(<$+y?zU)jywTn~XOlUX}f4=h3=^dRAPeCB0u` zW4I&v7Rdf_ef{WiwYkFO!qmU~V_>F3CD2L;N#k5a%JS#_9YUShaV01X@ zdA>GQRNpb#{_S}Spq+oLoRKMg-`+KC|Bx8}D3C3{u<@!w6G=rq7}B?~s{0+&nCcse z*6k9KSZ*-)ykmZS;`8&ir7lPbYx*oOr7@!S;W8H9`a--E1`@3(hPyJnt)aWIC9V&8 zy(##+MFavogoI`F;tWXw)+jx$Jzv@nvt@Z;JNto`{&iZYLPTSOQmW3r(8s@8$q z7}aW?e|M$K?eF4QirMYFVCeUEg<@2@IVM`%_^GNv1OJ8?jnBO97oYk2$Mtk$ZKrLMc&niVP@ug_eL-|3uz!WvxA_v>^~y&REHDVJQC~@A{Gd4N z*&e9W(YG{n;86Y)>KUoJd>;98C#%imA{=x;E;jWW0WL84cBm5JNt9D&v`q=XBOzdkB_0lT4+2oUR3b;vIV8GqrfHJ z?(@j;JO(J)w}*9OIA#!3!O!H#pN%3*TQt>2NGx$+e3bmN za@8C+{?hWYTEyFnfjghd2c`>KUHHViF|%!9Q2E0#-d1)n#THWJ>}yJ^p>3Eg%|^4s zHC*+-{;%-w-(_zMWFCU6+Im1EFZE>EgHxp=YB_*D5`4e9$VJzvV?*b(*Iuot!^k=O ztXq&TSOHk$HaRIEjj1KhkWL}P;;j86*r3lk(;mbOw$}Nx_7JIW6(%^5Bt6>G`uM4} zglGMyHM%S+Wf~N1<|V4F7ee7=_oosv%pk#P+X|LBmo(JY-Ffp|ug}ZldC=yC07tyj zlqSL(D@Fj#5a--!Du_-k{>&0h|&v|Ygm zE&gAYh@b7-Eb5BF(G0)d!`79T2yLpHz-$3{=fD2YuzIf)oDOTiq$P_g`B`ChC!b?5 zoR7yCGJ2vyzZGw+mUb2Br@4Z)Hb{NU%D!|1Q#pW?P%nFFS=SV#q%WwI#BFDhE1hW} zJ!m>)5mdJV$3%W*S_8sx{7_-vFrb^4qvlQ`P}_p>4NJ$L3C-*BO;L1M@yDcolkjSWx&LJWDm3~I zK&&Pp^4t>-YCe#5#GAf$)=ICpO~g{il@UTZ4=Rlz_kS_KPucTaE+>AdW&(E05TD{fZ!Q7y6)lY9h zk9VxbkWJ&706z3D6X8qyc<{w&mQ_3i$p;ybqf;Fo9qk9y>)#lz27dj*D$h%^M?oW1 z!i#iwl4pE5AVB$f-;+JIl@bEUC~`#iV+hHUMjY@IgY?Z`S;lPJYWyEhXBkyx*G6k% zlL8`L(%s!D-Q7qxNTYOzbVws1-6=2KuxUY*?iNtG^DMqI&iSbhhXT)D&%Ne7=QYDH z9AKH?3u5>5m}P>NK^@blHQ(10I-0#}%e!>~;+wSoTbBIahH2y2%B13#>+?A0jjo~w z{o;ZA1oAx)K!z9!MKamy4ZZieIH3Tv=J*%bANUghBI*UpU{{dzdO_@h##|6S2RpOi zY~jf_{7@V3waxr7&R1O>WLzqB6kuwBefoQTIO4T1ujIU* zd6x>JNUt34trU^rFM^SlJ`11wf6bQycQ%`&jisumm%7(8@51-`7ei*zh3Srd3CI6? z%-4pqez#HxSSBhhyLaSE72|h%kK_bBogl`;Z75y+?wxp=)n{Ff1DfMicC>nV|{xIz2y1hGfru7@+x z-57)r`XDmMiC@%h^+#f{8}QEYy=LvB9~c}A*V89}7dru(0&q;tM(djFd_7LRZ9DzG zVB$1R0AFMmva<4)gp8~eij@i%%50|@vUY%Sk8ju3Ysoo7i^ZIIFRe`OSv2PAJ+a;AII_oJXG2bZ_S}b^{Tx6;xG@Tl zy<8n)(*4K8xvJH$?_d3_X0fQ|tzBuiM-M#TRW|AlczfJ&&l;bQ5G0I$+tI|DoI-ct z7h`S2Ej0uG`EO^j6MxwnMn4}jn60d3%DijOKYz5vv(S+y&y%d&y1)yYv3*bU{Z$zo z6Rg+c;3)Y|+G|snZ}()d*0YSuOZvLNL_i@%m>Jv`f%YLMBOz5=dmx)Y^E2#E(g6aq zhu4vk6ZoSoeV@ATR|4Bkq5ro(kQnp_eg$ImP(rs%)@M6@ayQS9JbmQz$y|Hh5yE42 zF4(L3rr?y(!|Bb0?VdZ_w|-Yg;Wly%NCNxu5M!9KuyA?GOpU*IC!ZF+SvB-QMy~y( z%%~d(a=&DMRY`ze`V^9u{H=mW1Suyw)xVx~jUDIky}@kcr%U`&#aA{LW5%pbU{-Gw z?HtdQSE8$s?5M?=SWK99lz~F;eph=cT&1H3qPjRE5uL_E1PQOmBz)>D^&{AkQ{wu< z#FVj>Xf^$wZt+!U>!y^IV~=TE`dy}}LsviI*FSvPzrgwq8K$&KzWO0_yk3|P5TDKG zYzI4VMDWTTZ87mQhcXBP^U-j;Lc5CSMZ+^tLxs6w=Cl*XQOb9Zlw{;%S^T1IvXBk(31QXt5^aVw;44 zi-_%hkMm=?zuBI9>yH#FXV6rv8q@=pQi3@zYr*B@C6o4#=%0?3-{^aGZuFEiajt_B zK`0KXP-fP5alrU$_iYEKZkNvqjM+NK^G$LnebG4mvEgp*K#p>#saJ||(lJfm-IuOK zEC%i2uf$%v)>2nvFImoReO-??+;nYgDoh5=8DccH5H&$vwd~ZlqqbydFha}(0#|GVJac+qh0-)czYVtP+}d*-J0$DN z$N-1ckJFo<7Q+5lIN${d-J(-Xbi^VdApr*`J|1OyI&=^*Woi0HP;O7M5KSAMo7_)p zDsoxxmQ1B8XQspK$v3crg@uJI;)(Y3M}$@pAHnC&Lr@z5jo7Gh0S)YxZES2n_t9ha zty0~eZEDX3RzrXWzDcJ3xuI$mK`C+tHsA1$@c3}amU!-xxrF_(O+{KS#KhUGZY zdmCVRptkB9`x2);Dz+SU_mXL47`Cyuv5~!|38`K7B}kY@HYZIfDaRXycmm>8H89)c z<_Pz0MVcH6xV^SE+ORpJIehIFZyyc(aLVj`2GR2h_Iu zmm}{b;fZiL8-G|zoIWQ$6YDBwK5zS zl+d(4inx>za6z@);wo7cYgCw%+t^_vpKM;bCVO;5c8Is@CZF8n?roSmwq7$Kv#C(J zB=N`ER!TjLc`xxlm^hiYb2ab#kB(Sj3X3Q!io8A$IR96Z&cQw_SQ&x^V{P}m!~9-P zvtv_$F*NtV_tw}5LE=_qH*W31k*HaezwEQvp*N}U(D%7OUqsMBvDW$N^>N_yeILeO z54CbB_PR1HIFaWGnUoLeI2G?nuZ?`B0E`r2x`A1;eI{fNDX8fr6y^n_5%@S4Sbj|J z{`N?JoB|N}-~W$L2IO=MQ|#v@5ik)5RdU$z2Hx$L@{5Uu!gTE*+LXf{WK6!(JLPu1 z2e<6H_Qp`pj@7oVWp}|GjEYoLFca9NQH*FPm0*u7Ji@5sfI4Q=))ZmQ8s{K|rjj_R zn##&1=Ue{k>uc?L9qTx^6;9PnQc)5N&q)*3^p=3fEYg_Y0s?7c1djo#+MlR9>UF-| z1sPw12##2KlXzCi0iVK0HsbSGhUH%^too9`nOW`K_3r`FWgJ>mYqAE&0ATV2#FQWE zmCN5q6^DFElOSDB$I((f2~3+X0% z?H9Mgp4Rs>85JM?SEV|Y;mZb9b67Vc7X>(j2K&kJLsTH|WnUbUd9Fc23`<|~sZr87 z#}1GZCD*qjxm9eYws$qFbia zE&%b2no)SbK^RuXy|Jtx?}gu?AXb_h3GuqRAbinDI59^Iq*75W?~WmjtsW721cdBC zoZha}ebq-PKiBmJ{u%KNnminKZ_~7o=rm8|QeWq2HR8-Nsxx6jt zrNbW&17NEVRGz1lZPFREX2DV&%^Ql}(X&o}Q@0sJ0v85p_g?$6KWHrtVy=Wfm@aaX z#2^z1ATgs(40L9QA7g?Itx+5b{yhCyOFCpQIrIzxj#L*PpLlX)U;>T=-?5)^)VC>~ z*biSPtPflz^P}GyHHeLgW5p1YVn3cC=eo{o64JA9r3@=v~s_Q>A|ID=k5m* z|9-%6vQbraaSbRrq@LhpQOKx!6SUVjHc8VnNL}t2BTmSCES8W%8gAuWI}U z&1L>Z)m8W-w%k32&qNUvcw;mbO{fQPL@Fw|J#h0YOEdShlP0jDZh5I*lP&b7^yHzZ zev*M2w@P`3OD;sUu50eTImawfx|MuTZQ zwV-vs710_;`lU8t>fhxu*ZQWe&P|~8e`*rjH56s1Gr?n-UzTm`qCH708sj&RL@QFW zgsgjBquvu*#BRsYAd)G>{Z>vk6(-ym1VvG-Y--gg{h6-eJqde+rCKhU-8ud!?&D6) zFS58pb;s5IkU*x=e~4ACjK{XzVI1bo5+B8`TA!MM7f>0>?%VrxDk%OE}u)Yeiu zRTuBmcM|H1QlnKr8-_?t6Rpa9*wbradq48Fj@I*yam6vE6uRXQYQnt#F2>+1c)ob{ z37Pa)7R5+(1e1iYcvTnHr_R>qA2#kyKid?TO)(VME6~)w8?Yb{c>NRA&&$-HR=fH17uhqUYtKS7 zn?f1ucTO>ab~KF91pSvmc{Ikkyp9A*Duu%7(0T;-ALj#1T&`SiTOvS|9fWjGp~TMl zGxl4cHod*w_j5rs{Jns1ncBOlv>4qJ`}gKby(B#JL`GH0wW2~kx-~(+ck))?9&3cZ zR54_J!pV1vLf*Xpyezm)N_RLnwE9H4_@O?(jl`(nmlMi*4mC_Pkr*2Mws(bnIta|o zFv`@01T$>u!)m#SkGD$C1EU}j_=4#2gmrF(@<`(T- z@Gkgu3<=m=bBE;uGST9VtYBb~slB{jN%{GiRRX8&g|XJ9FDTI-72 z+S;myog4qq+MPoDDYm{^=M^Bxc{@qG5>IBjp__XR15jX{*Ouw50LJq7Z<$8@iqoMu z?NiQ#Jl6F5a#2{Gn;&nTUV6RGzK7sih0f2WMiU`p1xr6wJ>XyEIW@OwBlnY*P z>t|**vY9!*eF}qh+QTOd5OGc^w)>UYe-jWoHp*jPMw&~EL?-1^)1)b(Ns}@Mm7WTR znFZ}zMsts;RqB|TaSK#yF@iXUEw7>6Ci;U~Nhm9xVwgH|3pEQGRk|Dw77d~WZ40D` z!PTk!5=;iF2sSx_it8y){! zT6<&_z57E&LiVbNyB7+JJ;81Z>1Z!Ny#UEXN+4w+6ID56q(nwOw@nvLfkqCYR`7I@ITrrr7Th zeG*#`&dtVS_^r)1UY-)RIR2PDlt!hfc_R@7Zld{f9~>gpk8;8%21kQ5O?8=Iy&)Oj z5(?^aN15M<9`?oRnRVhtoxAW49336a5?S_9psW*BYR7_Pssc?P7$9?`+}aCs_H;V( zmu;Nh>*9WCT`b^K$y=d-a+nASW|p8Xwa~qv92}(<)*7Ap<4$02=Y) zYTx(JS~RJScCOm<9z~-eju|)M)Z5n_vH-RlEjwf2X9fYJr~M;l2~Z;F)2=P8KD7HvRw5rgdgm%?(oaf*sJ-*YCRp3) z41tAu(e#=|WgV>R3(ofBaf^^XOFk!F;wD+MSd@NDpit>Eq62V9g)eb06|W&Zwsr8R zdE#MaxL2ChORQS{yo2;XB;-nhfZsFNs2SvcVpa9YC<`s&flJ}NdypQt*HP}z_U}d{ zNv`5k1SdGZF>9H;o!ruk&P9MQ)(!ZVK)JR;YaA}x_Wa_QNb5kyW(@KGS8CfLbaihd zk{h>mt}?*F8df{!w{PRZXRS$?y025O=D%|6Moazf@eanTVn|&qq&E^-W11I*hB`y! zE`=vK#NFqVK8`n!mt!}O;33)}TDE#E{=k1Vzx-}_T}u+Czg!t(7`+ekxa%H65Q7@Q zwo=WjwQQ`SX}D?tpI2I+yVx#-TAylxTCdt1mXM@9W#Z3_Ld0-2-^vA z^dBtcwoUna78Y7@rhMD=n0NE7py2&Z;pK?hjhX?U--Am`)o~2Tj(ziS*OnV>n`eVD zA@eQxnuu~_@^Dms0l-XpC#@MJE>F=dyUTPT5!=7>s9|*adgUeVJ z|KV+VRriRV!|vkR3&E0uW3`xYmY7gO-@3*vpZeOcf}rJzRM_t`_-Q+5{P?pn@}Q46 zH4-$PJos4%Nz@rKPneKNhC{wQ7LYDosIGUud40@)$z*cYJ{}ha%Ve4x)ChZZ{TfqR z!$LGLAX@BUqZ_;`=X{>^EC3~MEB*Pd7MVmn*jIknT==|&dZEQe}{<|S(OZ;{wh^ALpS8Bt}W*Y9fb$mA^jFYiHhllB66A)iNYh~-Y zfeXCp2fcBVqM9z>zZzmMce(Fj1f0g0fLojBRQX>=S`KRtT?W3tU=&(i6%|&Ezy#;C zNc@@S>36~dyT5Ipjz6f6C#HVIFXGtshUkZ4jYK)r>>>Vzo{la|PyI(9u{ZXZqXY%j z^8-FP9Suk5aD-KgGek(3oXzGc(wj&ygLtE>V;yrq%F<6e6dh@cRG_NCuSoRi%neut zKp2_AH$cS$zrxTL5fhWektWj25UUFw5&6myo+kt@geK0sFW>HVmCFd*XZH>pDp+L9t&( zk)GT}x?ZhrN>$nvrwWZ8if1wlnoSzG-nW(q@c=E$L5$%0>Z;t)*lOwk#FAbLXHRbT z@?Iz!;C=pb!45@w4XHZwhkWx$AJRO%QEKSG5noC*E12mJYyu+?cI4 z1lE{<;P~@hln3zzL`eQHH~FvN)&JC`k8Cno(yR!5KmDSahIvbskJ|&etQfrT!p9^Ml%|@3&LV`E0(j6b@ZS{j*P4h)}0WtGw@ShW4OQ zXVws!%$LOU{{3ks{-XktUdJ|xuDrx_e?L6f7J;zTOD7jRwou6IyW%>~oVeg(si64H zY=$ast#Zb`4liTUM({T0Z71M_|GR4tFL=-wJVngKUw?QY>3)7ZUa3nP&uRCRud`s@ z3BUe3GoVycT^rs(J;(M*dBMu^r>p=wZ0i|h?o6$uVLZ2oH`te!c?Xh-#&eVj_|{hc zXCWW>_FxlQ`1sp*j7;v(>Rk_I6v1<7wfjbNepxB-G7%OKDRtG1G4otANCa^^u^$&?(;lJBk7EIp%jFKUps~bKteLIA~tKH zgs3^0dbaIHM#YBBU-P#E!8*y*0N)1jztnf<+~vY!CxubNtErVC<T{AP;J-+8xwb zO^0L;Uv1nQ>+7rU3mlWNeku&Cd|n-%HaGq@16?62SK}A-3r%MW&>L;{^X~!`*qsA+ zg*H4QN23MeD@nv&0e1C?)F_Ki8NdjbB#22=7I79Jd>u?+tQsWUKJ$)6Uaf_n>B^+O z62K4sR9bxA3Qt(47KJv++Q~uChL`5(tbFzqKm9^|zcjXrm>n8(; zKT_>$9CCBC%AzCI|MbG=E>_{{Ae4{Q=X9sl$-&t4j?IQ(%93nm8qH>Aqc--bPmzcd zQ5d``iu;9^ToeJSBT&KX;}|4eYxY9s){lN*Jk5zc6>7?A$G(Hhv9d$xIQ+;#aFJxC zfiG(oX59&-qbauv)LaJ)yYiN3lFEQCz5Jh5m8l^W<5dz_KT?(Y-(pWI;+N5(95g}b zN=wUT4(8VYnxonfU^`(H_{wO-4c^XW^Bi+Fo?EX;&erI|bv!OEKJ%UE7H#vvOw&g% z!I4HA6 z*gX&DoD}fjkV$*<-o#`Jta5tsP5eL*JNIQreL-oRGjzZIuXznx8*s@a9PmH@d@pz2 zwz7R$dB^EZ&S}N*v06h12aEs&M+_DUFLm>#n?c{;ZYsYGKRuDI`W}nm*DB1v`>1+@ zN>%=^NHiq4fsGjb7F)Kyg4mBTqs|sPgS-cHG6J)UXU6*V2{<(T{ojIuk-pvC5>}*+ zwl+8z?IeA}59Qa9@X$e;UF~E-FV)5f8#0Ny%u#f#wLhuKmze*m<`1W2eu}*&sryMA zk(a}d5}BsuaOKlU#^bfMMVEL{I<)3TU;(PLf`5InxLCpSQBguDs$}7K2ewmpCa%#F zF>}ss0+}=!vTWk3YLE|S!m>;9Zf?yj`73x9?hQzKw)L*W0Pi&gE1tVk#&=+_d=C9d zX_s5T>^7ht+edQ^)-J-P8yR~72Q_t>Y`dr_;9~o-B8W3!wuD9R1z83YT)ITsvNSEj zWL;fdGqa|89bQLu^AG;$G2Ge$T%`il)|ysNaB3rcumt4qi}=0#gKE3)h}iPF2X1c( z0X-UUi=Dh!s-+2H_V4^ehfMhgmOntPHYmn2{p=pkppvHg@#-{cc8FF7_?x|tk@IUy z{U9@)yF(<`&;A>M*isfEK~v9CP0hi}jy4YSU82SFkat!`_rhqAQx;RfoORSqo;47g z{Id2mJMTl3giqmm-7H~3JKXE30K&9!X>6?}w9dIo0?9E=V}Ii=GXFKix+hBJ%JA}f zn%MA=V88A&S#k9M)ePe|AmD*LL{4mBQ5Y%AM#4nl1|yTNk)N81+c_z~PhO{NNAU%( zIGjX>ofHT`0G-=8yKkr9qRwt@m-q}CK3~F3^r&`Su$5?h4*Qa*NQ}ekd{F+^4CH9Y zYUf`^ClgmTLWhOf0AUq8qqWAJec;>iZ>c#oydRpJk4cQz@Si^|+AGSyh6#ruXO|IS z8)nNsxiP9x44oQ{yh$$+C% zv7cI@eSuwrv-Q9KA`0jOE;dVgFL_i{rtORZSwBa)}_GClzIW1hPD3#Lp%GWuc zup|8~qkz>huRM8p*8sV3xY#m7ARN6kNT4r~2n~_Z{VX$QTr&vwAi^0w zgIw*SdbP1^;{xE%Ou;I~by(70Rj1>I_C5%+YYtc1h`Hs}0QH zahAzq4f_^74V&#ZrZeOK>Q6hb*ZOyN5nHyYCtszW9PYVs)OiR*j?p3)oOb=au66bE z2rDT2O$NqE>D&?TQdWHNWGPm>9dqeI+Dg8nT#R_uXs|rC`Exxel+_gqrYAviGb3~O zVc&?DK0g7P1#fkncE5CnFRWvnBG-`V*||BM5-b85%pL;OG{OZXuwY(1`Dq-=>BpO6 zSvO`goFmoIW6JK<Fv1EQPkz$;zmt9N%{51{v)uo4j*TCEC=t- z{1)L(vdE_fD3FofUho)$IL_+oECosLAs_-7*EWAooJ{BDsy*@ItYx=(&^;U786*Uc z*UV}dj6mkSI<+H}SS_Yf(=6(*RrI$D%_lyziTs{T_5gVLyFPj3Zj)!g0y?M@PzyKA zxj>(W&|rkY6q-O1#WzfmZx<`UlD63G(gY{M20%kzoHAdjk^96S&->ZM)juaNXv@cr z#oj&`0fZuN-q!xFk6Ek*_Kc*(DT=&6P52eALVV@OLgh&%SPt;Oo%r%}#R;k|- zP(`Eb#XL4&felO^C<*}^uJ%y&SQk(4jTt+$YD}8#1-SRhWj^M~h3#e3&~i zp$zz>zJD%xK?O>EQ)l=}&RdEMNJA*4{JWImLBB2+&|F?rMqU0*=S$n4yE|0pRg%pY zGTRGW6O>x$;KRwNdx~&Hbc2@V|MA?~*B&v*{7zs2Wpegt`pbV8=k;r5f4|J@kjGOM zF+}3ieEj4LU~%|{hK9g44ctFDh4U+7I<6@o*llK2e0Ub4{V&qTe3Kee=P|Y4b;p&;hLT_*tI_78MMAeb{MO zYtm_Qg(;LZ03&&qf9m>QK?u3tS%;1Cn8YT?;)6UFXvVYvT@yZ?t0wfgElVL%yf77M zz9;LwCWEj~jYF#B`>F}ux9rgMzkea2W@NNzZ?a%w290R=(WV_S7vviBHdBHcwBb-_ z*?k%@mA{e_41l~Qkk}AVO7S~3Xb49KbW6}En5#krAY!*fm;A1IcEOiT zJdh)Qcs1+FyWJgu0)Cn5GJ4?F?s;R)uk7CT-OhIVrWj1NLb7V8rwLIl@5SuF+|xZJ=I|Vk-)oH69jR5MkGBTPxsD&A_@g}Txzq}D z6vY!N$Ui4q4JJQCkMrYYzPx^5;bPEfX&QKtr!faGI`5;<{s1cHTXslr&^r_VOP+w| z`!ykU?f;VgGhhL4P8$NyyqBIol)JIL#4~NSUQ|y12GW4=8*(Blrsi$Rl4lVT3c6UE zC%XJ@v1Ui1j%yB4>)6NYf#Pnzeqkq;1dq|rf7LADB*B<*PyV9CaU99}UAShM{>MHe zu_fhXs*7Wx=chuctn92-k1$0!@VlHCtzSbBZozAJa1eo)kME}~x6AX> zV|T~VGqj%|H0E3r4aq;}09$>(U1Ail?yOH0;QDPRy$`xW8aB4p|2un+0_P}LKlz^=q8i&(AE%PLIkG@9+Ek7x+jlMjp?T3%Re!|AuU`mZ37iywIif)91s zbv?|JHC0F2y9{QXo9Zt8ijzR>?QxuRL7B+ZXOtToD85CA`zCQB9>o}!Tyh^I=a z13VGE<7zMkB^5KfO_3>xvX~{|(-cT$T zcn(0M{_{fQwgA?rN5$G?7({}2na@V5skrfGxi)nXe>*XYS=61mmrvu~ge8%l8zkp5 zTlTt^u1LreCs6nLvBuyN-ou0f9TdkqqJf@0Czgj4o5b7+5AW>E3C_45cPqt2_ZEsI zw?lF&EI)p=CEAVAU)K;zp+`gjyD4Wnb&egB?5i-9X$Z2lp|8cBFo{(d#Cf!mspX8` z)A7oC4!DLiq`2qp(Wt1Zo`QNHVed1DNx-d*-|1lb%~3m@*W(@LuYJp?k@q+=@79fL zBf%yM@`6GEE52&i*m)Rv6ny-2A4e1dFh|*=j|*nP7c`8k<6tqp{DS~>T~%A#-iiKL ztmk>WDze;ut&@8GCzD)^-1{6+ZInpw>0d-S-oYDt5*5=}iRSi@D(3%{6!~1DdKF9m=u7WR)ow$hr4*+0|<`);IeO63s8yEtK^=bS*|ECY4w_|GQ2G9)g2zt5C8- z)GPd_3o?x0Ewy4)Hid56drNPOE!qjNlH#+3o03T|EmI&`Id>r%>lsL;gLz=`AR~DH_7qy zZ4(C`ESk@u$Z~g}2_c!K`ORMwJaQ|2U`>~LeBdvpT zf-hTnm)us;p6yIKPzvnHFJa_NYAWN{6XKajFV{4hMw-VoUPWgsX?0PJ{@ZwLXXGA+ zb#we3)bqCYop+}K6uw!0p@lYIym6tY{kRJt?Lw-nl|2MM;7IR_*AcE$(sx}Wa@*Dnv}@&`dNVDHt{e@@&a z7?GPz_;>%o;}w_xXF(K}uce(ENj_v^BYrO~Akh!jT!5&Szjkc#;R8DGw07aqf;MPT z+v7LVZ~kj;_Uxy6h0MFV?6VB0dys}3J21TgKqO{ znTFTi6JV;$dBPHRY%*XZrp<;TZS}EhF}(_DURqij#o9TqHwBAnR6$Jf<;BH5@U`9- zW-V+L^6?9M?ToK75vKsphEHcrKf_{<7FJ;dlrR^bw zi@`y;U8)cl#|miSn|O@Zr;nf3wkCQdnyAeL2R(ST*DIM7^sIsjt7>XY!9$@=%@}H+ zF|@No^T+w`p0QV)Q1-x2+aU14t*-u1eM^77Tlduy?*on3YHQu+ATn5O&Q~L0W=a&q zp!5-BHZRR~$>(fnT+5^*jC1!Y;OcaK<32u#AL@jZK|Zpw)lMCvR5pX|Gf&T#>K_#v zEmQ8~mdTqxY};e!a1IV4psT6EnfR(=$FVh%>_)`hJbI55%I?=`PiEapX?zObFrEJtRT9)w;(XZ4=`9P85 zBG?&&?Ij2-L|~gxNp?;m11ro@9^!*?%m@zarjX?0-Xs`R<~NVMXJ=Pj`pcBB+cVq4 zAz!I{1{6|oCS7S5SuvY+@)Ds$ZCqU7ykzeiZN&JQ!o}8?ob%S#*LlEG(P8E_Lv>pb z`S0Hczq1j#n+fNDLc<^4$F6dcIzlLhRTG8u6+cvsSsV*HqtWJLF(k_beL?Za3qBqO z{Es!PcZbLV!>k*_r)`XgPi-&Dg;F*(7bh(YaavjD(BK71J!Ne_7a*JAY@QvUt_42- zUVw|n&0Kp`UlMq8LIGy{#r)VI3rA;Xhgtxp2U(;NMx$f}WCb?@Da)oWNK>OfQ^7D^5dWmDs5pVOuc3sH|xj?zPwht7v&C&&Bxbkv=|Yx^RZaR9-`p zMZQPb6NvDj662n)BjB7!oj?G!E4!snD_okK+%5^f<;Y~~;9wNC9ns2eL)Cg`!`pmx z#${_w?c^NPn)QMJ_RBn!UR0E{+};=o?)9wlV_r4hetLR|k5Z;)78a5V?_HU(6!9d` zYJkD>u9JBTM7U_rP#r2GChr)AaABdU+kp(Fb9t{Uh3d-#^aEFs^(M0$bdQtKMR zyLAdlPsazAy!rWgHM>w|hYT~}+@1{a9hawuhM%^`KBTjU(}^g=;{OGouURTiO%U(g58deu0xT!PV0<9B{Q#cTN_m)+J>I4-P7v9(ML@V0%L{>cfLb^}oj2 zIXE~l-db^u@Q>Swh_YI2VI3Z0$u+svS9OcH5w|^deWd4K=@0HQ@J!QGOz%CFs z#nxt_h#L6EdP?_r=tk@Bpu$MrmMs-4pEV7D%>UAuRh09*=G1H@@Yw-QWAFaAN0k<5 zHY~lSH>i$SwIv_p8bbVj_hjEh1ZUwP*xlGzs00^s0K+&2gY?x}#d=s`;qsCvx}XON zjld8^2_mqlYi%u$MT6DGvdp~Uv-WOMPpvQbX`8=Mb1qXE3=}sHuP}Tz<358V!ns3q z63|*W^2HfEc8W$uU#Zw29%Xz)pT8i}rfjifZ@3rf(-KEZj&AyYRQ`i{0oNcU3o~%* z7kt}swpl?vCu(Y-ANnVR=CDKQ?Rg`!)wVVcB_CTfR$bqG!!o+nVCe5%9g+XeI|e90 z+#BIcNlVBs_Z#zIq(3_W<2(&f_zua|P!E{b9i5L&MOA0Gs_0Q6H4FCKVd_>e%+qLq z5GCu3aeA?TeRFkKd%Ah67>oEg8aTx<0lTN4g}t4=VNMWk+bmS~pIX!o5PN^9OnOdj z4{cAU4UhRn4URc%^}iN-SNdzVWekcMhK%KYw_5xQNLms!6MIEd3;!eg%sM0z@w(zl7)^4qTg-PJKLkaxu6;z%5aA~*Is#EXYm^+Y!E}_vOywZiMUPmb^-xARum}H~qsXw2{kehX z?)K|8vqV4o)G}nsKVc4$=5{uXAb}25G|a4Mlmog&k0rJw-8S_NkKAzT)|-gubjh+7 zcc{KGmZPPk1=x5~FI>KGJU#4*6}qf`6*ViMl!ocT9ReQ&TW+W&K!372p!6*GtjpxQ zg#A`%(We%W;%A52c8}(!rWsdT?_6R~{q5pp1L~~re|jxHP{D39;zz9;7^YnI za?+fSDt^xifF2W`Smqf!UPFWH`X8H9Uz&28@aX7<t z4x`}axVoAJ!ML?QWE<(pIL&I2ue!Dtyp~YEyDqJ)%=Butue|7NcXxs?^qC=}^}s3A zDy{X3rW|%kG`tfY$)dfz-5&qa!UtD008T#8=V2m}qk-eBozA2%?KhA98}isK0-hn4 zqLfHj_@D;g8zZ9=P*i#0j7SFe4eh4hAy#07mb}0GBaSr4zUW%)fZZO;Utr3_lulw- zE=0~OO#CI8;8yQZFAkFrE~;Z1d`-a?W{4Rr%Kaew(`P<)TsT|RZoWjrGK3Xffa&Xd zk2;GrpD#ugYy?MTRqq#zoIEmMQlxw-^NU4@zAj_(jR5>%78k~I!sIhNkV0*gY&65v znV(YVImr)Kl zH*}S2uDhzU&)h?t#;21j4zB&uDkQR^CTF2g#7+K}ZAh`NWhpSiD=N1)GXFyV1CB1a zZW!o_qBd5Z?t_q}_V}|X7yy1mq z-sHdB{hcC>(oiv=1;8mAk7*^40;h>^W}0{0%U*aafBhv3@|0QptC zo_gjfCF$tJsZ?iyo0~^HESBC89n5AVk{r=g zO4gcEQF_W@u3?~cqebV7A6K?{(g>dCtIY5hdJZxiS_J&IbZ}oP1SiBS zsA@QA2awEh&6FZI*^%GAqEyzb|HzSA%XRKfAXCT6hY{IN^UPwhBc7k3gmO5TJ2RtQ zpA7r`c3Ul0L)&-@43}FX`c9pfp0RXr7~nbEf7euQVUL3S0T=A2q33&I{MHH~`yLn$ z=%BXFz6o;K#_U)`XOfgIh=~@GfA*70yK$YZO8%Dss06ic6aXYZRvA+&ZqLveZe{gt z0X){)bE3;^&qFQ3SyXa+TsfBCP+7~Pc$O@D`ZFwj9ddUV7QQFeX%f3Evs^1VE?Ade z+_G6V7%iEs@`K)_58bydz~Km_wMHDSl()RufO$gVyxQ@C893b*I(78FJ)i+UK+u<} zj??gAUe}hrcBEcur9i~YP2W&3LKQ$bKZ2PgIOpF7V5$aL2s6PP+b;N^g7JF2@%oHO zvk-AuJDB;E&Yh#%dJOh?lAncMfAG|4vk(0S0cPPc=s?dwJCr7TMHzR!$XImpmL$Wc0C7axR0*P<2o49Kz^vN zuivQ3I*3pDrH+SzfBwd$(3!&>k}CY2bt7@WChk{r^1<7{UTlX`@bj_CaytQVS=aNE z6SZ^HL*^XqA0dB>g|H)cm}};5thkuU%1VMb#xeNabozK#*MRu?LpmKD-INW*Ix}~7 zO_&h305J{p0$0^Qm;qe`AWRCTiVq8-^M$u+Z#d03u*3sgp5Y%3bi4ajKp&noMKtByJqD)p zEc<31vF-OPf)nR zS9ksmpla$V$?dT`^y=nT%EI3tABGMW({Hi#+B!O${EE6W z7Tk~scH#FF%4%7oQi*kDzdspDd}Mm0tEJO7*BU7eh5>gGeqp~*Fm{0m%{pi^k0dNl z*F{;a&ut$e-{s&ztT<`~@4cs?=NmGwhZ~L;W@Tq3N1qfVzshk|60-G~2eZYAH~U9! zP3>uFsQ*<1Wc^%t2+YsW7=!8vur*um^u>R1nF4PT2qdZFeD`HY{qW(#OtZGP_rkm2 zeij%v;ZT?u=0VCawG^7OhMu3N47s9@5+jyRjc49EIyx>dx^tJmVRd4V{U=Cd`Z$9y z-Et`i3H&xj?@89Jsl}i@S+nK7`1H^gHk8@Vx2wLZAw~+k(dAen2Yie;Wkkp!Fu%%~ zCI4REgS)Aop`m2+(%}7Zcee-H6H`K-_;em=;5oPt&+N1+)$hGZMd2YrpKtgLO_EPC zwii5g`=w8d1jpG$Q5P;v5az>G7le@iqzXPFKIbUEn824>vO1j7(qNYR!+NuFCukJp zQKZ|(Ng1Qzq6$4~1=)C23`d?SP=yyXkSx^jXbM^uoj!z!Th%hBAV1Zkz~!I$!yN2O z1tthjia)0pV8T!p97}M$?NBn*MPDZ7!M@ez`N2w4KW&(pJc*b zK}}7bb|07PcYdcyB<^L2W7%E7d|y9#^~!0>QrxBbR%x%smn@Mee(J;0I^A2|e83P*mPHmzAgABGM>6U47n7c(}-t=PZ3 zjY@=bX0O6kaC+3NC!L5?4k`i`T zBcjuHA^nAQ*Khj=!DDJe`z=wN>u;rhyYm270!Zwj;jFmyh$}h}5S^)`)Y2RIoxxcP zoI;ivuclP~46`F(GV&q+!X*xDpwZOo08d!_4*gYRU0lLymQV2af=_~;$aXP{eIO~V zrxnjKA{`dULqh>ekC;D4oVrB9O#f2r_rY$*^Z8bxSi2ddbeu zol!{rW7K$S?oz?!#C$jUZ(mw&SlqT|t=MsG!gzFlpY~+q-f8`~u8!5o-#wa3KN2G& zW%K5OZZjs87c^+_MH@k(z81wCVGj?13TBfW2|{f4GiC%{96&nV98quWO%Q}NtLkL)^aL{npE{3+)`W(6~;+G`3Odt+QE`!D^r$x0C3 zh!i!vP`u0VWk&M$?2$(LulPnutbe^}5Dz~%u;FXl4x!Z1#$YuuzxTl~=Z^S9+N*_7 zcm8{iDO0psGMHSli6LZ)SwXF%Y^?7WB`Ue3QK*n@x9OYfwTr&b(RTwos_yjtDz-_b zjbDK+*yxYo2-5FM2QQ5G_HJ2F=Ef9cLmiH$fAimrs}r=?C#mPZ0wk80=04Y+J|Hxu zTV%db2Nzar#^fVV9G<1n+JotoYxP=GHAcdN;|z4OXd3E_|Fh!|Beab!0x2n;Ij(o> z=+L!!$}%)-v2=PGU#}$~$<@6;f!^IU{pNRYzyT>4Le-Je(7|+Vvkx4n$o(2Skc3pm zCe8EKWl#_T7lCBJ!O97LJ8_CQoVX#OfcM$$p`WFoNwbP!WkhcsQ0a$N8x?Kwd&+XDI}hvGq*g3}GH9iMxu8^4x^w>E_ub^Y|x0mfhz zQG?E86p0!*NJVyB9R)vy%W0*FJbV5~7i$q>(;+VRvR2q9$mcr4UU%+1=A;lLBef3i zcQ(a`cF|+5!BW{p%rP|hpF~PBg4#5UJ`wv9o4%AJyl}=6NJZQYa{2c!vzmM|spL!` z@PkQzi&o*R33q9bnnj(jQZp$&R`!*+{taBCyddn(k~q}4(} zjo7xO$bFW-Jw)K)GObULOmFu#hmYG+@(ZZvQWWa7eXyD3 z>hx&gFriMd(#554QfjHPHYWM62|}W5(Jz??CvVM$otTCB>VZ*HqI))wMSda2?J7KX z`jr(oG3z$*Rid#djl{w=-cM}Q;A%npD{nM8b)}O*wgE~7_Pi-P*w^S0zy$Cd3AT00 zkR(2LxZqr399Tru6cUCz)&@ANMy`2SbY>qrXU2U84l}300}Ar9%YtWUfFyEgXrh|0 zuj_px0@M;66S>V!z@zBC?)lJ2DI9D@?C4BaC|aFTkp+YM3q_j8qr(Mg-EjKWFX}!vs?_+t%M73i|Q&-tH6oUM*@(U3_wdOYr??;DClfwkcEB zc9Q=AKRP$Bz*sPw&o&5q9Qm^E=yww`i5f1UKn?!WNk+ks^IaJLARqqs51)s}8~7RM zk&|Y}8(fy7m|*oSPYEn3-|&Mq;)`UDbcekg#irAK@z7 z+?#|y42`mfDRR=-gd(woW?qT<;t-&o0NItEDL;l2IJi0F59a~pER}Gu;NZY)e$1M~ zk2~N`a9mT0X_wcdI;58E>!=^TcMn!1?QXsl5iusd#<3;}Q2Wzk+>o+L(ag~YF+#2c7#*W7hq370$1Lg#2W@iK*g59wHXBQY#x81Q%&-d=*qk_ag@X<8 zlQ{6n7;y%_E0h(KVEUs&yRopFGwUW(ocHTxEv?K+i$?Y@^uXScRG!7`-~@3qa8xse z#(@RKic?2t?^@w3xnv`ryaD{MSB5a>N-ozelQHs8Ke{N20#m{!8s5Y9w(sR7djyxD zPQZ>U(9Q0VaimE>^9+~?4w`WcnF$Qq{eGI3vplelUIjX^Nzg)&3Qn7!canLgCI7y4 z{JCAwp>L2>c6)(JlE7^@syVHI=np!JU4PDAki7;@yKS(x{_oiH^o#`S^S=mw=Xh>T zYIrCH;hmM?+YORxqv`e|Ych7krZ8NeaHBZ|b4hg8q{+%}-1idSgWkO=HXyXRTYtt~|r6tNI>AwdG_bo1#UjEop zEpU(*IkIexz2h3?|7VZbjW-2dZ9OJL@c{GeskJXJ1#npfcG zjP@$tRToEDNu%5tW~AtuQw~%KKrA#!ZsDi`SI-sv2imY z44)S_RAmt`_e`Ki6w&vEWigkekr<`3#Kq#Besynp=|=?QX>&F72!^1b55L}jf#TV1 zd0*IRP&GIJ;2tIoqfY+*hluch!_Y}auQSr+LDmjPh;8=AM%``kf-Y_`N4>CxI#QUS zHpJpb#0^PFra2Zn_k>cP(1T>RDMrVH6Oic}4}n}!L@${fX;u(xNC6eeO{lY@;dW;0 z{RkE|uCCO5`NZkYD=g~ zl;Krrk3V+iIK;P(xMsXF4&)XJsMNfjtRl_N@($9@{egnKzWxEkV+M<55`gCr!4oV! z&t_%Fj2%>3n{fhn&ys{_PR&iQgh748(J;Xk)yb8&{OG5P@w!><-g7@^*&#id83$nE zfH*ok?`U5xE4L>Xbv9DM7`+SXgTIOSeq^}yz?MAjK}Bi z6HTRjdik&dO3#hMXL8TlM}x52-y@(`W?>3A($!5@!t3uUN5}#gq|8jl%3j?11 zV-)sGA=WasxyZTLu*Jy(+V0nn)wPR>Wjk-@?OIe*cY@xnU>}O(Q}#jBNcb6oARR5# zVg|SZag=={CfR}dHR*l2^cDSb^{2~{Dqq=>ufIZ`e=jnJPE>gh!~{bJ;wUBLFV%X4%OAX z%_wK$`!E}^va#yMtV17|SeD8W>!z#d_&PA3t})M|Nv9=f9uEUG7)-iBCG^pbuCAfr zE)PZhky~jA9!vFEx!&t%Z^NWE;_F|N(I!aRk4#ZV`(%*#78|I%#-cUZQ;`CnGeLUC z-;gNLfHFqPuL19fJZz!qj{a`q@J(`q1;>@Qz8~PA@z`%|N~xK#@=sBydoZ*PpKO}W zQ(xQA7P-h6QN+JtMi2K9JUh?EO9QSxq}u6i>ZQI!s}mdMJQo z5c~Le4ca{?_+wx{Ps( z<(JF88zJD$r%Pmdq8z!HxcuIo!8<+&yi`Nu_%|15JUGg7dLGfa+@EgO1Lu z&#Z2zMqzyg`Poo#%y}@NE5@P0?T`L6|6@)e21)P3sKNV^mm-B9gJ@3OQI`EqH@M7P z$Hd%RO6lym>f4{3<+}5Sh;rSPGrsd@q}HSs?mT5I8TRa&GW=D!Wb!NITIO$zV^%fc z1Kd5#CP?r%IR#ppnyEV9#Ir=lfQAA@F1CCn_JSB>3XkdcwhN%>nJq^d>gY{*g$Ysu zub3|WM`k;(e6O0uzFm#{WR1oT4{!{y1JOmQg^Rt)H=M&ts=iB{daOHFBiFiBa{UDv zaC5E{Pnw!Mm9Ok`1bA~N`b?wwloJK^E!x)8d~r1SMU=4ts>fAJ6BbgpoVf7&%gMEr zg?QQ%l+?G75YuOn5R1JTfMG`~g`Gp{T7x_=Ry#5CYqey>+AXU3dz-Bk1`< zSn%syUZRYxZnG^J`S_sN+8(W}t`0msy-pixtmTjnzXCe#?1SVRZ)k$*s?j?vX~z@i zEHRRa;Uis^eiL@BB|gY&XCU7$k)_^2%@`x@^80zT7beC%-raRTC;K{n=(@@HH*3@K z{yiIMg6k|wguy_Ml3JZs2qC&OevIAW!`z#+Z*NTbKWcgQYBS~cnw6jY`9p6cTj$BD zV4mXT<<$FUbOwL|~P+Wec6c-UV?oE3Fk_aOEG#8gzj$TyoGXi>0&!-Bl# zIz^pxa7IZMgo>D8h5&Jj>c()6;f-?6ZY>)0GmGVD?GxWuBo*Uhmn2ZA|LnK=Eerg^ z5im|B_{UJ7Y#hE)8l)H#K!W<$en&I@3MO|fG>QU%@pH54^C;^0UU*XW5hBxiAKOJ*` zcVKFY#Cr6UrplPd!$jkDIsW|5DyL%EB~4;ld*;3%oYDce*9OC{iu-1AC>3O81T>-TVPZfxQ|&*{e9&a2Ffd+ zD$3OF4G{Z-I2+(|02~8@09{6a2A+{kHr_mH&Y6=%W6cuE+)ysK4*4C!Of0Pm2lMA4 zUU+jI0D9Wy?Y%|w2ffw;(?ji-C8+=921FjtLg3p0@P z7jeU0ru=g%7wCOO%Vjpv=~~#39vP3JQN_$gK>$5=V9fd%7^p5L1n>5Rx-7Bynw!oe zXc>vK3G5_AiST~`z^VWgKnp)VxO914N)r+~F4GWi(MN-IPf*)d&r#q6i5j)&{6t3G zOm9zki*$BGqCv?p3j$_V**Wc&mqFq3hY{fRV*)w?E4y?}OXL9L*nQ$w*bP&P;v!ek z_E`_RV`|RaW4kreSLPU-nLd~dtb1JMXIF8{HYd6a91scQ1 z)TuVs-Q2-WKNQ9E=;-Co+P8tBx3>4lA%;38ypPCS5g4_BS&OU5As>|1&HA~5bDv>5X2Q#BvWnd^+misSdY@E_o zAdfPZvRU9Y)M@TtZpZUVwW_0*ulK|0sYnQS5wY?--ge}EI`1%H8MQ3umE4niNy3&_ zeT5OK^%ZmDiLt1oi0HDOGn z%kCRR(&y)u?I?#P5;}fgo6X%l zqRzj$-oDjodItD`Zcc0LS9ZowO?CyG1b^Kqs7w(M8uOG2g$#NnC`ZH|6^VO3QM z1XQAs_rMkA2R4ya4(zLO4<9&IF@W>MdP%OzJRDDa7x5gb(Q}b zRHP+5!fa#;>&sUYR@IREE0IkLSQC{_HDEzCI?J%XoI z^-IthsY#i2`@S2&{OkQwM(lC*@t)pKWNb5?vWW!9uXCE>O0L!W)q(@ zPDcRZrX2RsV}@mW{+oSs^l@1eV=}SR8|LX*yB0Q*gc+Mwvy8!8I3WMWAYN+!uNNSD zFH@P0AOR`<;;CFI^4@a$x5+T37IT_;(4ze-5ud*V0oSXRE1PS{1x-6xWC)GE74(e6 z1WRv0)dX-`g8aL8H%7Pw$?Lo?xeej{R-w1PpWNt8UnL|MMyNizpKj{6pvr$28s+=B z-cNud+C{10k+%$1XKV%2%{-$nYQdpmf%N-DbsE!Dwmj(T+8>a$H5ioVT%mNl@k|;r z=dIpPIbxDetG6_Q97)S2l}^$dcDX^erTlE6AHKpN+V9>=aNLDx@)*W$H7k6noc#Px zjbIn;dvg;aruJBiIDLh7>ED#A_YO~q@!L1R1mpjhV+iu9*XK(gd^|zH<7>7%VQ`ZJ zdT~sr$JRfBlD7hOQ^+3`Z-V%m5Ko+7h!DLtdKpt&k{*EL3>fX=J&hD2Gt4)NSPr$ATV)T80O@8`&lY?Q3ItB2YUQY2`6Kte$Y$T{y(v9Csm=%moX}DvDB>=@GyVHwy zH%gx03x{EMQdg&9`?iCvoy|(lB-yODwY3Zf_AVZICAlJEXK%3-8Wq*RjG`fGPtz1K zK4lEWq*QqmEMJ^wqiRl(Vx9#JAWJacq)}2TZ$3FQpo9<~-siT;rU+^o6*Erl4JV|) zx*XI{V3&|Q_Jj3r1|L6vKY;1NSD0rtpI;PT|A~8@=HKyYGj;?9UZKYdHjeI_ojG6E@r;c)g%?uutnFgU@@ePlWU9DEM?x z*Y2bJ_Azk%0;^xg2D<;hCYek{*utu1Vgl4~ZT;gzF3s$Q_BM@4f$i!bW`(PjCIYPI znQ;4=yy=6Rhs)=_-iHa1-R*7BASSYsy4Vv5E+VDx-S+_eboDzW3-S^-27V>V1J(Q!R>r#|^T9E8F$hN#eH>~qB!NuCz()P43Cv}dlML3M zQ8WosMwLrba|#6rP4tMcVWHIDltX4RRa%+prkZ~i%2;QY>E=qQm5k&p(hS~t;pZE~l==u-y(z-7-;#>|9(&9_YhM0Ayz zS=)G0ol3El-9?#1YE+M%3|88g$r5Mz`;hmu6XVt~@+d!Wn9Lp9#9svMeuo+d4^neA z@_0%`lB%`7UkwN39H?f-%6rB(8}|kMnGkSjpwg6Kz)R@JzsGI-!X8^M`%XW*xQ;Hb-h~ePKy-(jEkcbZj5W{5C>o7t{13D1@rz+Y z4ozXaZA z?pq&H(xL(-e3+d#{v!duPCp#A9*>T>}m_JnVPf+v~vM3?+(dk`Rt5w>zZb_iX7LYWo_-1(Ju)oy+J2-Ofef0)7+*guR z@eiRjeN#)coSa@QQ7W5+s)f#Mtm`4mVNyn$UVWmiID#Pu#}*84F8u_w82#r^-Utw) z0pb2WPiFt_E}1dv<-7Ssso|ko2p-Jo=0@ku)ti7YjLiTHIg%n~))hq6@(BWa|glh@7lGH*)H{x?vz&eO&|@zu2+7$tsJv)h1HM3 zVrG^`#o8t|)TFNs`zOp3XZzoX;hq}>uf4ToS$1@=p;XgE-SiOEosDrO){q06mcHM3 ziER4dGYy+25y99>8IK9VB`c}!eK2J#<4N$zSLo@uUlJDBSi-hVl;{)882SV|2U(@v zI&5YqO~8fS6B0dJY>PDUzYu%ZgRzv{vrK=yju_gQKvyXfK41Fp_rr?dvfcyrfwWB` zb&}E%07rxH57Bg8U7c&O56Q&EUYfGZ7-#h>oscu4Yg^c-=kxO<13J;bIT*ReEgwL} zb-Mrek$}ozlLR-B<@fGuSQjM03r|(2pqt?Po`e0V(Z03 zAxapr5dxkI$m}!NDIGpRhE*78R;#Gxicqv)#e_9_f>q*w&eb--Sax9WE$8#SB(i0y zvf;8fa7lGqKZB5K7O{b z@BB$Q0nz4NZBW)sWn52vC&N?iUszJYsKm*PU#YADp@)f*!X&oXZ0>>LHD}GmoF9?P z)-bM>Qman&d%i+?nmTaVNc8gC7@19CZl$0KwxjE9$27Gsn5E#b7;iUAwn(3Xar7Dc*Msd)cLU`IDNJ%vnwsl?kpkDTJ_91LfTCZoYVa2qv<&AEC$Qn` z&Eq#dw9Tyl0!3(uwzf=Q;8x2@QEWB0>1c1?BXDqz9aF4WCLV7#;#6LZdPurI0;__T zrXrBI?A^V+v_!6undRUc9~KRKhCMnW1`@qQlTJtrTyP(`5+|t2S@=j7-bmp2m|ScN zP0ofdCc53#cXvnR|9E8hY5vegk&=Fd0wG2i-vMA}fSn&){P0@aFOici!v1{DkwWO! zd^|3B8dlgmNd4=`$&;1Lyt3N7eB^dD3|**@{&19+@5H=)_$*&A`%>b*$?r-2A-Un| z`^WF4hJPLTB#UQNAxU8jDE7hCzJ5GLz!~k_#5evH9a#Mi-2 z7tsbr^(>X&+}s?lHB~ySK*g*%YFKO7vj;vWz?erD4)WsLk@_1OUxaw+8pMW~<(EE2 zYiV5w1J{oT4|{T8WY#WWfIF&>qX^Fs1B&b`-?@(iG=i6aK>}l01@)RD~^X%J}0D7p3+tMw_QH$pC`zTbHn@Hr1fA z2{dKA`A44-@j&Terw?;5i^OKwGq8po$pakwnACgMT=tEtQY~guE-^4$6q;*X9LPS02Z{KpW2F6lytd6&%Q4<{Q~nG!Qm zE65R(%J@MqB+xM;XJvioUr0Q|t?M7VTfJgOt6{b?8{l`@!nO`DV}&zg zzs0sK>3$@5ywCJZ9@z8D9YeC7G#s;^UF*fi}Bi@>3l>mRw z&}`1K_F-+|qP_KoQeeGi71UD7r%s~y?L8y5nNQ@VL`Q;LTAv#RB^s zEAr;qqn8lq^O#A;@3@;e>5(eS6x;I15o{%3yAxPhyl9&!*3s+0&Q zE#HZomzfAwAcNvW8{qd^Mcsy*I>{oOIh&-dquI&C3iG@_wtKa@OEAAg_4x&g#L64rQ4@Xu- zfMuN>#@6=oVZ=6o}Bw zuN2Vm3HaDnT(j8HTwZnO8v?x7=3cj`Esp&qO*fBSaV!+gZ zL)O%s3QsENyNwx^t7$NOlu=2FeQox<6)dBQ zPWNB?6=M1oI`rJ)2Rt5ao!y+{JUm=Zdt+#0eZt!Fh@NpD^O|flQMf$fxWuH-v&cG? z+d-`VC{G~V+4=S+BjENGNC!;*F@n=H1LbTA58(EeD3@(w1bPpj?nMHEyt_L}QOe%y zA8mUIop6~$?Zv_`y7B@3P(OAsoEfrn1!e>tGro(U&p#6DWXkE#no0hHY*iwdU0BZt zhZs7WZDtP_pEqoWi>rzMx?yG8M1e6)SslqVwI1#gqV2SdduV-Eh@4d zPf-Rcf}Udm4ou>rO{o-GbXQYRw?Q4ZbxG|3h-b5O9ZVNg`M>Um6179tDMYQ^;afU2 zUq?xCR2DpO?*zt0fz*(}3vK2i1MCoM+ID*r6)cao=&5ueQRsYtVcrFNU2l=6S@6y} zoG^X(J9wSB(ocWv?o&0Ca=&G6)ZnSw+9={KP_< zS~K~9s2?fo+5nd2l43pefcb*(6a0lQSxnM5X&g7p8`&1k#h+P6p+12;TFr$SJm;8O zG66D1E%eBX>GJcqU_Y$m=9`BrDz1d=;o-4Z8);C)mR{vZ5QFO z%=;Khn-`B(MrO1eyti(*O0aBrbU;KUM{5Ty$&U55P%_$?gTeEN^8&kh`_6ps;j>BJ z2NJg!mk-O9fAT0(5Y5Y_lmiaC{NK*vKc~{N|ND1$Qyy?fchi&bruQMh^Y%h}dNz&S zahhVfw5epaV(?lhP3J<840r~?Mlo70qb65zw1!$T7hr>-Rq`KVK_3%W&d0cxwd44_ zBGOOvfq*l9Z{2MGXuph1VX+eEADpi~fd1Dtd5&R#4+mr~&}IZui;@LM+=OAVD67uj zV6&dcr(NLqZb>S`4xu}~ALV)~J1#BaiU;l$TBb`eN5kMICmyiqXZJdi8x zOU2fySlODwL#sg@$h1cTatqAtD-7Q)6UTHp3lu^S;e;|a$T+xX^t!s=>W)Ydxx)mG zfe7N0f9`mQJBcjv7m$?;Zu=?9*g1~)J#V@jC8LA}yeo-4;eCOJB>n^|SFQd}u`xs6 z@xO*Xt{uA8H-zN>z7ha!ub?WB z6rms!YlMcp)3#u*et5rnwdaq&9H15{)B~V5MqeE!3=*eP_=;hFBG2?ohToX$!_Rp|P)X_q)DuY$}3)m|?_Qrk~<;8dA}zl=C^{oML? zf&;ub0FVQyj%nz)t)__XDxUcfp6{UBV&^O6RCH2pTB5la5bUG<7+)M1fbvKYhjahO zA4wS`SGzza5e)ZQ+gV>wPI;Ze0ZE~V9(S_juNH{B&d!3UfCdBNayVe0vJB7mT;3l_ z9Dd+q{xW|E5Gzb)a$9{a)f$XId5UH@+x)_#JIZ2Su1ydQ$UMK-!2tjoM8IwFxQ6?o zfd8emD#1`FmYpCDJ~Mtq`?G&mo#Iq?cXy2q6mOP7+$%9_B#7U%1WhzR-zRgasV*o9 z6E@E@%v%AD1=<<_a`Ovq;wUx83DIeq;>So;8Xi)+qq@qy!3f4YxR4^XJipHwb% zrROU9?)eGMBI^$ac}n_U_1=)>lmj@TxDI%3*d(Fp!Si$Wr;Cir6ZbBJrnSB@Ei{clRgwv z+0}q(3cv>915i>ans4bvfhD1^@3UXm^~w6UJ58oUlFgANC4^8h6g^5ox|Gio; z;BSz0ux`X`c$!x8b0G#u${9Xus$y zd0GbmYgyO4Uu=Sup_*au%gE3jXfkr!@i5i=!79{YPDe(*^^XK>N8pNr4|uvPID5Pn zp@&fpbl8H2N*;ZDy6zpJEAS1zzdn7*$^KUw8URYmK5sa1oP!3mAAp?LZ^skC-fFHH zQk$Ga1%+pfWS#KBB?COgaQCWWTki(#?O(q}(Q9q2707V(cr#17UP3eA7#1|G*Jf^r z!twi7)gR`(0<(TSHvWUu0Bo z3;}_+sQCk&WlQ#aq4heUD2J+xj4Iace=YJoJDq_nY%ZsM;pNxZ=I_7Sq-C=;-JriCntLN0eY=dZKqnS48lt z!!|a4+G@D6O{h71;bh31Dapt&VQe^j{V7qXkPkuAv-N$P#{!QOIB(#?y2w(sj1b@< zi`u1V6MGr#MU^d z;0z(HzK2yvKjCh$>Rh!0%Hm5Ia^>{e>Z%lpL-l^e*E)b>&6ZRu$5{{Fgfapb*Cc9a z-v%R5BzkBKv&VUNc4?}!(MwY%@BD)g_t|4SErLjn@zPXq>>DlbDpTjw8V!$VK75BZ zRE!2~!%uP30fMAe%EUnu!=E8s6kz$Ho5?A?Vhy|kAdv^+TC(#R{Qyf|Bg%Lhairz> z2GO&gGq8|Z%msS>IpAU3k*&{@>#Ie#n$PskEI`piH!Aj6kKFj55b}mQP3ILtp`-*> zH`vrfvmvJ8tsGs$oiZc0=rac<=`|WSKyc4K)+U!RAdlA5y4Qo0j8E`Er$JrbClf-j zlxl^ynzP`1rq{7G=?r^hnp|Q_)z032uxS~XFP}~Bzo@*t{9sOOtE8v2;Eyk?0o4FJ7=hj3ZL!V&Mki;SM3cN;(uSLLK zR&wOv>+Y^?F;FHV<4JnooyP>N7R-`^S%BHksys^8-P#oU_l%fK7V3MYm?BKLmk~ zk8kEmI;W2yo+rM9s!>A!@uz{x693x;Pqru1%>fg#exDxy_S7QkU5UFwP(*&~TdSzQ zM(rNtXazWl3u0}P3Oa!%ZLbROj!DBor`Yh13Onr$$B{Yj)_Up2>-Q3~^78a+#P9rdDglC7 zjs%6=t{)qIV$1iEg;dC!xi*ZzASU>G=E{eBO&Nfj2@RdQVp&~}OK z3iV0^MLX54ILJ=fxslqf^Qt2IAZEYtj}aOXlx4ntfh&Lx!PUMu;>ln6x|}25Je?s> zM?s2V!C?71a;d70rPqF);JFig9O$d3qUzbqDkQQL*$=_ND&Q);LV|}z$z&Wk<{Ex( z7P~+jcP6;rXh4cAO~mstBbJPmWasDV&uN(PA4*dgBGZrhP!YzzAq6L!9jMLS7cP5; zqO^QS>lLC<64IsYrCfm&5}GTmaAtn4ogcdZknHA9lgg|OchdR~8Cdoe_&;9eN1Ew0 zYox^CbH9IiN#|9vladPEA%UpqKcYs$lZI-4T_uzlWSPd@y^V%9~^j+^IyE6hMJm<5*{@!>a>-I9AM2+C6WruFeiX z!|;d(ce;1R(MPj^A{LWx+)`-VwD_>u-|=(6RJZnR0m>vX^?)A$8QcD_a8Fk7j|j>9 zqv`Jf7Cm50;NA4x<)vu?u&E*N9@A-=>iu6YKqC)fWTRh7KTeAK8e*g2SdsDB5asJD z0sVh?DSA)wMjV|`09?c4WJiaU@`-kGS01;&&!|a<3Q+>o3Vcm>Ql}xXPH~zZy>)$Km*~gKLKP(FEcny=qWh74Ef8V=rkTc% zzQd4~4vm92Lv(6#l#oE)EV`~by=mxCfKJ|i_j*O7AD}102m0XD6QLKGafuS#=ucL;e50no8tL=!S*jdxuw~l&e8b-yS&^o zQ`yq0MHj?mIyRFfn=zoWgjscCg~9I4zAa?TtU4r{F%6kE1qlquAi55M`l(1$Ldy6! zSs7*w7rvvJW--F1yx8#R6Q#;!3A>V}U4m~gNA~)NjDsc;<$n(>+Hfzn(XK~$7sp9U z;7oqAC>D-@qi<`f1TABKa8}jqms3IOnWRdxB)7r_ zu~^gUS7L{*hL+){;*j?7iQQL)%AA)ttujqBU#DPB5IB7Fdv|O!!Mos*H2C}9Fk^y& zKC7MS2ddAS4Xf2ybWv>|jrd~&so4GyH<6!pD7?KEth@0)lEvnB; z%@YY7Z3+I3>T>z021%@);-#+ysbH{P#lQic5J+&@3F^wf!_>QsL(oR^Hbq5-aTTBp z;LM6Ojx8tuM+YR;t;Z9gh2tKDd5wtr2JYoFA29L(y6?wYw+=i~{~+R()PXV|w2iE-Y|4{xESFWN_s49vr`azu6FoG}#SAovD;dY$fY zX|fm2rh+Avi5b*Sa@+UK0a+}h2gvHqA{?x=6WP~6=bWb)k5s0~x;15-Dw6hgDt_^A z5kf@FcISm(s^sEg-$&vkj!MM&oT%(CsMAl()+-*kcZP&K3Qg|2ut4T}Rpq11Vhrla z+t(H?6<}dIGx}k zeCKe%AozdxIzIn%5|skM%{h0+7Jt2(DDbOngSs?PRCmDcbZ*zE!Ou`vmQk(IY=gFb zn&E>rjx59;K=J)a?>ZVnuqevZ3TDEJ75VSLFZCI7I)>{K{Ag3o?Rtz8%yKxuJpM?$ zF2Hp>+Z|BU>5N+D2K z7!5*rFn%ix1t-@C=6S4+jn5NUt^6#;1V-vvwRQg;BsyrPqzjEnSvWqGW9B8)Pf257kMH0 zUqBm{hLUR!m^q~=oRAp+?-%Dkr>DEuy|2(dul&Yx5(3*DfK{)Q=J<%k)ag13i!gS9 z6fBB!q?G$hx7&_M|Lot><9)Wq+&RuR1xoTCJ@^yUe8R$a9HBKP)s4%!+XdU81!F(~HD%8=+Vu&h!dk+*eNwrWA-rl*pI`YQ& zPwbr7r4saeuwv3KRiYx8{Fx>kww90ju&O>TMqrmk&1Vy<21yaac|`X6=G`5BF6e1Y zz5%Zju7o{dcFv5aR1ch)@7Z${jkiB7+L`c?P^i4qmuU)X)~ww{1E~sSCFOZspeCg- zHr9=X7REa_%?2Yx3VUb(GKX|}*_ja8#G?AD)#a_;2P7{vIg(uyHc5i$Od)Rh+lM&I zW~LwxGN-OtXtGrU#dQ58!W79`q2Q*!BcPV}L$-h(SdjuDE(P_~8UE|)QX6XMuvR#1 zQIi?@G z#LflFhDk@0I<;`E>|x~UCeMln#K73$bx{-x)<`48F`~z?Q_;g^{a%RA)G$Hj0K^^h zHA;4^3VrN4(x($K2nrnqda&qUR0@5rjDGd&@84b8_0Dh-Q*q*MAH(uPQOt0qg1SbN zEYoSSEkX6D`)gj)(Tz~vDxKEaR@mC7^UK_`boaJpi%0#Z5`)X>{oKBR49j(q9)nSIZ>U9xR` zQB$#%+@Rb0{RgkHT&Tj=GIqOVp*ZVoP_xvjCM5~fV-31;K{bmurY+cy<5vRGog1@1 z)5f~>Tq;`>c_`P14lTo!=)>q6#jWX9_1W{3-7w)-MPYFXs+yQWUaMCvf_&VD`ajY~ zsopIu%;Z00?o6r!dmw$VXoL4MErT*?{|4oN7e(~u7k|FUBcYh~6c4#e!ojz$uw`7j zhTzI!M3m3-hvahDz+infn?I;r#ADK;+v43HHoRk24<{B_f!%-YOa3ZYGTlO!hrLK1 z?#c$u7}Lm+U6ea|rec|$j|@`wMJRP#MbP?9q>uuo=oksuW!!CM zx|s-2GZgW_`V#U3^WfkWQNqP$`d5@StX0!RT|BK?J+T&Ds4+YeI{1@yF}2vsWMKcjG4~A64~oxHA29{!<37}M3B_+_q2tQT)Gn2zThO)Z4U zgthR82n=J6nZ?eX1Dsx){X3;z77h4?)B31bX*u2>Vsbw=8SA)vhlUbwff$ULH-*lV zLvZYl!jY+F=hbcS?zIxdcQeqhyqN+h2US{i0|dqQn{aP+O4x_3g#7>&7Mx!#d3&PO z;!slVA?(8C4|qWe^7@H_qCytamkT1QjezL;(VUJwG;{2Bm5{M@TO>>I?-lrJ3OH-m zQkR+?HPk%90s?bBrm@G0PR{o)+4+~}*gLGV(olq52mEMlYUn`FZy^l$NuS+$Tyns9 z0{jYBSbvX6%G~(1DCSdpQc>Rxr|YC!*NXSb7VP|%booUdb5g4URXF`pBM6*(%eDIV zO2T0ywuyhQ{)efv4yrP0w>XC`NkzJ(yFnTW0ZHkU?k?%>lJ1i3?(US91_6;0>F&Gv zzI$ixjQ``D^Pc@a`&n!K)@j*GFv67C-rK#j;zPdt&?)?!MW9?!*&%Iy9k!Wzm6}<@ z@^aP(YYJ6nlXJXU3Q^^#pViZ$aUDJRaXmeQ@G4f*RmyaTM96#^YDV%kwaOL-`G3n1 zyMy&Z0oAeM$Zi-`M6J=dT$NsiYL-!N;e2%SZTk+e(wNQ9^?VjJ0o+6LwBNS?7JBfd z3#=%F-bE`xyikxD_xjJsKeo-yBTs;(Fi6wtMNa2L>q*BYEa#z`gp^iNz=4ghxUw!< zG%Haz-S5yKoK&drn5hPflI5j)bj%c>ZxhqA(DK~cWg6rBKK7|W?9w5($glLHOI-aI zT@wU2zbXhFkyhCn=>Ki9x2yifgM+YVF~KsGHolWoqvy03#lH@9=|2AJ88llW`hZ-= z3u};|6Ew?|btLim)sz#hb2q!4Q$3x82!Y1|0qjJ1OI0w-Oj#yiV=bGFSE3QmKqarw zP~JzOeF2(dR)%UaAtvF`@VmYcbiiIJ7WTBDhMYfrPRLm1%+QskMVOA#)NjyScBVgI zFBL1EBPdqRZ#}@FyIErLI0tH8+Ux3>@gAXi`i#BdB=K6wc#59={StVWa^1FrA|u0F zEn!j^%)dV>RO!K>DT^XDi2G7*xnyO)f?NDlq{U&-kha^0BlQ)7Xi4hOg#et*E6^HG zc`wZ#vr4E;6D-cl+jt79bcu`=@BE|M1=+Ai;0@BL9}$l8EG=)W%)ZhzKqJyqH+C2E zVe-{qnbxT1C{}6BAB(LpE+i@9i(_tp6hCr~)xkACI_Q%FTmb0}d`bcw-^K#D!FRaA z0X}z0qznj9wNnyQd_9jzuV7QBJhE7H^I6mbOg-TQ+>QY<80cFDWL|$ZH_4L5C;=I+ zwpIHT4VpfKA5BX#xI&L&ka`4Pr<6A?Srww9Sa?7rvJXt^L|&_4h^urQ3q9Sudjbn< z!v@_x^bdbDqUYSL{cz2fs6D0|=m((yRd%qahuD{}!UaVHSDFu>O;%4sJ#34!m!%tg zCm?s64jR0{jg3wte)qit$`8zJ_UJC>Yl`o%#xa@%o9?kQCa$V(Kb7_qYTx({u;ks@ zuuyU|51i1E9=51XP@;-X@35PcsqZeAjqRR|KAY;#d5h`3ruo68loV3EeuF2RL@Bw| z&t}IDCyCU2@14UCcfI}$^%6&pqZruSgj9a%`u1uin!3PsZqc zA2?CK>Xc4Nyp=xx(E~gs1`;Lr68B;rW54131{`jrbGZBtFJ$Hwy?&QHJh?v( z_S}$SMcdZiSXa0b+j6mvU+_UF(raCXS%~0Z1djN{qt2n zkp!7s+ph?S?B2`nJ{Y93SYWeSHV1C?yP@Q?{8MrmHwFt^Mr`7Q)XS8nF9d8d0Q&`h z5@3cf;31z8>W#_P6V)*Z>Xr?ZTWd-dMNLo2c4&naS>FB}LDBMw_;j3;oVW<&#~9@2RX?B{w1ZYRfi(~^9>;Li4jg>x`R6VRj8 zM+Ds@$_idH6_3!C|NT5PYb>!**{^y!3OMG#LSHO|1=?hEq7b z+aOu%C(f7V&vwbR3|2v=rx7}zJRAG%wEe@{o)DGU(aH73AMLhB-!MKXP!+5k0!8b? z_OSY%Ap-ol>K)HuL#4d^ai7n8(TVG;xK2UuOE5^?*8Mm5XC_WL#s=^Xul{M{;84e~ zR6Ly=l5OednYVXv~;MdyT@^Z0cwe9Uez(wkCvMh21c09x%_i;qG)5u z6r{G7SUeWq%qmkKBhI8m7kecUkEhj|>Cj~*RhqF}68C#`QyW{jADv!;zyLVlCJLrfUyVz2o#G;`@QVK?Z2QTmg~j} zG50vX{DL|1X%p!#6PAA(hm%~RI66Zo8a0OcH@B|Q_+!}PRc>)<4%Lcb{($M*2F*91 zc6xRnRb=B}dH4SQvC}_SBZ)R5NM&_eGV8Hv-8%x5Xgr4kUz2)LHo_$R3I(uvVYoKC zU%q56-V5ICiCU5rS`gqCL&wR)B+8k7vWr3LHNmz;`r9Uw^{1(QU-T@$b5Q~v~IIr!#x9_dfI`@Tc+8FZy3IW zcGq~J+1`#E`8L}>q|a=6zr|FV6ngc1AVv71(ww<#fb78^* zUQ&d-$tnDY?wC8HxY#lW)y9SB{DZWIRR{c{hlpLepUZeB^Cxy$wia)Vn7=N3_&HQb z0*p{fOT?3~nUQ*E(fS*_#NTSv8UE8~f?U!kJxFkk(UaxgQJDAyL?>P?)OrnVBl5n- zz1lBO5VD&e_)%2ALJ%(WxG(Se^w7dWE`VO<9Jy@~R3J-1!Rq*r(YG5tW`{i8@nBwd zx(z?dTBIp#3FMGu6P7+a`+%9{rSm-7>xvfiw8C`gk^o<0(`RU1q&R$-_+1)QJteo^LS{%uW6shZBla>tN7ph(T~YJb^j;=3-VpaZ_BY9lS7r zN#pylYRg)eJhXBnSNq}_6jPt4OYw5DJ63$y+nz(h~Yh(Op zl!_XOEQ)8hbKkjaeMgK#F-&LFI~t%Fe6hl`5<&_*!Jz#rRXV8}gDq9Y?(xnU)c-i- zlo{t?BMJ%#1RdWm`;Ss&^f`ll0@(3m29p5@T2q7EGZ=)-n|x0H(L(828`p*B3Ky-- z)9%|7_SIP*5;p!c<4~w+K|qOy<){79>rd^6$p)4TBf=&%-_jNmQXG27mi7Hneu_JB zD(d^1loh1KUvRQHmA4K^JFfU5<^HtR|JJ>>4biGlMTs(jaicm7Wa)su@PK9$^f~B4js{ZJXLd@neO zRX#p_aQORV^o4EOoM}0OyYHz_rh4|!Kr}^L1IDmUG_K#*FjKkQht$SMxJ3#=s;vq0 ztsh77DW;hE^7$LkDG*tXjI8!7Qa(S0isq+!oVKc!6~r}4=7ZahJ5eM|*_`BQSZ%e^ z^n)vZR?dm*p`11tcG3eY7#;b-EZ#im7Qa94C{D8wnX$bmu7nR0_ zO}=8(;JakZJh!wUJ32#2JLFpbCI-j9dj(;R03jNf&qKihbn4okSQew*du~wqLDrUA zx65H0nSauwLhA1BrV3bCc--6~--2Xuy-3OFp9esh07S$(+u^6U=|^zNI^jQCx$ zuW<-#%})ID5NKnAZDfU6dvkJy;ci6pIC_dG+Q7@te|iVS^y3NPBt}?_bw8%UOe??X zHik^n<9)$WxV<5Het;uxzl9GcR|;X^Wn}$(nTFrZ!xVrJJ`DQH0 zyuG?JX$-$|{keCnU~-j6Dwv-huhwQ#s9LZ)*m?DWk^=3OW*i5h+yop1&Kwq;sX68i z)5W&?{;@~iu5;+mJDqaai@7)AdcTRQ?%M8`j8USjx!H)tm>I=h&w)`MRz!S7jSc#4 zJQz+IU>Xk=*WM^p{;WNx!AL}_O2b^|v#p(P zeBN>G9kRCe3&&8Qa7Gk{n5y+G6Z!(fvuv((6q<|$DF=4aAA`Ec)KwoF@$JUWHK?e2 zaRfWNBkFzbi|l#R5WI@iV6D=kRO4KhB_VzGzM_k=k5^U@f#^B zvSi92|Gk+i#B8Q8<4TpO?~bKFs?_bcOD|f<&TQ|GFck{;@Q0kp$`A)5?~x9Qi9@oqS?h?)Qkdg>JJif!4uc`pb`rArmx9IAc_ zAyjOeFirzLsv z6a4(ksS^N|Fd!Tg(3wO;0QQ}D=&K&Ujk0aOx55*auBk1v2j&a8)C!OsN!fCzngv%( znz~5dwMZmw9QdNJPyUK?T#DvjDh)f5pgcM>wg6?n>g6k<3@Zr~h5%)sLG9C;(7eM_ zF2=SNf%@w>9-S`lS3$JZOB69Z3QGO}>;R-5iI&XfX0Mjk0)Mu?wl+!;WO2A2L zeEo)ox{Y9R1)ez5=lu_P?a(FnsC({!FSQD50)Oss=K4GPVdpFnF5b^3;Y>Uev@Z+k zTygvJqc|q~&_G+q@KLvdbgg6~b*qPwD0Q>L@xxeBe}czc_=*7w?Czb+{^8tIfm&e{;KQ`T{csZO55>*9>Lu zV0^FEuDs}+KX8_%q1Ec;3Hs+#3%#T-4v*DS16;#vA7zG-;(&CQh>4k`7jDr|=z;4? zRb+%&>q>PO$yQyZSpguFf9-_Swqk;)*}@m+B~8%dRdJMY7ve;ky1KdsB#cfyYSd|z z5}{Z$1P5{9FxAT5@McD{DIn=_rpqQqwR%6^+1fM-y>D!hCd|`!Or(&~v+|3*=4ib3 z7taOWg@GV|@v!P<7@Io2zH~cJi;5lj0ani|5^m3UWivzA<#~t1pccKIHOy9nMD%m; z@xA(wx9Zkh>I|?CPUqi25LMUq?ba#oCzPj3#=a~)zAbvFR(MG?eL~rsrg}Jd`*sn^ zay|Z3@Q<{1_x!H_bJ}D?P<0b{%8{kDpx`_w1CH_jh{Jb-9*WI}i`P;aIVOf`lc5qE z;k_=i)^%7qE4Z)_I{naJa&My~*4Xx;x3!redY{75%25n~Kle-nl`yHJx>|Vj#%oAD12!KJTAhpW z+7Lj5%wnlXBYbh1!nk~RS4{X@Hu|t#``E3th8115c^3QQYje0KM4q%f8vfVfC79Az z6cE$fXQG+LkY%G4Rjy zzS9fTLNkG39s|)-QTJ*>8Y1^g=qa=BIMT27OKMZKYn*ZFs60q0i`4+dEZ+H<&nAkpBEr8M*po}IyK9$3x4?slYXN(iXJnL8J>(8J?*g!Mo}M8 z!T@1f6yAO#btCAUHKf^nWn)+5&Bl)bgx`2{T-Cw=sn0-i)^( ze_J5kKiE^%~?pd7(|y`u1D2@wt2F zw_5|qvBz4O3$tWzAa?J+i;0i1{dQN$MnJqwT{8(kK-*={- z);o(e?%nuz30uBXSFB7Ssmr7W_KIAgoCUvret=#qn#|fPtLp4MJ;n4Csus2b(5Nu* zR8g!Yjo%c=a<+1F5kTszwBHMJmO``e2$ARsepxnR{HTbCasq7dN^S_yQR1;%McKrL zY_XLI9I~GVi{K>PpMGTl>7 zB5tuaoRLFG-~YSe%A)@F)8M_l?Ezolvc(2w3d1OmC`08+npW{RCC{iAUN9LLqC`C} zravy@bK{~azl%S`r&KgUKU(jqIy{8FXx3quK+zi5KDblSTPS9Rzy^APYphN{C(blo zqM7CI_v;J$P7HN2`35Pz4n)qpxo@RaA3O!sFk+zS+X`GeU_%RNutkP@Ob$FooM3ZE zDYV2Rauo(O%I0R&li+BM$Z!S`^JfY#-37demKw5l^;vLp0J=3cEeHJ&s^@cU7$OzB zDpmUY+QEt4{%|AFmcl;La$%{a%p#p085v z@PdO|NMMj>vj^Q{HYN`eP^$t9+YVvU>NsEEJm1`_hm{tq9PkLbf8QNDfLD*H$$WpZ zvBIMRKl(4JrUC)B6O;7dAK}&}M(1uGzKTePnCLlqBB9m=?Z&N%r6gTQG!O{~q%|Mv zWd4ZbM+N&nDF#+!(INimZQZM%VE9g|U zPnjNtcdoA!X;NkorJi&y0v~+6h_LQH>d);iSZSRV3;tU)z4Q&z1Eugf75B374DqCnyqN0677x9)ts>^VQn#A)H6 zdjw00?ZSb-|74%d*hT{86_dKuJBq<7qxDZsmVx6Y6|8TpDsPqRjXEm* zz`LT(V?bFj`1)1NYt)hoywCvk6BjUErpy<_uYK(O0 zP+ce`&>BcphbX-3|I5eCm-!9?GkIMjWl#`NS1K*+`+MAK+5oFXyK<^p1dm!~7O|#5 zP!=1^z95+-rYNqVYBU5jlf?)rg4Jn9gAUEK`KSfWKMCZlo;pxeu*=*fmIZ7uq^jH{ zU=`U;!*DPg4;#?KcbUD~BQr`mVx4P({f6ktC_dpwBQfY)O~2X8Lq8pS7MAuVX`3c zSIF*27c5g=akw-kNJ1i`Hm!iNpXh0`(D?XdFi;nPay3?BA#eW|!Zzq$e+4oO$2U*+ zB;b`d33h=6&@pEkPpSve=^5AeUaJ7U4WfEv;MHSY@rRYvF@k2bshr~Tmk`ts>u*`o zxcn+YlaH-Ic@~iIrw&~j9y1}SdzWG_Ts@UN9W2-4N|GhjRA|Paij>{7{*$E`Q2&_a zdnn~!2>0&`A<@=pe0J<|&b(Kl)!M#GTeHJTyOT?ZEyt+a>JJCjg>hLCM zuuypn7HeZMKJ&GP4i-{V#az?8)*ci=EuQ)dP&D#A3f8&u{i)>OH+Ztqy z`~c?|FuBbt2lt=TYFZ!+S~4W6O;oNGw+%BmDMEO+#RXi5Oq_xiD0!Yh!;8# zPsB(VPXiw6Ogs4NQtoSPOjlL*Xx6Y*MJQo8>5@yYIKdUb%qt_cSClM|H7@ZVq6swb zKd^($yi^JR>8+AV_#aej`SC}E5MdSE;1@;r#f%A3*RK`EW$%=TD<@ks`rEFu5K!WP zCc%Nf33g)YOmCNaht(r1s#gQBR(^;xvm{9Et$yME>Y^MY-ls1Mlq}xBki&QzktzmQ zkuB>%b^dSe9nrw}D@B7R_tVyKX$?FvOM-w>XDqhIJj`S4_l*dd0=>DGk`PU@yJU91 z*ynA>4f~6b8wTG#1naLOAb#hFMoTgF3_>^)y3a%2#ws zwNG~k5~7Ru2d;UY0WH!Purz1T2bZAgQ%6LuHd!N~V4NDNmkD+B3#LL2BaJDNB>#91 zE$HDp@svN*YspsUU}Gx~d?D&j9Up7xec}nN+s6&qgp1>m$b6EFDh?rJJ9*V;@~%5A z_SU&EMS_-m{nr-5D`ZhwLhBGWLiAobig#K zlKr7gsbbzrj?&}jxC(9`%1T|~x`;Uonf^dp8OCa%&sOKoF$GsV(@)?r1ox;0+J6kg z3`f=43>AlRvBtFXTt^&(IdiWY&nzex(u`ZAIr7bE2YQcB_|XG45!W&+1tyiZVVSVS z%!F|HYTtqW?|mp0oEpR#rMO-%#xPO_9+u=ycN1bc0?Dq)1~g&E{@%f^1X?})!#{su z!TVaNkZS?wn0A54THujcin~Gckb9f%{~0v}-TeSdU+0f+edEkVtqN(h;SElt0b8;$ z9+y2TZZ|r`txaPZODFnb_qSy%o5TzeyiDQPx9XKih|nbTA(^AEtf0!1=`*=nmdb0| zRzyvT*59=F>H=?4{3))uu36h_E&siZ;WK?K`ZOXWa9*j>m(&m1`}0puSXEE|br`qi{#Wis)e{-Wr0PDRgFF22 z3~cA_)?n1Z&0YZd>3kpewAD|2y(t?`eLZkvh&7#oS9&ee&coSm#2cKWE?j=g_%Nn5T;^TOK6sX*M91bs}7A78dKAKMMj0=7W)qMgTAginVCEcQ<+yJmX@r!~jE~$l5fA6wX$Mgwq(Zth%#0s>4tOTwi zmsaOP<4y*kuR|msYprK-$K??uIw~k*J8M)>pu`VQcW!+%%c1>+Xa#crkwLQexUjc9%Mn$+=(flF&}~ z)IG`xD%KpZ;sOJ*K(8Lls=?@4>MU8;^V2=h(igH*)ot*w0aff1V`V=b^nJGJRpd(eh|J_xt=hPBcuq@mu5 zzZHvVB@2Y(HkI;oGaWKw&@`lNv(3ITV=XnV74UnhJ)cm zcx~Y)G;M+yP56i9n>gj*&;mToaU3XGv`RGs+=RY-L^@Y4JP4Vaso7HxkOvR|{ z2<>zNu429*DH7_$$_0W)G;YalVwqW3aWZ#jBV=|cYMRd#sx>vA;jNgRtv8)`#p9BA zy`W1MI7FZVA8`WxUR!tGYHA@rl8U8mt83mO?YlOYFO=h0Sbk{>db7L&Nb@~q5Y+3@P&A7c*I1jiQ-2`yi$$IF6s zEh9CkpPzgTYxi|0jdubpJyylY>Rf^~zmpT0Lf!Lu%Tbn+o-{f`p%_{*=vV#tWhr1v z)yL&VMWfxQQz%&u8^dB;U^{DFW6Od6AAT?Z1~)WawA4SsUJV)I;g4|6f;E@`SRDVa zeHQqJ)vGAE+6cesbbe`d$hhC9x@HQEp+J(8lRNo6;0UL%=)jYiBvr4C(7<0{oD`Ju zlMM&18<7JETq;7Iby^(6@g(X4+;nL+7&4^_fW-$P6W}Fp1T*I?64TiT~&>uo@swXjr z&fL<+B{Y1kXyI~BVGEoCA<2@J29Wo{xQ+lKzL#tqN{2aL#))(OKJ67Plc{+lrOLJ& z{J4qe;hBYs3l;`0c%y(rZfqNWY#TX?nsm%0z8kmZo>1&l)D=*r4-55I$pOY-5K6+} z=cRjqD|Up_r!)huOaorLzVpcO8akTDJ?g#${2^m|DJv6<8$_>Z?6+&Kv^j%eb8qA+ zOl%ugiWky9*qCzxwc{p>dXkkMA>gxnkwrwj5vC27B?rDU${hv%L2amv6!bEpAu8AW zm$O?X-e_^9oqq8i&+qkz^#`eI^s62(rl>zAgj7Tf1?%tm_^`)y<%92RelL#p4aa0z zaDHxlZ)ip~&oY5-HP%t2+I7KfbI|d6Xm6T9jYO;_iuE%ey?2G3#^4i^?_alsV%h>- z9F%=>&-;oHL}+xd*gCvL)~Av29(1k$_Q5+`u_`(3Z$dSB7*(`k=r4Bpsr-amqn*EJ~$C1TynKoN-5(n?XPeVt14I?ZuXQ|RV#{a*<)FtldMql?SN_-r{m&{Lx0dMpXBFVYr7}q6 zl_Uo(YdQvzarb)rvRBF8SQDQ@dvru{hqX95{Svd(2W; z%*m1@!X2Zyj6}e(@0jJKZHmaw|$4LG*@NASv}uEFPFd&F^9+1RzscAs=#@% zKLIbn@3pV%J-{*=K(B^&iI)Hu-;MOw!8orv_oG7cbzq-Q3T#`Xjp}QNnQ^?8A=L8I z+QFrhfd@bpAds|wqrrOQs>F`qu^j7wetX65x+XJ^=gVqFeh^}n3Su4`yVPv$kx&B1 ztQwzzPZ1RSMWdk`cyL_%r)St#?PYyUK_%P~*?|#JL%X-TXgkd%1SP69SjY zGJLC!Y?XyRB8E;jPc+DE0pM(&mFTjYe=2G*qCvd=CD5K9poec80!a74GZjJ3j1j!8 zKvHYGHZS3yt&ycwD7w@uHPvlxZv>YvBhe%tB9gG{f&2rITNz|)G@0~Ctw-FFXi-|G z8JrDUk~#MYzo{5yS*ZY{ofZyL&mt*eOg}4@7Jy6=#7BSX6Rzi?CNy3ay5D@t{P~@*?pM>SZqlgy7$H$V{G{@K2ikgqL=r$ zMs;TIEDKA!$DDZK!at|-l#KBtvrj8wz`w=f@Y}@YIxnT^ycduah5`XDO z$Ka9M))O(zuLp=J)COksGWL9a4HwQ3Ur9!=`<*7{4W8#@$nF?B(r_@NSlRK`H=#kk z!=whj zVX+02?LhuXCB8|4O*aF1U_~mOdubX?TvAgXeBVYxlimZZ6-QyQd(Q6&|DEzLbMeBE zfCLwI8@w5F6f1J{H2S$S?D3g4g@v|&6;8o$g2DIZ_2aFJ3#U)`LHGk!O{SRNWSk5m zal}66VY+u@xxAXzjUO0t^$TMuV(9{TQZ36TA>RI~_U`L-uQGeY$G2XA^#Sv5Xkx@P z)rZ{_b6DWVE~UGvJ+d^i#)NrL1Z#8p8^#tBf&>KVEAxUF#n{4^snMrQP?> zJyuF!{+5kgl9`vXS_#B%ybAt)6Ujg1(DDJ87U4dQxpxQ#_hAA*63>E& z6Y&@>d$f3C`JBb(Ktx_e$^cLKB$ghwC42g0wQhw~B}BRGO(qiAQgntUq`evLpO*^bT{U#QHy|WTsN`fXk}ITAxaGkH6>XxG6t0VS&AmL+U~CxY>mu9Omh{r zl-~1@StvWL*|#>C8heRxvo&z7&0cv9K2%c4%cQw)o-~Qa{bF|tClL8GE%`Ps;>@I>|Xu9Rv{jl%{g|`&d-Y()! zPV@~o*bUx%;6;F8R5)?NkaP|s`=L~_{$oA1dJAnJ_ci9Z_TX}_awfe}d`)y^MP5I0gdRAqctE+D zwlNRk-)h?^L|@V_TsBw)F5^xs|P5pY}n{!JJV zq12!LN-t9g+q$u%u5<@F%xWRQcWGsrAp!)J#P#CUsD{se{gh)EYbdBut>|$jMngjf ze4r*xS=kLW6#X;@CD>@D2!C)+ag0xyNs0q=;8bl7Y03R+KTv!z0`U>;4KWoQs1@tP zsiZ!`a@qYjCj_2sY_K+mo{MzymDAD~LxD&lVbuO6Ug3gy^-p$$9{}uK6yjNDH2>T; zd)?y*-u`*F+GbiLU=sE!hwCH&DvK47o{UcM4e%?gS1hpPuy~|8jhvg3QcMOyPb^e^ z39|L$!k5z}xirU9SI$F38JpOyhJvT~yoB~Mmc80kT%hhB%~NLXIjov#T`H&dO6zB< ziZ2W}bXM6ENHa3RGtveA;PPS(6F)lFk9RzLD!j68 z#idy1trC*;r-fyYC>X{X|B!<7XY=GL&M4{0v{mE3&XT;@eLB}M(j?1(yBW7E+lJ?T zU;p+DP5Epfi{uA2tTo~rBJG?P)XI6Se|$ZX)664v@(=VMUzSw?N&cvO6SZs(KO$(j z<~2?H?iU;!6xl}Ij@3wi(wD&33-Shh+FO7I1j5^3t+u!>B>Y+&7q}vtA@JZM&dADw z#@Lx~;+^FzBZ3qE9`^w%9Ua2Sk=)Jmn9fRbrrqIhDztF9R|PGhqq<*3SrGY7-B%Uo z+oMcYdd+pZ(4gzxBb>wUf?<>~X+~r?_1o0D^@-bkXZ3EeI6kS-^LF8?rikaO^(O+G z_09q-Vw^QM#)LQe(^1dke?o%r{1apnZrVVlx>l3TcN*lf#}Ys z(?-dzMj7!`)X8WF)aXgk7ng?By)MLIg}xN;bYW^kL^ghnnBSLmN`c;~T=A3N;#k^U zmH~Ln)OrgZoKJtp5Y48Zu@fBHuy{5qR}P;{Dh?v*96`RM9!lbQY=UZ8z~AVH4wmIC zrQp@ic}Gd93e5mp)JQm#o0cDNJjFo^0|vXBo8O%%)Kjtj`zw#i>A#4Ybb=}dT)8Uw zc)*C$5-}hA;Fd)u^_eU)g)JC9=PBbK9aQ6enSMlfk7`e*Fg(g>F6&yKNnKCf?j+|g zdy)_>rw!e7xxf<7Z9S3}A~{2Td8;f_6s;<#B@j7Lj>1r}RA+cAtgldlSX{5p1o~o2 z72(Lgs@C{65hbM?<3>w-h&JPBD2tup_VaqG)crnOYh2nVsR2ER982j9@_s9flo8HZam|X(qq_Sntl|q zOW_(%Y#?>ryJIzu(wvMj4vNYoTm97wRp`4LYi@C9dV1hJ+)(p_VC+K{=~gP`8ikbq zrAdHlSy^@CjTAUX{KKn1Qq` zY-w{Q3oy40e`MCScY~1u1HMsGMRfM>IXc71;_GePU9Qp6odXb}# zqI|MkjBTNNT~Y>gRnum=BDZwEEO+RhNjz-l{|wt3p=1xg3hPJvIfK&H!jT@a_;c=q z#nG^p$x+|KZ4GPuMc7QJsQqC_sX`D@>hPt<2~U=v$tSgTu5YglHQri^KvFS@kA^1S zqX~N*r;;=`AX~qL&^S!J8dSeuWFre|T8b+Mf*2skXrDB+bgz4~L!{REpLRgViCW&f zyN+6(A-?GF#Br9LhJ}fW(bnis$=R50&Jn9)o@w*<8nMJm z#;~`gQYg~KQs}VaS6Up*#hYV|1*Xjq3wH|&Ax<4%CKO20y%z!T=zKVyBGkCdkExvp z3nELUPOTqaA+CGhS5Vw{R?|l>k`x+qx9E**3U}|!d5G+dn{96OsB?V`sH;7OL!ZV=->^qB)3b~ zdfEHS?lki%HB0)<(|S?q!Hlu1jV>ek`c46O*)=n2JD}erM<^W_ZO9J&(!#Gr=a8IX zmWD36Sp!Nl=#e~dGQIQPcKeyX#u^X`-|6$I( z1Xe73gNxOEH)%k}KPUakfYa!qmgc;JoS24>ieky%q3l-ssJJ~=F}^`YC__rJWZt%1Eo%WI8>(H?t$&8DbRL?)c( ztC7DjsFV#!!Nnpp77g#l6XBCfa|&rwwCEN4qoNlZkUCo153J;aZ1}rvP!$Jj9Js^8 zLhs+-j=*qb2|ht4vjpd>F#m0JoIgUXtj)`fGdgA3pAb;m`W@$);t@Z1)sB^w{$vjt zpc=o@(ZFBFhOpqwDYM3G4*Q3iA|De$!4U_FW8~0$qL4zjU)6m1U^txfJSb~_@VIl- zg()vTev0ujHI9#zf?b45iSc{Q=&Sbb6Z={O|2vJ>7#o|qI|5E9sf8sfPas;EM)Bo_zUbvIXaD*t>z@Uk%IJl3yi7SZ^_f?<2Y_w@)^k@N(! z50YM6N{K*XlP-2hz<9j#hCE!n9y=21aUtqa5wk1V1%UA0a^=F922+*phF_XL6)%&>k>meR%`IbH$Tg3 zUNx1VQk$utiD-Kko3>p11YqhfqleJ%Eo4w2fgrNq?&O!8m8ir`&DSlp(W+&Mqa7oy zf0j1fD;rSfzV9%nkK<&@0fVFDB-C9s);}uC%oaKnnNmc=I5{e8jws0`ysvA8^gW_k zY7Ba*Z8f;?ph-3ane8i1^+)`rawHy}Jac^QFJI`phj9BI(&n{PR5n4WH99drPpg{G zagXCR$Udc+&b0akdFiF9YBSptezMkk)@Y$-{vkw*GFCWuA`zI#p<-0f{3UaLQ=LTsq-Nqfj)D6p$x^ zofTg%+BB6`Zv6UteeY7my?EHT(XGxEy0nowX}oBqM}Qf^|Is^USrtE)Xf2*el1`R{ zt66W0VIz*mBGYXB>W=@gq5*2Z%rvX*`sP?s_Z8mf6~r^TSIwd}<|yF<1i{aq z2xTHR2vq5aYqT8r$v<1LIklLMl%n?S4f}Z1Efr5PJBna=G&8rzff>tMqcw-2Eu{iuA zq_K_YFT4T$_Q+(_f@S{IEsW*0+H3H@1HY0b%(umtDu6+Q2iM@DSZ>O-1A z-t&XF6(hHuNOb33b}^imuKvH6wm>UP88nwnYI2czI2fjT^m2H{z$r9QVL$o0wixf7 z*SebjC^*%CGw%eQ``3*tOkAhi!#EhpzjZyM`8>_O9YxFwoHTv|z_ihqvTRpV+aH_* z(pGeeEo0xe>cHdV)IzkDpq>x=S;@yd<6wYJT5WETQh10}rAoh#%7>Jaj$xz$zu5Ij zFYMP_5Ga$KO@q{>)Bp7PQosq8>gIo;)j3=Yk%h13)V`F6`8r@Vh3Y4NlcA)Nt;!N7 zSHg^nfNb>DDwH9wHAlRV?4B>u*Eceoj`OhLi|O`@|GDtRIuqn!KSQs-JsDYq{aV*& z(NRlnu%hGHV74WS8V{GSt*mzE9Vua$s1`M32&GW^aG#Y8TTg-A^cZIaq36}r*>wKUKf?P z$>V>h5FgCi8tWx6+&VDLy#h#X?_$P3Ni`urR96I+{Bs%FN8B05R-s|Lz!l&D_4>Fg zNUQ0O-p!x*Z>;#QSkuSBnk)M^(854%p^J}(MuKrQBx=+iDWNufs1W8D2^$q!{NL1> zaA#+y>Ni=cZ3d?1B19`kSJdNxbTgK)4ZqRL-}jxydf`SOE(~a@I-h!f)$2LVN-IIS zZ=eP9Y8<#ZXpqgRh6PSf7P`D6sygqM?_8$Qzr%fmNF@nAUSMlc0GbxVJ2vZ74g(0T1oL@T&@4&w)6dNES&I%62=ecz3>msP$C_PfH@B~>2lywV}Y$B*}fcmh;DkDg@cP~*oyv>{zIMJ)@`qWzn-OH zlG(o&aXa04rF{GH%crY9TK9$k>x}d^D1Z%iv#lC{H&7+4aq& zq%|wnb3!V*>HR`DYQkg6?r$ipdPMW!#4v7NLIj|d(P!`;oj6qU59yPWvkr8Uc(#_r zapp=B_(Eey&=#!*aHtUb@}y3xvIZ_5|5zII&Fb9Rur5Jief>9yYq+uWY)WXqlX|o|6b(id%rYS(Ty8`lx8??>v@&BRVEmR)g}eY zo1YUvf8obgFFVQj-oAdR}Q@@U{Y=N`lp zZ9martFab*I*ohdf?+;$XaE9Y$rsg{BlkRf0s#!GL6$wwqX!p_rQmL~ zg#BXI+e+!|TJUR^L{9u<-lZ`N-=(fY5KuiJP&g3;pH6VM&dxp)2$g@A%0Kb?a)7SO zyd&&TFKvKowDVG;@>#gIUz zpd96%1xEESkO~3Og^r{uy0n&K-b}O?;7cQiJz*E#>c!5f&^=f}p8bX{+m6B+bqFnF zDdgm59>cQd#@Slq|G0kFZB5jtW5Y#!=dAI4C5-cy@>6&iVTe6&6&%XVz6%|oggR^% z=kj~EH)tM;I%A$@K9&2EfzN38{Db;O5rY3=>MVn*eB*At>28EgcS&#Q4nau?=@t-> zPU-HDl#rAXkVd*|(|@|9TUrF9&+U8Wopb!AGcwG6o_)vqt#vKW#^pGV77Y68$oErZ z12y7Kq949UW{%+xP*Fg{O&zj1JFm|>;Br@POzj+XQKP&|>2FV6GF-=O$3owS65kG~t^7~C1x z2dV_)7&}1`88|44zSGj8!$w4=!;6vWwyfp<*h)3{!GMG0RdS=A(8%F0R;2ju_^9_E zg0hX1)_?yd)Y4*88{VEoiAgU9`@DY@+L}JA({mAZ#QnT= zC7i#E#?_dgDPux(6P70sSENiGwuVgxKcuXk>1IW4fJYbvz~7L@hZ*WUTJ7- z)IIg$`N_kz*c*OJHur}8_W(Wr9BlE=##urZ?5NLuQ z{Ai)KJ-ef1Xkt`ylyXfTD8Y@TBJkfrDQQ9z=e<{4hAH8XJw4gQZxlr6JcLf#9-x=E zl)@5?2e;YZr(^HX-70AGV(i+_!mBtAxiY@RrrNk_ox;R?k#3}V)eeG0?DbWOd66li z7vaD^9^~n|O=+#7KRWG*8W}(vjBXD`EdfLhA6R}n`=VDqjJVPGl65Yxlx$&X)OQd)?2>m_z9^>c~TwF&b&Y-l`R^ zr=MTNc`F!{fp3POpy0pmLN$Ueb?W`Q4!E)Rw>rqqT3$sswr}(gj3MSXjmugdVinrx zfxlzl6AZbAKK58FzZh^97chck7+>h<=wOo6mP)VdFL*MD6Ak|TW{G``Ym1Wf%(L=L z_}g@82Y0RiYQWP&u3KfB?>XYdcdXAQFd9Di!eQ_I+O%1sLQ>a-pIw8&QT7IpuOCLtxjtZu5JxhmNm<5%=_a@}1RR6vx5u zaH?01fsHZ+VQ#lMa1Sj~lnS}SvUgV)TP&7E6GS-4CTuecZNB7}QoL1(GYttva<56jY2RQMN36kQnz=z%$EjXK~DV2s(#FHVbDs-TE%|N zml>2R#2$EMFmdQ{mRD5=8-S0a-vp{(Fm3JIk;3aU#mNuzM!CyvZIL8^JG?xw1 z1GAPDh%Y95n=Q@m%0_oGdZ4ci1OKXkvJqwG7H+mu7TsZyFrQCWl;{U~IrY2$XI6kP6iHX7b^B;0ss#Rfw zM=xbcItskL_9K827Ms2K@+x65AE7I63~ImM=pX<<1}?gs8b>YRR=%M@c;k-Wq8e!N zCushp@lS^#8gF3e zhFkl<%#1;WfU#OI96X?mIs`AMM^KqrB(rGz4Ab-8jdt%*Bl^7J9}kjkHxkAjo?oea z18J>GrH#5@8R#~z`Z;`@xgf`4Y&5aOS`k>ZUQp0_(s=V=vGZ}T@I#P>IWi@aJ}rdi zXpR3>M7$MI8!gYjw`sE}WJjaeZv6d=(LL9Hk+xnl;L(yH;!$m0u@gW?JjW{x@=ap= zvTxsLfKs24)lB`l(pgN8URkPuRYL$V!$-_bubh(v3-k^8#G(E0nP?e;gGhq_3LrpE zvrF2DSlF=$DV}9h`RlmM9%D|2N>QvyO4AH4VR*WTCt)1l zww)VCkSti5M=JdC&;7M71|d(Y<Z zo3`tJtz@^P8kspChK0c>xP?ZCUun($d)u5{V7+5wICGi&h?0S)DAr}DIcvCkL}V>I zzDB6l1-!SO&)dZ*|6CN~{JFA|EH0yds2rpC1et8PM71Xq#rd$z2%!yuVC>&?pg8Un zI3OQ|^KRDd^BMfz@Sg47rSS#UG^Fys`is!p^^ohyV|d9hs0|688SWyx?&Z1 zYYy7=Qvo@HT-zMde3|AB$W~wr!aLPNm zPWdT7(`{u{6#;S(V({BwC!^{Kme&h>FrMC(wY!H^RfA7jTKxjnE^g;k+!+JnQ z2pn#n}Aa2UW+| zZupW6lfr39WubSRZDyW;?X#Q>iz=e>9dHPyJAH+ZjJb}1&y|xoT67}_L6}DW!Ta%j zhX9Dot(hTt*6VM8Th=w=8k$M`hy?T3?#nNBpRFF_|NFF6OlsSyy#dd4reLiSz4MT=cgjf+4g6+e~dSc!H~{NDSzI-Gi7 zBGz^llN1t*?BwQu&))da_SsTE^)4?e39Hf9?W!Z@k!nn%9l;&MCG)rgM`q5l78&&+*Q~4@M4rLlNZ6r4BKvqhz8Bk-iM?9C zVU0m_W`R5L;OFK_n;cvdb`@C@%;|@Yj41u_Ho}fT0%`)_bro>fiYBVH=(%{F=atz9 zp;s5Yny8Q)SvvUs@w6js?eX*}F4ym#phcmaP#7Uo%)$n9%gt?H(#6|5dNuD`-rJTp z=YJMofWZLJSH6}jf(->at;UYELh$3$w5ZrKNpx{?O!YGhNq2qX}P z!S&4;d++UZ?tjryjnQ2Q354AWWO8mceU`y@OW?QSn_QRbY_b1eFM!`xwPu*<|>gX++G#P$v2n$9gnvZg*M^vRnDzM z6~=42PYi8Ok4RuEcEH=?>YEl&ixQkzvOD8{f$)`us&l|rk!QS~jcz&eI=i3e8ZAT7 zf}yr6|B03957(WE?uCJ61ftqHd0=n~#|%Ii>|Qj(tQOM$mMTvHs?J8MW2d?kZ@mV6 zB}Q;VN^SDuP^D;$2FbdZW)sQK2bXVk$(G6{QVNlxKs`%XS%?xr?}4bSlqi1+Bg#~@ zux{q~bl~}Ek3ZRxN9*~W0RVXChl<%`Qc_>h~cdi#!Py~#>B)hAZnZ!8fz!pC!45b%nKdFZ!IpX z)~_^;#jg9Uyi8nL_RCtMy|vP$@$tsJ(aEh_{UIQ@;J2J*x`xatNrS`2@LFkqlhKtW zG5yg?bWwtQ+L!x_o(@F?L8o-Jra0G7SK&s_)Lpwfed4qFDgyZJ-=*~P_3l>aAD_XB z{vg~!Rv}{U2_JQ06yX1dNM&Yt<=A4=4)(PV^H=zclIX;K1DrVthJ+aagd322B>2}H zg)nGr`iaTPHL9iZhaMA6bwF7e8|R z(xU}RF&X^b+6#(cW#OZfTjBHq{N*8U{vHt z_{7q5+^I^-AXXulASCh9`{dNari%$OQ`%TfA#r}bEBWt-c=s=7NawY9o3VL>mzQ0` zXa(j)g7|8ObSD5Pq>V%UZO@0C?5r+4#G|^=Ib9fc5Ynt~rqZld=?!7g1{|UwnCQwx z3|K=MxgpXt>NDN5v(LQSsl$8eeznx99RJ+KHn>CpuwOuXBkSSmJ6`^HcHfV6-i+g` zzB&`P^%E=33Z&c{S9&~A8&7{q@86w?pNnyRC*SO3YaX>0lhKth&s`8EJO2+o%_q*xcu{iNJ z>tt~UH2#0_JGfOAhAiH3hNKEexNBv@@6(Rt;V&P>OSM2~{ng+F67UPGcj*fl_^nMJ z%Jks0hbW*f*a?W3{-+h>B1IA8uG6B5D&DOF*G;NtJx&v|a7n3p!D5M{awF_&1h45U zW5GZq(a-K6?O#-YPLT2-~7ho5_HGSk?+1n+mw_e3)n9!JoT>z5~(7lBl0p~Els z7EHH<$M)#)N77$enuF_tL7fLncNFiu)=%&lhd2WyCyptz80SX;HR|1cn9-&X_9JXeU3{ zkTQoQK7hUtLq-ly7+_N6aVA2lYRhWE^9*NA(B&G1VL}Tn&|`YF5)o815jy#E_<%X z$n#4vaNlR~^twpu`!ZY7pZgC%O4i-~g(RXOJiOm@h%L+nSEjV48fA@xx9?d;5VdBR zsiv}juX}YU>MrXi#*U}D%P^U`D1HI26{b! zl=dKwK+SG%9h!~%`=`ehRYLI4^2as52vTm7{0(vK1mZI>njEx$4wn1-JxQHYc3e2C z5?Ko$bv!Rv`>}T(*7dEBB1ch~t&@kgt!W`UF@Ngc#cp*cU@&~o8t z5+MQv4;%A2C>}r4VZCw-EycsDK$g7IM7%V!;nQC9%w)$O9)YjZDijh@k#q_S2{e*^(AM&^m7)L*hBb=2|m&^uDh?w8qGI7UHSbC zxTEf&l_Eyjhx6w1^f)w1cc#%ET-MY_69{z>cxl=4M*StTQ0BLy$E ztS5YWVJCRXQg2wTfKj??P4=X^Tu9uvPH)*)#{xWYbDn+MY!^TA0Z*~uQ#9b|_B^a; z1&L=c%agM~u*3~8=USFJiiOe$9^!Z4@&qt8jkTmL-x#6x0hq zaVIJM5PUR8?ue*mC6FhGuI=$>36aKV1GDBhgsjhMsn4$NvJsU;ga%fhmgas$)n}WX zjPNI)Xufri1Iwemno`G)0sq|R3%zEpDc3DyS)hm6c+{aFk~gJh{KD7%$Q7zdJY<@k z#%)+n9$2HWwSZVHdcn_*OGfecgLO9ydtA2SxCizMG|1Wk$lf9MU=9R)G8m^KaX!(-M<+6st8YK$Yio9iTRS`{A+ugm{CgYU4W}A(rs5uD#7Rg zhW76VP$mTCiDP(~@*IeNSH0{Pp=D)?5prXDt}AGO8EyLvt`uA%W$>M+c(S&KX{ws+ zzb}!_fp>>bMcNx%IInMa&jo4VP~W>toxi)wogdEkaWkQD^1rNfM57QyHv<`)-Hi$| z-D+0QTg`>YdtRX49pk>pj09g@kaPZOB~77-oi3*F2r{UNe+b!Nnetcak6J@XX5P)U^_`fslJB=ANG@6T59wi>h`zuc*4z0w(zywuLGtT&fN$`;5f^bg z0?EO_Ld3`d;T7zc?oSHy>O}|e)p$W!i(POIO`d$s_`;pRXt60~kJ~u!xl%&SzCT|a z_Okccy3zfvU}xfXN!jHoZ$jcTMK(OqpWs7d`HneK*yYfuC67U58O&tpsFzxbA%Ot6 z+U19#Qba*+!P0-&ENc^s*{)i}Zyyl;MZm#oD_W2I2ilb3hMzKe(PJh}(6w7{L)P`Y z>SMYZ+>#Xj_%Kh}sFI+<$T2^u8KKs|!k!4v^#hMJ4P>{b-G z5kNATK0sEVQ7yUl1JdXe;`<`zNQ=UW82RW=?bJ#4cc2aF=t#LJCB>(@^>y(&2qrv3 z#t4R3Sy|~<~X5w3m)7YT?cfuqs0W)Fk+(Q_*P{Ey%NydVihi>fs{Yw@C zoJpPjm(QmDK(=n?Y)9%KrLTEdk_rCtqJRh$R8EKMs#`Jl{4#HkrHHN4?Td>#Todx; zsFju_qsRjBTp!#f!5#xO2PqgeVid4H0)D7^Y7wF#_(jN<(_^Qx##c;Y&5`FaJbCqo zE-1l2zoPn;oSd9H`uAqz&hh+s-sEe|ksr)&QI{bzs-HR2p5qanrf24Am{kgFbkIL;hqD7uxZ#}F(GF({HEmHC(7pNA7=^1H37vzc7G>zsK z90Vdo2!6?@7mBsAetw7M-@3B7cwzOom&QLHpuWsH-%LWzkP=;$LKNP09%F7K?CDl$ z-?ps4VsG~b(@;`kRNKr; zfSyET@QI`Q;(hzZB2+l_V|eOqG=qU@vohWic_Q1mXFv3r93n1g(X{t{tL4rY_-X28 zZG4#`BnMP7z10ePx*vb)yIu=$bS=d+gRWm48-Q$2>h0h&IZIb66IW_nUYpZopNDpu zHOY40wnpmVS^$v+9zflyd0j9wmlIlyuqeMMckg5=%ak$adss7+7j`wTBnZyiI@i76 z5>D0@iSz1QV|OiK#T3^mX*(Cg10AnGQwGh0Dw>y0EN69Vr_O)`siN@cm&0C3lZO@P z%CiEb{zZSId6A|Nmpx!r06O#;OHkpO{{>FR-L9<>y9;$1$taYSb>uxoQDfW3!!h!l z)35WV<~1O>!4K**JVdibRTC^-IGK~93Sz&zdD7d53%!l?!Z9HVa@ghkQQz!$*RXp5 zhsN4Z1`Ogx=Bt^DVIYsjZ#r<)E9&J-7t~M(BF=&ll{L8;4JIVA;PO=_G9rgm!7s|S zYmN*5yla1f>fu6`tre|vQV!zkB*As?#mj8)SD?*5B465%^EOFKZ_nD0> zGU`>HE56loE@U09#rD#pJ@aE!AZof8Va1hMZefK8@uqti|PyZ^c%HVXq`;FKQN{x7}c`TXFN|vH{mD z?!sHE@4M8&p@d+LvW{s1hCIhR?+0pNTO^fUFKu}~qQP`ky=$d1?lXA!dIz5~#Tr8n zwLoc!PF8(}Cu$C_TuWD{&p8&@Vr>5FxeXT}AAJ^+KXW;>XXTHN9JDLWNHXItdKQ`2 z5*Sl`sa2Fmf5^PsQ@(XWt!rBi|3(U1BV8O~)B^BZDxqx4u*==C8bhvn53`EFi}3nk zk5;*F(=`@p+U{Ndv~?=1ZbM!uTq_A{;q9hc#lO?<^@Xw-!}wSl;Hr8*Pu3c#Hzp37 z6RoU3;T##fLd&xn{(gAzboKwtmuYF-HEkKT-D3`De%q11blf>Pltysh33>=*mU5#e z15O;93+?g-RXocul!=E>jsUzvFtI^YVGA_AEByF!yYxqgKf%AnGT^N%$K`w0K^!X1 zuU`NhS7;EnE9)?(|NfR*WO-?(+oiZiKE9ULcjf#_MrojUQDOP3iF6~S89hhDz5jO> zuUT}6hfFp6O|5(f3>(U~q z&~Q*@p2(X(Y8&5`@u#dqLtJ@Vs+vFFFBLa!&0V_CnD|l-t3y<6n6Ltc zNVGva92hjKegm`STgpGN9ML_)i9^l<6;~?U@8`%aiVAxeq_wt4AU0OJg z_`Ou%nE#-c`fI0Q#lccdW4(Yw@lsDQ3E7!NK1ALkQTtb4ALj_{rH8n7QMKs;%EvX) z7-pR%qlNAd$TXf0MyX|3gIGv!2p5juFB`YY=>9HYI!KYm#QA+>8Z?T1=jY8xcIaji z`5zekoP&-eGC<~zBTkgg>lXt!rMcg|x@+4rxKDZ65hE{eTKiKjT&s|@;&?p)&+YHu z0=ydIifVnXiMJ>{U9UWZ@`50c%wyCXEg`3Xq#Af#RIRAD_-#%V5@INVWS7sWcmlI5 z^WiX+8!|ctT*}v>RkJa&TG4-YEI%8^-v>nO5kYcUqJp!8 zyzS%ssC(zP$=J_H6J-6DhPg83O<+Ma084`g=ZoyYZ*<63=xrmiC0MKTAOr5HlweSK zYEPKB0n1dG%Cg7H&8$HFx37$%={DBgQ=g+X`X`q^&)D$?l|3;t9Zfb zaedd0f+jxkZM^-zl-mXx)u5{Rt%d0~m6nG^>^R@FwciNu13&k!1b|m;p?o{5)CSRf z15abqtySruXSkvH<9vSSA6r)vTj;T6!SWU7V<++A)09urlp?8{rNkKGEr=2TlGima z1-C^wY{0w&4i}PEzc$=hHKQAaVoM>wC#^%fP0y0i1jo3!tD8DB!g-?*)o13OBgYNy zT2K=pBQV#MDi-Js)@A4sqm;GuEO>hgy2thGQX{)AWFcB;2$*wsw*upND*6wucOhSd zl`Lnm?AC`SzA7HlFKt#INbX+~gir0qi6Z8u2n3vQN&|9KJqZkgIZ{F-RT3g}Quap> zT}bNLYt5x;;?%fh(;D5^NHxp7JF`pz%k}oLRBL#MY`})=9=2??2SP&vo2u49anGid z7sl!q-%7)2u_vR<-8gBnA?n{kE?q3guM~evFH2>qTD5Skkkd8FZoYJfZ&V#4|52R@ zI>nF<;y1~1Qzvm5$N2ra!#&VS?C7H?w$Xv+ z2wzFHSawUM>LDd+k!@w~X#G&X`8`)N*k(n4-V+ z^RV+uWFp1nB9@B7@=(!RP6AA^rw?XI9}w-g)uIL$EMh11L+Ww5)#1#z6=N4N*OX+p zC)L8ig_M7W?=@3QG_VrshIU0LF5V&NAo2`*TNwWbRf43dkjzs@W3gHBq(NW$tyIz&`mj%z7~O-K)<@y$(OM@MB_?6-(Kw=r6M%P+Bw{ zmT0Fs!;+LKXh9bm(tEAf5#tfkEpMJ#l$T*f@P&~gv)Z{V)My@nY1FT>;M1F>jdg^V zSK8_%`U{vi{^2VQRVy6BQAMv$wl+5jbuOAoq}v)au#>&eA@wTjeb}JSV8`U_F$B$f z|C}7Ox%;yT*E5{5*Rf?DMn#W?PF^B+v z;R2v9fgG23{32u9E_Q+DCBZ+-yzkYb)&6B+>wypTl|VDYUzxygi8n`XAOu%deiWD| z6$HBFs`VVz_@6}^im3e|-8d@(4Y~?+NH56TkR7c@$8g1i@JVPv_#s&jx_-NhI{%3V zI`46KPNWB^xnx{9)pQ!v#(M9W7qIBOI?{*FT0Z^@@~DSvyHu(P>#SkYg91=6uPxOMfr194Q3sO?S;pySy+Ir{XJxeIAZPt9q zX~rI89zrCmxQkwnKghDMrbKvTzZDkdMI6>5fA^3>a`1zM_Pf!xp)CiA;B$haZ>EQ( zI(Zz=L(M|@R@l?Aum%NieyF+VnFF7u8U8Q7uW}fo$6T)doofajhC!pX-+yw6Uyt$@ zykz|H&kC5|lqc1=9A<@$dG{i_B*bA#wkoab1+{!K@9%smVt4$3W2Xi%sE}qFk){n3 z#1a#*)0f9go^7{`#VCl1>(hyO@lmBs-_V)!+_p_(MF?)y`N$8#jg=^<^maPzZ?)YM zsbJW*NGV!j*_NN``*)?8DiOmy)U@j1E&cDl=IBPqhI5GO<{lA}rjhoLvn$THhZI-7 z^cc4uhqLIppWM~aAPX*H+s67Hm#n+#mU*J+GN%vix#?BJxjq=T&%tlL?0F%6B=iy31*d%*Rc7Ngno= zqzN+$-2K25UCVKjYY0U(opjP5B@S_EB7yf8u1t!&EgmpRf1gzhNV^e-e4gY^Q>srj zV~E1m)JNL(s#NA&ee&;gq=-hd2hrMStFeMt@&1IbZ^s%fK3MwmjspbU{1fmz(Wt#I<>N+2`PpADp_Lyram!20d2{?;{ce(N)x z6?JQ-Ce@ux6Mt_1uROpLR|8S?3WU(4roE%;4&a_|^}Ouyk%hK}<+pf$-{&<8FLvvB zRGZ4-!A8sb92z6`6#i>46FBW#h{b}(k>Kba4KZ32ADbN6)HdYeJUZMJLy}})hu=9xMnQ-F^#WWTtf5J)jGH{nTOxdjwJ^t#4@X-%1^oYiq0hCw zAD84(A^8d3q4k)71>T=-m~C-)PwWO?KT-o*hsgf?rJTou97ZjnMM`(AOVw*^S|mRq z%CbFJlm=I6P^{ms;oCEH&i>AR+ur-wE@o-nxx&EpXLd(m-Ujw3+t3@F2o-{aIC^yg zBO{{?&>r(a7%fsxNeHBFndVJ=UVM5JkWCa#<4eI0$AKhIB)$1HpL2DAoFxyf{qgFJj>BVRcN` zI&^^76ni*dYU;4tRb;!}IG?>{QMWI`eL^pHxXbq?Gc ziP^ur-M{ql{Jo8V+d#1##c=;ir?cnZPsT|-DYU=6=b3n6J$apE8U&$05gVTmZjc>N{*(9V=|dYM#7kJ#8@Hw zJ}x^~QyG?18*Z=K1%^!Db@zpo6UKaB%Dv?HYvV@9`eFW5B^-J2$xfzMmAm~7Rj0@@ z%9S79?@$~7ppH3k3qCw-CZV^eKtEdx=93EPe;4JSJGCi~@JgQ&G7*}Ulm?21?~-6% zFh$R&1u~D;1mp+LrkWSZPcH-s=<8BU)zpb^e;!%4*lE9YM{)eaFOP31elk=L ztYTlhJziA-yt(s@2%2AB=kZx=F^BA8Uia;YQ9tK7R88l_7dg4=5^W8iVNWPiKUS*$;8WHV-U2H*u8)Cq8LWN^26#xiGu&{aeu1XuH_$Pa8W-PijEI zJh-@#m)t2{MFp?}gP%hQ3QsP#uMrLY00uK;O2H~(6>4_u12?sZKyy*Cj6fp9>ZATm z>C8CKtx8y^eMM7~CqO+VTRab-ZT~ZuIs=@pp-U`T1L1lI^{WZq69f(2B>O(y;X8%m z>^skA$lH5A2kx_+*Fnz`jqe$LjnVh7ag&y8&J}~MZX)zwFYo6DKJt-=gk0lB^i&d< zkQIUO`KtyzxaY#DrqN+Mjby(^Yn_hs%&#dZPJwBXGTTSqL4k=yee=P>Z?tf}4wFMD= z3aZSJqEen9TscwR>{v3AKo0AdGRC$w{ly~JP|J_Vv-)8&VcebfgeJb{C>_9tW0_ma zHds%jKN0%8Naz#)yl#a6Ig96iw{zE%7oVi3=03Jfda{OzONY0(PuhI&)L!YfRia1$ z%Zh#91llJY+{9rW04=lrLJr{Jk5v1Q9c^uW6$XtE2$*kbK~io=$L&d4?Yao|EnXz! zyd)(5+W}2Jh(Gq81u5V-BD;4<{c^OCDk^Z;u1@UUXiW(`$COkC4;Iqm=K%K_)2Atsc7;dqo`f>hVrY$Ki-0j0c+_G>8@J zh`jJ;@|X!?4Hu78sTaOnWHvv|Kuu0RGRV;lfH=m5NK`APlw-v^aH&rrk+T0quKul{ zj<}FbxBFV0s^nE>UQ6Y~A%+r{3MiT(0HC&CEjHuNupqb*vgLD1qg5!#jI>s<(%`7S z_aD{$Z_+0$8nJt+tv6bqOTH8KMzPvQw^d)iv3N*cR6bIJ*=W27(BmLkIQHlfJH<<& z#wFQrtV8O7~;#| z7<04#@SvfCDX&S$MQe+Kdq`NVIJbOr(>&+>^APzf@&qnr(d27aq^S6$UiW--n^e8# zcAnsi;9jRNY-y*goWiy@o9!HB5Hf*}KU3T?WvZ5Kt8zxF1UQWw1&ylTW@eKx&A#Z% z5e8;H;M|^Q=f*ilYFT;t*&+6N3fo}$QqShG&oIT5@}kr~0Ccg;_CyOyKTGV?QQ zzFUQQOq&1a+dP454wl1;zvm@2jjm>(^9(nGCmAe;Jv>q~7#nx;;*p_VyJiBJ`D>(6cpOSEF)14h zSWzse2h}~inUQ>VFNB$sc|j@H3$Q)5elbn6j2g!6-jJ4Z3JXNU!U`Ti-s$0yDU)8P->J>eG2dQHz(p{>N^{ zN}Oe}2*I?(yD7IAT?npCa8J7smG@AGe0`p1nD3=KR9x`F#9M21C~K zXID2SRH!{0MzFkIh>);&uLUgVRB6M--@i;kvev}avRwVPUH2y~x{NY&4|*b7WPLC{ z)uAIRw%E9$P^BG#z{GY!wxRh;)h$?9x^H#*7Q#U-F=)g91w!?*$^cqHP=lnH7Yh+# zis48aR5X*3#X!dr@+j2v9N80YSwYtGm_WpsLu-%@Sv*3Hr}m4^XRRqD)nyn%IbUg( z{_=kK$kZwsgP(%&kK((5+|xKa@|ur>DN#u4k#fVf{hP^0Mv7cyBY@=D)QfD_xLg`> z0Nlp7C3!|shlhRnq=6n*!ini9n**RyAvwKpJXgH`_b&MgW48wjbsZeqj)#o!vFV#}Qc>F%l9z;nBl4m#>E!M9c zGLbtDY}H&An)^4eZV&}9V2Q^^iV6%bGn*_uG56P2uMjDAo4ySwD zJf0g^kbpU5{iWUs_o8HnX5oYG(rA6R_;`Mxv&5O-%WPc#tI1bQu6GSQ(qOH_=J_G; zyv+o=nZw!(wSO)r!r%TR0o6t*@*~rA^r_EMs26CUoja@`AyJvFl{V4Q{iVio)1&^? z2Hk^v8nN)dfx|#mOIVNMt;vniI8nTYdFSR z1@7a$u>W=I+C~g_N0+a}ygMG09gmCOA#Q*HkRYUjn9iS*7WIvdQCjLP)U{rcems@S z%vFET1RT%Jxe84xWGyYGU&TLs%25n&)I4&v8vYp%(DWy0Zh!y&T_Qbqc&R>*1I)s; z9P^u*Rup;~cG%~q)x1lveH2!vIxAQPtL}>o z(dwq3ivG>PlT3Jj^sYuNLtL6?SK3mY_6*4hpGf+FCt8gp47b9K%&!e?RO|I~wfa~T zRpw+28J|l0K<;Q6R7S6gSp-ngZl2+0qSK&2OpES|tRBgDu&K7aB*pf8h(!iVs6tyw zycZ!PIT_TP>IUK3z_5^7D=A)@S&U2L$t9Y1l6HU`!?z!UbBOenU|Tgr9BUl32;YvybIf|~6>nnU%UzBZG`UHkom zP&f^$&^CQLE|M8BsU?OdY7h;jSHX)$rjo{$lNpU*t2{n4QOtKr*>v-3_Qb9MHHl`l zR)_ulC?(9MpI&0&zYnBsdHJ5Yu0nb?*l%XH0QSNEgbs8{qA)qC#)Zk zq!t4~T%RsnwuTefD`Zonu5EoB21LraKZ#;OfH$pT48oc|d>_Oy!GrDWCyq8zavNLz zN?!!OAnzE#99{h8hPp(V)eUWt1fo1WK8jE=NrsyJ zeeX1#Iq-D!KXfnZEpX8xf)w~ufcd#!!z=C@h@4SD4Iwgy1eINdMH&VI0tB_FkAzj( z&MTb<`dJHO+;e#Mr=7rN-H*jQ2l77=$AOHsxam&+$}~O8k5HhX`OVZ$X9CY6$zo-O z+=q$oo|gu~NntXFKvA-3~+EEd5$rZ04n)Fx!1Rz`n2tlCRt>>5Qczilv%fl;KLbi7nY z;DZ(uMjWMQV({16R2cBKcssF-`n=L$*!L4deQmk<&9|{;{^$JRj4p|DFU1rj&T3K4 zn#n)u;x_Q}9MqwqNO8|&Vqa53U=Sr3 zXp%@Ft)*?g77KW(k;B+?vTP^t<;U5hIyrYNt=@HIR&H0OEmZY}D47uUI>V4zA-{nD zGJ_W3KfpDTj)5ia3<}e!@9!m^P_Yt>9V5XYoV0_+I+zyL2nBqWIPiD0)8QSh?ZC7JG|*TOp{$7Ezi!zS1C6D@Vq_*U5RT7yiCoeA z5&BUWBd02UKAJb3h#kYa=?K|aa+MpVPb2PKxYsY~Qv6SeetJmjgrG(i=rX{sJ$~-3o3P z(px8Swc7EQu~JAeK5**Qy0Wrztr)&ZnM1)$19=wnLW7cd_lo2`@o`yW;@5aE;&ruc zsGAP}(X-TLloz_Kq%aT(*}hCOrBZ-$mw+qeZ5%B3Dybh-Fz84*8Ay~?Pj_w)O>}XhAYGVOOMjTaf zMIQC`{Uk6cglKExH&d@%QfWqIDizf(n$rLJ;=do`lYBV;jgMRE>gQ|$&Q9wCE>Obu zmz%OgI^f8~=-V~;mRX?5p(RI;vM!;p9bRWOes;I^L=A8-pB43nu+x6#i@Zw&v3!tK z$HSv;i>R?QaBb=XPJE!lxq;4uJ5S>d%y(&);Jg~U<_o}dx9hUtZi&V6?M2q;`+X*H z;(mlhx;i7TRc_;64@rKNf+{nKT-)AU(|_FLs(J8D?X!T*)zzD$lc=EHm-RJr&#^fFm2m(PlpWThjh4u@G`mYQXCr*dXs`-=%P!ULC zP+E)G3Z>(;syb%7S4_A?iE!3ZTnEy{xPkni(O)FLPkLJV00Yx9w$I0_)Xu4 z^9JDu`a1Typ9YGO;0-N+A5Y)M2Z@{<)f#>7G$BPd zP(Q`{)*yD=Sr;*zO}$80C>9M2rB-G*wNy4m^|w8X8=UJ@%#CMeI2GI_k_nd#Pu9iWPo=!5G!|!1Jsn`=HD9|!@Z1oh=wAy$Q z$M_q6W>xT4NCCTC=L+Z`6q4%>pz}fT+wB*y_dmL3PwbYZ6?i)v7Y|7pBt%8W?V00; z5@78|OJp;Ff9G4i>14gF=b>*S*uPwWFYPnmp>(Lth>Iftd;>gFDUW&W*AB@WEy)q* z>GsYg-ytZ3>4fskNnF2^ggu#mc?EUUJ*`XqOrk{i-rvvg;g5?GtVIH~Zk^pHLl+2yih(C`Pz8J|Je(jf5aov|=tOGA*^()d9H{>#n0#_{rh)i+?NuJ`! z;0}8ml|9d-;`T?Hmup>i)F4YE;v@KStYo1^k2lQL%QvMUf*X!C{3<*}V>oh9I$zJs ziB06<;VaaW8!ziOzX56TSFD>Dhki$%GDr6}iq3;N{Uqa!-`ann0Q}h9t!R0Ge{zs% z*ZWKzna(PBBIi%YM}{c%boA)@e?;G?f~-(uZuFsa*6gk{qUHz9dPNq=Lr-c@GB%Fu z!H)?KJ+-7{TbFfxr66gHN&V7=?|nrzfAn|lK0FGJ37)!$;v<3RD3|9Q-P4z8$kMJk z2Em_$`B}konSkqod-yOUz%!cV#jo!%j+*J=5ZG5LmN4R?(k~F7q|e;$q{7hT!@W6_ zp>uOeadZXoHC$)~@*w(WNJ+D!ryM@fuEz-62m{}8j6WpFcGowKc$BR?ED-kk_3N2) zt{T;qdSp$W4TBg!AHw?8JW_CTKUBaGgAA@;uuuO+2C+m%{&}bT^tqH2wFG4MvSrSp zVVK>DE%f+ZC;ETz>0p1MS+#>-o^J|hxlvo}={`B# z(lc5A_;~*sK(ZJRmMJeSn)J=RSUBSZOLw_m6%f3v-60LXO4sfQB_zHck;vDE4xlO@jyy+a zc1TECf-Uq3y!KhB&x8IJ+0(D z?f3iA_bTfP;3G)j-bx%a7_vkMD#N@ zczXK%X7&D>=(fj~`T|2lQoQeUoCv)g$xh=x@v+3dQhYm+RL{oX+RxdD9q-G%w9tel z!nY=p$keE>GU;zJp;GRU-oL|tw*{!0U2}V7w=ri_;=Jl!FrG&r2pKpc{iNyj@2m2V zTCoxA0f5Auy2lF2`sP()8Vg*I$ai}2dy-zF*V&KK!X+RedVfTvLYK=vKCNJ7zqipt zbc1JKCs|A+e^Zk#Fdk=)a0)T0+}(#zyqcR3$bsydQyN5tn|(ELj?-Ysj8y?S#mcGJ zSK6l8Hxt4KPra05MT55`Sf3}%{-P)}?n})-TLAr)Nyd=~uIa{@rVti5FXR*Q~NRgaAVN6Rl(-sIytm6-(%w zuj(G3#%Z;2>;?sB<)V?zC`{XbDLypJW_qf%J#_GPllWt>ft0`JPY5Hu05)69Hns?=!zevEQTqtfrNsOUh~TC;XZxWp$Vpn(w5~NKcV| zkqi(EsL!*F^DbWAcvMkeukw|U%70!w48pD^XhTt2X@B@JLJ?LwTjlEc)Yvyf&*$Zp zUw}6(cYqZO5DY8Imwc0pPVS{cFyZAQlw*$15u0NJ#DsZeW1g|Pt>Il6#c))@#b`dL zWc0>q_bRVjUwYcZSQ`I8&ws=^9T|Laq-`6icJ05wT!F>5UY}J-tKxPGGn8lc6dhu zdj+8UrnO)CNyv3Lv;fU-pb6_2$5fAAf|`{vwbCGG%&QV2xDAwSNSjAK=iAkaOzXbBt~`@_|xMQm+| zsWO)bi{Dg|c!9Rxgl0$dxe=tJQ!2W?L_5QBP~aOer~+j=S5N|`_b#)9-!awxAnjx1 z>(k9dLsx&+ZH~MyWcmstzh9aH-Qd6T_9EL*U{UMntJF0_a8MI1aDY(zr6r@qJha^6 z$;K!IjaRkVbJ)Tb8=g7~HkCs~_yG?_^(F?Q% zmr|No6==@T-Ln9qHaE(PwuCqzp2ZooyV?DEo@)m0fjcwRe%vjIjpqZ%4&rnc0Py0-{PZ+ee4aoXKJzOev z2MvA(1B4Dj12$`|%T7<~DrfhxmoltMAJeZRrNvFz?&>kkNJDY2;HW+7>x!#BElTs( z0aFg$BaC2}rM_9MHRK$xhP8HMA%rIQ+X zO&=K5ZywX~4&JorSdq;7I{E2|f0F903`2!#ml@WpND)gGCDSsinR>^ydQychYoIqSDA%-+uH z_1AB#;%>(oMdk2C(y`-8)$7Gi$kM;N&mme=`Wy{w8dW!^n&LW%RVC4@ls>5)w`pO&*6idHP6x>OWB=^xpL}5D^!Vu9}ry9qLp{ zq3}`L(ySl+Zzm3=4Xi7&v+dhqmgCVMEsHBC1l(<-yPtl-d*05|Ecc)BcN$5zrtjy2 z3nOFpZN>hcSz}KD8CbhiUY=mSxprQaHL-&6Q#s}+vAEkYxgRQWvJY%ycNY`x|r zi3E8jvn-suj8kB69MCQZSGhn-%bkd-mimqV;`b7s|M9PKW||w5V%CZcW4@vk=c+(> zKin);2h!o9D<*623&5BW&#Ar_!3+w_-;K-?S#C)HM^VQkF6@|@*X_fC;Uc&_p#$3ZwR_Mf*HcLzhy}&+nF;tsKCU{zFo)r$AN15>0%?hM;F>>QG1I6Ka0` zym<{_7Y^FfjZz+8gV7z&PK7V&=JM%Wt@OobJ6@S-75q0w+!;6!1u(>rN{s$4Z!2En zRMq3&n+0GkYkPacGf#`*Eby8i^(SWWZ3d2sR{nWu7!CY&f07wX{32LrQ>BKv;;mmr|k@tOaMp8V6y1e%!Bzb=@JLa#dXaLyjIgn5H4 zOcBvlvS=M_2IP*y+3oVR{@>y>=SVF(yG?g9|PJFyh=$Jmh zlTU&|v0ePcGnme5PyTE|^7haIO@_~$!E<2?kseY9>6OtCn&LCMfAS_zz~{VmUe4+9 zR`NF!q-y`)h2>>3Kw*@Vw>BNSqj*lEq5e#MU0Yvz1XpPPdiwY}6>kWoH(&lrtx}gn zH2m35%>1N1qKNR|Pl^RxeX)4ps@INjQ__IW_ z6ahS2!L(fgdmmf;=*!TwI_&(CPl}XQOoK{n)a=4|{tec(l%QE5BT6R3+q_c)E;_DYFB=6t_B1y$<|MmM* zMC_4+QE~k$TW;6bl-2Q5qmg#Ujbv!!20D)l&sCzv)-T~u+^y%)d zqQv%`gL~Q7j=u;EXYCnK+W&crti;R9d$QM$liQ>Re{0LIhi8_On5&ep7a~b5wL20G zmn)qA?>Kr1KbS11jWO>h6QMfjFDGT`z;LR_45 zTc`c(B}+;aoF{bBAwQmfcjCXG+UanuWHv7boJFDHk0}%|T5-VWxVQ^=XW2g_j$>sJ zSI=w1DV?)JNi{~s^X=QoS-*;vvI!v5sjuw3Df_a7s_4A@x)F&9|P9ME5$T11Vq!o_8_Gz80qeHHsj+ zNpVu{T%n(?ynGh6x$5@O*6Uw@=tynX-d2%AW5yCS^AItqJhVo_u|NplWjN|B!8qsM zON#kQshuF7u@!Wev#lAt#>dBOi2n7%@&oLajrH;S>CBaC5&T*iE%xqS60EG4H-!~w zaU($yXCt_W8A_O{?%Y6)8dyDhgQU*42gKD-*eF4jaeL1{PA6~2%`38vwvcFgc_REu zj2Bj+NA7?Tb8_*UB);AM>YrWB_42NR~rpe7K??rIpX6( zA5Z7E&sgE4qWWdib|Cc2;JH8v(of$Q*cd9(Z=K51;q50pPQ!2q1inlKj-{-?IZLC= zNPw6&B$yvJSbzcA354Yz#B%cvlze?$BW8Jnep+J(UvXAgm5N6dC>GWG7mMTg@>Rk0 z)?A9}Jcwkz6>x+9i{MpD+^Eth2^jK{;U3B|rWT9NsuPPg%zHvNg>1Zu7)#=vofZCNiLxnO*n9A<*>96n4KD5v}%uvU( zxzaFWGfnjXtB63`88}}Bwjl?Lz9P8$a26Cvg{)!q4}w&sW3LEN#pd!5JAPgC(;0C| zAbk1u)|VF@e&s5oNp86#pfaE&%6w3$>`iB3CPd*T8jrA0o;>txV z|IScK$*_8Y#VLM?TjYwK<1M#)#w^~|e2Ouv=9XIFIN18=bddzpjza1Uq7HS<$tWYI zSE$=dQ1NUVfv2D);Sy)%#Rel5>5?SESpG^Je`{C0%$#bA1O^zu`&ORY(p&0%*875UA9AqeXK(}R zc>kNV$YbdVud2uP41V+sJ@TgJ4r0*)E60`(4*7D%WKoVk)6t$WiX-$)!yIU-o=je+ zaFgY>q_PU{3yH7DQpm4Izc&Fn;emt<@!|Z$5sYop!avi4L-D2i3)Tc9G*LtAPlb9tRLC6rur`n^Mj!SqEXHLYTNihHPd-VFBel+3zG&H+Ua`|tv z`Oyc?kx(2ecBpX3Nm;jJDZ#)}8tdZj9T!sCrZsL|rWtW+hQo^sag!JykQ#|bMw3#2 zg$_pK>7NCusl>IcC*CGT{DLmky&lk>bjsE0VpscVBP=-Hgycp(@`_DZOs zqy#UfCQWl*$ElL2SwY3U`^3yjMf|#Km9ogTt{0@V)c$PrgdIo6*Va6R-+D-97%OS~ z1-N)<)hAV)*G^SW(z`WD-q6JI2bAj!eewR)L=i1uHe5PLNcP90EZR>vn=wJ2tS3H} zyH7NF^Uube@}yiOt}W*biofLTeTM+a&EM#{qR7C`NZ=GR#hN#>g06#WC05q!k6u4M z$5d!Yg|0Bnt$HdJOmh#0S^(vqI@7KRk{`@DA->-vLpSOvz+7 zZ{R6TK+vP2T61$7V5Wv6=Zc?m=foBSpZ4duH%Z%-vPZ-g0)s>4P3_2!4Y>2 z;qvSqX3Kk@EsH%2;#!D}EOzSL;bu<7EcF;|P6v4^I#~}(zL#$8{FL~r@~=O~=_9Ov zyJjofEWc$GDOOv3+BNIY&tJA<e@Yb|QMefZaHEy8DfIYr~K_-yDgLudQvgB^~8}t8f}mlyCXze|IZxCLPDy zVT(cA_;yY!FB&yGOx*mq6&->QG$_5@Io#r(bqJb^wO=J-oq;FDj6bi?xP0yAMxQ%% z82P^AtFPtH7TITIhq*||x<@C#3%Pc8oVU^WurD?3K2<;EI`8}sk}z5F_H^F*@jp;M z9fV-h$VqsgKnlkPjWMD%vd7Q?+pNC#s-W}QF>&hMI!ku*TeXDK@}OHbL8_#IwrM+7 zZf1lm1$tX0*$1rg-*tRc@jv%3)k#GsSQN6pu;ch0A2xHS@W_$)1SNmb=hiJF-TNR0 zo{C!s&B|5Z3u01>xK)M~+G2MLH!D9Td=YY>VDua z_k07%K?(o}7UFeP0vwTl!G!;lE1eBbZ?QUk_rjX*4#t2bmZr+;qQsi%)hCA z!0)x!_-_jN$~KD$_Z3ti=RNQx=6V{EpMWc?i&M1a5PyA{%qNQ(ml-MO5Z*Kjx7~P$ zOTiFLLV++95$}56I^IMjpTzop6Mn~#kj61a!5KG$8m~})kSw%hBdFPm0VBe{@p(o- zK!60PGU@#G=}SYNdHc}08ec5JI$dY<){by&o9U#4$XGtUE zha)ez(pVf}Tt~=s}|6VGjrC!YxU-$Tfx-ImU6u-i%V@&6QpKL{IEWUj0kNh^``zX2v)g&@W3{l6LZBM#9_-M2*JQOw08I%&`<5=YB zizsg==#;3^;uvt4)AZ{|=35_>ud zqc32|8-`>*7=kmYB>19=Nq@MMHzdNdq|#XP{Ld?Lbfm=n9P%hTq5Vd*>>TrvzeFy! zAR2nqfc~V}BaeDEHbou-+BeY|Bhx}^e{p3dV_GMjJdm*Td5@gB3T`PoBDKOR?j49Z zBW)Fes$yI5u1x#r_vH1sgYf^@AI-P>C%83ho7QiW<&MK~;#>>9Z%XAM(&jw_0vu(O zZ4(VDpY|j^7%QYOK#90Yo@9;ZC3EZJha|ITItH z<~Wft!U{sx?I_n^JB)F!tnM)v+1z2>quY=g`Jtx!S^S_@M&!O2CybW1>d*=beMDJ{mgAB7S56*+-c?QHd|<@zzH!V8QlGH;y+q`7M=kM}EpgS~>nH$$#7cmGdFCi$?tbG0CMyL1+pZe@$0 zAthbCln@b7H_b`b*Yg|Y35qKf4OWBw7<0UKIm*mAmRM+TweY3D)t(gjPzMd508&)#{lw| zJ=T3nNdHF|mhlD%rTG4l4$4q14F!2(!c6>)biM-=j;L7Dloq6zf3~wb*Q6dc2yV8s zoi8Z2t;_YhgqAvk=>G-Woge_DgiJcoUkI2U0TcFLL;)Ygoa4}U&zm&+z&kKsJOQCP zq-d_|0UupMl}2lip8p+U%UeAye9i8dn`lJ|>V#9^qhL%Rp`pP&?8@rHSGKmU<3M2ZUM*H4qumG4@^n-)P`Y_f%+u<(qo z6J`k!hHz^bduTtAdrGLz|Lv=`Y1>P2@uga3a8?f6tvEFTR)E3x=6ss{ZV++f?H%Q$ zhyDn}7~LP&e=ZsW7}Mi&3=cE*JALGG`s>N{5YCG~P&e2)hEc4cR zh7F<~cTiwlymE&CKf+T)Y?4vHUO7o#k4()n zA2gTs;wYw+tvzqpw3^1hTGSgbC6J71JxNS0GdTjBCk-;7mHTW}vLhdo9zZZUEotF| zRcGipc*fNFxy|_Xvx@F~x%OYu4p_*`YUJ{au{Yv~*M&Tbn}uJCeNu4#3owCf7h6>( zj}5}AtT9GjCD_jS7UTI^@noo+ih2B~?<*SK4)>r9p^-Wf@&dN9At3^PT6_We^UMlu zO;ENyOJ)h5bJ4l%P&ueJh@{Vbo-F$5`?3tp#@gbKwH1rK=H8c~U#^dGdp->pFe#ZI zBAoBu5dUOj48c{YS(&#Z5Cm#itqU*;*r2pvJjL2Zy^=oAX(Hu(L$c|q#4MvZ!x$ME zsftdUVg;OxxRJ8$C6Fnqc$Cke)`tipKI4Rbo3*E*r7gwVhy;GuLhJh=-~Wvy zf87cUfCW7!*Kn!fN;U+A$M>s6xUx1C=+REVWS zHz%VpqbT_8fb(MlS1FyTMyvRJYdDJ%t5Wu`dm=20uh>o@26^l~tvn34!zal2V7=8z z5Nq7j{-meT%YwEpB2?xe3vANKFmX(n=ZwHq9EE_%f;V0UsZ~_;Bxzf;p|y`krj%S)!e)d3J(yXPE|C9Wy-9X@ycWYGvH#dV5!-HaJhu3h? zzfjcIAL-2bb_=Z3xP;?JfdY?Ov`T$CBNm}4-% z4RCre-I&K|yrmalw+y8^^m(A6p#hoR8+&`$@d_wlGp8Z^m1|>*&s;eBJ_?WHT42^Z z*4PU*fr0>ll|hiH=}+1AUoM+x@U^;mhx}Y2N)*wdtYBjTEEWB< zMILcjs4+-pp>8S6R{B6tl0ctZ6TYax8U|kbR)67a4!;D*N3Jm-9x;%14?)|yOr1LE zXo=H@1sOjld;0eeuuc|^V**+J%=yX3&D892F7d~QMTrP@q)X4%N}TEfzE|l{{^HeW z%q8>Sah4(cn)ji09yLy;eEAiH{G3B$lw(^6(pf>`Rw#RQ!`bZwq?JVhN@@^=BG6C& z@q0dYh$(xvjzIZtz~cV3j#c+IRTqqn>P27+cL89?aU;gz#g~g?3i{7vq7*9eEs!ih z7KUyQ4SW6%qYZ=AlTo;I@%JhE$D7yw_m{vB_5#!fy#UC8OoPgQ^T3t3{e6tEJ6YtH zC`w@fwCQih)ZBM+3t!j{*nIbc#_lCRa{OH*2$Pf6y$H2OpWZUNiI~P|Kr-WaL6ArA``Qq}H;MYfB>QCW%A515Z{Jcs!*(X}pD0u~ z#u!41jd8T&EzBrOTp&94zSMu6^BAumI}fjq@=kqQ^M5<0C*EB*cF1^i9^8FEgbSU{ z-$^=XAA`(>A49ZtS#O{bPq2d}^2Ug!nZe4!^a=t=3z&p4;l)`p%SrrryF1^B)7BsxX8c2gBA20idxW!$+7%~qn`Kle#F!#~-VS7Q9eBbib4H7GRnB7c zV;#nA>Jy)c4!8Z>KSt(9wUj_)^w(X9f-4rYfH08IG=n8-Pt)Y}CDpn}_YZhp9KQiQ zNtfwSNkOy+-Z}QZ6n>;__`pJ9jHquH@eQMN?eY<+rQ#&6*{($mA%}O#qPY$8{FP| zQovsQhfAY~34x9HYsweAg-Qk)0u0yOy1=sOrz4 zZ2=EX1pAwmD;Us6;~(q1fgkyBPyZE0-C=j2@l#CBHTWlT0CeNP&Z>I5^63ft;oHcL z?Ro`wXk4F^_NIM7zvTe%jrQc=_$7B25O{Cvn9(Wq!sAEqWnk&dByC_N5 zIc2FnC3K!?L9RML*l2XgU}5pL%^v7{MSc45vb(QUs)A#sS$d_Z||EZ5W10%{~-A_x9 z2n`~v(yhME+U;KXiV2w}^_GHp@h52Esc&UO*5ylN7Lji+>;<#%lDw;C*8}G5IByg> zV)}Lq#a?g%o#u?4V85Mk_{P10%^I*o)rE zD&}z*;0knjv0JwQD*3$6Wa#W8{!&n=n6fR>Oo1SKvws(XscO`raDx`K+0!TeGdoVj zK|Mg&Un=B{zIXV4T7Y+~1JLw&Q%+5JvNi4nh?%WGeo?7E4;AcrQ;b8tz{m7`*w;s< zEkusCt1pYR-`4|SwTfZ*8O@tyR16FZfe@~cWltO_T-V2kfM;!)3?gYcs!#R5r8mLh zwq~f-=}&ZqvIn1Tx6dCoC=!n_!Eve0l5~T=De`f>cbTr!brT!DIpCPAZFs!9e?Rq% zXBa+J^fr~7kMXX1k;> zNYZE7VwgsEkj3a|X>Cst_EWz<cj%h!=hW zETZ4j{!2+m6<0BT!5DmQ$|p?`0mx&+i43O75#$!^vEnd{P~249p;|7-^?!3oZ$T=K z+B^n{kPxtr@`go%rV&5r?*{$p*_KLv>fghKt&=$LIsHB#y4xJ!gPmiqB7}^Qrd=Y# zn2ouv`}L_J7-15A5z9OSLHDykU~ytl^?5Ur;?AGt6yts7g==l%LOK37wja^4UM5`~nBPRZH}ia?Frr9E;MSdDSb*7sPp$*#Ff~ zjjlc6N~K(+C_MAGC_{TQEFB=*%Q5RiAJ-9ZbW^)B)$|L!6Kj=9njF^s=Q)LSv^EFb zy0-EcTWrL&%k>Xh|Ffa*K>XU!68@4g-6MyKMj62*N5aqIOsym4tnxh>)(CPO^|0I zmu0n`P5Ee;V(dPRk?A`(NSUJ?BTZe+H+dbyI0*$BxHRD1`;S7xJ|t5Fh^GB(>mmmWtS z>H^<8(nk~+C{|39=1D;tnkR00{P%rA(qz~`UV7`h3O)OZ3gVF7B8HQ38_d#TD{|HP zMaO*hq@o%~tVWb?ZHQB6C)+uz_aGGp#I5y{we8jzYRkXjzPcyAs`c|j9nV(U32s?a zjN7^%tX@K{+bM$qqx7A<(ow5kD~>MD^c^_v&+GC15xDuvdE)#|<3ECmiXhv#aOhqk z_lV;m!^0Pl)o|I;CtC_d0iKb!&;`g<#Qu@#(cT_$`81WxDs$r(yqSS-XYo6Bt;-xF z6Z*QXIZrY;5dF1B$4J7dcaSpLhTqrodV(hi5s`XZSraF5_wM114Q6kcgO78)fgRUc z8J>Q*(kMwNa)`O|uYi@=+TooP1fPs(Xdn=`$17-M#t#g_2RvKD;oN+Ayy~QBw`>R; zwAVu}?JX@6Yl2%x2SecaZ(N*irwy*IitPPtAYT&%BxXR7fE_h!M`Y?~8k)bSV`NCG zXA8V@KOKZ!JUpTqPKY8xd|M{ALxnm1J_;P@n~B5h@XZciyFpgihFt52^WWfiCZzlI zy-^G_dtlCAI=-&&1j^~*|JW2&N23s$?Z)4?wpb&2*Nor($XPd_X~ESjQ#0a&wGY1r zBOrnu(vJUoEd~Hl?!&E6$K4UNkdd`(w`uR8`IEGl5!^jW7s0IQ9D9B+p1+?Fh1T@m z`2yBQAH)nQh?Xp?&3gyl=cdGSs{!&ds9|cB9nm(21oBf^l?C|KuK#B3U5e?Jr_r_O zmKSw%;>u3h5lsm8E+}6>9pKdh3i>c~blY?TC7stLufTQ!1e>U7O=aWZMgpif+3uw! z%DbxB{{30&1qO=V;#4&8!R2bzB~h_M{DhDAj^mC8nwZ*XO{eNq{2Tax)xVU*vMN(d zQRAUKvDpJ_eDQ33jx8o>`Q}i2iXVP`uQHOc)WUXgSmJ)jp_p_^saJPVBn1-pvFvsQ zXY4#ti6Pea(vl#L_|s8^V9a~s^U-kA#|g#uU7j9U0yhOO509XRH8g=mNvON#(+BE{ z7^S^ACJH1aEVr|VL!q37oOILE)2HfF_rBK%XN(VIwVWFtAX5yO!12fYp_LZ!`oZ@l zQ6;uD((8E}_}9&I+6W>bTp^2PZ5k7dVQTZeRL<5{Q{kveWkrSw#D;Z!4?+9Vqy7WU z%J1l@3sR)A(9Y4NFK0AMg+8*DrWf*!AfHez`n zLdO(-r0ig@SK`JpOo0?PI;p_8e{(|Mg+6bsn=tWO1&gPIMw5O9R<8a4^d;+%<20YJ zvBUZK{q}IAwiR&DcXi$`K7KSViM>=fdUi}ejY@ta$j2GKFTOqF<3&$&XECp%<989IFGrt)+f?I{>6r?JUuUfm#e0wl)}NbV;eRpyzqBD- zD~-W*xORk|6{EmBSXlXAA2!~Mm^{Qt-ESdo{zVcscHZLw_Om`u1~$AI!id!M{UiNG zM(1BvK+@Ctm!Ls0XIKAWP}+wjjng(u=I@-`L{2dWOx!0?1-ir5_t_kc18~Nt*Ma&#eJ5njaHv;IvFXd*>8_F{XxRt z02p-=Ko0<8K;1rI2q3Od|sS?DBbId3zoK zuC5XEupl@Y3)gf zHU!zw@Ntp=D9OqZp0)FGlTfvxPtrQX64;H4&l{CGg*;zywFKYx0sJj3L_jrqwPMFLuCG`Q)zM=agm z)Rbz?Kw9MlXPB?5{F_np1F@fja_XkLvX^1D3|elkok#BlK5*XU|XKmR)5RpXiFS zPsD!(?1g7qqW4K!(Y-ziDCV?VnG0Q%I? z2CzrTRQ?92e zAj@e~CRZ;0Mxu7s(;N;{7_JkLR~ORDNlkjvV{1^U`+b;B?P<2cI~IJUtTGd{k`)JO zQJph!09Y^iI=c@laj|-=UUdhEL+@rNzU9SfE%y$NV>V+Qn*s76Q~gQ%p&?KM z0TJ8nLl2)EVMGfwvx~RA3X?DyOL5_4l@AaXb|%6}GpW^|;9S%aOZDgSI8xzb_`Zdb z3YcLxF*-1H5M+&?&of62aDXY;o&+ic#*3syMtbAR3+L_y%T$(=+e`agX>7$?&p$Dw z@1oUe-f^Ijr$U~%{D#ZqkkorMT$p6s9po=oEy~=#!Q*GE1=CnSSP&7XF%zMg+i&c* zW7U!m<*duhkEFoyX(mXcXPb|8GBb-CM-PQF-?|BekQgz$^s>rXs+`~s)u$sr?CnkP z6n)))MIh{$^Ir3IlvM@UVbD^$Yp8x8nLXyix>EB?l4nRylAOHiT~a;)kK8kM^t#1o zpj*QU8x73~>z0=JVE|@>;&IRPj?&xivM#>W6w_82@Ye2lZoOmxku0Cgw|CLjh+p6T zsakAP&COU(ZVBr)6$}PQ;lvBMKj>VTjRRO0avR{ngEOY_$;G7tzC%5nF*Gpi92xVk z{3(dG9m=27xrkqM&m(ubDVj=N6}F-{ooxv?E=g_7`?|~e-AS&#HrYTfIC}J=Ho~`f zSMAA5PC4@uP3`URdM!dywtTt|_FIbe>zM?F)5D~`XP5-WcRpb-ICsxJVkt!ZN@Xv_JI#AL4kjX4`=_2Z4FHEh_;qgk{ z5=4q48i^B0NYek!8&o{k=KV>HZ4iF(It+b#bz|dSoNmv#INJA{Q5Q3Ghz=8>;&zu` zy#drPI7}i9X@hs`c+{|tc1=B#fp#kv6%+HwRa)^W`-Z3mW(ayHIc$eReXtFDlCTh-#93AA<$WJuRt>BkAmXnCPA6ZlJK0w%KBS-}@^b87XJCplgyc?SomqO+4 z;nNQC>A)~xg}@ouab*E{p46vQ#o0S(7b{wm!ayGSZ(*TZ1zLz*kIMl1N>3aBt+B!y zeXpg$iL{W5-^auG9Y|D%;o7T-d6{86@EYiG3df+kl(&_N)!h7`v#o84%2O@zC?5v%H7h`bMJH_FP%yNiLRZneij;szBKVuogoQf;b%IPV; zLLm{Tw9fEZ0QiSeg8?(eZ1Up zH7wlc?^fa|ssRP|ZB1{+CfToY0nswA7F<(0VH;P^gEzUf~tM zr7-1?D*E%>s#s@|F}w~*J+(-nk!AkRCn!`k-HIY!!8cdG&asi&u#aMCDQ+5JSp#%@ zPLDRPMp4D`5Fqy{Swv>hDfEf6CWkrLu0H$p6z>kKbJTuXF=g!59t`V2cD0j&MvC1g(HdHC+ zOLDtR1GdaHa4Z3kOg}2b@oX?5f937>P%i&Y`J}>WyZtXy6a=|y8U2CNm3Ao)z{^lBn zHQ7n(CS^z?P8c-H`-E3%zEq1ERL$CXNe8iQQ$uX#Z-^p3!(DnAbr9ni?#e=PDd7P7dZ6hicT7#p3kYhxo3<O4-0oLh>r;d##O!>osc8nw%bObtD~{e^u#ZN9T(u$1&$UX= z1TGPIiqA9O)r>~+!;1_d97z>V!WC182DSr^uJ8V_O#$J+f`%@RucLW9q>ziz(y3So zErfQVs``O}uiIV;O8p|2%EASh0(vKvkGAY|+zJ>A#lSlgbyvb-h?2l{hu=kDd$pt-<;&Z-s%)CeIYmCFd+1RLCUO2rs7h;UOLNKM}+`7EG0~SK- zA~F>Jv77OkaDy3UNWtJ?bLpHODtR85!-A?BgQ8|W2eAWQsWN4kbF0Qhd7zIAA?-$Y zGJPK~(Dq6pf%;Ayp|#BvndVAUIJ*x-%r>JQG7#ZX5LIAre(eAc1PxhMEv7ylJ^jY% z#&;=>s|a91R-%hQFSzIt04#3-$Cl{rq_2ya9?n+t32;Rm!(eRn+**mw${w z!0(N(HDxHDw57~%g-S*@vk|v~9X1(k#5vI5^EiE82qwb=_fwg1X~b*wdQx{mKO*?i zO@}xFATm72NQ)QBt4&Cvj|e~4i!#r3`@dF!v13n5X`Der!Ge|HB(;6Pp<&ezeen>z zo=naw1-1UwBD={s2;BVC2}V z)i4W_Y!)|3!^8A z=~`)N>5?w#MvxRxK)Smm1nKT>2_+;%nx&yJY<)tJePQS02#ITQYn4jsgb&8{1Ip0bImWahzax5 ztyGpLVx0&`Pr=eZVcCw1&P44`Fu9l5Xe-0@@BM$TF!^Uw69*KY&Ez0X&UDt7u;pS> zMzu2dYle=ezC>f|h4wecF$#(I3HWZT$boSGa1c)4KXBOyY~fE~J+TY?zq}>5A+KH( zf4R+Wn9pcX3?3F`xc{obrNSwo@)me{KsazxGwabl>5uB!uyMKq2^jLqi*G6po8x7& zE7>pdrXx;#XOvVcHmcG$Y0QCn8DNbt?&jXWWWD5>crK(%WXEaSf*(AWeOoa zF|qAx6$LJ8TkGkihun=eK6vf>)B)==M*O2E`HuTfncM=V)MwBw=NqryUWRc$$tI3L zUEwfOq1~qR1yAxd%>aCcYUrOHqWui?PmRU^rgjIG*7Uk;y+-fM;rir6v=E?{atS-l z#yHe?CnicU^QAnhZ2K5~@P%I$aVXa=wh_M_M{`vV5tL|Uf*@3`MkM~wSDlZ#x0}G4 z^KX3jLsd(|oej3S=7Jl7k0((O%~vrp;5hQ^>8^nOngVV7BfQ2(-($W9ccKW2V*D;4 zRuaqb6%V^Hh9SMVb=cL6?0ATOqTE2B9!3adT(A@(TPmdg_jd#A5g`att!6e}n0$iT z4-m)14%)Ubn~*R+2FF`R;xOqK1#H_~#R;SjMIEFA=*)xf7%C8X1;!X;8$oou;f+Qj zKAylh&l|EInk-xB^ai@RD`40noA7#_QY!lr6p6vF1Hz z<`@kW^3TXDdg^iFb)uihiEgOu)0rwnhRF$vZ(;0%xPUHss%&lE%Qx-zu!dr)6*6pI z)w`j?_65~zpMArV1P@GSB`6cjGT!ezNn<~4Y`i8V3&3L;-ME#X*s%ZoOqgw7UhM^F zeB0;KCUF`OGNjHKB^=**>d3zoGFvctOG6|Z7rIg}6s1!>Z5(bqJ7rpnFYRytgIS7G zJaQcbQKSk$Z43VCChO^C6#hu4s>at|jE~+to1&^*7a-QR3ed-LxXe`n(b+=KUm`0; zwh3;(T1(yhn*5= zf9E(Z;mN~9S&+1|$PT|sy>Mk9+zUavi)&V0KXICPp9a>6WQhxx1>rG@(cJMg< z6M)VWvN=gLmgLXVpR=~0?}7SH%?cu5VHQBK z4kDe?Kv`8cv6*IDk7~QHus{h#2r^Rp>HU>oB86ANiMJGtmj2P7+S^etJcfUwF)2IV z1$9b=3lEO&yPob^WaZ57QjTyXNyELz_j|eO$ptC=Er-P9U^!*WE3WKHNHkPM25LT0 z)_pKC&}pxJ#wvl?pgcsOYpRx#56ertiiwE<_s_}B`BFJlHWgQS0@vIz6<=X^cj5Q6 z@EmVp4cmq>d$gDhn3$LV@EHdEeF6SUS)10u4R#$Mc@6%$zxpT6XU#v+4GD9Xzcj(B9xzO- zKySqDz4J^i;)En1?<&$`s=y|FA~fF3A8PpW`igE=BfbSDq$it8TD7IH0j57lVP%_0 z{y4a(s4^OnsLaevm4l~-!jv^GIur0zE!!rQ+SWs?5%7%u+O&hobBnd!GIbm+v985P z>?d)w$(suk zT-GAy36xN-M?3!3qkLaJ?fB_aUbCXAY^l~q9uZzY(qPlwF2CanGx4P#7 zh9gQVO%)d6vM-XoS_XPEw^km!s8)Vd4k`CI6kwa6SSE1ElfE3}yT4=FR$p#4ZaDKm zb(d#p?ciwp7sr_^`$ls2QFMLigb;@IzgYl`5(xnarJ+od|5cVDH}N67?H!{+xLNTe zu6s)svne+7^mwvs)mveH{?T7qcSM@8+%d2$(~)kU(3Mq>W({LRLW1|Kz1IU-z02qB zrh0(mQfdmOb*8_no=7o6Whd0u{r^azMSNGY4ITMy%GG{)S_#wq8DT8EY|DFlkDIrF zy>fD*B1RJ`Wv|@fxquG6wuPpR6pTUdkel-Qz|xp;^|+`mGbUIBi9pAjW{P&%!hbW#3QBlALXaL zN=%ZKY?Qxah+9K;;Ib5mKR5kU2p2E@9OD~^2Rk@q`$vnViz<*z3sQ7>!mgv#wkpZW&Y=kr+$9D-$hYz)1htwiZ9mv4BydZ z)@j32)^GAB&pSd=^STv>G(@o1=mL+?GvQ9a-{O!lRW;Mv3xFdiL&SQWQvXLX?j4@| zfB@QsH=HzhajR=crU}tm|GhrA@Bm}ZUs0i%R$obAS|&}|+l(qoWCA&x78@|kIzw{I zP;~NN2XX^uXa&F8pvO57t(WP;Df-Itv&508X9>X)Ax@w!xw@L8EpgrQu{}VAc-QNZ zf71+33OR1uUGNaRSm$IN=j6BG{NZnNafj&L`a6QQla;7V<^UCa6^Hl>;<4riz=^(y ztB`e`#bcWnilEke`}aL)V>kN*e|)-(Cg4A^Ftepw$tZZ~gds^7EX*DzU zE~-uZMbRa|5TbTRSB^z1*ylb+?8tWg;&W(~P0S6~D)0Dj zQwXBqC}E#v(GC~MIv%Td58|uG$a2&!r9a%5!U3W*Vi8}8Z)KoD0 z+Hfyov9_Y5wICg-5}1RLk-CtPzW}%bBd#>chz#j1-7;hKr;r9tx|zkSZLP6fj3x80jd;e8eE^6G+ixu3Jy_LbR$Wr9ja_PIe>xn zHK;BSVPbu9=xw5UW|&=>c|ZWX2eCqcLo_4f5~eSPkjp);Cgi=<~@+J3?}u zbK#CXHT_*Y##4RR$4X60-A!-!Z2e_g$~e1$kVK2*p?8Fqo4?_5NvyQ(7wq7OZZ_>5gU6M9@q2t*`7~St_x714Mv-6Rg zz_0n0+{l3Tz2fXMt!&$Mi+=el6xcLXVq7EEZ8P~9^_vuP?M7@K=XI-;2v(_tFbhk= zbL|A$J=OmEKCibm2*;tvcd*2Ec&mHcdjU37IPv{O#)yg~Tgcr788)6Gy!?f|g)m)s z0K@}-5?gvI0bPapnFrw|${L#H22uxQ9C<0@XyG*6{zZmG!xZQ=e>cf8S|<*YD3p5b zW3IPigMwJCLXE9aKA50?8;yyKP>S)=*ZghiOd!N?)S7S1UZIpw$M0vw)oB|hzSo_% z<`+lo=2=^CBo!jUP1Pgz%0aV50+^;cumNX?ji`7Mn?K4;wACtQ^LEG*FMM?T*7)8qbO{;670h9L!W?GidWa<6@1&n@5lx#o{n5`s+Z^VFP zH9!tAS9uAOGq*9h;^fbP&wE)H-qe--i;nbIUWudSi7Efrh#r*O)2sv-!_s7a*dvAq z=FR#klafsEfr#!%DoZ(wM}}4L+m9=Trt5xVqTN>rrQZFr=E4?lSKZhA!f5FN#)cS5 zbcpLfFQ}+#rt$n>oGIWn^s_R=8GR(YF*_<1w>eacBF=xn?YB+OofP{qz^8rxa$YuHx@W~;|*Wy~}CKHcbnJ6RllRQde$5$&zaE5#^u9IXl|6%h;mSSjo znr*?vPl9CI6yl_WMa*FtgqBlmB&zi20{QJ)fLO%xR<32zE+|gTeM1Dj9f+VoZSQxl zngzwe_KQhS+*Ttu0u4qTVJTc~+~c^O@PIHxsVKXHM4sUMY~z+BWX= z+ghC@$ah(BB?3}_Zym@?jy}Tu#NTY@JlxgqH)2)b)+3AaR*N8uf!+sh$<4?nM6wd}*+f9`Jzvb5(B-u+UN_nw@ENjJ}fm zvTfG5s98}sgTSQc_t!OdkD&W5xJ!&YZ;`Nk*-mB3E(|2@V{>zHw$9V!&mcSW7BIn$ zS>8EDPAa^i1$#crnmP2O1ji2Ne}#@h-CCvr=RdpEF7M=9iFq-~yuvaF`nw!ZsK_XR z|F^jy$#Ycf0Bi)>l8=$b*_UIx<`aSo5 z)Jrb_fSpTswu^ zG{=0kd35D{!tX0 zdUC(AOuN%jv&w6*a?b`eY}#_s?CXDws3zh@*~ZO&CMrT`W7ZmX3RqXzA#gCYKS)+{ z2cGbE_nuMA_vGtXb{|pKP;GK@ZP9r{cJ|*ClLuH(mmAD!{%HqxnxP=F!?%R$tXX0a z)BrXLPAnb;$B&_;khNzA?#RGr!w)#;mZpUEhuH3=X6XP&Shh2QB93+DR z&va{l3|4@qu51G0d!bj}4Z7qTiLer zoS>U~UIuaxf%>zyQR_r@LW-e~PT)BKqu!)D!fH}U|LrjA)#dX9eX z@Z;c4{6%*(#ARI<%8|%lWpF?IsUSs_`(o{)a<+C>Dj$q{Yqd(@{t*531fu(s(tP~n z@OR7wbB5+`rRjx}+0@9B)vdIK;MO#t>+YzXs115qM)*d}vy?T@bTXsCHxgmRK)@j_ z9OPX&hXsy!LyzlVyHfSXVixg;z^Z}hXSkhkr_>jsxF)tIWDz}{C zz)js9IWlVfY8$%W$uh{1##8GPg{JFks+usoxXYtN{Mjvya}7t?31!_t58>glttcoA zr|(2@nGnlr84J6YRRl|mef&1!X4y?xlu`k^kj_%UhJx!|{uB$Q_49xvHs)*YRX;cTWScOrWAozOmEg268wmQ%-FN+Fb($F)KHj1m{PF&+QrCl9*5_ zYV-K^urWuxAe0L^iJ$jSJJhYX88O@C`pUz1l_`;h}a4Jdk^|p zb#-+EnJzcf9VghM6IJD{vv!WQLbOeUrdsc`ArME}_wmWeCPG}`cd$s>yu)V6{xf!O z{6P4o$_3`V+BLhs8Q&OzUw&>08D#Es z^#$WBZxRkJ+P0dpU11Vt(jmXqa*k}&~TET6yqMMd(@ zTHTNP=b-Qu$=@s$<*sabrPS3?0;v%fW|_tN;ZufWvWd;xL{hhdmu!}=Dz!^LX)2@_ zfb@W>L$sc%{2iJD%u`{CD4#_*S67br3O;SCEFTdgwAZCmkiOmkIi&^ z%RTefC!t}V{)z?K_YOjvV+#M8z6m1*);JIlzKw?`&lL<|tm-q9#|<;&>~9`ebFlQz zcv(ebxnN&+3by+9Z%RLu&0-w`zSaEGXzQW;c>mhg9o33#t)LjQ3dVeO8K(gYb}$Y+ zl8gdUPQSdOU2gZe*WFEqIr(ukjBkF}u<|>j%g2h!?tSGH$Q2 z29zOet73e-!K)FamJkF`M&2Ji6&1zNd*+3IO>`ua0FwG?0z^3*?E@mDJiY8cNEwU9 z-Ov!ADJIri^+WmOW}E#4NT=>64Vt?~d@ku) zuGju~(wzUrAAq)7;r_tFU=64$&dm$V@ z?@SqDll(eFg(w6i8x2F3SD;X4?G|k4kpQ}1qP(3}ZuO4*U-N9$Ld^4}dk)Gq0f-Hw z$iIm;TRjuy8GoRE6I4U&7ww{(cgz36$hS>cq`PfgdDx!riz zP;c>}IGIy0_zBpMaTdV`(Wc&czU5t?;d8R&MVcb`ifCQtY0p-p|0<`9`bXl08@cXw>ge?;D(nJ1ftw|%4^wa^M#^oisd#+Hs&egGv`y-Ac> zkq;lf;GQ2W(UHbx#oJ^+C=YRf=q-VW*G(9XgZOE|`){T1;x&zduVUFy)(6ZmYo6a? zOTEHX|2`8y&s94g9gwa@pMdlNF^BiX0+CEy{Dyy3758u!STEy8(VVB=n5w^mo%^)L zhK8cJWm;^m93OUll1|4(_z3 zQ~>;s-@)J8EO&-Ije~}x%dSO#8WmVk|G_Qfz24w`@GHU*X}-4!8xkjYmSL}(%F84p zYS2gU6TU(ibyA6*8N_A16{y((5o)QlkbA4*1ZC=EWoKL?hRs{yby9&E--XVl~q! z);@R&7j>hL5~TpfR%9!v2zB_ohb`CeFug*_c)D#g;}+887&Rc5ckQvT0j-dX;ym%f zDm02@q8#MDu6473S4Gg&JXYm8ajU@1`@L&Zw0+|1)mMe<9&fFv%v|H{Oev@Y=+9FfV

>?X_yqgME3h03MOP#lR_X_1s~K5);V{_Aw`(@6u;Ne3NNbRGPlH=yv}(+1pXuY27Aqn)g-0COG^ zszENKl365kW0@YtG!5ZpRIbx|bE;-d7JwY$IW?tfd-WH%D%P?YZxp~~;^^Z?2WOXX zm~~UNn^GDgPKlAkV5&(JPdKAe>>5$zCN4(}v@Ec_2j0a9+puaW4A#b*R*&hXr03B6 zEo|`WJw6xWNb+%?FI@-6yIP?P{HAT&5>9)VV{$>bXed-opYKu0b@W^~v@(iorbch_ z6?j}9i|MXC-Cg-k@Bh7Sa`TGm6F`4Rmqzk8B6L`HF7Yqu`j%dnRd1WJXL*ZW@OvOj8a=V2ZhgZZ!K`+JDu-Z+j#wXW|G|f#0?)7Gs0sH<3>2 zyWx|1$KHU-N$Zz8awqgrlF9c@%Xrs6N@iGjwLZO8jcT$)o;|!0!k2a*-2tQ}CZwcS zhXT;a=i@y7$0(LH#-O?MY`cfOEQCY-*>Q$NlHT6q6{kbeHo=wRdlm{Na@~`p5tqiw zqmdgAb#*WiT>1EP;t4!6+yAOiAd+`;^Al5%74yEJdz{02J zYp`d)6M=Nj0Bxq-y^yJGyo4M*`Z+a05+Zk@)5?BG&b3n3w{K|JS{guYM(lGp--=@s zT@+y9r4GFA{uVpEHdkpTiIhX7^cL|h`rk`z)Lwzej&VarU3p9Q;o-MtzNqz{tswZg zhojG}@4LGl_z^SUlc47ZpUvWhJ7uAUI77ynlswM~OutvkO&q$`gv;?_s|(qiSXFBB zyX(xy8}s>`2!EtNxVOc}r9J*6_^X^D5v>J$aRhQ7u#0FG>*{%9r-`sQSeyqmtK*%{ zo!-KcCCzn#jt)+DeAjcHhDk86(83S1Jy$;$HNkd+iMkcw4LPr)XXHcT^59oKm<6+J zujGeRvLEM;diHwDN)wuV$B-OVNRvlx5t~AeQdgTk;n-?k6<5a;G)+v|&+Wf3RgRXS zd97O572w*KA8i`&+QH8k4kI`W9>JDZ2j47)F=lMn^;5LRZw}&-bNqvK3!@UcY^hBw z5&gyU=&RV{#-a@m1QqeYlKY`y6qvJU9~rE(bY0uHP2dc9jA`=097rcN zK)nx2A>ty7i8JF`h!zmCUD$JNw5-u_tM_g5svLdA>fVvV@Y8FnK(76Me)i>D6qW42 z#Y3gG^u2V3%ulb8$E-`0XdiwzfDa;+sscnHh>N0{oJr`>M zcTBfT<1F7}h56j%Xt-H+A9cwDBB&f(gRag2kNu%mNzc))4XZ-y;Hsm_UAB`S$4hm= zKoL(ky!-FAInCtd1urKi;&WmY)!xWgetNV>dN}jJ3|Q|XG&twplA*b4rOf>_EGyMyrLnE1&hAZ8{v*?w+BFvku2CfkLK z&LpFXNEF!o%}J>u7KZM@1V;Z01P&rL2`!o|DwCrzz)B!P7P6x`zz3K1oe|&5bXz#W z7_};|1FTv=Anb5Bn)RsE(N(D+UNPJ2=1k%K@YolOwP-f1iYQ+tGSJ)nhkjoZe+TM$ z1&J@=2mMaG4Dz`T$mFogSKYY|wfyAZR8SY{kr*4b|FW*-49caOP13$%(}|c)bwWA~ zwWg7~1S2+-1LT0IGFm@9?g4WUyP(doq2FSmC%z`) zcl$^}5H+@udAD>PHPD(NfjMrs>B4}KO3C=J3}&cY0ezng@%;OL4bq#!CvK0!ZM}9n z;)eCqv)y>Z^!(|m4B=Gqxw6A3SsQzxdkF^`=tX!Zdsl!$I<@y>%D%1|Z+I0O9Icw= zeA@L0ZTJ~6+_o>wDhXR{#)EoX7~&d(vacnhX+44ZQ|KmL`;Mf&$6_Gr%Js^Dkw zThyTca__aEz#?DYtL4{NqMWIxxaJcv63dB9NO*j5bZCR|X+C@`CTbL^5e@S_I3Lq3 z#EB3srE%bu(=A^Nvb~IujEv%sDA|-NnSSe6CIV2tQJhS4YulT1W|DpMgp`gpzy;5Z zoD==QOlwXAXBWGJ67`cC1@UV|rhV-{7;4W>ZUH!+FDd>qHU>Px4E;fK%qGMW~{aD7P}G62*_;=ikI1)S-`o zwn68gGw!pk4q)yBZk+{-4*b=S6TJD2!WCeb2oY!9pCh`yd_r^Z5N(7YQoFHwyS0RV zFM1vRZo2P`?BCIRk-~dftUkXIXZefvha&w2#D)lwW-Xy&Q4AAlY^SqrNY}M2I;{7ABPF07+gvITLcilF*E^ zCyGc?+zJM)c~%9rnnT^REw?+ar0kzslwrDh1fm(3Q6Hq^ZM+rN{1q_Q1Ug6hrUijl zi@RMN`3$<^$>6|P--A84DQ|-{B^@)?^nhDIgQtd+%Xqv3$c&z4oKJigIJt8 zRI6>L#1Z1!hn63uXg$s&oldK%r3?d^#$i`rC5jxnRrJXGQLZpsf&m3R{jhQ~I z)atO!JFt%J7j1Xohzrk2c5?+qdzPVJMR5Ws$bpPn_&g1un>=Ipd4>UP00!pFUB&{v z#tq_nQbOsfv=bSv*K5xAXJ5p6|5`@O1qkGu<(;KZx|H^;#u7^=eP&X~Wx|o6I#Wb{ zhHT~P>)w`PX7<1k7?`6A{t+Lbc!9_cwgsYz&GW}t_+Fxdf*nBcN`O)>S3WHk*B!^& zWtx@EbsJ(kd7wUZBE0j;7gp^jy+Jf@pzX*;KkqH#&(^CfXlUK-X z;ur!GZLQ{nMr|e+%MV~qO7JQT6z$)Et1V!S>*w_TE09$pPz2LNkJf+e`Obr#ae5%L zSzBF|Nc-NzCtN4s7e@Iy#cVCt-2ad<;smrZ&lou6%GudZZyUw--2qTRc%5oEZ#2C5$ zPQAH8;=k1{AFEDAi;+lp5o9iGA3a!n@000pW#$AsH0mhHpd2@gW}kDC;tTYazVT9k2Cx(F|e&7`KHL&*w~X|g9r3~93V$8FIxEs9x3ZI6F;}xVE@>R zeNt2Rg5%s9ot|53yrjhGW&5dA#R7f-QRK9jf$i8G^8NvOcizSrF_OgC5Vf`b2j#6E zkl4>O0Oqyhs>aU?^&Qh&+H~vnea^OaaQf{qKF{7o*|0_Oqaql^Prm|SAAF>7aSr5y%b-oW z4Aho48b++s<2*K*;^0{`oF=NPzcyL?L9_hBFLt-%T_iVG*AOuPlNw0R&~_+bL|<53 z%qg=;ru#LqcJt^?p3p8u%-C)zzHuXLu)Fvh8PQq&_A9WXrm$6i{kgBbnFD@aq#=SiHSLF)UeI-t?h2Jlg7ys&QXZ%%(52jgrvsyGO|EwU6$6 z=xrUVnu3nw!;jMjUq2j=QSj(@3a?LP)cDxLa~l!muz<}K-Zv!(s>%jDKgdKLyW_u# zveIrv^5UovzD|=|-HAIPhF+J-hWVa3EnIjh?Lx(#qht1N~Zj{!JMMmgbnOPn1PMYvV`3JW7;lD@_x2x4T#5}z6w6((-+=zpV*Ei8h zfvc%70;f^=@|zS3^fnLPQ#cZAW>olRqAUaMDmW#Mc#z#Vd5O3qyxoE?bTH~^gz+oy zBz5kUUXeVsma*2Da4Ws(ur~8C3e%CY2FIO#|46p#jB|W7}A_x&a|AI_gL4nQi z$WV}?grUvXlK2Ix^i?P3}DW(hqg4zMOJ0$OM3$y!?dHlIjv+b&z zBOO**ROI03n1jUKXqtrCP=e?FM|NT%Adhb0YmOXS3w!yKX2O%y$V1Mw69wDO9#{AE zM{GnezTj5;fp z+Py?4jNkl@CpEhq&-$|RY}3WwiLG0qXKXZ?)@yT?RBZ09fi_csWcAVI?1H zIcA3RHxC*!vn#08W@iU&hEDDG8V?*EKDRF~hZDzZ0+hWm2U`Tn1(gN8?@Bq9hr#=ujRz&D4DdO)Rd_CDr7@*&Kf4^UTI=}q*O!V%6Tkh{UwBJ6KXSP%7 z*)qhD>^qa0W-r_9>eAbvo9@!caX)Q{w+*3t@`m7h3>@i>K96ACo&TwEad*y!wmoO- znXM+wkTPyyL?-1G#v6i_rZQb++XM$eCf{Who}J zc{C2e;mxc-Pi_vY{1>Jl;1Cp)$h7v?FSme8!<8P>bXO7W6_JF*$z%0+G8t%gjgtor zxeat}pEvLt*3G{V9uY@Y=Sl44%Xl?+7*e@?m&wX+Q$7E}?o!r%4BU=u_gNt-IV{X9 zDGCDH>zHdAz@)LkG~E#=Wk=lds(pVTeq(ydfFraLn(O;G@zgUs{ETsUoAW#x@w7p3TrT?}&U?}$5@(RUGAhdZj z_W&nKnUV@`9U2Tbn;Ifr;YVH#y3daIIemw5U{B0_!w;2$hIVGL)U`G=bQ~Tg^Qd<~ ziYL(zU3+2eUKcbLx<8tcwW^H?DI0c81;^INEJ@mF1y2;uy^BR(qT5a-VEloM(~k9M z{8${Ts)s9lb|x&PnnW@WS}B;v@k9vokiS@>%p-zK4(Vj{uZt%&G>D(*+kf*YC0DeM zbl->9NRjmmdMxN-1wi_JVn^pl;fAvbTYR@@5ofG|c`}Bvd$|_E#6_kN;fgu%U;0Fo z0RKqCgJ2BFD-? zlxG%jiBvTTM=K6=r+7v@jw)9j!pcm_!Cth-84}ikT3X9d0rHjR=fqJ6D^*lfrU4?r zFjh_P7|!?)z{jx9_Mw4caH>j)Z`mr3Gloa07J-65xJ-4X!se2~K&nkW@Rz+;^5z}I z6{k0N@MntoMjW~px3NtUmLzYV3j~NGyPn=QxWGe3P2P)EZD^YkJF#=P0`K(V+usnF zU|Q_r($b!wcKL_fyP@TtsjAfJj1~T46z`Zt?Eub!Vd)8;?#0D#M|C$|Wq7M{=n>!h zrkMP3Dl-j@0mrEM-O&={%6wJ*DPHDZEsSx`vzrx zUw|d*g&Ezve=rxHP~xNTi0YR!^2TqNFdiu_fEr?q-x9ef^)^VRn|ttcIpzub+ZqQHLjInRVZNC;rkmyA?Q>zRil*d)6M~>PQFx@W zuy*o}U~Dv8yp7Ny8Q%@#WW$qs1W*&fCAN^hHt zuA2C5n_L!R6p};GpZYt!*|J8~=p(x3)zO)-4qXvOE9XVXV>vU1|75^mPHpye3`?pK zh1teL$VAXQ&eZ@ETXgUgW+9+P!c7UI<=wv^0jukQkdmTzp%{N$N&}U_BoW{d!0d_{ zAY|rUcz(I+B3r4e*Ecpw0Rn|96GUkgO|#1}sDA^sadC;DFGq<{Y7o1x1{M5?iH)0` z9U^rzmikv6!^5oOJW{Pn$ip=bCS)PM2XaOn`=c?27puUoum&zu|a z%|u=nNVEX7C2E^0-*oA=b#ZaI(~TSylTI9b%N4O8Oub)>UUGXYAEa-mafq)m%GjBW zv=FYW8qsrYnzAF=CQwG0xcNZVJqKb~isdE7vpTLDnp?UqHc=qRK1A6QhsH*vk`L`| z@cu|=Jk#8X-&}gIUrKi2w$)kikIDvIKe=b-vY_W_q2pceeEJ1uc#h06#fvz~6+E2- zJv^?HH!A&f)^O6$3gxSvE0i!DR$8k7j+h{&b$82d*6UjAHSLYZjdTWnVhr*I%q%l4n zm^N9{`^SwA`p(IW@Ts6QuZ`B3--u@r;IJfsms|3;&ZfZNl$nGeRCr91p~G!!aV1uk zRVHNec?Pl`%*UfEQisv3=^EAJA$ofOT}l+S)#dMs25tFl9gO0>qf$g++k1wiAKJbs zRZyZ2X5XEFHZ?b2)k*?JJ6KT{ zB~>|a8lO)rEY@aTC5_#OUBwXx3MytXr*3}}Lu@NF8t8Ip2x4!$ozT`X93U8bDr_T? zV)osI^1Sa6yVwTcTZW(2vl9i*@SD8FMf8VaMo9`8RzxzQKR+?EhgcmKxtAGxyjY8W`Zk4X}q=)55 zL^XS?`sF!H&6?}a^MnV?#kVMTiED?Y@Ec?=CYpKDggptKn{k`M%4}E&FrvXe^hxt>@`_`(j9+9vj6f|&|I=ka=;tiv^l${V?=5T7!QwDM*gbFzK5bLp`bkvO26q^F)gfFUl~QC$596j=c~%{ zF;+F^rntsdNKcomq0*ZTRRrtTXO@7_;z$9)+VTPuo69m5HdR>{H`JKAK zhjTeC9vvUE;yL^2mjhXoFUL^qfy&gnt^&Y<7zIQy^9mOFS=Y_aL0-i6qN7(?b!g#{ z1$2K+6u3V;WZnDKb8{mAde%L3Q_gB3!b987PAH^{NXquLOR5e;uY|F#u&~m(@x&-w zXfJ&I-Zln)FX5;WofhLQI5|b5efWFb9?FS)ywuX(dOw)Ovoft73@bX}$atCYgV9N? z;giaabL!Fi?6P>%U4I~b2jAFle-!_*FOZMautW;CxM5r(lGBu&1(1L?ARcZw>d~w|3L)Xa67b-?kP%Q8}#4jisvVB)y zd%!qgj#kepfI~Uic7<>#>|OygVxG6^<_rmh^HN^&ZJd;x=1K=Yr&Z5k{LilAnyG5) z!G}Jf`mLcPQ#PR~NRFg|`mu+ShmVBP{$us=FY7ZYOzVE~#lrVh>MIO10#byF2zFtP zBUj^65=y)aQ7`Aw(Gky$iE*3hH$66xeA6md4fHWxiv>t!HCNlHP<{eKPm9JVle-3w zW^&N?nq%b9GBY&I#-8)B#|sRR8`zIGi{6GJL^9Vr5s@Y#ZLdq+aO!M_w)FOza9o&V zv$Xm;IYs2=hAYiLFFlRI!D!jqXaph?G60rO+NHdgcU|zKun*4ra9+N?Km2w9#jD^U z9#)?v>`vXLkx8S(dd*Fa;5X3RFYA!Dn$(^kLJNhJ5{#1lm1%Pj&0;?H9~a|-CDOJ( zJT$Xvm<1SPzqYIs>VqwCy`TnW*1;`2b4q{h_&~Ne+6FTN*;W2;{LQEisor0&qAe=2Tn-1ey*hTvU!wGcYYE~W;=6@Y;(2MDJ5WPtgUJy zM(us2;4T8E>AJkHO`8tHx9vW4Z}cXKpdrBPkUItpettO3J`~^VQN95(ga+x0L0cR# z6$*DP#?doA-*Y}OIeTBnQ_QEc)+Yme>6Zj_;Iqc$_;ljOGKd}I53TOw`gWZnSt3BZ6ff8r*B6vcERug7LGD@$zOG20;BoTo`K`uV;rx}U7BN#LX{VGeI z72g6Z&V2X}_S|TGTXdP*gQ5cpa12Ru*AG+*N3+M7cgq%Dy!v`fcC;DVnY7)f?LLT5 zVKd3SD=NRD?HhDkiWd|{JmgdrH*fw?RX`ZGN3&F84!>X+fPjJ0bV@i9uXnakuT%qM z{;E}#e!g_>1`7^A&>MZjCHJ~U>Inwk0o`#MOwaw$iznY5UzyX8&+OMgfA4+DThU`7 zC@hlH@&N_50-u;vPBk5X zjo2!OQ&zb!(V?DR1qZ%&0fWi6zzq6Tj+=! z{4?}Q?+-48L`YHN00mQz0$e-5mI8vfv*rC`GKQ1fDPw(0tH4hO8<8;*UR~W1(|`a; z@G|rE@*&8mu=0~=#w?r?IhW@m?KFUeNhYa>o3?@|7SGYF@IkeZW!>CKG(#;?%BOfj zq>y!-qH#>58p_Re&yIbWG_eOMVjD10BRgO)&dDD5_z6}>Gp93eod1G(aQSd_Cu%>MHqtaSfQMOYW}?Fg_|LOD>7M!?q|^)sW_eo3 zSZ!{?8rZ@S)KFWzxUA@U_>2iKdieg@=safm;ixWa<1&l<$pysCQi=sM2D|-BY8LHH ztea`IOc8yuLxb>-5@v4w%NNCVFOz1D@$yr+Z%%~KtXPwqyGHmK&_~f=t%DH z1QjmwYsD?M>-tP?puTZr)@UHdlY_5hshvs7_UA}bI7on0lsEQ1bRyKw55pmZEmD&+ zf~*Co*ItUBAKV>fFUC~ref;#^*~F6om9_LEP9zq62@4O=$_H?H67F^5`X8FkGOEh% z>-y(V(%sS=5D+OT=`LwRLb{}+yCkH$OFE=ey1Q<=LApUoKpNid^N#;V8OT7-b?v>@ zTyxEzsA-olho*Z~!QYF(92i4U4(>!r#pPpsj(8Ax%iNpc@7}2l zN>?;TdKOM@qIUt&B}^*nbrl4zg8@gLveCFg!~zoaRMYHQ*r+{Dp}$ru!E78+4$zT+ zxfWcrSH7HpFLSrVks31e_r@DJ}<%YRb?*}Ge(-oLMPtG3S9 z)~|1QC<5O7ACgT+P&Pcb*Q~bBthQbOLdlWX^x3Zo&LV9wcU4U}V#piBuYzjl?h*P& zpjI|5c*gyzvd7-c*&T=<7Bsh3#5j85c@&^3zT7`t*aehD_2#1 zh8k?fnWl2|v9Pj2AxfDtadq0|Wmtx$!R12|79QG31zvh<*Z^tFFZL(59Sjh*ib-T%z`HN zA{JcdNe++gs(}gJ637&IfeS7niF&s6)Xwgv<)h7~6R11OswfCi0w`|~zXJUBUFkfw z_Rh|c%juuI?hgr8+uAxyHP$v)TF_cMZhS#>$)$(j!JKW$;6ecHWlhqO_9clTcL1P zFMfzGBOhmc>P?;wwx#p7ZnP^3Vn<3pCiJ7+ClRNjMTe89kKyCvb68-SLT(04yG4V> z;N$e48?Rzw7QZiZttjGMnib<^d?~l0+gk2PsQAExX5K+R};a~{3 z#ID^U9~fIQZt(B@+j;}>zEjuGiBq0Fo&Hx_R9RTG5I4s_N!4+&){w@k-6(t_P24JC8)c}C)RHdLkn^XrocjF~9Xu#t>Gv}PrOe|ys!N6R} zCYbfw0b+V(QzjKQ?O{p)y+2Z zD`ZbHbB_^LUD@d6-?XVIP`o`ZAObw0so0ArhAK%=2b;YIk^%~W7t-TLCm>VtgmFFM` z6a?mFuTid3K5d+)Up>%n4qLt(aA2R`q>Ral1pgZ;ZOdR-=gWZK_837`+1K&-7s!> z7G%b1%+mN#P$F!ni_yc39&1)?5`7J<6+0ahD&NaCLt~a6U42}lwhlf#6B^gLA)Q>E zR=00>t~dV!DKYGY)%f}aMn?p-?namK6o$vcj(D1@`$ zphJoC1y#$1z4f~Yc5YSk@4P=R_z+~VhDb8!88pB79kwf)hQ8{$HcAB%p0|JK!08$T z^UMg|z*Sy4j-sm(X}d&J3c(q$UZ2^&_T&}*YV?L~AtI?!^a?_NnKy~8G830JiK`D{ zi|ONs{Df=J?d1{=hH`R%Dw1Zbr>A$=G}0V(?O*u`9}%30D)U^K0yw7FFWMYd*!2xF zR<}8!+Hasdm6esVaFOFXX|BQQLIVFm25((}7h(Z{st(l==Alr#G2+)=mVuJ+r=4B# zEo-_w{b9y%TXzZv8RqOo%8>&v*}oaMrD@&ral)vlm(w>Y^nYFosxMke48yp(XkzhR zbvos2>ErgEp5a)@9FX lF)8H@+Hc-of*>Yn%Tbw3C&24$w%=rmY~?Um-)iu>vUZ2A)- z_)`j;nW6@dXEn^z`RU|6$2MP;za37H(3V9GL-RHFRptI$A4EXlN|+nBd4WepAHm#x zu(Iv(C^OLJDx&h4Ct4RwvhsXL+E4SC0KoS>1kQj|=FfWwqb#mzA?F{}SeoiVTDxsR zx}#A-Noo`)^LUGch5X!G9AkXU5t=#fuV}xVhxy0$*CTdWM?TN&zK1@i z#`g(`HGA$io8hc>E-p4}mFNWfPD@LoNtk-R2bahJT@#8QI0>DUI77l-6;*`?zGIR# zES;6oRa^Qc|J~`;{Dq)O2`D#b64HI?0+?Ek$-*uHG_v@6KvuMa`05eJzqk)VdF3Zf zIJ(*KI-bH}a~!7btCcXXpe8s~ zS7m?8jEv4@;4I#_osoHpPM8$?s6-q@e0h(&MeI595z=eYUK3HD%V6i|8J^30{`Bbi z->xHAz5RC%Cc-u!J^!gNfOXry?0RZve-5o|_Y4GgCpe|nK@NoL^>t%gOAqjrd$jd= z)QYCXG*PQHMVi9?*#Vz#u)ap4@}6-$M79{ebzk`ABx-V^}id1X63q_1)C>qK&Wb(40QSrdwFDVg_??eh~$NnYoIwbMDQ7#KAyZoag##Y0i6bz2XAPA zpU0{2VM#KG&=2|i{>ukS1j#?l)7}JtxyWNd#qaX;vzVaYKv29^$^;*G>D z*fh+k_G(zXg#IWgIXhWt381GACr{R5779?cR?X>zyE66+iXLF{A7B?Xj=gXB{0RG`D;ZxI}{2DuQ@Jq3a%~_`b#E>#R*?R z$oa%y(?HUW?0B&q<3LGcJ>HMi#y1$h|5`eA4KUfbPT2M=tY3W z!Fynf9UR=ctbrAkjk7hx{%3VZsL1}r;eEJY@1{Ez9+b8#>eS2ajw1)~z;2v(V0`>^ z01`Hok}&_WPmN9PqOKAO(s_WUFWj{I<|Ww#a}_c^q6nKg8|G>BVX z2UUNrK7GNK8ND|y+yhXn&o_FCSK^?NU;#Q@AAhmBm#C#OA>!Q%g|>afqYc`Ohzd7+ zEMEp@vmg}eCO8cv_=H-@wt2?GG5^x`lYZNc4BNU8Rh7DUO0KDjLB}%6R%r#k6ZqY? z=%KRx@ioj`LdsCpj|%cz?lp_nP6~g#K`lvLWD+Q+rxky0Tit%J=-IJiQ>|r--N)|b z>D@~s`@7?Y??YKklk`L{aR3!Mw)R~5o;$-ITp$Az4D37eiRcI)%I<8DSJ2UwK!2|Br*4`I?S*Ck4)xrzd0;^&`PFUOblC}6&bG8=TSQ`%)#cv zQdw~cTt7lcuJREbL}uD-J(<%8^VPB=IX2Z!OmB2w=C1xOexziGH~mckd&1v~cU~$= zC)x1rckR*RLY^QVq}m7}?o$u0B}`F)9`EvgGy?uyW%U!~c2eDic20>U|FrlAr}B?4 zE-wiZzi-=uA@<|bdUm_9aaxajQ)c6wEJbd?xMf}UzvnKPibaIGec5FFZefY!wN8ub za=mEfAD<3e!34oCLS^%x%JW8QJ~-nHVZyXPgD;;*6>2UZ4ZgD~{_iI+E%U&v`ACh~ zQyYCBmLjdL4oGxMBA`^&F16c#J?>vplEB>U7=VxndWdyH?w+erjHid=hQ_LMz{(Ue z8g6lQd)|O=_k1Kx*3h^)dlCeR_V$jh;V+KTN2zU08Q)IL9t8Rfu!u54syv<5z5gfl8*Z4-)k)o5Yen zGbI|;@RLUV3-2P=X+Lq}?R69A@97DkpH66NA!o-FSh8s#gv8a*R{O;TCpj&X3Uff@ zqOakfI~y~)c*1BDFc(E#QpJDw4ts9SNS?!tl07&{i#dO?I|B^kD9Q=^Jq zo&8%fvg7^0Dk_%)w$bI18Lf=|sLqR31KVoK=$@Oay&v#u9-lR6PrZ5DpFMqK`RD5F z%y-5m4~42`>m3=U`le{M0e6;o3gM<>FH0SWjRA99&C*$L*w10|Lid_&3el(65`u+B z^R=khJBeu}r+qr+4Y3_M1S1C2t~eRP;N0ItY=cvD$SDkHVIZ)XoC!>f5;EfU7DfFS z^?76w<}v-==~23Sb;vyWa7?;QHO)Nja#1LSTepv6mfj2fGV-e&5j#5{N5(|?G;B~S z8?(n1)KksDzjVwE>c?KqRZKc<77e~48T1jf*LW7C*LYoWgcjfBSvxHv)6+k_Ua>8X z@bAo$i(qDuT%+ee-p`Z#NZ)4C^zr8Qj}ARMhdZ#J|2tUXOe%4)2nE34_1@bbqz>aQ zoNE$GTcmA1-lMg8-Kw@E!O0I#5YwAl_kYjG$N^+&$5b7)Oj)EJn+Blm2Hu!euxAYO zy$Oc{MS7Z-t}YLiAT;$~e$L9u2IzMMU$-?iHg*E~iDcCD5p~U8j*Qf6Q_^D>{si^F z5`oKEr}+^4PWh1XD`~Qx360?p^cHR|xpcS5yqc2N+ZMU^aQz0K$D>Y7=f7^K?7oXL zv2D4h;9h>Cx>puX6UykfM>|q*@9pVX>Hw=T9h%!oL+~9k@h>ech3_}i!zadk0kn-_ zffE;gu+=e9QR8>B9|&D459-^x7XpDfaRo)KavjnW;n`NY^M{Mu_Y`sR4=esuBEM{? z>p!oWwSfl|ev@}9Wne+vH{~~8COLwX85WkqT*D{i$!=gOd|}19F?{HrHMGgr52+LV z!jwAv1`UD~$-4D|Ceg2O)u-e zl}9UIIDni-{QMaGwfA`C4F!c6@OY>%vZ-B`U1HR&Zmz*XTZwoohV!XR=#=O77P>|qL!xT~22}s**gOLNN|I~=2nSMN> z1?!NVNa2T_ONDGkkvX_sULXZbL$uI#&k+O!FuCjz}jah{dap{;?g*cCyqe)Ob5+G`} zPM)CsH)jz)Fo=>PZ+T2*>fFhcpb0fiM{Nn8LK+QxejC0gUhGq*+ zboKt;^YIBhz}DP7qoa`?531TtAhnd)AY!t6I`OpSC=F524=$x&pTM`~A%eZgQpDpw z1-W5 z+j})ySM!HqLr6%de{vEBXj|1FveH;b2rMiz<9r)++Jng|=LGHX^tcX}_*d_Vs&nkU<#c2Ikt_qUc}=J5J|gejNRqsPmf*zjpUxR(Q|+8 zp}-rV;ETD1jTL3@;!-HD++XJMOKQzy{=K8O!Ms}3@CC42fBX2lA4q?C9X^q@(`u#k z!`K6=j<@~N3rEyd7=!;dQ&Q1;e$n3t+>g+skrY^GLngEXlN2)dK&)HwvmL(VKhq8O zX@Osx6fsf}lLaOl3!YAaR|@;LI$EuDi!@8?7y-4EuK1x#k-8Yu;`ZnRCx37ffJFyu z4J)v(s$y))*xW_|1meJdq@?*@dCcMPb2NT3JlvdXpEEY$aw%!QaOykie=RGt$QWK9|>Sj^d6_6m=|ib0odQ%+BIRI>`BJuYpcb3_1%kn+_R)>;zdEPVEv-2 zkw!G}mmz9dyC*XvV@QOhWevH$iAfeNi;Pby9FhB3N8fP{E3SoPfDm!`LtAU>hux~y zcFq*{{@Qn@5!Ly4lTkAj6u#@ zdAFM<7_op-G7_PL5cIvy<7e_&^7NoQuC3Nj3taQQCKvL$$<{k>r)w=1`;Wt#aYF;w zzd|rziHym(QE1&Ad25hc-m(+7z<~60wHf%ccGbS1uohtqm-KqHY=k{mQzLf1in*NL z5_Tu%*D=PH9^^1YYX=1)RuPzenly-a%)9QNe@Ude41z}_VxlymwSDWLuMrh+YNM05a?twoht=8sO$#83V& ziEUG?u|i}CY%y=-ViKm`_7RyBK7{~4Qu?S=!Q^ zOHdW{8Rg8UPdhC75iA-DfOgpnBk{$2xrcvl`**B2TM_g&&l zAWwdQDuGKj`&+vULY^jiqiSD|#P_(kXlE6Yn~qcXo9cN>AI!!8u3x>I29>F&Upp%7 z&z2rMqtVQ-g?appUU=1N<*iW`l~n+v&jNBM{Wd|bu#AA<^08*T$@m4=4H(WNrY|3J z1BJvM6e`SUghM)>2#hJps?9z?Y{*7}Z$=jksnTR-BaL*D%Vn#-Lv@M4aRT3Jo&6|O zZAC4nMY!*BZ(g_kHm+C!yM6iCfRl86ceh`*9uXPYA6u(lBM9jwgjKIq*#%!=3@SU9 z8UjDzXv9VgEaICdPZY&h?~kuN%D$<4#KMiS#C=$^=>7OxwkP# z<3a-vWVp3EKXUqR9qBj`5#O#>5tMW1-R9U1wOpq;@_6p`2}PRP$lR5xB*ZUxa zTb*?18;4q9-?x9sB5z);Z6?l-y#ZvEe+wnrmgnyaUR-^kPk7o)? zTl*a`FB1>59Ja;?7oe}bw5vN@q2AkFpZvj0`ru&2(r3SfoblA(#DYF`F#x%ckA z8b2G@t9gl~V;0pS+~l&-zqHk#es5>&`&rOT;Y&FIF{}I=YZc=T-6r;uIf1Y_2d*?f z6`RR7^TmcfJ(!;SLPGUaok&~f#DIVCZyp8p(iu^K`D|{TFTnjbwLp(8`H7;TGgo6D zxF&b8myZ>*ddQ?UO#*@G&GZqhWA8Zl!DO$l!19m(E9M|Xs>U0 zk6r`nuoJ)TwpNg7X5REMO^tmZ%oip*adeH-puJFGT4b1p7VBrgYjxCRu)lCEq{F)lZXh}AUz5`jEn zr#pPbX!;T2Tbge5>(?rieb74#vSF(7KCh@r^Ka*F%<)a}fImod@16Vk(y~rfic?T} z@q6m187izP$zoH~{To2x@yoju!N+bkn!X7CTmIRmEYg+dG$#>pasE3-*HZj8=3Mmk z^>x~SG66{tP8_UfcJ>N7Vgtz0Rp@IVsA?VtDGMIv=LB%aDDs=l&zkPiKQX}mu#z?Ih&k1 zue+2s!l4g8w>Q^*Foh-g7!sG1$Bk@nbAe$8idgNU{E^`t6Ntv_F{A`KKB)IfN{sZx zIf%5zTOKjTGlix*fargvT~MF81^4`G3rwTHzgUx*a7iRD?F%3*9^Ro+M4M7!igGNTYvt^X6HWQ3TySHyi3CmZEaCiBB@aT ztx~sgGmd~$@<@Tr-J{KmwTtT7gk$3os;1WFZZ}S`(v@x-`X>=}EkoNyV}v$`Px$Qn zHry}45P2cAVDqb_3quRcgyxSj0^kSBmQ0Z%Y0G&Nff^!xw2Si?EFfxEuw_QDlZIt& zKK2MM%_+fTac9)udf#4N;xFpO)!NmGo!rFEAt)S@R-3-FcI8LE^FByPrc<5|S^fgv z3WS`SBsNj_v<-53#lmUY#5lHvGmnW{3|~xn8a!Xbf!fdGGx<%kHpZU|;K2Q+P21TXi_Bg1 zi-15jNq$hui0X#h&HwxcLJlXm9M1h+6 zsvqn#Ono~C%w~)RM#;~r$9EF4Y9;}CN|2&HBm2$?C+}=cHb9lfOr>}okf6B&fH{yDk?P~mz)>EIIHHRn+ zR>}JIY*csnm4)!$RVezpcDjusS8sz;os-T|L ze(fY61^mAqN~$@N=4I&C77P=Qs{@<2B+uuR9ikmd*MlByVBFb%KOoI{_((hTgi5eh z>8#uHht0paqN(U-n%wZV#k&YDJNsNO&Vg|{oLAX}0SS!Q;^-nP2yiW}^Eob;9!|EZ zaiRvV{Sk@XuG&qH#0>DJ<%0CN;n2AF}Sm$JD8Tk0|8jMniAe5xfOljuE2j zb<>0JUkB*j64a0QoAfH39e$Q=FpoId$egoELz(MWZFHSiG+n*-N^~f*YGaoD$dD5*3*&f$u_2yg!@>(-o9^je?;Pj^n38u ztDdcvT1x!g!Ir6uapN(G@Dcy+q{rRvkXPy(Oo#hpCnKx#KQff3vdv<~^rEs880|kwepmLbg6!IFGd5eBTgG{sQW^WcBbQfscge ztF-f?t?-DxN&aSh8Mxt|oN$`;1d=#XJviAM1I?x+Z%Z|;Ih!%a*q^+HmL~7-U!++J zU$&lHR2uixCHg}@=^;=I&e~vJYKF_bWgD*U_x+0-DGT=H!?u!f)r_1m?VDnft9`S> z`}|36ya%hseLB_{C5ls-r!+_eXgdqolmd%sM)Q<}ZV{G`2`PoVl%tQf&Wrvm_;dv8 zvG$xdel9d9P9pi4qy*j!jZ@P4N`xh3Tak)GZpfti@A45FpE5TP0mh9AQ;!me~pIfdI~< zDb2&UPAgbAc1d_I%@I-MYwyI0Ld*Oun|U>tft?hiE|#@N z-o|DZl`SNz%;RG+0rw7}x|Z@60=P{Eu^td5Gga_EFF^d8@vr+Aq(mZxrKD)o26cMI z6Gv9YdH0{efTt{9)?Pw=mMmJbSR>Dn`xPT9CUInt2D=tM4xDA%?Ka*`vtPBz4vo)p zUqR>bXgORtC`sSH{m$|k>^hh}K$Ve-G_gZA&w-e(T}o{HA=C|w2xlz=`!=<*SgY02 z?qqS{&-jQLN6b0gmt#Cb-?6(WVMS*j--;Fzj4Y<>b928QL z8U*+YN|?x^J%6nUuWxKX0SZ}`bYw^MWx0})l8M$pJ>nEPmOz7e{`M4Af@lCozNY50 zMVdwVl=_gMkWdW)>CUT*Ta0-of=%9T@L^@@vk_1D?yuMk73MVjJcEqC0e3s@YWLYOc2Y6cR3lB=?XSdZ# zOPl}Ri4!_fL$1Ek6hegk^MxtCZXbId3&X)+X8E;~ zHNKY;`J*TdF7I3hzUU?pY#19U<4d&JGDY)op3$$XCe6e~;vG6*1rPcUY&i61&r9P< z14QSK3le$CAfy0zy6Q{3b zqZ|n(RW=U}LU&^5q6Pw7nwy`Z_byUXMMyjzg)r|0fzc=$NIa(8a;gj&yoQ#c|9xzB z`g3E=-8T@e^h+>ek`p#sUEPx{+-r`1L>jwJkC;`~RFTC{c~dI#RKw6_hR_Cytf2T| zl7)+18XAILc4r(hg>5MlD{hTBLcU>j`}{up1LPT;Zny-7aA;Ju%g1M6{N#1L;tK2v zH@D+oG55@ykI&uA`fYp0zj#Xl-gHG?6?$4>7tnGmA83GY$xT_RqFq039mPtqIa3uK zjjBVh^8BH7y~0aBD+`7~7#?`{KD6})ER~~~zU}b7Cu{-WM=b^hy?Mm`Er4X-KpFVl zTitW()oCedkS>E|@kn6D0;f>P>NbeS^(L%FY%8=_JpmCLj*Lhk^4c8EPj*bFw#uKq zs#-k31XWwAI)Fzi9>o_DWdOkwkTsbsF)yB|VjKH&kEqDZU_qrND>CgqZh+ynl`1)t zZNm`y;;WwBpWiQ|n=P;pgThP|Q+zuqCS&O%=d?SO9TKiM{`-6(%wOns8Y-KvkNqxq z;B<9kV-}vihn*$)Eiif83;o2+u^ITpOtGzpCso3^oXh($D76MXmpJcSGkzdku%}8; zUIiaGD6o;ekNrnwfRR~zwe^QYIK1C0I4;ft33XcNuRkv(1#UQr@uz-{ci z{*tr3ckQ{M1IXXfUKcC;y$@}rHDatI|3VpXzdp|EQ^^|rcIj;fkk6%|Csc1`2AzZf!K!j41J{?X2V6Au4n3TBKA)=+>wtFv;! z$X-Pzng|Z{z+!P{$rdHoYuojE@u%%^u6^$}J*OvcJd~in-;pLT$|1@@)aie|Iz#Fa zVI*LrchiiqjzpGzI=tF(gzxnE3hq=1ae7YCdNARf}%!sF-v%Cu_%y37x`Qj-vq~lDA7V7;-=W)zx zUwS><;DCEpRxG-F{$;*J5QE&=MvrvF04=e&XZL|q_i{rPcsEIYs70mUzQG&-whneO zMP&^xnj^Nh^htxt9-OgWRxvNrl}oRMFI10Nrx-- zzE{x8JHMp1Mj&#z{GTF0nG_Ir7p+ zWQF9<{|UdVK!{7jL=ta=^}C*~{j*&yW=Gdlu)U0~68^m*rX1}(q$Ih6gq3gOXk3`hK28=}T;{nA|!*=&@S1tJO%EJR+zbKu34EC!Z&$(BfWi zLp*Em-*MQ?iGBO~x)&+_7Z}WaYes4vupc0lRL9VtO;IQ`VYSO`bTFY$bptTEs9Ue7 zA-9N&orwEoenD0^fpC*W9;iyfx&x!K24~Ek*VyD~{C`h&ybe!m=3nRxSZ<~1fziu( zh3d0%9k2d^|A-+QaqO#`gOEk9LZ2x~mCou>RKI?S|FF9QoC)`)wRWz%dy^WeJV8wO z;k`RAnP%a4i*jl7^SAISBvT2$y8&|0xhNXFCbr87Y~~PXcbg<$kJX?LY~ftol7Y(< z`k@9#lO_r;<7lGB=KaIT$lAty#}gONrp(hv@t6guVxzry?Ofe>%_aAdkoQ`wK2t5}jjxkGA$D%Ma=WZtx-s1z?;}>@U&!jQH@+AF%IWi}JRn zqF9TmP7WC?N2~7sSa^cwb84|96IT($a*7K*KRAL%x6dfB!B)8I+)Yf^6FnG@p4tsa zA2ZH)(oXnKTh+8piFJ#I~POB%;I& z9;U$+&S3E@;y;tt#2T5!_0EiVwW0yls9%2b?YvPFh|P}hkfp`MgHSkh87T7;9d21^ z33!pkk_xN(X`*Nn1Gp6eU{UsEvU1E3ug){@hCKAPi7}*q`z6(4MRgr`bx)|yU%T;b z9>20JuKh5zs|km`>7m2oK2Tboh)r*gJ`$nNgg-YNmI$i=$Lw+(71gv(pQ~gXdA2EI zl$0?#62%M-R7JU z9cw*XTX~q*xSjp)!uR&*C@8ZGBD(&WhI%$aVAN(>4OPh}9ernoq~=g&u5PtlpRSillD%@f*sbHHc(uijjy{~*OV_dP#n;1Ugg*r{V5nlb zkEz)gt;gIt$9_Ho?y=}_M3&a^Un{Gd$sG??50^iLXCJ=^Wo>N@d@lR=+UxJ)XH+sF zVc}Ak8d8I7EV>Ato2MQ;Tn&mcwPZw<;I>b4n{2PcS?UwnX{Qz9T77pMbTq1I^LZo%n$!zC*%O`&MQZtMARDc`m$Xcd7jCqH$zY~uJ(=e$%d8xY-9>BI8kRjP9ljfG3&gsht^hjL) z(Vz-tpJS|ziy#v)I^Xc$ugl^XhM0bs<%H3Ws`la>+lClxKDEY%W4|r>QXaqs^NYws zX0d#)y!a!6oo``#JoNRKa))jMfo^M|jvA93fefvX-~dc=yuz;y7IaMq=A2@&dkfaw zOaql}XYs8S*l;Gtito7Jd%Z*tE*cJNgB2SdOknQ5?Pn_zn^T1m)DK>uLB`tye`bMU z#psW1^FvaSQ%BXx1k+I7Fz4}jsi_^W!Y-pIl0Q17Zl@rN0F&shLQIvHEXpz%CX%Q5 zLFW%z4X4`cx2G?LDW13Em9WK>PbHyg*l=UXXqzxepCLx>pdKewHu^2(u;((u(jNOVgDRApKUc zB2bYSe)=keS1t0Fy6M!!#lHv*fPvtuwdMjG=_2ek;4=r+oWq}Qt}3}$oD#_p^zgFh zI5$z2x^;gBV#h2#rDL-`%sK{Q!!|-T>wPO${4CJrNWuw~`)0?F_NGrEU*6D-AJoXu z)q}-Dd3svCx0fxsEWBixnk+u!}+wyVCz7^2js zysKPTJqlr{IcpcqOooshHj|qbS;47h5m&si$O`#xY%k**Nk(IZ(iuV1X>UAtHX(9E z#rzDRv7}Pwe@#qULh?<^GD7dYmiSLX#yM)Y8xc9b3Rs5?sZ6a9Rd#W)4fSinp`O-F zLRHGo7X9orRDV?0q(W%JVH<8>S!d=iY>kJ_?}=&xyNYv^@90TM*at!OtH9Gb&bzcU z4fQ&DS7%+?VQt$1h7q>?t7>7g87mCP6mw5Zyj!ee_YTj6Qcnz>*x!u~Sl{+7#gA1!Koq%y9CFM8X>BDoczD`%e|u^qijH z)-H8V1mfVMlTU1qOM8)e2Mp_}NN3EW%CiJzIij%bU@?aq@RBALk{C~Xh`j3x)zN>D zg$>0RU=Og%dX%O`?0X;GGp)QbWF5k$LwN$Glw-8s8GTe!l0sU)CodsmzKp{JEfN=y zl6HQ1nUCwPg{9h?Rq8nIl?G~Id2P={Y) z>+j#ca&eAAS#?{>iB*GXZj3zcLrXJJr5^}cy?hYzvo|$;G~mKJ7ox@`?3c? zl~4y+6pPeI;Ub)wVqMAdG0Y(`96kbch)}9j%2(*>TDirb)J#M;S`SU@WR9h+XZ9yV zekClN)En$_*f3fI!t`Lvv5p~|-r$a`MA)e*v#Sk56<1aL@x$@}uzam4|m9S?o}6n_hIp;nCsY z>YH~sNy4fhM!Xpugw7RM!r*>vp|DN#6N-tj9@B<~7XLlGdJRy;s9>oik??~Fii2P$ zpdSX!cjWjJlxyJo4PaWtWm_|NS4T(x*t;A%Xb(hXQoxxBGP}0I+PCf>%@zW3B-fm(Y6;4xax{7w zJvt0~h{lxTP)46mp)fHOD=KH=yuc)J-eFZ)a!#4tOiNIz9j3ZE(*dF{cMb?Qc&Zxk z5(;2PKpnoX`1tw{*&cOsa1TyfR3(pF2l)Jhz2qM1=8ObLk3Pq@Nq4G--hW{+sn%rv znG~xnc}P~=2I4wFIKrI0YAMhT{#}IPgX^9Bo)WQL$Hy2zA3}nUd;7kXC>=os3C@k$ zl?Rm&e!n+ZYQCKP*!SJ3Ab1w+hgfC!G8-T_jw2GDX_`vHZM#l0XSSite@L3Skal2i zIxUW!1w6Fwe@0I$WqT_5bg)=FuYU28S#>1GV%(i`^C?_J=J@8;qyvEfNP1>w=4ETS zn;Tt5Kz4pMAY&wX_iUsb^&+cF{*?e*&}pjlJld|JEt63qWDlOr^|NU+UG~iO zDhRKw*7~Y&Fo+VH2Ra$5tQvhdKbjG1rZ7xBauXYRd6Xo#q6=G2eE2C$#I;=J)M*mN zScj`@SzlCgq@AcnjqRyE7sQoBU?Fw7%&Fk^96B2{YVjWoF02lHA8sc9BGW3DlzQTE zZicI*u%da;zvT1AT8vt#YB`Q9;#Qgn(kTG)*&`UM3aen{-c>4f=`iuDNbxzml_ zDb7?gte;OT{aU&|rw=~-kPC~gcRN9TEg{laQc_1HL=g>!(cpN{pz6{t)fG23w;KoE zJSV1zt)f;OtpaAV#o@myi=# zY6exK6FE2!APB1A+tRqzeMV5LH^2n!uZ_@-pO#&ZUYea9>|4iL5G~RWQ>WouNciNC zLO7EE%TG^`IbVK!v>B)ynXo{M{QK6)H06tZ1f|>P(KyS>yV%{;wKc~r8r2v#zKqS? zpu#U^T7?mlFj-K9&(waHt8^Q44#%oi#y;|AF?IzA%!xPGKXe@9gz3&QAAZR+J9pj6 zQ~1ott{Jzi7}hRQDRdlgLfbdj_;X8!OC9&Ws}<7UGQp{Q-@kQ;4KU=#f_sZm<`_Z) zXvVRHB(CxnM!Dh0_;i~;_KI6DN(%k<#t+&+{6kR*uDaI5^E^RGSm#78bI9U_xY zx5~4@HjVM7w8bCPZbnJ{C~>f$YC>6DLtg4R88V!SnWJj}OvaJ?$?fyEHtT%pak`~; z??MvVHTVutKIP>Y%_SXJFvzsv;jB@P%J}i+Q}*36kDT-lcGYM!4%p~oXF)Dcw{~zd zJ<3(V^mg3iH845@P>Oh(DQXk|pQ`hqBYERX79TAWlXQyeeZ23Xu=q~naM^@`PSE+F z^GCXjQ)s9OXsoqnj=MXn zf163OJ#9X_oC;^atKM8;@CM`oMKd^T6V1kGZ+aDOIzAmj+kB!^N4fOBLT8qY&<bXB{I(liD zxR$u8#7HJ}50N=#{cki)>XIOkJ@(C{7^WCS8| zy`&k7-Q+B=GDNTb6HiQtq@bI_?C`-ka8SyQTWUoaz8nRr4!&gdLBX&2eE7fO5?smH zJcAAo6;Wd1Ke1K##(lspUT)X=7y~ce&R-W zBVXKU)3#3fQHUzWgoCX`V8e?ejOMZizfGvR{JZl%GAerV<1-NLH$9J@qR9uQQKZd6 z(9~-A&DBXsWyxrVIC{y{#%>WMWzh}RI76lpwhr*s)i-svL*j_-rQGF68!Xu@PG;51 zv!8)U!K1GGu_vI0jC_DM)Re=`22fUdg0Y4<1jsPc_V}dtOu<55XKslVFA-2sjW|i| zANXixjT(C`YS|Uk$Wxf)xhz~Lqou!Lvt^A}t)9f}5q)7p&L;K}*6KW%e>a~lCt@Hn{Fd-IoR{oHl`7$B0aMkIq~b) zAqH>vN*9j^?9g_{wO2WVx1M@sXFD2e>p!v{5$2?LvmAe|V%od9j>9($PP?!X+pok- z^DWsJ0(YD@#Ph1=n0p=35&Lg3n<(8=xFjwFalK`AXEXBkC|>m;usHEjM1wl==I*Ex z8?M3uLZUgxtypZh7>DoAT@>kz9P}nP1&7gErTN)IrY7N3)`H<3uXH2@9nVa{o(8)0 z)IB%TXVwd{y2_1o- zMCa$&s~owBJSLeIjct`UPd-RGNSwVvOoY9zzOuJ`HRc@O-zdV(#W?S1PiD-SihYr= z*cZ?R=@G)&@@NzKN05GA=X*3Bh^9J-9-tK1go#$pYmB!aIHB4lKf7&&9*IVH0*t?u2J$<_Dt`GU@FLGquv_A;&=759*07o(Lj|-!xE}I9!oH3?2mq#fKWk z4p!(V?)Pw<%ir{H;f;v2Giq26Ta^!#e#9ej9lB|omc$L{mrr#-0uH=_E^hPV7ZJS@ zOpqWYxgtG7-v@1AHzPl7V{_kk!^g~rr9_OJq8Pjh^sQp$S;ny0<*^&vbolZ4oZx?6 z0O~CdXk)|grg>AMC@ES2Vd2*)zc6}%2MVb6T1h1sP-kdz+V}U;x~S^Fk)~db66sqF zv1`KT!r`?fs~JfhDK)Qir0TBbAu`dqx$anY z>oosm^wvUFn~3wTRbbF_(P|0C`A`aPIoOnU#j2{nWJYKBNbRff#FG6JKXy#Zj9mgS zJJES#I^ya+rt))ib`$5JoH{hkIMT&gK@aE_kFGt7nBp8Lqh2WBemo*TN56ZdU`f^q z{)RJ1kiZDsHAGKkozAZ^g*v9k7@#i&iKpq)K~8~DP;3=+6D9>Bk?q*A=r_iU$YRmy zuthWz=->j95!^l&UEt38`8Jd=554?hqdZF&mHf7(c{7U9RX<&d{|6jCih(h+0!QJu zf$ZeVD*-;Mp`6HYTc|~7;*#DcE$YZ?woFZVXO(OVHw@y#D%=1WR1G7Xx*_5O_KX5X zq<|a_ZqG*wtYq4?A>exC4UK`}tcAZR<#w9W`bThVYt#1pI=n#>%&TbE^jn3Um?1K4 zWXGZJ4A1NbtOza&ZsJkl1aOkV0hALljI$TAe@1Eb|9Cpfpt!oOX%8+L+}&M=0Kwe` z*8~Xe8l2z~+#Q0u2Djku5Ind`&>MFN-^p9`eE+GUrsm8(d-dwRnw1(jc8b2VfzPl? zB0a7n?POm{GXV*!uBX&t)1+taXb_unoQqwrT!-?ib$nmKC^w(_!_h6K%Y<{W#yC8Y z%}1@2A!(iG*`=dz;#@~xxiYCmb1#!rHg`&MeM9|UfBNq}|7`l)y5ilUQ@c@ldE)=} zRdJYx)*2Qkpn@4o7T;l`qXd3Yx-65}+<@Bh!itNCC8%P2ujtwzt?{y6suo{Mvi|J# zZ$L*SK#qzOYIwN5^@4lVk2rxf%9*kRTS`oC1r|lpLVF6TYV?4Sev52`RdtdvLPl*rFGf1*nPq9m!Gn! zw~+Mcx>YhxQuMmb^CnMbi1kEQ$PNN4NR3q1%N~Idhch(v3#qoWrcs@?Nu4%h8MB>x zgp&S+W`<6^!KwxQmR`{>uY;^_8fwXu&X67MK&VN;uKdC{Fpkw3vML>f@B}n*r+fhA zbmj`bH=z9pAV$X@qfIpOSmo#40!u2iL;q95hxbd>`eo*tVcMa)trpo15C_*6}S-+${l@vf38%gx4^7GEEB z1!`b`ivZ+`ew$tZ-SNkQY_y>I_s8W*(~pW1rbNWrivX{6;YGY>Ad;Km3s32fiO#3K_lph2VC;TIZ2kE6I`eF4%*za&g6* z50NB1#RE#9l1ELb9^S;LKb9O8P@=N5@nfPej0=y1yR9_TbdreYeUEB|=o~ zN5ige7xaUUf10`=E%ckpMu+-G(Q^4%n@ndRa!9&je2H*pGeAB91mBJ}a**q~!Wqi~ z_J%i*60vWoS+oVI+7gUy3t4?vtBTfIR@oz-w=<@bB3*vB|B4tCm?#4<+!HMVqP8nT zqDCEf71VE@^r8^27GvzCSk*!18Zu;p0Ot(_V|H5QasXm$UyjQK$?f#Ky=To z!tN^cMoB5rJMY#i&0EmKL?L7P=?vqE5H0M6@L*kMK{9oQ9D5M*0htW0sc}L5uED=` z;VpSrHvVRK7lXVHxf2NO=X7S6HDIR)KeQloz9$4@%0eXc)wef}nxVBo%_p!Ui`qVN zjoh{>>*b$vNm)gGkX4*Wa(^FIn1Ig>+YwnQAqHqVB@r%j+#X(D>Y~^%4CcE(PM&On zs+be|2t390<1pu+i-r@)U@U_$9Q6(rkmRuY5B9N@G*}*(={M`^fRU0VRDL<==0x@$ONF6wH15?PK1I+LmCT#@Wn=j}{~EmqiSq3tJ#KB+x=)hu>#}wncC| zJxA|5BiMrFE!Om&8F?l^=-lhsy!aYg{piTv!IEk$ z;;F&nkd!G~*5CaJz&too5WaU3A&pHZw-ZjAn96`~{RYR)Cs`sL8C~~Wme9|g^~yUn_+c7G9NqrbONER5!;vkBii(TKZ9Vtx=Su`+DND8SD@;5(6uaO&Ev zmvG94#?M8VS|2!0l3p*uC||`v{z8KceXnD|`5}q?32vn0{Pv4w}$g@PK?XCYg8bWkR|9>a3C$Vku~WHz!Ur= zBqFlo!|zguEASi>pdaXy0ls*62;Y3U`}y#r`w7+&wt|r8 z2cad}%1y)<(8baqxXS&_zT^+6hS{)g!lFfM{<1AZ924&3(bdy)=!WMOv`4WXno@>e z^!VhW z8bQnL>*UfiIo%b^TDpo8Ify$a;nV0L@oTEY(S2n!TRl!R4n3{d?}c{vn5)A#8L~hB zc-LM=l1x{p@gqZcp#ss|4fv%y@sT@@zEj809AKV^B280>tzezTP2mzja0i0D`4*=c zrp6h4t;p6{J;cP(1hQBKe4#Nq+1RXL)=_$UP)j%l@h32>&=%V$)i^QU`$zax@&VA?1#*bN8mCT^a4C+Z;lT_H|_~10YNw zu9Xl5bUKul#sOYhd9QeHfhiZ*Qz9QU@=t#0h+>13@jeT?31TJJ`-(Xg3GIz7r3d<96{?W*5 z6*DFD_OP*hwF-llT;Uf}08kJ`Slc=NsOXMzb>7#-U~!Rfx0K;*p(c;qph8#-d+K?v zg#cjIaCO$(X>&c7lf9SuUa1PCpM3|S<}W<>mtPfr#&*S(vcH*Qv{%rzAlA$o<{ zHheiM52gNpEu|)b;HSz~=P;lR0t~gYq^(Y3hJ z#+3f&etw`zDU=nkwW)kCqx0cq*U~r_wT)E5S;%^Z{$z0zw@?i-%)uOyIn=4}5{>y> zt*-6JM}VqZ?>p8CWleaN)2K_bG>joqlWLt+7~D^d!&Y(p_dP^{>e+OfqIA}t{O>8W_%hLSUblUsn^7DgnEq3&GvtnhqJAQSf>(jZW_*!- zJCOM81p>t`=zzH0(%Jbt_Q0Y6=xx??H(NZ_Gh>4NHpWR0MI8v&_wi^`tPtXeFG0x| zvaNR(F?4L*`~IthFm70zeNj zPF}aictFgSjJKWb@iRTjXu3`XS!o11d*bMUniRrWAcJ>g#M8KmW@0b}vmA z#fesgjiEqQN>p6pBOY;|>R;Z1WVX!uEP9!>p!QtzP11MPvke$AMPR1IxcnBI65yYa z#@7UU-?bi@Gll9zj@-B&$#AZBcWs#rD?@tjLd+zbJKr=@E;MN~{ zIDw4Igf@X2K#dIBX%a!R&TJKg?fUag=LbD?|t$*aymIe&#~q zfnwu=^F}$}C5)gns1tM6J0LSMOGm7|gSCK80JQ5`wP1tpQfb-6fbJAb$$Q=dQlK@h zKJWRp>x_>2Bu!Z2PU}&zPfiM1t{&HkxF4wpK5>4Qvj`S=C*0qEWnM>zY0;Zp!Nqi} zW<-?&GkyRE0IaB+C*c=>mqYfq=Iv6H@FiyctLD;Wqv4F_rBcv8A}4TQ4X&z)h#M{Y z%*`{7%Xgpn@b+7A(lS*L{lHIQO&GK#q0gutI`vq zm#d97<%`h9#S1FxjIiKi? zu{wiAAZ0?4lY=RX(!sDVODbKKL9Df$cRQSH(qz%37POTgbd*J9A*^_Et0-+9Z726^ zn3d3xt-VVF)+VEUjH->W68?~-A+t8k9$q*4*DtIeWt9z*DktBn5n-mK#p+~9A(oIB zB{YphTn10WAT`Q8+3LxVV8Xw#H>T zezlwfX4|wOWSEn3UHEKe1}&lAZZV@CV0eq_VF>jJKutp1_!d@ULwwd~KxG=Q8jy1R z2zyS_^l-63<5)#)250?8Vd9WWdB5SEq`}gRmQJ}k-7jofoo^M@5HluraP6vH-Rc)e zck7G*P~k_z;k-6cB2SsO7Kg}yE<>X`H)+yP?8~Q&ouwiR4wWKfYm<*pFZFa+2o zE*sC$Fb27SvO3^F9Dei>*TL6z;026MKpsM_o*Z9@TT{rWctL(gI}8$Gt_|3djVdwu zi(=dL*uN_dd0~9g8oV^_=^FirB2b_V3V5_b47k#ZJOUP&MD>+5G3}$lh>`~EX)M<5 z0drS=RPerMfaUr1Rd_>G#H49?mUD;O920km;*KwegD`f8bCODF#Oqhvo!8ubwQJ1J zJd+|%nV%L%%&%?taq~nsEfWGQ8=Ku2IjE}c`lTbl>YSl_k_=B|{c218?`h!oJicu%0!Z;4PSY)KP?tvVV_ps97>-PcTg@WSU!%eQOGC@^g&% z))ICd-I&p|Y#&@fA)gE|Gl*oH@SV~aQ%>=juvu8664sN_Vh0A+H6mUquzcPmkJYaF z)RHx|bp92{Bk^UkmsOBz;i-D%0sMKoRfg$^z=IblD84g!HceDKpG+!ND7ELuQz>Hx zjX(Ux2j@0ottFTgpjy}LWJfBH`SRgy5X`i(SM#Gxi|#vpY-Q}vH{RAiP8Cd6RLJ&y z0ok?T2sdaOq=svI{ds9Nu`uCV1g@Ki#~rkk5Ds&OmNKteA$ZL8KWoZhI%|4oa$+;p zVp%hgyVpa53F-xn+|%x*Y%Fbrled2uMjXY(%L^F9{3~9Hds2O(L}O1nu-B?A>ei7D zFe;Lh8&FMg=-vSLafEl)&XjI?Vf|DH7mqRS@lqy7)L-|1(}NqL@2D})#n8=k zwzjJMDJA4oIEe5e(9pJR%mli<91Yl~4^ZNE-qWlv%^ejf${(?lVaT$M#Q~Vnvdq*+ z`I|e$pVxx7mpZKY^XnG;`JnC(KYxzNqrecxA+7M^e4GQMJ2NivRCD051n^S-X5ZE& zpvrv?N9iRMJrmwO1GhzUlZJ^kIDro5KorO=X#Q5GqcUfTMw8c+TKEfWt!}-l)_1QT zqk*Xr_%Hwm!aN^UyH2+XU@35BPwI-6wuM6Gg;T{T0UD9Cn$^8Btw7=g*89A;gTeQ+ ztkPQQ#-izpoP_8%*KT1*DE(55_gpcmpuT3t6p71cF4@Or*c|Gh`w0oG+D7yAE}xjR z2n0GFa{YMCo`SO(B~=4?D+78)U{9wZh^PYxqD$+#WRttw5rjolqEVdscqhg+3Ke{a z_VpS(p^L>)`m)PS7lme_f?|qbrTT{-NC7CH;3*?K2BaW(?%}49dM4NopF4}-6c#Yv z2)gRDsNaOkW<{C8+Ez)=GPI-0M`ytfb0Y^$HNY8#>l}z%8LuV$3B^=RL8wr!UnHAw zUUzc9K}|>x&km-AcV0*6Nk*^WBmk0*GHb}dO=x#J;G8T`q@7X140^oNLNlHg4blUN zaN9HR!1sJWF5?;H%ywhzaWG;*8ox^KnJP@%i*+Bb`G=O1Y zpM+Q53TZXDi2ZJ52W3%>uH}VJ^S;d zzCH;>4+1Qn?!PD9I~KhCwYm9>&cyVltf7Tiq5Xl%&|9>?LN@Q~R<}w=UHLfa%q` zOZsMBB{MKncfXP&uMFYq{YSF??dpDzl*y+ZWZmws0gT0W#rn~9*z5KNk>royD_yRO znE=G7#@x}uih!E#zr<0u8EihNBcCw~a|8Onz~I4G88i8dO&d#1>X->%7EE9=K=cxO zWYBfuUfzPCP=0*qUy}nP&uQE`S^2C-avXY&a#MLA$cV@xKi?#-|4G0x@$NBH9NMTz zAa-xwx|!v2c+a&G_ISQ0X|rtk%YB}D;CRMmc#A{Kh)(IbI2U_Px-A-0cbPwTv06Ii z#eaOv`ra>sE%mkVxijbKPZWkp2L0i^hQQBbPfN^U6c%i=m{}33YzU5SYOGI98+$nv z4zAbnTmE+=I3B^lA#s_|z-DAv0y=bs`2<4qa&gNphW}o7!yo|Vyw@4(4ld|B_S!(z z(DMn~*NbEZGDPHD@dNx}>#-d(VXrWWjD2;Cn61cj5T0$z2BI$xU&<1k^NfADv~ogw z6;)G1(64bm7VniMW=3{D13-+Y*D*_66=^s|Z`YrzFnOJ-8S+k~g%!3pNWNJrmS9;) zyN|Y2TES3XKJts3OB$JpV_axe*%$yxoAw|E{oJtQtjA|kI6o;7H^2ojRWK4_T8o@7 z{D3xlMJ=nZ_TIT+xreay+1i1#XKpyoQ7sqoxs)1C>MkkZJ$>`zj#PRDXD~k}qtqKwIyiy1^PfE2EQ< zHcm7I;)E%Zvylt=_=QkzyM^wKIg*>*MDHia)T;nv#`vOjAr z;ZCu@pBSeBq6szA&mWoM%SQL`n{;Ak#uef`@e$ee5lB#Hj33)_9v$8MSy9ISd%iY5 zRD7B$vX3iq4appgeQiQ8(*Y|6P@G|QAV$u@CXwR5|?`8o$Q*j7-I zQJhr0SZd8|U!Nc`bKT@v%R9>>>5o+TK3p$a^#7Mt8)s1I~MOnmG^FO}) zzxOIq+`2{7;Prcx60x}<(ODyXT!cu;kWtrfp>*W42)60Lg4{8Sl(Z8A0B|7X>>Z;! zzu`sQQ#c^%g4K`8vUhL*vzGV-QX=N&#s)KudRq*(kdz6H^SgjAeo&FI`T?)bkADK; zN4S+#Q`LrZWlG4f;nYHx<$7s*PWD~<{C)yb+H|!EP<_JRz198|F#iwwh~2Pwb7<%PgL zPAIwdq}UnlFwxG5wu1>0sv61j|I5QQMu<57@$fEIM)DSE&5ljl3^WN%sF*UFJ>C*&xgh4&}o3>c7Ny6n$vekD}zS&Razgb z@VzPlc4)f06^xj1Z}^K0>M$=#(*$N}b?3GPG){1q`$6ud)$G5>N|o=*nvSv)Juz5= z3Ci`2h-D}0z4lWFYYzb><&^kZpGFzWevo}9w^2Nyun9@W^~ejWEKS_ABTvq&ylAxMUz5p2K=~*Op>|H~KX~pOMvvDYhtr{zS6}(kAi|>D<1V#O?!0 z)|6$+IvOI}o@eaAf#rn7dq6t{viSR*C;z5AYDDlLTF~PQ;w1n2TQmgKYdm@Lw~ZU! zkJO_w>x_zfLMZq%jVF_Y^p5WzD!-&l!rg7msDonO6!s1W9;L#;f{}hRuS>wc43L-r zUgr9LYyf!6@9~GBN$0XjtDbfKl6?iE7=ciknCdI(v()kFRP$YW%d`;%x}iPt3gB}?+)AK$86 zTL31cq~EC82fVB(%?c)^@!iYtU^+7nadnu|_U9zrjK0`}XB`l6tHoj+Y_=`a1Qvg= z@RG;^n?*Y~XIhO3B(9@7Ut|^ad4-ML_5SE7v9A{ceyGCYjbx`*rQEB7qLF(ICnQdd=Fh{XNek-^`;*F9HiUWUp4j zYIiZAyZNn$p>pr zYMz5p0XVQW7Y>wC<%yhmM?Gf_+ZdHj!xml{(QJ zpc)=i8bTZ|uS6I&TSkx=a*Du_c^Ng>aHg_5^Bpw)3m?#I?{Nh_Y03iEDlI3pCpa@- zYB1jcaATqDH{Rv@*T6cEqmXRpJcSWPbGNF`7{ncEk`j_cHi*u2o(4=TIWDGZE8!_A zODMpMaie~POm_3kxj@a~Tz@*o0g#x1QQ*m!*76NN5n~NQ0LQDv=`(QSZp3O?|8fbe z7Jx&m{~0m!mUz?enGJZsLJsd$C4u86k#UDlW=QN9z@vWWIMG~sJ>Tpewh|f&U~4b( zv$jovJU7n@H|VkddsRj*G~t7ap-@Hyg-F(HI6z?!;(gWcj1=X zfRc-3>A1eZ9H309kuMqvM;Xy>;&e z$2e(Q)7oQNnoC+g4$pLME)a5@kS^D>K}tWjzhLr9qAw4FtT&)*)+p%fi*R`cZSa2) zxZT8dUF<#JRO8?8JPlsua{r1ij)0As6lmdtEs`oM+WdFk-TZXj+FIe0Kv2}E!~}oXrPUIb4^7xo{p^^wwrnaLkYGGe2o$Pu z`(QUpP_<{sTHJOZPrR{iJO7KW&4sj$7cKFf+wPTzkl9JH+%C$XTm{rBPb;v|P zLjuMdRnyo{0+`=;G2DE|PF@-QXPlKnL6b=^E2*%>6*4jr$pzAITb@mt^l~+e8Y+sH z7@h4jQ~m#(hj4#l%|fW)Q#kb436z+N;!&s^4=@3}br5*G3K-Q>ry~Rfc4C;;wU}ay z1F(j6{JKAR{*+?`%+X_4#gss@c0q^RtRK0(pZmx*>)w*OOHiQD9kEwJ( zHpy#2xm1Jsj)NeWvjx_(^ZvL=cG0^AbPsIk0jklqzAXF4_BoaD3ffV^@r#TSC0g_U z!hHj2N2urSHdu^iyig&9RN)MVZi{$UFo?$RD4$DxJ31}fBBVY9KKN$qdPW+@E7DbR z#8SZ8!|36y4FOG4aKt{8b~p+s(#e7X3}i2UQ5KPq;N zW#CBzHy7(pNkW(SxYC7VY4}VNVy%^QF`wyUkx4Z%)4GFjivq>@pxE%*X>JVOu^^fu z!dDUX^y0o%`sHpA*t&^CazE^S$}I4AL0$m7V*_B`d}OINGBnS@ak z5+W7xW?q-(#c@>8i1|BbLbzwHNs@$_lRh}3{2<*HIi67Pw%aSRMq~SgtB$j{Ex&cb zBF5I}&{ixv9sBm+`74twDIKjTS5;-SHU$!3BV`mch|CN|@*lwzxpcNYCI(13(^P~F z%ix5lWG$0uV@bcDU8f)SW81D$phvCEwY9SUg161Q8gzbi6X7Kar(BOyf)ctYFp#uU z|5Hek>G=4$Te1)?uq~%zAV=7^PS1oly=M>$eHboOG6(q!7yy=5b(I0@C%~)#Ku-=` z=6aql94tB2S6>?M)*s(&8!Vr>kKakV zBfQ^ni@~qF@;3StahiS8H9%WDwS?aVeBk~gsdw{yP$P)|1#BtyZ$HJfJ|XupqU~vY z{Dj8-i)egsC$gME$a6^lDl5ZIT0A7q!HNMe47P?ZK)`xt)+>AmJ_+OTwA`Q|5Zo0> zN@(#ORDY}0{Iy|9H(q;5j|s7Dv7F@7o|ARPsN0jsmb_&;XiBs5^zi)<>8CPKX)g{O z9fg!yG(gthc3d*{)zwE@Z<2WTW2Ryb-Uj`nR{87!@8U&=L9jXE$TZLLcom*U(i;gF z1Ku`D1&w3+XYolfOo8yqx8II5?1x?0-?B;Eey4pexc=kA!?N>k|Lg^d2k*6I8&ClGM`yaxIp7b9obp#baxC}H6PE99 zZ`1On3$!t3d%ygga|0HQH8yw=E=&g_07!-QSZ_C4pn(v+<@D*`v#pa5*>)yke=p{c z4zUPNb^)_>&zg$JtEMepg#W>{j+O;Lz%lfH<@pz?&r)UpUN5_Vb7<^t?fhQ5Dix4n z3t_4kj9YcLe2!?$L(`kEVuw3nnYHwdxw89ofTeUz&Okraaw`zvN$F5v1Cp%?B}@w^ zJOKYSV8&`I#z#M%!z&^QO`ehKg1$ny8y6|(8UYh_74bY_Z>mP4T#MjHyS84xR zKaR=+>=WZVS8y)4cK_9C1yNt2o>+gifS-pihk1TjmnRg9u~p?%=DludRl~?tmRo)~ zlR?|Z&k8lrpiCC)=s*bExY{7!3`S8}wqRJnNW7({fJmmrQf1o1&sTDwbQBIeSciRL zg&i{-`G-9IxVeN^YzOO+2_u(<) zqXId^A@}xwuhF8Q^YwKypg)M6oqf8Q?O(UU__)IFRHiElv=NJj{7{nf%|dHpg!gmc zOxGS9BS}9mm7Sx+!P|`n1IyUzliy|go+W{C$(e#DMlL^g)?tsE?V|wyCD2c@K%9^L z24HvBHaE5#rbJBdPSIf~^^*#ET;=J${kxU{|M*`V;N|RVcTf|$x%KY{)Oh~%foB$;YxM$@F_-V2$W#bI0VTL)17;d>1IR7=3{uNy` zpqcgFcoOJZ1Qgxhaw$E`yiT>6h~uDdc8O?FZ!} z2`hk!>&N7dPZ{*>G_Z|`<$g_=U48YN;)2^XqWQIujYMsRN$oM{S;;^aQQGWMOD#a% zcO&0m8+T9QPfz^kCX4RDZUtX|vyh~0d9d8t$)?rSmypwOYq7y1&El@3w`cbNmvWEQ z{tqXcyk7MJ{1?Py%`>hu+QaZc>=u=X-5zG)sjgDx%M09Ocgd-Vc`9D#i+Sk}2m%_l z0%!(<;z@4eW45C+Sw>t;JC>j^Zb1bl2IsS5D}8n5zSGG95M_**^Y`Fw$xy+K_crVj zJ=jOGG0XY~_o}hBjkqoo;MCV*8VEnx%N)bLGCBCgSw=@8|G@w;A!w^7IY{li7@i?J z>(aY;{v+tv!$3q?)xB#M;@2^U#Rmv3YBa&U-iocHoCrm<;m7R;|TGqBsaQf@{SHXW8=O9o>fd%Vk`eDdX zX0vYc8sLWlSy!Opr)yfhr~7H2tz z`clL1;W4Jn=kzys9V@r7j96=Rt84XGo%rSt+ea>v&T&Hj{Qix1MnP@_(lanHXq`^Ae0%fS6_VT|T`6=+wS(G1sX@qm4KDxmv)8sx*e$qn0`!F7sWd zZ-Dxh)j1*CcV$ZHw%a@mB=;9c6o{-`F z@NmSa;1fCYdrWuGX_WLl3EtfcKb-$G4@gc-6p{SNSZwv456bksRj%>OnP=YIg<+66 z*D3~+1V0VX>J7N8JuIYSfmwNfpRTB|inhT_8Awg-KV>Msn}>XozoTZU*Yanl|4PzH zFb^7|frnOKB4;DKnS7#8g4N+2G^x|Pkm^ws(}u_>WDG9GyJ^HGA=V}cv$>1HZWdXR z6G>2SQeRVVtTqfVfxjhFAbQzX!Dq`&rr5y;BAJZKiHvx^vlZUb;o%WL6q@pZEsI3A z)}u&F=A8V=H?^}lI61>Ny(zwZBcRs!{`C+=e zBNh|@po@vSM;^n;ZE_A)W;#vdIa1)_r8YR@&(48o=9V7|D& zNZ;!Jk8Q)xBaWl{MV+Y384M-WH!z@vKR*A5IoZy1=z;+$j$waZs7t$b2XMH#$t^i* z*TQf{4La20&U*U#yT3Bev0&@Cw~^NL4Ag<*x1b>n-_1fq7(c+IX`eEHmFxePfAm}v zZTD@;3MNG|o{#>*2uvF98_t5p~{p z&4f^5#{u!iH%RCnT;ZudWy-~1qkxl6?VCC*6+1tyyhyBc%+SoV?(jmMI2Gy7t}rl% z=3*9$)1q((#((&;y1Dz|?WqR2KcM=2+O4SYsPloA7M-px%w>LlSUYM$$L=FbGQtNf z^MY`N(+JS9SPv!fWQ09gC`>N~=LMlay%Q$y%QTG(c`Ho>2h-|ToG3*(>{RWp0BH-j z6|cA-zp))Q{dzz_zkEUlO(tE8`4T#GWQSX~rL-^Zj(y+Q5hjY>h!1(*EF)!)Q# zVs&x@c@7b7aNj7);^g=_m<>Pl((@t^25rk|Mhcm7E zSWARxv1}%ZeJ2!Cu+C|DhZb-QLWnaWUB#i;e2Yk)RiQj8{jV@n2%uQQT?zG@bcwCH zXX)E&`74d-6lGliUwUs80f+YPf8hZ7*c2d|{P`mTmr#)RWfiDUMh?6g0Yzurdz_mR zTvzl3i;EvUFrFp>DiXjJ2lD3?LDZXc6B?$`sCH44`a}CWCKr;(09GX?HC)a!ns2qC z2yE6w{Yo>+*X@5DJO2FfSZ;HDJ-=E7p8Ep>u1+l6$!&PfG*CYX{1D6oFp$h+BZU*L z;xO~jH+*(I=q*h-4?gB7oDux34})9i0sV_AjH z`4xR$4Kn&zwsz_QSuL0HbKH&##_j99&oD}J1=coh6&oF%h33s0vj6e4y@?S&jF3iy zg5V)$ghLZq9>P;8tD*?*k@)34{$4E*IUWm=;^nRR1ka@}mw)d*o`+F{o12iO%vpNM zeB1PdX~&eYjGZud9I~dYs8ryU!nR7H`Ge~Bv zoA1mpset?hE;dhyh2cmq6+3-ki`gzC3V|ic6|Wh5hnFAdKe z)BYIJB6Wb5DekroR5L(~@w<|ZB0Ccw54d3GZ4f5P#KR`cQH=0z%s!?kCydv1zwEqQ z%k(~V7X%vK7@x2H{w3F6-1XqIxf&r1x<3~!BR|P~UC!NUKkw>4?|S@T{#(RgmyvTs zFZP4O=B|VP>(__Ox2q4e3sg5*V2OY_ZbPB>li?P2j%CVa%JZuBo^`?Za6AbalaSnB zb(<8Lwt8kd!TN4Oam9$T`Kd3FFoeH-Go%B>;4nS`aX(In5B&8 z#&=+YO#GQCkmM775vUAge??mA9~U@2H_K5T!&R9{MQFIjfndA;sBHhsW1Tq2-4y>4 zc$d>4+ZE3NYF*_Z?Kp&`)bTx%Bj%@M1TM)GcoUTYj))WadF*#E#~PTn%#0&=!y%wL znu<1_gYXwgGY* zb7WPrH{2an5bFgMo0hO42TnN|Nz;i;mw31+pBX~5+B3F<$tO&OgYp(gYTsOIy*OvN zFMMV3X8Ka(|VfAmkdMzhi-FST~nT5JaRDhgxj#|i>=i;_t-w3~Xs*P!@s0+&N!NE5*9+@ zHSNQvsMQhnELFKWs#y@BolhucK*iLF(707G*Vdl3*edV*K=nvnhjzYQ`LZf9tv*+- zl2fIMcFlrS`$u~ZEiHMgbVYhyGAig`^MBiVp(WNc&GR5lP^}AZJ7`daZbc*h{Sem- zeKuSX6XDb0kv!;wG19PQc9Pr91?;J%2-)0-lN6$gm>pF2(GL_Fm~npb#5xr)7XH0# zDyvnIZeVYGc4@@>3;13Az5SfnjUZgj_C^vfx3RC8Mipcvi;m5XB?S##M|ou_{dPo8 zEJq_nGX20&$4E(CMG3_>;1bb((}-(xOZ2VuEqw488zA-Vn|+&*{%sLKR2bJ|RIo&- zBWd1g-Y&j4Yf30!gH71eDP=;fxkGxqPi(3e%5IEv6&6|@YNtE>OjO{jIvOhVhbjXN z5n3E8X4VF)RYcX5+9H`TIO}Am9*?O_{;MbM57uiVRnOI5`Z_@>cUQGatD`bSsU$Y=nl+DLt=sawx7nhlEH_qvGT~%69A;b?}ymtw&T_xr6PSVK5{2F zPkvaDxM3PVBcB(Cj;l{D`|B@ShmByu{;N!Z$uPs>;NZ}5Idr8?a4>!>is2i`$EKmr zFtuOp(VhL_4K%cN{e80ihfMJ!bo6zJxj)}f+e*hl@T=3?($->3SJTzP15PzOWIRjB zfWVUzTQ}0#SuEIM6`Ko0QN}2lp1~69`TX{K-uUnsP8;y&t#j;13gpCPy0*zEQY&sB$pSkjfMAg=YC>bP z8@e=B(_&;6{BL8h8=&8)aeZFbEj{3vOo?vdbl_8oH9mxZ$?3r}c}O6zNMsmRkIZX2 zB&{9JT@e=PMmLnb3<7ePOibzRaqO`ZYMJ8>YC6q=!hVdUqAVh%g~uQqkBtZm6gEAj zO#cw!V#HRYrZT23?{*C@m2myr$RKF(`aIqR*Yn#U+WIcnv3^A1;g3rA)^`?x4zEw`sqKW+_22ylw#f_zVly(bp}c|1w;NgQu=u zd++cW=J^$!iV(Prc6}wP12FGX@RJ`&CxD@KvtGZ(QGn;L4PQM{f05^SE@FuweCmu7 z^YbimLUEp3;eUd`M!#b@>3I>`b3kpgMFg+WXvwo%5jnyr>U5Zq5tz${LCCf;n;gw7 zXKCL)md7OS&i<@iw6*ss6Qd$wg^{-gYyZ^9`#`aH&~>h=CHuM_Ch{#8HWlH}*7!8R zE|?B6fvO$C32bg{C(fpk{(qk}+_Dklz9s+|z8M?=>$lo!GSCF+1=OcWFbiQ>pC6|Ha;rh!Db z{_{UG3`TbE8+K7v_#-{eJ4um|i3n3$$wDq6q>a4Ra%8tIn%QoR?X~wV{RYV4rfoZy*p z;UkA+PjN#R?>k`&AxFkb3}iC<4S?~jA3*PCf3Z;((8{Z^C%OF{Qp~uC1*;_x{^hG0 z?$Y`Fm}*t5tR5@=!_|+Pe@m4{rJ&3c5}7F)uyaUeIn3AocgwCuyT_+>c)-!oK6^Z4$RruJI^vZ zAQgX35Nkth;XLXxcAq?2^jFQ^o)||MDbDwp4;iSrmobug?0&@0@V28rcao4J*r+Ii zr&LI28^V}*e~-8goTCc3`#;>F(7rbMy1FbBR5Qa9T3DrIrDuXT`Lb=$F8)m*fdv8N z1qkMBDbcdetGd%3Jio7VY?tl(L*iZ=C@3)IZS2lcq6mCQHL7 zqR`lH5l22H*|7RKP8R5#3smFplIMtcsF)ZWJp=!9k9*R5kGY+|AEvRo_4h0gR)Z2z zp+BIxkY04d`|L~>>i}~Jr7pF>8YH%R3^qqJcf#GJ&=Hh*A5P<*2Om883MGr156sIg z$DtNy>a?s1yT3zPv~>DLTc7YcHO1B$>k{_or3oazll3(`ef0XY!fbx()-fxY`|5Qh zOH$_#qrSL!9fWZlHfb~&PSb`IXdZxMD)F1<^b0UQkLZQ6;*gQ?&absV|0MB{BFnBN z1X-}xZMPGIqT6#&A{MNRlGwuaXFHDu#J&U%RB>9oIE~tcGN2RFeouM*CIQWg!0Y4@ zNZe3ip%=XHHz1)Pl9H*1p~i`jv_}c0(@t|yRN-(F%FSRnPDn*=`(AfY^$D@VW>>MgWiwOiZJGf4a!o8-^@44qe%uz4 zUS+u^aMXTRWB?i^?tfBDBhCKEn6w}iGrz1)g~qe|@;+``m>ujGfn;jvyqIwXLS)9N zvw@>44jJ^7{Z~8ze_Lo`5RiqS3RXLCLy;)HQD??+W`|3=>K`-_=MCX$H5Vk0TM0PU z)H+@m!oN`Wapir-W*K)l_S{`!Aq# z0?nSkf769_N!H>^BIB;JhY8RY)@-4nx>j6R7;xfEYt z_Oznec1DXq`@oTp+(sfxlkp;LDcq6p8cQK@=SzMwOOG zswq3!5R+1nPdicn(v?SE-xSUhAg3BdG^Tea8#Q6%L$X+ckE_0KJHuHG{o@X5K$I+4 zH7_HvyC7Fm*ut*-%P6BjWHSm4yYr{p?f3%0k3 z4k+2}5fHhaRUA8fBr)ZN6f335JWau2wvbJ$jO{0Vvd-2AC~1-Kj@y4 zgl!H99B0k?1+cAZ&DL*N3*j>x@I4IxmRidiByZ%df0j=h5uUMC2F48(7#CEV`T&;9 zJI3>>8j__PX*v6hsXAWC6eQNmOEKb{F*zH+9L{=52FEz90AS6r{>!L5ztVNE2g$fo zJE}5&w}4HS;Y`8tTI+%LQn^_WTQam^=sjQ%E9Y+zbY2;v1PcuhEFi$pk~?5o5j~qT z$-${6rKzCSPJ)0&{r~n#p zf+-TX0DeuMmd-(&PKi0*?~|5?FL_$FT)9#~x~I!MXe{L&sZY4^?k-a`&`EIyTVl(U6T0OS&Z@fG zhTFeoqnYy9Z%s?oOcy1t;lBgxaoExXE)S+}A|Lp#9i&p?rr}cls5^}a3~_%A-te8~ zS@z<;ONlZ;mc7nMWMizzpE00&Le%Jo*u{)#VFT~csiPlBEA&1{I=V2zG0D4R;Da8$ z3!~)Q<5q^5b(tKfoJ&#^tg*H=Jr+3XCp@26RG`l2v^ae&uiD)L-2KLmbI_-Ha8VOU zy=WmfooL~35E=yt0qdbaQcZIn{{@TwzFs2s?{sJ48M5;SNz#Hc@2nFB&QD1W` zQCyC4fiiiq)Zh;dM@i$VE^o6&!seVlGwDs6@w}YFquT&l#{TQ=bNMC=LL&Z1TB+_k z)y!zoGUwt__`+nLRdaG@=X1l${tf&QflAQNIz|PSm|>F|)K*<5eju_Zppr$PZZ=@s7Fr7xXjd%$g>(b$FiwiAM*r!C>?AqdyI$ixt&}=(5EwY15O3uO z_x`akJlTQ=+noRV>`)L4+z~1&m{0OOmM)r4iUj?fP`U2(@4ZCbxDihjlg#Ipn)Gm7 z9!rblbWK4YE=WAMBqG_4A2=V|yuB0Qa{d%t7O8W^1iEZRRX-EKP%eGS6z1XWPJbL% zyPok%T{zRCbhE_#(u?fyVo-b{<5Lz$~2!XHgP!K0>1pzwu%WPmC> z0VThloHl?8zIgP?PDv(5PJ7Abm`QImkx-XMT6!B~c{*r>OnL7Jfp;fi=e)?4Q+nGa z8P((06g}F$UFZF;aiF~ORDl=l0% zB7dy{1b`#hN_hzmgMUq-)A2dX=#e+RC@eZataM{vv=2@dn9Ld^ECodYE$KVWMx2!{ zgp;>S81kxxK&G`q8@BOrdgWs2z(#?U#=g- z$Qs2QYvX35wsDzvyuNY#yh(HV_Gu(kF-56hH`oWpOSWGQf3WH&M8;WBO&Z(zjMUx@ z6X%}$>woN7Z~DswjYeE0(1t7%`{!q`+Jk^5*V39lEskW;n3%dvt`)IVG}xkcm^i(~ zpSuR2k&UQJ;OUx5~?t}M`(j6~r+F8kf zx7j{cX}a11sB@Eor@V_~X=YZhr_YA*BaO)y(%^4qWiz~9F=vt@Ls2%yMWJf&m;7k7 zuPuP^I-vhmuBAYl7nAt7d2-~L>wL({X9$fm4}65VeB!^(DtwgBB~>t#j#+DKduW20b;qZ+xBN!bj<{fql<1LkV$mm3Q}HG>ms z3Mm8Ii)kw^5kqh>ZRsL&3V~XYo~7P@HH`pb9boP%nrp{1Bm97L0l;T`8ZtUPGSrPp zuSV7xF9B|#;rjJxCaPeY6M2&v8q|UNBMkP_4Lm8rm4yXT961iO>&|3i(qQ}agQ45m zq*6c8iwrn~1Nax7ys^2KT0`eVZghDhr2X9Su39aJ6`~0l5A~Ij1M-W<;@H&Rff-tK zuMDK=u~L^+nPdm4Z!C1`PoK;ERbqes z4A;EU>Y2WZ8IGtUraugM)Ks8(cg(sn2oOmFI zzDvjWfqEWdWMqM!tDF{?#pVHbc0iIHRtJfLtC7c$?fDi*!8NgDi|gNoXkSVD{OE6c zh0^)dU&OElNw8$F*!h8}jQLjN$!0YpF}8bM=Cw5nz+7-V>@}n@lz^Id-BO}KG%tou zA?i%{#?oprOKELBS6sOqV&OGk%&Infse)6+LlbSOy`dW}Jyl}-6^I~GTE-jjI)m?REHe|& zfks3hv#OAU=Gjxdi{Y}qaMg<}Ab+)*lA`*8o4bngEoJF!59wEZwiT3OP)!{_N(`}w z!J>w4B3pphbeT-}TT567P~tSZIiI%J>is?o7p|+yw!r;U9357VYnuZIPSwowfL{uC z8Ng}~JG?t*wdVY26@DA^>8JF;WfVM46j*E+$H=5{Oom@@uHX_;pOk!RCf`dqGwLi1 z;L-d8F#p{k*OjVO=@W49LaBA8VFpi)g#+E;Pg1i5=Ow&;>M8V({92#!y|o5+-=PhJ z!0-r&4HBSp?E-hpft!bxO*b4aWpVWNCa_)n!RwFA$&j^eNSX1BC+&UqW3nhdq5AN0 z5o*0P8WUfj`q?e9{tm}xw}6kwICAX8xsWIEHswe|A5h!wR8y6hG_rWh$(xhf7hdNhZtG;TC16@!(n=`Rb@W^=`R8P9hi#F9X-T?&JA}w0bHX~icLhuYf{L1UxlMa zCD3}s6XGo1GzCM$@H@4M6+Q9PV-qsl#O?fsNp<2Zt!i?UO_%u+vyVJt0xFGqYKx6{ zhs?x=y?$N1P~`>_1qJ+8OuRHowX6YXP=bQAC@6=&1|{*d^@PIen31T(#-;lAJaQO> zLS`(43Xq73k4$XU0RjHYRRxWBJkv&Kvxz0(fM{cwe|}t(XyAOE$AFRCyIE{D3iOw_ zDE_*k^P8(UAN3<9jTg8l{}B}TQ;mB{fW;M)=}HZ%oZ3y;QIma>x9K6g51p$qV2AI#QjWMOX_dwynPA;%(aW7n?SiVMPryJDUdkgLA}PihBaraR|H7T+kyBW zhf`fviXQ&F`0;oG{?-+W?4)VyJ?0O|B#T&ox_W#1=Z+AV8a{K>_&DT}njM4X_)vj) z{J{YQpqFWD+t;uCGvarP1$0`Vk&}z5J3qqmUekiuZKbb^ z2GagjEJDDpIEy6pQ6aOQ7yjce=f4$>^@8 z%TS{TffO?W*b-zu2CM#$oi~pCx;Jj(@C3`zltbrp(@SpU-XEIY)9UD2l>-Syy%Ej1^Hv+PIoBkT(%@7E}$S8asI7lVo!LD7ma*% zZ$`iNrxf*-+V_}_N@o)#79u32IPurNq8*ZlZ!u2gQ$Mo7*sm_{kGl{z-2i8w^u>!8 zJW;tbK#DuJs(!lCx{9oc|Hy+iA&YEX(~}mE@4YSVR!n-1AMzGy5x;ZgcUy(eA?x_s&AikWHsh79F^6s zztROOGF!(4yR_kk?2 z{D}jHcRu#QpNc*&BJu4l`>gx#+rZP<(s0LySlS;B2xV*f6r7ur zO=N)2!RN#n$oW%#_LD#*1Jf2U(q5;>4kuDvMR z_voD$yYm@v97v$AyH@QGzF zq<1_WQgHfHcL3Ry%>sb8Vi01NZ6@%-t_h{V2my%egF4MEPinntjdimFXfB^fqMW&p~v zR_wV!lZTeTAe%>dyqYaxy*e29K|YaqgGpzbAGC+(syNYe(##f_pZ^V1Lco)vr#i97 z0t>L<8TbXNd2Pd(tXY7Hqgl$&%w!G{>#p9uDC~@WE{9% ze@eD!ISy3MIr3jTsy7-<$wJv*!{r*`$r-DYqOAM*1Lh+D|9k*c$M*mg)m(-g8rmcZ zv0-E-NP`#*%?F|=8cdUUnkp!^M;`2gn(37KOhkZwKejSUqx z<&E#I0D3B%iP;Bx1;Z7cVGf`clpS!Zt53`PVpSpTN2m|8G;%80QK@HE32|k3Qydjy zNu8V*qGl78;U)_viGD~bS~zbOXYLs+jFGIp4m-l8QrotJ5DTLjGfZaGs?)m?=G@v~ z^)vHw#2k+nJq&T5WQE>l@hEnRO)=qse!+PB=3Q+I_IrA-gJ&7HXchle)zt4@SA4S) z9}gr)wr)^z&VaZQ+c4AGY}^lZ#wGGQ{J!15uo1L!mtZ+#)NUrvAh-7Jh`-Wep*~_h z%)^gxg2&UA!h2@&L;@vz$!4jR)DC|q2ILD^UBpHr@x64SX!RJ!Ld?Lw=|nt&xcwb z&8;vR*jD{O=W?mz8$b)It(_7Q+^^Pc6{Dj{X}zu+U}%h*H?xaT+@q8}qF&)TYQQx< zci2zX%1XAxR~x`7K36^>z7fT_B}N`0f>>|le=3NAfzHzI{zV=?J+5y=Q@_Z1g+9Q$ zsJu>rQ{Tf7*v(H03JRy5cFPRHLVdMoJ*36JY`{htaN^M0*W_`g-J`YJ{yI7H$W5Py z>f7elQfZpQ1AnlT_-U-Ym2e6vdbhA-X7(PM)^_yw|L@UzgZZDB2sr;OT20^WQDm$F z#T^zEy9wmh#M0?@$|YEIWc=2ZE3|_4v{!$C`PRp>XndZWbk-5s>(X~wxB$Crq?~Dz zGRizp1_RkgD6eN(H*Bci>XV|Zs0b#-AHdg_6zJvk6q&t(?tH>|( zpQw>(qL=lutD9zdz83Q(1(}qgOnyDUjP8}8VxBxbD^9tqxQ{?~sc|3f-fY-FW3*%%wlFB=|vx>C_QCn3=4TaZ#!T z_Ju5oZ9Buxx8_rMLk-x*h3Da93a5JZVGXzNNK3>bfd{&!b}0*-I_{&=B%9A6lb5PB zdsuY(ISVH?h81yo%%P#DdZc5X=qp6ezuWgkNm2n$7)TfrQwdlU)JsWCx?%av zJlY~3Nql3FLd|=Shjl-m+VxyPv;_`@KT5Zo7OlF2-%Nac@{hmK6QYq%ik713Zs+Er zxUE9dXA!Tn_9i7pZP_vGv^_}TEqdp6gh)S^ZN!iPR2~zCjB^O9K!LEDNCv>!ed4jF(9Wu;$ zeW3w%rKu%{=-s~Ge_#K~&*;YVsA=SkHNYr_{J=29)C%L^ zmn5VWT8@GHYE8aFmcxdog|{l#j&WpHcjArw=(}a6v5Yd}t6$e}Cyo={`XsviF7c>OM>Pe=A|vQMli zY=)62ydUV7@oh5@s(`)jmA+f2KT<#}vZLpWVi&AXr;yO3z0>_&1lV3BUKytQ%X%7` z>=A>99P+{km=%-1!cxpqM95q$Xt-V9DI>^`n%MBauH#Pg4Dxx@XtY`g=M2o5kS*ac z9vawx@?|6BEW41j2GvDhM}!QRq!PwDf6iYyk3B;WlC#B-r&$U7;_kcRxEa2; zwHg6+qqP)-$f^_NE4Em@`Sq&a^(@ndcYuSh3r?O^s?Gp^vYR|Am zyTnFNCenrzTC*)1v+^8yML_iXZ%J#w9*LI00f|uNg6Zykay;O$@*Q6t+l}^TiG^ikM-VKV> zTKWIwkNkBUN@D>7;j#A9MEuNIai9*_O89e6d?#CbMAYOk#=aDLpmGK`4gxz^eE zOXCi2N&Mdpc+^``69{~XVR`z4T(~-oxa{uS>1oe_mC}a&><_w9O2xPi$`{27=1ojs zlcEkt(X`C~40#>83U-O?t81*U6Ph{ZJ^+3CKQ911ON1z=-g{%NFB|c#YTaV`Jg)yU9Jy6L4O)W6agG2GdJq3rV67BccU9nCjm4@?HFB0V z2*^46uJ{NW>JGRYeQ*4AwAQgq?3gRp(zNab)4MdCSb!EJ`$X^E9Trwx-)@V%g!4Q>6 z3=C3R#Ym$T>K@Z?aE&fGBklO($r)$$+3C6Bsow5HZ||7{@`>-o>ugW7j%PA5WY#>n zBZzas$3(+yRS;|y z@$2T!x`xm0@q^z0J{xo7_HDw8VmQIGStnYL*Bm+cJ(u=7rU`y^gx+X55%3EbC0)2k zvnR?y;#YVyC!1p&O=GdSv{MO;Yd+2!d{c=nb;WM`VGi9vsdPyG0$ar7BncWOJgo#N z8THe|L}p3M`Bvgg8C;gMV(iv#1yo~VWb}plLF;UtPRE)3BOQ>W&TC|ourJG%+Y$FoWL zT=N*T_6(K2liP4qM-_Kf3wOwr3|y7s#Dz$Pl@+znEJhVV^NC$hfkft!K)cD;rd2AK zo%UzrWE=U+9>z#$xew5nbzg$Yl1G`3h3nJPSAy%&P@!t=RXy zVZ&?p=3>?E?*pOMI_k{OpVR{)7p`c~h&`9663$II>7GA3;BN1h;xoYm{B9SW1JHrT z^9f8vL}uZ-a-S3kM~`q8gYbV0QAJh}1-~Z^Wx`g+6`&Ueqfj9^`=+c}b}0F>R*ukk zud&p7Ag_C&$rIsc&vS>tq3ziCz9YhQs%ph-Z`cu4#h4TcoD&<^C~~R1C=_x-F-jh3 zc|yW&1GE}17cEO_iV$Z}4krUB4P|Hf!-i#Tp57&Z)R_hQ z(z|3;Ao_++QLA3;lT2HXCZz%nG+c=%QCbmJ%j@BYhE^d!Oc}%s*Fx^Dz*g9Q5JqS( z2tMu6JcC=YZq9b>VN5!nmLqq4odgWhl;MN>r*xi~vM~cf;z9yZh}RItujbD;;yXX_ z5h2MiL8>mB_*v^4FtYu0Fq0o6zD1ek9m6Z$8tYz)(AP?91Jc4s2uts0SVh4N;)!`Z zRPuPbXwM%r`FRl|Ajo2;u(ijME-59S876k zP;2pDgVAt>Gxa!}v)`qAqM|IY1y-=C-heesz=kOKXitQ~XTFkhtS4KBVho0?x74-a zhA5VzvwrRtQNn>?XSCRl|1wgN;b7z1)<8xpPy(+GEZx4+V2AVTPhp7B7m(F-z3 z_(bcpQK5X~vf&luT)bPYC=|P>P?a205XbPtk#=o)roqoRZO=&Y*b*s+X`-qowBCfy z49_RQdNRB_a&UUPZLqMRvvML;_#h0K$MjB_llauxs{g|(MMGGF zRkTIZxktdbH{OmZPMKtm4r7Zb>N=ONHoj z($dG1o1lJ{$Wf%f0}-^`3HUJ^g|DQqW9+t( zyC=5xbM_coQq2;4`|PpU zc)D1DV~J}+VJD`fLGjOU5+rGZIU~+Yz;q3_?ys3Zj;~+-WcDxNT3Sa_yFu}NW|}xw ze2+^#qtvwapYr2MmFno8=oK;7n%A%1P+p@QUIotjpd7b0t>T@W2+!dJ{FB$B8tPr5 z+`N(dTbOcdG24Rw<5eBa%PkUNf&uuDGl0s7AEsRXP!xK zf~u=&XyfRq#5;`hw2|Hdxl9B$q0S%Ki;LJ#ie$72TZCgz8*GwvE4&_;3c0IkHaTFy zpE$`MaqHh&v9#0B;(%<~_)%F$Jl}q3sv=^n-L_=BE{tK9yddu4^?<5dxm#`Lw6h2$ z_Gkkr#FNGvBF&*<>9HiEg0ew=V*e-=W1#d70E$?M3gTfG0SwDR3W>yvb& zSDEEY=gv7bD+*0T`=)UWJKF2TdKIA{7i)M(@XvYZQAYRo?4)3G9Q&I<0kVvmD#uWC zC|!g$=?p3@&xy-oc@(YFlEm-OXUqYTMbj=AUS<(W?IORSHFrXuc*H-KnZ5jkP8Mqt zC~XD;V(wrI~_e0q!~IwSJmUr7^K-%yV(*uGP=x*aUSgxWShS z{@*FSPA}HUlWa-_T-FUpeu9gW9rv`%nD2nUKA8%1W1gvXeb<9zz zih_JOOIB_yEg7uOp1@#?czvWdbw(KlzMr8!xFysh<>Ve_`}fan6S)pZ2xVDhN354H z{+)gWM1y_GzcP93U0os904E(1xN_74rl;N<0Rh}6Fl1q%hce=eUscDjfAsr;eNSnTG(q8 zr>hpZdz0g}?NC*JA(B`j=GAt^=uQKxN9Z*;^!lLd!~K`He@3{?K?Tu>RDW8Y_jA9L$5Pk}Be>)N&<|UDL~nIfB+58#gzn}St-Lm`=-GmYpIkg~oK#&~iP!G&6AKq>QhmHw9fvcZ zP%%!z{TxCsGWqjTbLF)$u3UuRRdiqNZ#!!S37j^1*QkW(K=VL%AH)tbmfFE=0qCQv zW?H`PXb@-97R0V56`m6`&9oFMU~P*A>A(Z#i85Ssxc@GinwM~5adI2}=(qZ7+xi(Nfg^Zd+*P+&IU^6+P^DI_ftKJf$8eH z724vaVW24GjBL0NaG;)1CaU4;ySLOcXsKlME6MAbv)HVCxyl$)0=A^ z7UV@Z2ueQ5EP))3X)q2%Eg?+CcZht5a=Bo{JS>m@x$VL2enYu@Pa=>pua^w3TgW=5Q zrYXOcC(^E98Zva}(;;wP%AGcG`i+-1%h<7RzVH=Y3aVMX$p#y(cH(J$_sg|Htby_8 zr`b+~^NC&tjiW&fUs*?}_df(&;yEvo$CFnKwy5{(PrS-q*_biJ7+f!<3Uk!CRRhQRaf0$Z(U8U7hQr z7~wGdbXGpbX(EE%bbI!>9A*{4k#16OV?9`J{krlC15)^vDs7v}wfbUo558Y^D|YZg zPbO3Th`y!+6m^!x$^yVJ97ikhGTd$#e$tX(8?(55SfqhX4M-?2`r9y6Au)_lo{a(l z6C>wjd$NywaF^6l&Uf2nJR@FEM0R%{oEmj;k}X@@0)|mWvu_-c_D9QjVuuA@#>^+* zT9H3c{AWVffOKU6K-`MNLQ82OU;XMbOWlGMSQ5_ao3_7H(!A#Yq6VrjgWtABA2BjVGB6{>>?d2OuI?rNo}>J%MND5)g3bGr+cdk4(VY3)LmtV0qs?KJ z)Oc<%D_x=wrn?lR(+{{5=qY03=kO7N?8ZOQh~Fi~Yp=im>F0OM+pUM+Jsu&i@NiJ!%?=Uh+9`Kud2M5B+s(`5IsnYJ)m2mLR#W<|+Wk}msfmxM zG#{31yNGGW7KPQ`?~6}};FbnI-4;DzgaTH6spWNBT-Sv?iL_H}x`t?U;UoP6p3Lo} zk;&2-Hq^ev@Ez97vA8w@v}sI%VK`4;pGy9sH`Wkz@VMbK>M>;{f97K2_wUCic+V%! zHcQ;~=4QptCO7yS!DtksHvWkvgO)C+xgJp)dd?|1*aMJ@m}!(hK?CP0@5Ikg!)fdZ zXDm*F0@+~!?A@a4*ZvHmPySDL)^L$m?NWAPT`XE_rAa7%5ut(X#i8trTI*6p$TY}k zg?BaPBT56(iKnbFkAuyRlbHw+F78*9b(%l&xgF%9fqMu5R*-mZ`njKoftmO*5Do{t z7vbd3Yikl4Bivox0l~4=)j0}^2j-b1MqgQ{G7x0(pWIFXUe&=IW&{iBPtf~;$)D>! zR8r^Z>i7TJfJ0mIJkxX?h0&J)3&pmYtVCDUv>ILuii}fJ@1y~L$PLcdkcAC}b%L_z z%0#vV3C9v%;o+2OSgNQ+ zvLC4V2(5b;L#jSIjw%=_T0pLxp|C8^Q}C_fY4XxI({*v zLt1_EN7xNDN(f>Pw_bsFBi`8xq7K5?qPJk~ipcau?ZQFAL~On*-hXq``N2{2h7Q5# zJ3y-d-g+k-!W;x@KP@w`SHY@32=I1A%R>2qe{`t)(Z>7bJ6G(#Upj=}s^PHe+-LXu zbv{*qc9KvGi;y5ickRp2E94L0bn30v=39|B9#3Q%AVx65ZE{flwz%ij-RbFc_lmf2 zXLjO>7a~xSYtKjAeqsWiJ6{5q?8S3cNU`oPXNZLHaeInWZt^#91WRq4onZn_JD!2f zq^Di`n}2N!0F56YEM;pVD!%|%-UOZYzsL^~>j_k~8$~d+qy0T+3ct=)XJJojUi+u4 zm-pDdRHGeA3c4F-7{Q8^Hdz9&*smt-%7I{#>kqxakyG?+`R-W$W1Uwxw<|&G1|v}V zXu2(Tt5HJiyH18cc){8&kW{3qr;wl(Qm`s4G%jzTjtmu)JB zU^6!~y2cx<*=K{C(UtSkiPS5IwBrerMN+xbF3k}rD`_RHiXoqGa-}Eh4}K;F-G@l8 zzgJF^Y0#8cbS&R`^>)5I^Aqo(tr=Nk?_I34U-D*^syqR+j(OYh~y69p=5z;!&^vEb~B3_R#r$ zGJjr0}CEPd(0gNlRXq|H(HDPW*^_MLq!jTY3}*%C6=Aw@QM`P6NQ-y>POKHt4`@hs=^>ERqvr1G3;xKdEG0v|tk zSkwv*4KQ~+v??S^qiGEOfBV21E*x{^i266OkH%Pd`3zu#CcC^MG>{&stHqA+EQ4|^go81CNmun^M3+7l4=1IDn92qnuI z2NqMH4_&wI!)?;w(B=*BdtRED+y zJ*@bhrjrYqM@c=$EC@Y@Emy$%H}NWoLhXQQxCEvJ|1`MS(~>z#X9C=s9_dFFh{7IG z=ler|8Dv~&*woy7Wem1p37P~rXREu!chcF3VfnXz#;eEgT5h11>j zxu+z}G4V#wu;)W|Z`#w76w=2+cOQe&YE3BW#-=3}C|g~16oIw6E_D)MbMo|v2DJwC znK4nX&<><7iWeORxGnVTrT?5;^0#%E5a6H@-Lyd_~Y$q48 zt1dIannK9qJ^h1V@C@m^A8BMKA1TyYTT_+ug<6f_i@`Xgae|u;Q%>bO*ioTZ->m0+ zm0Nbrr@|45>C1?>lX%8GOxoc+8=pPXA(xZ(XYU#Z-miE3`WAA@f$}`863bVL83&9M zm%O9e2Q5H{zJcDs6@=i^B{8&TY({@Jne@eE0oD=`+G910GE?bcRJB+Bc8^QPymbPY ze8bm%jJ=fsZasklU*V_376d?X&#fd~_Y!Wa;K?Vt0-@0GYm{aeAyPRW^a1c0UY}w~ zw_af>v2sXzp-S-`Z?YB*G+rvO)4cHcVKMh99VgK3DCwHtxT`9{VjBJL?Z!z}^HnrV zACz>Ved$GMQE@EMoQSo{P{RnRl=77f(Q-u~e4j+uxXsq5A^W$2&jQYJ*X@obKwX3P z8f^cE!peUkG?&-^{1fVag#L&g;cLG+WJ-LN3Ur_6RLRVb4i2#z8f{yz{#|a5Iul_G zmN6YwCc5R)2}r@_dw4r#Q=;>0QaR@agbYFNE9RA0n`>Tw$?f zlcKG3@-pT*IUjwj`#DuV9OV7wT2yl4EkD(uApfqu`Ieh0k+_oEE1^Jaqw5lw@iKC7 z*Dt_^R{M>6GWq1o%nUyOByr9uAsrn+!VIOclu*vg z!CM?XeM1t@&#{`!;%YPS9TKPw6}dm^^5vo?+5-i`DZ0OgoD#|y`4I#nex(4uOjY=& z?!^X^CG-l=nyi0sJ^7*$@0?q`_$b87_rKM4z`YhqhHUHou&9d&DL!-V8VAW-tEJ z8diI$St0S}T375ZAw@7j8v8mZ5W$!}^W z(|g3U@n7vjEBd?XK_sSE)hE@NB?DV!xQ!?23|~;{b=OS76_5lLC91!C?DGs`ra=OE z<|wN}cV2VX`tn=-Vqw7NHfe8Q%+Xa$gvd*D*dj5}CNT_H zy7$^w%hE{Y?0`(vs|F1~?=1U6UeUr-(Sbl?@WR&m1KzU)z*CHvZGuL{hdzfs7D1!H z2n5Tb8y06+TB|B_rU9y_0csJPPYDkq{f^2Q*Q82sA|LNlvpQDyi}#{3|%(*TW3Jj^Fz@y67ci*eRsvMrihQh-i$_nQYabf z#i?SRj6TYTdYRtQX?^DQf|gx6zoO$jIK838-l{{*HQv?O zDbU5s8^x?4Ur<^YZSO-|-{s2^Vh(Yij;6amZ7fK?2sT}Rcln1}g;vyWgmc(?ASYO# za7{ie-sDX#3s8leM9}z6x2F@FqVlNG5Y%{|!@p(lyECMXlRiFR!0`$6dOJd^IeC)I#HOxh4=hb#O)?l04B>%d! zh_jLC*e!LNCe>3x6Uw=1q#KboLsYa5e0RBA6rTWOsGIN4D_#BPS==^Vkw3T0^UsCu zUpLlIkVGxZK!al>jP_G%i^)RX?q1eB!}>88Ri&dM&m9AZ^TS4vyN#`ub&%>==XDhQ zvNO*>)D!})$YrEVa*e33EC!#9z6KbX8l-gKI%bSL6DG8*Z?~eBV`t){M0dM6)*eX! zrAhDEo-_A9Zt8*@m)nS=&wtXp8}C0)-v@Kc5jtd}a9FlJ&P+Hh6+&hwI;4SX4L4?g zbkrW>+k-+v3y!aoRGgyGtjs!p;e~i4=<>O_GYzc`?d3!=DO;`i_&h@HJ-eU2Zolzc zbd#}Y`r6n0^rh>`IX$)C)f}PAGmP6?_j-rYbjl%bgxH}Z9wmOgOi}zZW2YCYv!a9H zL`k%Tg8O`Ix%`@QstlHyt?(})pN8yFU?|ig(f7ynRIRvzwKA4TK{%s@S$09dVMRaf zTQSP#$XY$~X-piJaKD>NiJu`K%J(+y*uBV51i!RXnS_&Blj*c9;Z-y+|KqTgPAGDZ z4Haz?O~kh7FxkAj!vt=A?d0Ko#!2cqR(@f@pR;|;io67Nry-IoK5k}YyUV&s0V#PX zT;i$?Eo+Y9k+eU{PP9T!L<{X}s&z$&crZ8YUM%+8lhk9HEMxU+v(W`Z-^B`n)n5uL%?Z||pV%@nAYpeh2$$#bVVq}b93;TgE zQ{JS zXI$$1G*Tf%D3gKTGaJq+ZAwb9QcI0~{9$AUYbFiF zf=UW|27(@dix+4C#;CQK`C3utW0~tL4S9euJ%*WR42z`^{@g{Cz%8}c|32C?B>}tD zPL8j|=c>CIifZlg0pW(JQ8Sq*G*5-7sYtsmT-J*7;j3%NuKVo1c5e1iaZu(olb#uk z{%t66$_MTVqeFiG9q%_aQL?Hf_Lg}@(=CkWDmZCoM$hv*D@tn&VPJ>(C)YF^veg<- zV0Q*^GWi9C!$YM%>n_Y#{+(bbE7M&ivc9?Qr3TWq#YoD&GU}Xu?B|%ZJX^$&WnsQA zBn2k2&{F+|*BKDEONLO2$AVb1Z2k{AU>?9wxLsOt^U$a@{uc~9z3r=!Qa zcjcaA4B?hY(P}PFCKcc-fq6`dO*=EGPMenvSN(IiY-rDlpwF8 zt^$7|>Y?5S^}(SjRkHU=mQ>VIOL_cTOdg`|8=Lyvymo%IlnOl*DXBh+J=lcehrHb>pV?H>4C_i7+zbYvob7O|u08hl zslI9G=<0ub?1+%_(7C<}II+$Agi8F`O{bx6k`8D;6Ot~siHo)uiL>&8Dn3eDjrOlK zc-1{5T}Tg<=AgTs1!1m&#qqdF+BY__*hqtK`BdOwDfGwZL5Bjx5;IXWin zbN`AXhgIv^cNlNJ=(_nZ3@Y=yQ+zEg?y>_CK@gDY?r3{_J14$=UC?;jp7IUPe||o> z-=LtSeLQcKV(+^C$o=$y{%Z>FS5;FFStrBYg{%!v0Bxf`i4Q8&QAOiP7KxZ`)~j(4 z6L9@vX_gxRL#LpL4f`qo{cn@xlU?Z1JE}LhTYR72c=fMR#*eKxmgNV%NQxz0^|DR5 zjgeRTcJtf6t?aF>?z45b$Gd_}w6Xf9#cv9d{TVM_K1!m^sBQ7NueAO3b)@|LeNpC8 z*bZ>X5kBv9Jy2mUu80He2^)YPt8Hx@KEGQ3@|&zFgW;dBrmu5zPW*cjRMbldPpKay zj%sr|SquPDAB(^ScPR#Tg^KCu1dnhrCw;KT+ zitFzk-u(C16 ztsD0fkcnEr=N&R@aRdPei01yXDZhRlQk0_}r{gp4*gN<>Fkq77=IhL&XbP?K4fZr4 zD2*&qZ^7(SS{}qN2JN}c9Q8@jjzOePXUzAMR$lMeicq_hixHy0bvQbOH zfsVG2)*#sOnk6-m!qK&O8}Wb%%#l;NKlyG&*_s#LSMeE7edcm-mjNN2Idj>%J27kOl}0 zh_~9hn&xvWY9FS$cHvEhiEY+l4~MCWHC~Pkau_N}R?UI8DsV&YrFj3Dc5z?o!p4ZZ{jGe=qgFmc2|uu}-A0<_pL&Ig)$WFwS?V)Bm-Tq#Uba1zgL8#sE=-6=;MYDy0f^M zxQc(x+|~saFed5Qg-gWPNA@sk^I&P~}ULV-xi?+WMJB*qY&epiP zT_8$x6d!2$&1M1_u#Yvj4~GRzmcR$q#+FjsmL1su13{dX$XD4L$uC*@&a|9Jj8>0N z+UZ~wp0j~TE&p0tFM0)?c}HU^-fEGPOoZCf95#Zcs7WvH9M{%L!YQqvSeB}@WtilLu5iv3 z|0hz7JW4t0jhfj*7bo{o1sM(+%3i#f)k={)IU$a?cI z0Kj#2^$hv+V)VH9pF}!_sI$$$HtWjCP-VllGFV{1F7sU`zX+}NDj+&#gW|G$?fmSV4QmwX#UjvuDXX5${E>Mi<~5J|N3QLyTe*L2a*=z zjMubtvu$h9v1Q!hKM)HLPkII>rmzBX^_dVzld!}_Ki0{aJxDClfMps>?;H28pCN{u zB-cHSWX^-BU6QkH=f_7#od~RPtKx_FCay7aP!EV4spsgNM2e+nXo%ad(q^$GKkB!freQb% zQ$ESjw@Zj$ljwF!>wW7YjolG+I2xF^`-G(ND3)WLIHZndc*&GK-3$Szp74~8%VNzG z%1y$<96lstMv+&}S%*9nbGJvCS2I35dv}ZECM+)949R9pL6ZNAytl$0M+SJ0(33zA z#`#DRL-QW7oJgU~_z^_e9ZzutQ}EMjkWQ=0VK6=3P2l8%lC#!IH!5m0Ac0oI6&0n@ zm$8YPm&d?fBhoE(+!vV!7lI5`G-2$qkOlxJ*;4ioaTxQMG3d&Ua5#nQVn(W<{GU=> z9`+pUCh5Ox_<(jMbrynF-GQTe)WS97zdv9>zBPrg#QMwMZj9O|iNg;v;H3KB?lmnz z?AGHow#m~`R~|Q}3=7<~a6(N$8%!Z4ar%$7y-GDcd=nwsCm@#Z2_3FUE;6Mb0IW+tEd5RvHDvt7>by-TB^c^PTrEpzq65e9!q&1W608)4d9>(np_~17gMNP z4|BgeQw?Q^*PdvTka~Q*t=_UIKe%JM-yfs*41c`h5C~NJ=KlH8$qult0pm%xJ0I`9 zi-O-OQ*$>`Cge_JkwIG9v>mfdfM^+jtjh|07|BtsVE*y0OKe6|_V#8v4eEI522hkY zuIN4^M}i<=A_hhL)T7tx0Bn-vtMV)MX!-ny^GN_%>SZNspruicBRTFwxViMzGDe)P z!Lkxk^G?7zmRiVMAhxSN7IJ}W?K$p<>S)X)dn%`#Kx`v3jt?+*ty_!6k)W9%dUzsk zxK7Fba_e2nL&JU4XY{MIU2I$fph~&8H;eSMWd#n*dIwLB#Z0Ya{7xy@t)Q@ymB&C% zk@dh})14!o8DqHSE`R-bPtWt*I#{&xXQ>?rF&cxQ7)DV#GHU_vUtH0oA+4BnSVSh4 zpiYm-5wE*zmQk$C_y9(E^LOrVGT_X?LqCW(xo47+>e|8BiiG6b-mP~33uv4{2?z+1 z9`;>%;e01Q3s9(#6}rNH>6A7_2-2b`gr-CkY$1w-;!f)^#=MNdxyp=jF|ow5Qz5Hi z2a-(rHc?4E?eL&Dtf-<@mNy_@s6D}@eiePPYL#sjLC?*j{xLEp(90kR>n*<%#Xdxq zgr;I2B<^g$F5D!VR_V+rI+8TWFVKb;1BsVSQ!7Y5i|vh6X)*(+BSXN&KQO|#m7v6N z)EXnQ#p(zid)S&G_F3#?Q+cg7NFQ7q`k|Awm=k7Jw`?DAKyEM z&9j`jTU5bszDjJfH8^B-NE_daER}jIBKuMzpnn0Zs6Xz>Wq@TGV4HLV70?k&@>Eqs zD%7f9HlQ0F(Z~cxTW8TtYsH(aDa)UC!s^pd7TB)m2re9FX)3j5(5*v}282J1V@65# zw|7K~1{Y|Z+bn0|g>AZ_ZuKc7wAcCh9`o zphD>bBj49U+UU(TzLxLPQJc1DbbGdTPu>`Sd_ip?0{%$ikvo z$hE%)!GXgzH*oREEB7R3YK!V_#Ff6mM68eYW!yT(;zGiyWq^H?`AFBi$t~T!VE%`; zIedeSJBn(z2N3C3#TOI=#gkgh^z|)4kRrL1yH2@7xjuMlp4@dQm@X!H>VEXnmvVqt z>bT^af(m)2dXU$@Om|F~iYRmNp0g%^NuVppX8dP({i#ZoN_Q*47^K(2L-f|HnKW|c ztfxHoi8QZ{S54lgK&4+^)P5UaSOMn)}E(f8IF8K>bwm$oJ zWruyN`j#fSDG6INMMi7|6S&#WOntt2BU)lJ{>O39FEb$U3^S4M)vQb*_qP_Wk{O|8 zsn0d(~Nw;v~pU7G@N6$Kxr@t8-)yJOaG#;J9T_JbP(-bp4de%URv$*@7=**OBsB=;=nF}Dh-*ggi@20HQzMN^Y6rg zy$0`xync0pZZM|H?l?}{wY_013%+XJ`yDLEh9v@s>NB7VEp3)2xR4RN`1=C5rdq9N z;XEZVo<%M9Hbht2vEM@tP4{!8Y%Ce3GD3x@rPjj2BUQwH8Rz*4;^4Cq(}^U_l2WIi z{HTdI@!Iyx@`?PcH?7nVLQlJsKEr8_ctOeyk^8RuI^ANZ->PT+Fmq@A`O_Y*LUxhk zdu@On@cw4&8IY_CsrDAwDZgF*RzQ=#jl)6v^D&QGPhGxB<}H+0iE6U(mNeYoDE0R~ z#64Z-$O@dwKQg~a3U!V*xn$tJdgfJcqK0-cSU0K&Kt)<{(ygJ$BF$nV>0JHb?o5ii zIB*ZJ#h`1|6PHs}^YRLecHDEs9K#zf+8Ab0fw{#V&C1*3T#~u!x4@#1l7{Ci#J4&o%8mL>%Tk!lBp6DmR34)8pvc*&O1HP%`86)! z=jKLzyt}u8wbn2?i>!H=SaaGzTd_@=baWADYRS2!*k??A3DXm@)*~h`S?1ugdk`{d zx4DGwiXIx%7K#RUzVPXanz@9< zMeU@K-8fy$FdeSWz!cc1&;VrdKb%fltROLP`5`i0uXub*>`+=~8x_*Q!Br8r>J_ar zCvc22WKrr3MBg-K$l$iF&JPI)Hnt!t82TlJc;0Gkgb$nQ-#XGL<$x+x&p@xp@JXwF z4F(A%CvD-}+G(q8DY3$$%&=Y~tMd)liS`ty3~mh_9Q??jMQv)(ya`DuNrL)!c)jj{ zkMWP_)aOYM?*MQ7fjP5|ToDH`kua913Hy`g37TkF4phTH8F58=94hyng{N*d?8te* zJ`9R<7+Q1*RZ<1f^4KDpwS21D8&NB*2HLGaI^SWe;48?UKwv`uXKgF{ zNPRF4{`R~zEv2gnqpfS{bpX6e0T+&kFj^G}Xmh39AP{`N%RuhdO`I|`#or@)0a4L} zm!4V@eLoY}N`J_8U!$;E8lP)hcGo~|AV=E_59H!6wMuHlMlX3?^LfQ{XGjywQ(FO7 z!2>_efCJF>U5B`lUN^pZsrUdkI7Q>|vud@&(0Evqci~SnjEYc7r#FT7jwEDA;&0|n zU({lGb_h2T5bF@$*4;cavkp*>0qZ8{J~6fQCYi{u0Yo?xZaP%NV4ozD>!?#=qYLsw z?<4v#PCK~Kt|rMX8Iln!UiY^D)*?8y0pTlTfOS}jJ^6w07DfEx+CQH5kpS8!hOBN^ z(6~B3F|Wul5+orliMN4peqOrZPbNBS!Sy$%mj)z71Y`SuHjqKm+r2~BWxn%uyjOA4 zLTP{O22|*fvEgg@!u%MG?=#~A{}8l-QlHdc+N$p!?=ZdP(OPMUsZcI9;3_Y-Z+_V0 zWq5=>Lm?0~P_QsN8Px;e<$)*P<#(T=or&>Y5F!t8U}avuy!>oaT) z^d{mGqmrgBE;rLm#N2tP)|?CHASPWqlBkzVzt>u-32VP$)mN9Pzs)`NnQBBg7nl|` z?_%wSisImyIx&QU-2X1DV*7sO_l_gyK~c8uYOmKx?9QryksT+DH#auqHcYikxULHrN`zM5g~j8cZzI|=EoFwdBANKNVyb**A)?E z$M|eZq!_P<@p&oty83c~KLVzGLPdl;bOQh)|dT;2x;WW;FoIF%v zOeK0d_+{P;OTQQM>EMvqY4nb75|Ncf2(1)J*VCe73#FoHT(JMCP&OGSk{URr(L<7R zRz_DS?_$GrPTahT(Ro)7v0zp}Fb8l^gJ6Jc+?Qi;-)(v&`p*|R>L~~Qb|GA-C!)eb z5GV%2cj{C;SgqO!;c4yq1%Svcc$F<}IAaa+QQe{r4FaWv6G#b*AMT;o(ICfxEn>wV zB>d9?Qa_9gk>E9M>rfk_`Ei5WR3KvZ#t_CHn2OVPG~Zv{Gd5Li)tSPL6-3f6x|lQo z_giBFwJ)m>d6*fl7^xLo8!H7dg(lfO1n6hk3j_lbEcXP)nGz0l{=^~Kis#cZOn^_6 zYE_C~l#7`dTR3x(!f_EDj*wJsZFDhJeUa%lkNpKI`g>VD-3RMyQIT6-KYB+VRZ9e! zOel<_xat=x1uh<34Lwo{%4euq22$RaX@BLNY4z-B(~R~(P|tk9svL|LkX^sWty(uD z&=3oQSAv46g@KZ1`Qd5Wz;4?KY_Ds3r+=f7u-4AltBQude3qG(-JD>0)8--bQwh9q z#40=AecNGF>@K&j{r;JV&XZFy=+l-GW~|Z-#H(snqX`6c4U(ZFA5kMH@yA3 zZTM1%Q|}GKHIAeBeTKhL(xC_#%IBPa(bY6>6hYE~m*knKAFqjm>O!Ji==|aD@G&of zf@k><2trRvhIt;#KjvJro8i#E^hq2Fe{XM8h28TK1*)34;_Kh=gf!# zSv&W|d*JD)$?dubP1pI$lg>vEYRhAom|FL=(cmdE zFhwk$YB9l?KWgpy&7jFhP5@~1#l+x!-&hp-MZ;QsVd-dP+w53T0wz!t<|5zX4ig-K zOYLE{&54!oYPEirsPZM}xy@dwJ$dWrzkkuR%;e1~v8ky5_#`0YDhsx6yLGd!c{A_t zH^%!S8?^m$kuCUPZn6~LLdUawy#_Wwl&}fqYNDT>wYw<0Kl~r7tFRx`22@Tj&3n zmGj4Ob1P+G%1`D`g*)fJv2o{-;bA~JB7gf9psjaw4h)P1Bvt@oodK&klZ{xFM}X)= z@b%NxPC)~ZW=16jpweh+o^|>^K-jN?I{Z~4I+dxj^tK_EC%YHK++jRk`|_x=ZZ-m_ z+txkqoSYmM^Jo}K%?NyHV3Up?H{eUDOrTAWvt2j#(iwr2%(Xyr5d4=zTwTg(&}&Tb zt#Fd58U}@$kqme;aO1Ln#_-gH4p689sLVZ+km(iw-rIaFMM4B67rsh90K9kHJe`;4 zYl!}zds)BFqe7ogv!i7XBv_t={L>Sx`RIQB2*CvZLc!sMtPP$@=3iObpp18ay|MB^ z4R~yC4%y|BEk>aB+WeGK0;m!*9$H;LUnK*J7;sxUR8zOl=Y*&s4~%Af-C>QHEah90 zcR*Icpk4XNTF8(*a>yCZ>~n?4gr@+l{nzoY8%@9f2k^pKmaJEeUMPc@q~l`GJ+f&N z*>aZ>BPJyYvx3yPyneP52}QPQrAtLskft(+5$JR}bS6L!Cm|}K<~UHs=AFQspYUX7 zg=Ni#el~(oRQQR<8bsIe&`0xzVYnKJrlF#qInQVeVGxNBvhVCz1tX~u#0?dSE}M|J zpMXZS!BveB^QTc#n9Lo)WHaXz>hrj?AG#cYSq;Y7(v!jmv?rF8l&_UP$AyOgp!_%f zy_VYk7;VCETtKFtzwrNl;Ra ziMEhCu-7AZiCB@`1a)Yu8A-i{_LEqD5FcXM-+cDhcI`;k(AlT0vZb!6vIohS+4@l1 zLc*(jT9IS4!ng`Cpc(aIyO%$Gu`nX4K(qQRru?p>M`%I0MNHs!>Q)7Yg*1biGUedz zJvMmj<_9Lb?Hgmifsh;Np|Qr%-~=$J<s>7$dxPesIYYDyBjng%E#nvE3+H`^6!wjtU{LnxY<4jMD z@Rr?q_XLA{XfHZZrBb$8#jGoP_zAWZ_B6MMU5i=<$mT5Q5suN!HgR~A#=x08syd^L z%9orHQ1^*Ii{mZW4G?zKz0+5v5BAu`9>^L9VpH-`mOx1+gmG(2eyuqYZL{lvc{bA8 zv>BvlI%!B3*UOHg1vI?EnzB_UN~Wh3e^2rk3v_!F?UIIhqy`oSb$bdoZTb?Zt|{;$ z4$PBGY_bV{+3JWn0;qz1hs=vNxxef>I6kEyAXM_EFX-u=gnAISj&9*;LQNA zxd7e{#V_CZW?gUS*19LWR{#JU+;vukFjar*1y0B-!Iy>%7M9|32VwrbZ`^{^ul&NN zPJ35yOip*D>AN+Qa z2pWB&6>K&|XMq}+GPZ+RH;>6EYDToOE~u zV@mDa$2N})jmx>L{!aHKPjKms1E!Wj@%&4s)uP<-F*9)#tQ=8gcc>vN+csj9=zVl+=-$l0;fi)mk+vQSGQm*AJQ_|QSc z3cy$P=~+7T*G)PI|APdTT=0C}Miw4DKB8e_X1*S?s%P|hhjxEJZg20%fHb$V<`u|5 z^)y(gTUxAJlL6(0VMevJO=g@Pn7Qbs%YsZi{EqGk(?&S>)Jril9L{XcYL;@Ld+vom z>+yQ#MYHhxJ}M0Q6CgsnLxdCQ%eVCU`(+44F#BPOTOdo2bDSd8hb@>in0!SfWE#bS zk^O94mha!jnb*&UQR~g13ef*9)ElZJEY-=DyE;0B8uXvG`cCGq^hGqIG?kSn+Zwi{WloPwAOhA1 z=FlQ$8RJTXiof+B&NeCIl_*Y3;Qb6nbN))XpHGm>Z7h@ zw&+9zAZA!p9>n~Q!9#kygDZFRbvy#dhhxSAl!XB?g5OV#x2I3GS{sno@bl+cCJ`(KA6RatRSHjU{NT(4);I`b zH#^6~=$#eLO!?=7^tK+pzyN|dfI7vKiO1g&I!2`#iD~+${c7>$kY~;6u)94SOkCb} zO?b!=prrsjl4~2rPanZ*S9RVSW9Ag}r&X4Vh&3`#Ax{0N#Rt~TQL$vcwk?Q6Bq_Da_1;ry1tq8 z`&Yvey3&7lN#$BhciG-(AQ7)#3@R^#toCxLuB50}JPsi^^iF>m zS^ppxa1wx*neDU9iTa;necgG7)^nyypD+CDWi@YYcrl}>zZH(8emHZp6wnaBNY-2$ zy3sjpcwyF)iR++XQBsc~089Yw)=}oUIo2P%W8IFioSu08HYJQtl@YKs^Z`*!yTud4 z5eJRf)nJy5ImW`0RVmB z2ST+q`M-kuFom7N|;z}3v(SdA~JJ++Gw*|hgQ8_3h|_Hp~Qxe z`fbvER@DTFa*~UBd+btLaty)TzjwAgm6La!Ox=RFB<0y!BU@aJ#3gk^;1U)XKyAC$ zE-OV~9SHI{P%xO2;9wR_qtpgP%bHYDa_{S$rJj8 zxJ2wOP1D$uoSkzIVe2U-WU%Sv*B=#_oZsR|`Jk+~AA3Ip06VGR$0lRbt{s455^0Q- z$SniU&{(+t$@1TI@7dAe^?gWg(CY)38#{SBM=vk8k+oc=;EbWg(G|n#$d*7@cTWRV z{h~eNJK%Qr{l^8Kt)b z|0w~qpZEp3`cP2)P%_^GR=dg1{(ym#xar@lcQr_sQfkSQOq$h&q-#C>r8ZN>;qLrcm z)BFWZ?2Psg8oneh)}9 zi6pLmFOlZ&3_7hcFzU^V$JXB&p#zm_7&>LSm?EneO>#{zaTgtGIki_C;PencE^?;V z_a`_&B}OD*_@n^tfv7{OadGJ=5G) zuEU@U!uUZaB8EhPl8c2vB0=!HQRnly*ccd3nVFemR_h$m)wu@JnFB=fQ5U=T&CsZ+ z>wG)E><)){m9cPBe4j}9qMe%sO5_>Du3IP|@Ptnh_ghIrle8q(#ZA_mFbL;|#|t_` z`=-VgAtjL}fa&VRuW&Xz8!9Pb)s%d#+bz)l>;;ui!#}Y$7Is#I#>iQSJ9*W#l)~L4B+bi4;+cre9uY(;@lggUC}~JR-`jlJ5Ft?TOI6g3)OC!N3!&5G zlpCJ7s1e<08h~3cwF{Tg%z0F+6kD#AxeIe9S6zeGo{8n0+Mls{#d|4!vBWJ70*per zss704F@>h2@eLDuH3Kx@9EX3_tj7_8#oA&LuA&6xud9xSoPbUW zbH>`xr!O2mTVq~4UY%ut%15E^%u#Loz$ zn(3@x#?mJ;_ky*+GB*$IAZ!H(^fvLiGdbe!irEY$PfZGJMeMK<9aKh`1JXg*gM8_x!4ikWKgPHFfSC(p{8wRnx!&i(TaS7Ej83PHEkzX zL+hIFoqQH!JrFxdX=0p{gJJh!+-^0Zqu-cw2D-^jQCrKN^amra6^np*rOmKcaT}JY zJ=sq_C`jT>;egH?pDk{$)pGvs{zUeFRpb3VUdPKzXMg|jMP}pO=@V{Vq2XaG;U|#e zUeD0ZY`j)VL7{1@!O_7t0zj8DFs&IEuzGZVuhOHz4u#bp5LAUv+dI>hinth* z7z}wA-+9--e9vrlC^iE?Be8i8L7I#O2alH^SEq6)GP2vzMXf-297a?9aH)c)#2#?A zbaw;g-=m)L$Mp6`d||81mn`1nAc2K@tY?F%T?xP5{QtK-YSFS&{<_Z;954L(_Y=|# z;E3mcBFG1jiFBzr1_clKn1mnZ7S4S2MVaR^1-P3sk;e?laVV4;O+yDEqdM_NlQ`d` zs5;hQA>7VRHYhEjih~3pQys9CY*c_`NqVNc0^^|Lk}%;`>@>9n&E&40n<|iBF%tj6tjEA79lpabk1%_<(HS0*PDP{EJ7NVxi z*zfv1_^Ne%3lUJi%hQm8x;-%1_(it(?s0iVd~$BRd_>(qRpEhW!>@0yjnxcYK%Uq< z9HHF%t$;ZL7+pS?B#=KHt{MKBC=y?wMK$~b&*9mhh#Ho62LF$@`M?Olk5)l+T9szi+xAHFxt2gc2!Gv(LX63U+VcgNqgTZ&T; zm=s6QUO+8wcsDo=N@u^z%3abgTARE(Fi`yD><>o#Eq-O^XRLOPL)q8c_Nu59D@rJu zsg;HA~iBSS(p>Zr6=Z<5e1(@Go z$WM&v#;tY$GSZB zm692pcQ_-Lh3k(6L#Fy4=6(DRy_4XV8(g5zPfNkkpZCfi)(GRODV`Nj10fQ^)zj>{ zD!vdP6>_LfqC`08t6IO2Iy}3Zu*=Ik4lIABoFOugQ%R-Uq+{{gi}94W;Qn7opym7P4y5DEv8w*#89@D z%zLZjn4ufZBf!p=3R9YP0p~BQqMD_h>?7Hq3R?R`h}vu8`nJh`py*EI#?hg9@8-72 zS7>*de`pJA6;EVFW~=xkZ%fRHr(f$*+q;Qa@=?Jb{WGTt za1+2vm`N<%b7U|Ugwq4$`AW{}OWKWGNGvl@%X-nYje;p)#7INl5O+Mg?(y0xMBeUg zVZo4kf?)a-aA+1qXvf9_m4$vGg6~IyLml&lp+K|eQW^Iu*m`$Puq++Wr|nQyX?I8= zgKPe1@8{HJ;8m(ZS!xD#LF^!MD#2TI&s5Rnq8HBf$NEPBYQ)x|07j(W=iT`0A!0yW zVZa@#US6TJS6q{V)XNI+Uu`_zUPdS|G%%AbNYycOAb?fN#5_bfk?GV25SZS^3KT|k zE1rb&5(K@VVd*bn>0$BjZR0z3z4EHTUGAfOqpj4u#Zwu0SZ`kkWZ{9oJ?kzzp1?#! z5G&<%U+Pn=meHUP=MNofIcK4~KGh!twI)5%Dtyf| zokD$+vGUepXa8t=>}3QboINiZ_R*rP!L8TgD4l}|coSU*V^4Fh)=Vhu(0t|`gjFj& zNWy=$D@x0S9>~O8Wd(+sS}H+0Ic_br)8S;(4``J>7MZRx{#j&v&uilnyEW)hiRqL^ zu=HR&Eo_-zBc1tq{iefR*j>O(Z3ext=@;kO4R;y4dz~Fe4SB`Y3(Q*F%S5R-1yDMJ zoK^J{=rX^$^@bX@*nz%N*Id`B%I!#Vm~1;I%})0H8cm>fzK0T$58)W;(myVG)PlUY zh>04dr!O;t%-2s8E?>C6cer>bp8Sv`_~(1q6X$6=s`@Usby)bId59pAl~kR z^8cPpi=ODS-Y@4~t_??N;G&lWroI<_ zOjcF(&+<6PD$`Rvz}|$D`=?FmhScz5JD(moOM^$xn;|xyAK?>oT!nDRGNE0x#w}ow z4b^IkNIVD$P_mwIb`24ne-|ZDTpLGM8^hEKZQ1W?r>DYMp)~SDxX)|n!b;U91-y#M zuL)6?TeMLIRV{`MX29nI*772Uan2h@fCe}612WBc;2AJc*x57LNW|&(Q!=oNaRz{% z4ui=-tDS4q=bB!mKA`sDIF1Tc%#oO4)9LJ>sWZeuL{lx0tJMJ#P;wyq*xX#s&H%5F zfZjm?OD7Y*$Hj54w|nsWti|VeQ?0CR^kW<4xhaGA=GD;BMpi^1!HGxrw@Wx z|6@8u{$D)6kY!;&0;l8N;nggCL!n-%>|kw&V{#Q>-7Y%Uc)KX6xQKN7IqG`M{9mzs zbOH|Ocv4dpZx@#nnJ*;)zEO<-KIQxU=gSs=0;yDNxcyg2Xxgg%k(GO96mKaYAE!x| zz(i9}OORmf__~`A*+Db@hrO+yIK}5kP{W zAo*>f+FG#7?;4dv9ioQ@`}A5o>fxc11BJnq&{;IIr>4vINfo z@e6-J0~m`M1MXaVUY~V8PX#|AkDY-?iP=+(bq~L_wy_FYFu_lXLVkzPgUtR(ocd)~ zzroXtzHH#rjwPQTip z?~WJFdOtK^yzmBnNE&IypDV_YEi?x=hHGXbuF{>T%2jQBCnozCsT){IJfseDw8zs5 zg@ci@!NWZ9q8^afq}7gjUYhP8t2@%DQ*1u2@R)F@k!LlKr;9P9Oje>#Qsxr1M_o?n zug4~Z?;3v%8OT-K#y4s!Y004x7l1M0*UgW*W4+AUea+tRw+A4CIUcEc#KUt;`Sr>! zderSa>-OyZ71=&}-uV|HH?+tchTv_?do26C?xl5Nd3&>J@++WmRRg^K_oAe^1D1;z z?DC&N=?9BP$3KZ&4#}rXuJU6+I0K#vwWn+}A-U!Aci-jA{1r<1&z9L9V*>QOlUU$p+jpymwwzdf9JFYl?JEc*M_CI*? zaY&9&i9s-6Q*Hk1-$yP@U6N3xqIy!wBgPZ=LR35juJVulgmU&*(_r~P>VFuFk1&Lj z9C1byKt_Ze&cafJUB%^g@h4pQh|I`+)H0s3QI3gTAO4jnQ;Jpzji>_omz?PTYXP)D zo|vXLO%KlR9gkw2pu~kjj-iRvF?8=~fc9BTI<^ixIz|INh-4P7K-*tlusn6)KJY!d z>7hnH96l9M(5zeC4OmgLSZ9_DoyMqIXW`Hu`l4(X*Cgb)tU#bXa#&%gZxoP5ixgBK zVx|b>Q=15%y`Ijw1wK9_t^Qz?GtJG<0oW4pj)nfA4Lf1V>rYjNXKS&mAfQUwb7zbc~9|Q0$CTqrh z$fI-T<{1aPM{?IW0Z|tKC(z{5{PHq92d?y?w|789!$p#7aF~X@kST^DU(Mu|o(B+L zL@QYjNoKt?ec9$mbqk{$u$@cgEUwTob#oGq_x1BBd;`JtLY|?mUSNL2n@j$Ffs7^% zgFmNw6jlJV>PY|h+JtP@U@O+DYXNKEt_UNG#pfySt+?Zbr=Nqt|FTFVVX0SBPHH@; zrbJPo4=_QXkYHeh=~wDNJS>V0iP^+i&~<7cL27MF^ZAl)_Gs9UYDh9xTq~}=ztzHrBr3$pznoPrq!qm~@+ib! z1O^n6Dm5x^b~q!bE;?(3=^r}38lsq$%z=r`jwR{w?f6o(6>&QAmQ_TZp;k8sv&gqu z7fL_N{}LB2$f?L8$qf{0cQX~O;gtmqBDlEeBdY^*04X3`W&3#&nQ6w%WyT}p9;KN< zovyK!W|Ft7b40)v%F59CK4US){9xB;-x^uFO3uf zY)<}~>P5;nS5!V}{vPyZgUUF`+tgFd9KXl{aWg=8o9w~=c}017Jm5uq`NOPDV~{(Y z_TZB__VpJFDD_SM&&!Q!SmCQoU0!Iq2Ma|cU2=aDK2FM#W232r=%Y^C>Mi1X*plf9 zr`(VtGMyOpXDyRtXLNS{$aAHcUu1qG-UOwN_&sA4OeNFtGWu7PnTU+;6SOLxP9eQ) z+ky{7wJaZ|Q0S}_e>nkHRA%TBBZ(5JSA+72I|DX%B9mqE)2BJZWAuHDVe zty5rR%1My=_S5EpR7qHBJHe}h6EtWLI9&Q(cww!|&S^e5g>CaKf0Zq7g5Kk2%3IaT zm>*8XBtD15?~ktKjz|Dqr9mUbp|4O&bdK?#YH7 zdQFJ}ii(1{k*W|U5ZyPA;&Yw-IJf;R6Th0bLn(~y!JUP?yw7d}8yQWTdtxz@%w$U+ zG>XW?T2RABN^3*q@%=X0MK60s5Jj8U_dR;w_q(ni0F?cDoSLXCGq$-2E%0@W3eeyb z+w$t=>6bX-<~8`*IimJ`o#Og^9^+iNCw>iM^ap-meC!}p19M!!zc&bXoG-A!ujR5U ztl^eb2+x&vZqg#!rHm|`<*_dr-R7~GSKBj0kmZ96o51=0WhBC5iAIlItdQR511VD8 zOvJXA#d?16x|_XmT78n*(W!gE<%b(e;}DB6Z5jMH$2|Xo=xhDFt!Kdp#f$pQ@DC#6 z&9V0tyUjlXW~ePitTeZd>_`bGa&@IC{g z2(E%uB#xECN#}0E*gZhv&#$$&B)Zrt_LKB6FfZz?;Avr`v|r?xjam&%+YF2Wz~WYJ zK(qsRfu7*t6JP+r_j@drQgPvhUqz+?YvpJ(M*|pk4)L;>-dv(%>>iCs?xxQYzP`STLr)<$a%ytjL4%TOB%)zWxvO6 zdyo6Od*uBd!#H5K-=Pd6#40q4XH_D!NsMdI0Zd7aV5A}0EhZ@_Y+1eMPC$VV?(_ zo}c0J`Wnx_{T5BvN@7X?oZ096;r?EdDlwxujd6~v%wl-taNi>=mMQ-f9H6*CLDE2o|8q~kQ_qZ+&tjx z-#^3U#*6Z<*<)gaoLD64j6~M%$vIV5X*XKQzI*rN8fDDyHsA2KPo>PeJfRNBuaAF zz+z!rNG(rM4}KZa@1%wcGVK|OfLAZS#Wn+<{rIQoS8I&9xGX3JEQaJNPhR@`t`fxQ z`rRpqU7PaVcgZPp{&4tCUi>`Q5m;S|d}UVO_vNP_l%yZZJ4@msR-*tWNihH?2E|T& z;PQrVE-QY*K}tZ8KqRqe3fL`4Ss8vk5pl^tK_hAq@W8YZG#;i2Jn`hUu)7));0hsE z`mqT8a<2wtpZGwkM8FD+=W#zsfjw7nFcsFKB(*FEix6spShTu{64beJPo zbi{k-#m9lCwQ~jCqE|Tt&r5`9&XD8vB|+UkqbkSe!1XbrXu>&AEu3N-=O<0JCPo&E zpUca0{L6p-&%g}q_dDF*Kj8K2*Ld^hE$;5`@%HU4_PafX{T{ph7I*iza@w6U@-V7$ zQZ2bOey_ZrB>N>{ni-N3s1rukH4Rpq4W3+H;q3Gb7nc_}KRv_Kr%!Qqc8b1lv0AOr z_iHpwr(P4JSQ%+a#Iz6W&qSa``9wOh3a%p>OPph zf7xH2NfwdcOrs8A5BD@OuBd7P(vJ^NVmo)j~%*q8^wtnkjnpv5Kdg?*H z0V0+IIudY3$>N?_-|SV!hqzv2vEa4eL!+_ta zg<|7pd(zezBMRg-?wF6$q)n<;P%wFae~;aMj{?Rp?3LC``7s9o>vK(qW8@Y(wr0cr zUa}hhJ|*&j154d7?m1^!b8Uk{0(P4s$|sZDjQ>P>ZhNtm%9|n|p3}G5_o>2k?j11y z8+lrM#@-j#YqWZqXZ@{hsxn^XN4BL>SQm$5I+u^;RyK2M8&kU4a92g)T=x5ZC64Ek z@^db~&F^2jJ|FXm;^+wfJZM+w^rSuCgRcnwFiM(¥@qg@h%BOMr)+vFVn545zhZ zhuxELv(+A+Gah0bOaDhzLsQ@3s)B3|A%**G3u-GG65!2qTbcODC%* z(m9KJZHkXbEh~NULH7AIZ!1w|RnHLS5!;6y0HBNm9`0_i-R@BGi2M6HJZ$epd6q}y zJZiYpf`-TpZqX+~>g3R<@$mnek3#!g=SbUci5?vY2@hu0gJ0Xf(D78+(fK$4W?4T? zlIx`uG*CI$_Hv*btn*=x9AHT#RSF01E%iLJVRRNkzTcas!Rt4#arxvaPR}l}&q9+v z|KShu{KX60+}`43y+Pk~822N_afg%$Z(rX?A|wF&-4>hEjmyn0H`w}D+28ky@siA< zfDQYZ2x8gkb8LroDo@C!s2+DD>s8JY3i6nNoBs%c zN-6375MD5jdk?W@b7TpTS>-dK8+8{oDS?yl0mC5@FV}Pq)w8D*^^{7!Q{^}F5K818 zR3@dBAXnNt1|SELiO?j%_U0vSUu^L72R}vwiNERIeu?$`-t-_A*09m_G38&81w>wl znJz=C) zlaHalN+>2z>fFKzowY3{@-X25!sL*q87{3q5x7N$d(ZsTEE_*Z1-_5zfyp@P~i+Q=Fcj>ADeMo%86fD&x4r ze!p|!N-WoM=x1aqHK|h_FAkvfaNYR0DR+EK0lqYbb$;xg!wkpAi=B4Q6|5zI#VRnx zIzCYCkhPUT2r5(T&;8S{RPLKCZ=zjoi2Kek?3kWXowFqXVFoaQfBLO)c zk8wUm+TV&>mB*+D1B*3xqkN1}1VbmG?@6^mte}{g#Fdi-fEy@k2|&>{Qg&u#LZ>PD z8LS5 zcQ`Pt(`wJgzp*}!?V8nZ04yG8BG5k~a*JA1Xg3trm5vK@P^{X5kw(<08(e$K;3aQW#oR8MOq+olDpHJF0YxkU1+UH{m!}<>UY#~%CwUF!a{`k8* z8>e#Ko+&?suLVm6YBa*eu=14mwXUq=J}*mP_LzJXpII8~x$L(j3lh!t7%*8Q$7lgi z_t|$TasXB5rN(^LLl4=6)l1EW%amXc`d(tc^j=akR4NRhsAa101G%Tzx;Gv%_h2D) zIro2pB8rOo6qb>bI!GU4WCx~t7|U#4LZ%4KF0T`dRh(Okasp8+iWkZt0&*_G-$<~H zthpq-gGDjb5F}|5>w0B*2M-0~I3VYYhyS0wH*1n4InD$>HFNj4@~)$+s~Tt=Bmr_B zI4iq+!-&kz{@5Ae?!Q&UD;<90W*eNa_1bq~+%Zcyf}yrnuK zJ^ZjkP4!bXJyvThAMTO5J%`8dHyjopgXl|QWJ*cq31|qsnr}GS<|I5mc7f+W zJXRst1t}rwhHAzW33;ndXenve#NfoX%(5nRz9G28@`&tkAv6|sE-glxVgE($=Nfw7!YE_@zD{^PEYa2Kl}mP^#-%q3DdXKBTS}KwEI2Ub`S4e_Lj_;A?uz6|MTAtzT!@3DunDgEA!Hm38MQ^F3ePnc_{)B zdp20M+(v-qF?oOxL6ToR%6Rxp+iIlde_WrJimU;9TP`0~XxkR2$47{v#b(vPJHoW7 zF_|pTG!uAVq4EyiduU)gfoZ)<0WPv!?P7!%@5~T$ccD6*j!}ZFTjgQmp$sCp%A*S? z#!e)#okER)vPPX2^o3d2sjOe68_}-|))1RWo-+vU2;gFl0n59OI667O;5b{oshxI^t%#hI= zYZdG%r6|U%4-t%Z4JQYm?#ybS+%FJy$Tn2)sa8XJ*bX{pEIS1WwBXV%wV^&u8vAxDc|n26WXj?3lL>-^)|2zt?>lt6E#{LN^Z6o&dH}7NORZ$A z!qy7WA`JWV(9h?i0#~0oG;-j8&ia23m8qdZ)EAOvET0l|!-+3+#Y%NwA(ONOC<;#h z+1!b&Tv#Q-4cC#SnbJ1RO{iX|7w;D=^@^$QYpdSfA36i%i<@~t1TDi!Vev%l8OL(b$r=_uBijXmUFqG#* z+4Gpu?=jwL>Ab%N3YTUBuR|ICVt6R4jzmU@p<%EItk2Xg@jLaJKAua$6pQR0D!B*4 zV%}3^r@h|FzsHQjW6G_S!D9;U*qD!QfE!+9m1=8{D$heU3jB~GA!R;FBIs0K$+#CR z5=5aX_u9XeSE_gu9+ncgIyohzTpK~2hf*kq4HImfODRdd(^TYzI9?D9HW^bf)F!zF zA}ckloW)4Y@*5^9h`T6qgwzQ|!-4s|jvBrmk#kHE0p#JU34ltRRCpk|l-TGQ0*A-9 zdu-Ml>~>p(c8hMuq46;U_QDGtQtAMTXetLvy#C3vC!8ZqF_k!UILSImW_^G$HV;=6 z&pllT%wu94%&Ck^4%XB0PC@`E8|K-7P7b6p8=)7TtaLf7q@53wR!u37Z`9&6hCgru zQt@&H;{=hR`i>YAx{$D0Z}9f*w|M>f3)FRueP}_>;mw;jc>n%A5F(~cgSwgn;2fS+ zr%x1{XORMDJIPXp$qWd=QKb-f9-*Q6z!N0NK)Y?9Xl$E#L5BH7h>ROBBtw( z=O$azd965&j7;YJET*&HH&SB5vJrD6vK%7w9SEnVr#Lz~L0#1#N9-9YI5Zpnk}Su_ zd?2EDS5}or=sL8Kzx%4@brGUi6_6La;zXCz2XNCOAv=1(Iq?ED7+dTlBt=&W?>Bs2 za`k5VlAmmPje^As_9DR}yfM$kviG|UZa!Y&qMpJx6X9P3WoW9)7arZ0tz@P^WtmonMI0(n`JePf!4$X+5m9zABPf*}S&LL+3c^fp ziiS{5$6)Upd!JR7k};f(c`Wuq=LhY33WV$XGJqZEg~h0pK$1%+Qpet5q#@nn?VJcz z6>)U5z@%xg*=#^98#+U1#gmAOFm1OpkRx=VLn|Tq`+Y#W+2YF|{}@0*2%WTnl`?M1 zF#Uq|k!jNn3P>m*RD?e?hV-fwqWl(zsWiT0JjZg6*)~{(@Vk%VVWmbI2ROUk(<9>kS**za3BJlx@UF-Ki_gcRgDp*_j{g8C zFJ>8E6j@uKsqmbVU#!o||E&hnJicW4<~Yqn!AuFhH@;42ISCKs_8mU2z`yYgx3P9T zmV5az1K-%Wz5#Chw|+Z>F=ZL5vNpHOTvM(e!$MXbSw+4WwXD2`d7h4eeTKGmbhykI z3)SYfApiXo?iw0L#|)<57aR1);PLD1-(|fU@bH5Ui&+6Xhsq11jM2c#1&~JG3uaG! zT8>D$E&_Xy%6y7Bg4ZmesvLHk4c6NY=8GeEN3u~CI?H0!Kc%qPOtyI`NiOgNo=dGBpV)7t|#P-KwRN6py7I=F^EA>H~}= znD@sd1%f2}7}O8(wY)Cl9cgFzy^pb!n$$RiEWeEb)_LZG$?|%Su1mPPd*Hm6&SA6J zNQieU?{iphIK@{Yhs(?N`0~r2LaE{6;sT$)dWGwcA2FFu+1T6_S-W1XkO+vOa=!3frVDq>zz;U&qjGt1q>3g3SF7F`!H zn@wqm9CwV$45goI+6D zAZCLrIfyMnW`Na-%yW2bSe`^g+~0ga1n}b38~A2|F5}RCiY&`#3vKsxhCbia`)q28 zl*9TRmCeCI8|aT0`l)Y}_gXz$>EuN)N|c z-#Zv{U64;6eWgqR@vt5J!VzO(k!8K{r+|>$rf9&76Hu;gQ^SVloJt!112uy7^T3ul z(|2k6IlZyw_@pwIGR_Jp92N5t$bhTC`WiEGjs5-98XC*po7W%AJW=7xY4H5qmOle{ z7+jX0g(=WSF^nB>)MKyuW-tfyl!p@l?xzP7H@s1Bp=i z3SCIp@AqgLd)+ulv}5zs@u(5ejQ3MUshBttB+DM@a}wIoO;0sf=Xo{Xi=tY*ic~Jf zs5!fgr?Zlew2N&Tg}01>?NQpXeNu35nJg63Fdr&Ppn9@$^vYy1#qGl#{^7sHs!|VA?QhEcE_}6Yma(Ey#(ylQ=MO!GbDC1jp2GGT=4G6I zqSBG3B+lANa2wAd^A(5}>3AOMF*!Y?!N;yqdbH_%#=O3sGSWTvzJjf2aG#z_=C{nG z&EL^{*Y_0Jz~iX>k#k655ECAf@s+kfHw=dulAqBZKQ+YiIp>P3dWue-;8nRUXbI++1Jc_WC1E z&dww^C2xqtZVwXLh+Tm54N~mTc6;`=^TK0APa*NZ&iqLJMU=dq!a#v!`2ri7xJGWu z=Q+n|g|_XmS+B6!?a}VHi2FT4*J8ihBLz0NguvLf5<`;%7peitdUHUEE*pfD7pN>! z+(zU;8qS+^!%0&GFhA9Z2mXVE|4Y7e5RinwL)Xn=4&W@GWHZxyF=`1fb-u6HsDU=O z8)}h?g2%?4Mh<0U!4`F0p^H3rRaK$uTHN2?Ax4M&ZjXoM3X{nOP2J#O`2g=7rqd~$ z_o(X%XOk(8j*hY0?{WR{8n0i!K~psdu|rkY`26$NxW2x@-EzsP;Sf!z31D<1!{LB9u6k02>-bZ$+aV8sWy@GP$&#$8Ei!MGa`amo!>>JvBs=_JKgP8X4RL&~WJ6~87a zPOZjAtE(4UW!`O#?;wIF$2{F>f5rBY^%uU50Jta{v?RPJby(hAVlu69{_-`5Dj7zV z-G!DPD@<#@r^JzUQ8q^MnzfE1G9$e2Z@jCGys)}HN7eYe2759_48KF%uiu^IWo0`C zq8CnM>n<9i$_6JhF|RVG%9rOKEN0jRkNMae-z_R0VV4jP^Y zY}QMBc>gU{4>vf!ILFEH3^DA{g^)e<>V^|EBN9Tl!G6Et#Tq^8y5@xwWj8E?Ob(Hc z%9IFMN#flpR*aJ|5J(~tBu#WoK%$DnDPrP0A`GA4P{F$h#Mtxp(lJqEj4s|DXw+oU zM0qTg;R1bTMpSm8oG1+;1kS4|%!qf@DCbnl?I1{j6d<`IIb91Vv&_a(zl~P$>3N~b zoLUB|3g?*NR1I-Gf}+w#%ZzOq%QB@UcU%`8alsfG9TYwz87}0i}q<12;?M~hmvu6&K;gh*9 z-^*`B*;4wjiq!BJ8rt+6fl5IElsWi5Mwa3D5|vO(zzSvCrt+*2J6BK+o4gI zKWu0F%BEFfd&U$^X5I^B70-~E3{BWJ05(r*HWryRkrisAPcvB>1y&1xkb|XB0&>n@ z)A_;k4?UoI^gYUd`x_oTqn9cTBlm#NyGO^N>$)D)NM%!$*ttD0B8u$kKTitw06pWGZnAMY2IO4TJpLpp36SN7Vqj-H^0ZK6 zNr_NsIuG3dEN7mOlA$37-BeQAwD&w_NVGgoWlIjv$n>WM65$8dhy_Aj*SNjC!TaWx4RasIH>igFd&l(kSc_W)i0M0R|T>E*G$kB!A+bMn|ROqVcJ#>Wb8 zjVbDRE&drtS5)xRRc<109VY6G~-Jia} za&?Pm&z|ArWP#AKuEJ4i9h_{6z!9S8DvI|is=$UOFJmV-B(bs3t#w(>HUT$o( zaTcc=V<8b2E@EEE{L+c$n3CkkHjxyBLaQqKVX!#CtV5JJRX)#pPMP9N2Sfbt9FoW} z%^eORgv6Vid^xv44Su=~y|2)A9lAE4o;08s5n@7J*I2C{IFIPbDIQj9tX6BheE9;C zNrR6cui<@--ENPQ;}cA$GdS-snKqbCr>N^1ZD^qzVO`xN?dFT9Az1WcDgPibwDNFm7t=FS~<&xOP-U+ z$wg&Q#lS^8E=Y;SNCVbyI zP~@~bq~oa$4}^#otNUx5oSwr^Pk6J#;F&RbKgQ?vZ^eBw!h?HCA9Wq~dFZ%|*9jkD zktk8cn$l{l@T`y{8|bNwz8Xn~?a$uac=-%3pPyp0S)xl3b={z^2+{ z($o!nCBjpTpg|aB6o6Ece@h5mVkK0WlqOzI+Fn6bJ(u#NjNJh~WdWNa=P>b}a_+PP zWz>RpAQ#uj`98&a22d{&71*VkU@~A0iJ4)F;XoPAEi=knzoL1{`Bb1vsA-#?@7XCv zXvBG+iK6GJCRHzC7*`%cYbaAenELtFpzkzHZ(jTK=i0Ah@}Y9o^7!y_ra zqHg`Hpz@9$gN7u4k`)<#z9*pa3G3||4jt+Wh_OZ6?$GTWs>)-#PH^6#swy~NqiQCo zn+Yb2WBp?j75vKb+3lgUj1lFnf=&*-=7@E!X7Fzv#DaF%OT$Y*6J zEB*t(VCc?Lz6IsQuwmD@D9lhY6u{r>qZ&(8QKrlfZEK6cMc?JJl2Jl(sdqhqQVDnP zo9$=*8$}Tu(nj{X838PR?x7WiNtIzzUMusM=Q}qXf~?S|X#+q-Hf3-77e4H&z>!?-Q0l^P*)9mpb!vahy5Pd?^|@Cg?A2B)u3_}D|)1! zt~#C$go*)d&Q+@XMHEZuW?O%rv|kZ&t$^PsMi4CrfJ7kgSlLPJ`OkdQnR!+3J&_Fw z=+l0or?D_*UCY@^Le6*M5jo_qB>!2No`jb$m=y(Lz*Bk@9>KZcGz^nS0y-ipcKc;- zj)7d$jX@$cJ@aQw10&NDc%-*xrLA1lqX3))k^R}gC2~F`R8@t|c8mY|5C0Xv`{#c~ z~PUSoX0em{@}k33Juak*S! zx7lHOc8o5sQJ%X9#SQAYXz5SK?6H&}JkBW^h0hqghx}@&V2$za;d_RL(x(o~HWhd2 z-&V#bPuBBMi~11dC=XR?)ofJe63Fu@GSMdRwRz-{SufTotM{{$jTo2&JC5PaA7Ui6 zH1d6~9aC%%FyCP8$L1oX^k*rwij&w#Va8I$2atd7Pl1^evVBfm1U9j;FXlpC5zc#f z0@kY=++1Da;FpN{aMpM3?6r z)r!kyv!Rm$q7I31gX}^%=ivZ+{l|a7^5G7Z15ylJG&BS;GzHA3Gk79w*AJ-4p%Sl9 zFJ6|cNo3bpWbP-%d6x%~q=-$@tYwmlGiD8NzBmG1}wl}raAx36-Ji%B`|OVT`{;%&Lz?$EY-Os7+%l(61xv0SZib9009 z^K)!ATx;Ov%a@qW=IAc3@bIui7bEJrLI?qq$poK&{tBDT4i^^<=JR=vmvvphZnr~B z0d3nNM)s2H+JN1@#k;rP;)^$5pspLVp~G}G#hWkQV6$Ff(g1ZOyd;K#4KvLWD&?su zWy8MaYR#J$DA+SbLeaQ*t{n)@dqe^}@dmMTiji1n_1=S$L`@K(0)d>DHbJ~S3FMLA zHN@o^!;0)DU)E#g`#k(W&$G{gSMo*i1}1Iq)I{sKUU+uIv#w`*K}_<#@Z-{a)?1dGK2)5!$0$pi@zZRn6xuOx7>NH0ccsY9S{ z7rCu5<~C1CLKe z(oe^ehbrbJACd*usi%|?w6c2vx$+bP?D&Xkm;e9@Knz%~AF#T=!^7Qs>~|~7=L^i{ zb5wPW`-c_0uP~W3>>-*Qx;A3lbs!MxhJ{e&JrW`uc|4M#*WEQmJgMU`0L?0GAS?God!3tcJElN(o*nD(ZW5+{T!u z`9s1L4!u28fdl#m;+`=pE3{^ObaHer{b)P&E@YlNsu!;zBIRVYjcaS>EHryKiyv{240G#lIqq zQkg`ICZ!w;4pj+d!;Mv|I-mFLIK4WBnIlv1xPs(2=)Y*DcD`8?hwk7r-0 zwu++mudIP#Zr|bOn31n+7>p=&GUhQI(rv%L{c*DGEn(mN5HY4{9ME%roJ*d<@;u7- z0{wh_wohelk=Narv8YG?29Q|Vu)p=kpeUt3^hiX!fkoV`-P|IP+F za~*U#bkieZvtD8OaE-g0E9`e`OePNJ=g%;k&#+qFqpliEYWC_#F{14v+O7qX2dG9f znW1SKaE|HXDVg#(3NV!U)(}5tvAh8hEFF`|Bb7I%?V8d7F;~eYQrRPEUXlW8W57l+ z43=u7{o^r%(ePZsxrN>)lSyv7<&Q(UA}WS?9hGF{NuHiw!(@6C1m%W{oYH1k8qvSYyR@JBTVHOCeICr;pdZ8E*+6YQaHDy5f1`=- zweLDK^p$(l^P>f-NsZNN4etoeWQw|GUeI+dx-Rg>j`L`$Bh+d< zg+mOykrtzD9!ug*mNSx&Q1Ke6_atw|Y}PA$yu3u%tx;DT;_krtLPLy*U5C|ni@Ne? z>KcH0Q%c{rU}v2(FS%y$}#X!13`BoU71v9rkUD zcE3Z65%c*RyWJl5_xG4iCx|hksw-6FF{v94yKf_I?{4wp<>wO0Ot^UV3>W9;xVyeY zO|>|d=;mS)oyUx;M7cT5bD7hr#VpU+``Cn#iNP=D%yn9>nNUwAh%sQl+ag7v3muRW zrVSfPT~)IuDY1c7-;vj**3K~eLV0rL7lVRrJzVW{TegpziViIsc1dw1P*pWHn=QWi z=1-W;rg;7NYt&VRn~xvy)mPslc06al{N-QZ$3J?7$)o{N#BRI6-Q69Q%N1^J?@*D$ z(PECHlVi;0Gk9OiI^dkZT-u@(6HXy!UeuGt+IH;%iM=2@x#(K!ZxrY`#r&m^6EfCe z4`1N+<0ZOOG+N#Cc7{wFN^{jVLl6S7B46EhEyeje^Vo>gg;=9 z4x;nLrVrFuH@rGgWRRE)o1uMKsc21p0DTY!m8~%#nXFTKxxmkq) zSOBf#+c(5$Wp)KF7HCAnvhIuQvt1pu7r+rm-wpBQdH^e zJpuIoiApHE(0`u*U-CG+jUTZR{JXBng9;F&caAS z0wCVPj?nHl`1bABxVn6Y`Mg0F9Cq6+fP|{5(KI#cs)F+soU1?*`Vm8mL;;Q}G>u0} z0q@>@gZ26W&!4}~!rBO&q0w~E&!O^+ba-w|*|yIa3ejO= zaP@Z7kU$b;A3!e3LSzdw6;Donw#P7>R5xjg!Q4TMI~}wggd{ujV>_dE9dX8#mK*8#)V*&Y68UImdt%F_v?o$h(np8ZM46QwcB1d?Ay@Ol$79& zyyY?J%bf3fs26!c1jtK%Pko-av{-YPhuCqtmitRouElIp zi=zb+5n7QelgR`r0Nec@F+`4NXc|YBY+V?faSib|KM_^@RY6p36)eV)xU#h)o5=OR{_ zoCJ5VyfR*CVrJ9o??d^ad~Qg0dRQ6+(8seG8nG_oy=SjJzA(StfpB?sg~@b++nZaQ zo}S?0;Q`C#67%^S+ue@m+|_6%6U-M2v|Yg2*$JLMe+Gc?{KX5*=W}TTk7MXM)HU<| z&~^xcqb@evEq1#d0K(19EoSotyclL<2$(cA=Cdi9hTrGelY((;1b_}#SC_bW_EMZC z0_L+BUVZ)w54YE7+kok;0;0}IshI)UjDyNl35m~gIeYT5_iPaTl$?`@H_!5n*t@g~ z5xaJW_3auD4@*4UFOd@GM+bl(zxf=eiurBqL}z;-|* z7H!%Z8|9$<5mRCVb&UAxn{Tk&@9?vq{S5Q@3@Ju@@#aTZt@gOQxfb?s0$4k37a^YvSN^VQebZMQf+KEnU` zAO9nM_S2u@>goy)4=aEi>Sl_jo}j53Ny<%VV?vbB_Ye!S0)XTQ0mwo>idO;16~-$e z`KpYkn9A;aR!-HUqbS5g71XnYlvT;!AXW5>7bI{9^p%MY6~H0GC`>_iln<1htlQ=8 zGY&2H={tMR?fu%He=^r+P;2_2ZB}oi1OO&fOs{1ebI2H-FzaaALbgq$MmSblhPfGg zjM6AN#Y63J#p(dy>paM_kiZ5HL=FRy26~@BDPZ~VfDiA!!OhJjh&p)38=-z$qwRQ? zF|?6AZX73&cdi1tis`{u(CXb5tP;mCWrb^DWKA6t)ZsFT7F-r?b4gGn>Nul~cY@Qc6t1s?A1@o>KZCBkGn!E`!-cNN$} zreZ&CEv6%UT~l+21ysV}#kVsX_IX7U@$c%<$evB2lq!#w|8m-Uoj>6TGAyjX^mvu3 z{i1mIL*5D$L(q_}hXxrE#oIpD(x$$1j7EmfQ{euXCtIQKvfj)25?WPNRi=TV;ZCnT zph>b%gz#|m6#n7bPN{5!4P_KT3=@gqVkvw9B1CfVb%V-RGC0hCLx|Y#JA}X?*o>VZ zW6ih+a0o#|xxM^TqgKCKtgh){e)F-lsr|A%-12~7|Lv!~YwWs|#Cs|Nzy9_Ahxz;n zKmX~^5o0SG%&M5P2TjUF2dy;k%NBkI|6?9mjAXol?u{%dJjc?3r3W3Kf)R>wM>h>h zUkfH3;#y0iDvKV&ZcizG(&K}1w$JG+oc)~Yx<<zG9=rA_IvkUy%pZ|A-BZ5q`?XOI``#D>LMH|Gygs`e@~kwI zQsNNZj~@Yped@YGT~}z^gn#|^8~o`{-=N*^F`LctfBmQbgdctJ1#WI`v3%GA1WYG0 zOr~`n!;}a}o@IhFhIloykc>f|O9k~D&16Ymm+jbx#Y_~fprZ~a<-5o*iJQh0rr74vk&h zT;m8aqPxTxGX`*#$K~ZmTz$O8%g>(U?CcaV>=9$abUMLb{>4v04tV$OBX;|3-qc2l z=sJF;_nf12HlN|ut5?|VcDTE{!`ev3KaXu@nG9`IDao=0hW0{$9r?Bk8AO^iU$L>k9Mv z9Btc<0-%S72dq{r>~=f6d-o34*VowZ_gJsj*lafJ31_a~ZaJR|188QnF}45!UE5-{ zUZdT&sGAyuOFVo2230-7^~Y;Gd;T1=#XNhILbB-SbJW91GkPlX75)mK2y>TLYw>!6 z2zMevat!YgsEj_I_QTd5&p`=PykW(IF7|LRP(o3;5_vDw1>9Q z<|}zjF&G+q9{UYR3?FQrgzjT{?-9E#K74qKn`;i?^)4cYz~e7KiXFhzn~UwnF25@Z zSniNQVlOofp>qW15?0FxY&UCMJpT-5XU{+h==5RP8?$&(<%-L(-@i04s_9`pC`V}l z;|lsv(F2exIvyTnjpPC{P{UYXi7#!2tQET}sYVy2O+pT-rt+RF$fJ8W&OHhM96F{s z!<=|qNnx~@>wwS=+-gK2alpsc6ub_*gx)A+3Dt5>NS<8-|%KN|ki`Fc!|u}03v z?c0vE&foYL74K7(HTr)0eYh6J*RAFeS6Rzg zqRg>|*E2;9pQU}Xa>Xj3!+HEZ$52-MkZT`XW5d3e+=yUaHzJ3ANL%Zw#(aK^uIr#1 z4jE6Rh~>i)%jFF=n=RhIe~-JnJ8ZXGESC@1?e@lC&i8G%TWq&`mL;%JbqQ^|#lz|r zF#*%*3?Y2PtJnVmU(IoSbB$*g=Qut(hOcUF0|-&%KSeKL#WuB&8ctY;P;Yt}QOLkZ zxVrS$SGc*pLDxl`o}8jx-3WdbZ&9ww1f(cY5{0)YfACTVg0X$d^N`h^jM-DxfwH`i zg&t$s1md|Bu=N$$FWX$OFz2>Z*g&co+FNC^Ep2M{5AftTB8fR8O$jX*bo$AK#y%8hyaL~OeQ!vIl49@Nd>-mJf0O%>uL^(^2 zeb!-^-nfy|_HW4ahX$D*^VWWwX9;_i@OogoS>pZMud#f%22n&+rM&Cti1XuV%_Lj6 zD=Sjuq*Du~w*EjH^lo(&x?DXcOuPByJRp$6N z+5IPO1CjPv=eu~&3pM0C|3mGo88q{B z<|_91)&o9cgN;0tC)kXQgI>#7mPhkjePKB732|tYTl;4_pSP?T!qREpI`(AB#GTvn zRV~M=d9*(fFNWiC7yPbNab?F$gdrPtHs96?!BoUR6kCOwJ8asO zcvq))2?*-?J;H4)f>QUO3+>*o+4#{m*?$3kpO#yJ|)4 z&!)NtLkbKD2?U1$DX8Gf%{MNd?w%^!o#CB>3iap5HT&8&{{Uxp6rMtiT6=92P`yJB z4sBwJKD#Z$Mn4d$U7(#cbsQ`Hlh2@YYkMO{VEfW9B5VQbtx1%u2e7CPg~|aXC2)5X zphC{Vo_qE&PsKt3xBYQQoXNK&D3(^?p}8xrG#{nS?n}+ zC4_&f;N0Keq+YUzx`#ghnZo?|3?uxX=0X|k|5~!Oef9O(-NOywUhBuFlb$PgSJ`w_ z%gW0uu?YwWjBB|>=GbudJ+E%gSDZ7mvT`l0#?72%OVHIgWS?DOIz&g>?UY-ye%Htc zoO|6~qTr=tTzZXw{>`nnrxKp^(HzjuqjPw~pla7NC83N#jz5bxoHQM;G!%^{HkRHp z-U;vjW#3!Zq~FcUd9NlpOF8oWu*Hdl7BXy{r=A8p*9I?f=ibR{^ddPe9w($QSG`)P zD8ir5<5OenC$@&Ed&``~6|bTYngM1`@C#Aq5=ZcI1$&q;2v`*QrCs&S&PC326D=rD zdNWWmV^)?S49OhSBPZMPn_@@yl)$nX_S{#>32XR}u0OVfImE zo=g($jCmE0>Cd!NTM=NRL#nPlEvQ1i7*d4Ae_Rqsc#{Cbu$koQoV4pBZkAJkKdO7Ew^KmXVCdM8-gqk92bED%l@`NSQ=(msqZc|K4Gt;FypMwd6Xt_xcL_19M0aqSWRy%48yZU0|yYl5=!Eosrj|uF-w2 z8nH)pKA40>6f*3_ab6eHy>;clcCf3@dxPbQl#k)Og9MT~brj_2V}Ca|N#ZT|YsQlh z{uhx7X_$D$4j1B(T?;60A?RDPorCuk5W)RKb)DN5d_PrB<-k?XX-F@ z-OR#)d!aP=qu_g`?1!DEO;H;EV4~`0hUAgd4Xv?^UHxdm(3}7j5z!r5!_uHCoHg-Y zz5u`f)?V{}N7c`-m+qZ#V3|PxwBw8kin)l-yUj>cTeu^gMRma045Tr}f4vq?{QS9d zehyYbImMhY$)qpKl*Kjg3Q0^7{^UW(KbAnk_X`crAAOG(l6{eHgbxm+!@wM84BK-r zYc$k^B||P@1)|~sOIPChXYjlo*X{~Q7v^mffqq868+DN7f~8hCX17wB*d|24+4#uD<2LaZlL= z@X8`^pkjo!Km>pn#T6K5m+jmEB^*Ud>H!5<2BYQxztWY`l8Ot7K{x!f#|x;0xp`>? zTm+0nBqT#NKfsqDe|%%-Ben80|EUfv41IR(5({jATN@BEe&B({#9)<{z(Y8BX#Bm| z`5@oa-vHue)`ei@P@B|`yVIV@k<9&MpJ<9N;cZT(NAUQJW~EsY-(OS!lQ1s&>Q6$T ze(>RmIg0fkhnK%B^HFEh(cK-v^@KWr(>f#+d>KjM;^#N*ICyInY9GGm&zW#=bn2U= z)a?Pb2UO881_|> z{qW2zc{+H!uBlrctwyut>e=GwGjKG87?9ArCHSA5vNuvtMI)sqXR*c+95LeZd%z}i z#3h|yC^j}0@Ib}P&CONLFaA^!kw?NJ{+iqW%6w}W<82c)jR13?F` zl#%>Ugmt*q>(8R{_Sb++3JloTnWF2y|A9dn9{3Q~dS-4Ywm6+~cX#kf${H9?=X=~% z-F?>RrF+6DI4dmbZK6_rANc$BD>Y#D5i?L-h!|n|*9l(Hzjn1%ag6?6MN~W*EWT`N z_(W!M`B*}xZ`AT)nOG#G@XBM?$Ow4F8*uk7p`Gr)RL~AAX5Js5)R#N>;G#d(Izsf5 zTNB*l(08Vs<9?zkF_i!2#}q;!-jS_^BMZR>;ew5}1YUXVa|SoAZjWr|BjT{6i0iYF zK+)>t9rK()u7`gP8;G&9-LhuTgIPlmbYFg@8r0OMEYpoiONh%%HouHc&Ws5SO`m3~ z%yo&3#S_l|W=d!*q2ueH&8O*qO$$NBG_HG8xvGEfnH+PFC3^du ze_!>)6L5ci$^qx4xpHLFc2MfXR$6MLf;xv~$(iz&K8yUuSeMsOb@q-dwCQ3@`28Pt zV0fzY1bLbayV^--T9{dIY9)01zb|R){ukHGF0#7`?E0magFw{EX_~p8UCF`)QDL{n zcu4<<9Ws|RdFb#W!hl-k*QOzC`>PxA;C$z;=t^umEWSbYu!fYi&9#<@&L@N`TI1O# zp?YhTE%VP~yprzVO(Nc5KQu=r4Cos!w^Z5UV-aYu8V!7@+89#j#tERvGi6O_>1LXW z=lsh-XK3)fJ)cJW$bG+!L=fkebpqZd=jA^Zg8$83&K@J+bvR$+n3IV0FC4|cjdIgQR&m>mBbX=^SHeT>h3ENdua009d;RCzR#2*6w=bNVyi!bjLE7bwKv)) zxA<&ZxdYh@7=Y#4^u{M5GUmtt&iQP-j&xY?z@)nSa`#Px?y!``Z8B9JS2ev_)tmZ^ zkDPMgj)(YSrs*7qPWnFe zsQ1rMzf*LAW^~gANg(GJDW=_}ji!kJ*LVJ~c`+;8~1^~9G$ML#fZ28_lP zo0^RavYb8AZ?!7i{{CM9Yrxx>K;2P&ebMX>$YcXAFWdk!LSNx};G2H#Yy;ne*r9Dq zaTzPa8W4_pq6ZQ(ZB=6@9?RA_ol@@Y1j^Dt9wh~!y7b#M|2S9~YdGWi@0*0pPMycZ z%0KJFK$6>jp}(cU*xbp)?xz7z5ogcMz^UcDNgMd=FK_Gp8*)Bnrm{j-;ppTQ1T3iy zsm_;*G#*!%b`j-iAjj928`_zj9uY^3`qB)lv4Gryy4mF$=~h2Da)WMx$Ug3yekK1t9D@yhG=pWzcjlwg#ET`C2jL3kw(_mG$r8va>oPM2+cnCFwx=5Mx zyLch?OelZz*nOa4O~lW^d+o#{3w?GzkPg^?OnT9$UJ1h4PH|R zDC|7u#C)+!Kp1ZQ=2`RB z!~m%}NdnT+-U-C=|658CP^G@_M5RP4GZVm|nyl_K{}EAu1#$d?@DMi|z_S_R>y|)te)dlW*YYZA2K^_w98na^|?EC0durm)IoID2W5P8V@hS zCcFn(kQ8RkEml3Jd$9ZMOy7uO?;7}(9K>@_hM2@nvY|4O&RkpdQWcIWge|T?i%X$| zohBlr7LLk8rTz_#bX7$xUFJgnYKW`y*|bLn@t5$L+eXQ648v+jb<%T3uv4cvDpexz zEKdBdPmOa?kJ8jhXMbzs)3G}|kFa>{h;a&1Hg93O4akomJe$=he&g{Tmctz`ABC;& z!O*d#g|;IOJ`hw#Wn|zR5BR@#NdE-+J`nx}EMKXzW)|&80PjGfx&*j+bjAs-HIuqy z=Pa{9hz1`x#JrxpJ5-(fJS~>K__kz+IXO~UhuN;!HFq8X#uEStA+|@tvrj}5>m+X{ zvUyB6E4p*shfEDxW&@F78k+ASYy!}skfNMkK|uQZJl%>h(N{fjCJ$0&hn)?#iaaQ~ z`yWLuPaH){2Aubt<_Xo11Y8mPiD)|2E>8j1yVX{Xa@?OB&T(qKL3YEWcy}h?8ZLx%{3l!T9FJh%yrq9bMmYJ|QC+gUhmceTS6g+ozXt#$w*Nj6 zn%9h*xAqQSaRIMhNs0OMO^RTj*MzugJk`H%jC%WWGsTuD#yuv=dt;3L2ovZP){gZn zJ>IbkR=*akk{%`#mq!lI&w=UwzglUm$Z!8y3jlqYcS7vHdAG`%Icu^;!y%6VZ117U zI*FwUi&ByBIG&8(tMppdllv#8vMW=LQrJmR%O?%n z*Y+v|{eE58g_T=6JluQ-0P4V3Ds=}Zq`Sn$%N_c}uJhAa`DZ+o1Y$NRx{44?*fP{) zFPU5KQHINd(`YO~^i6_&jTzK;9P^{Uf?R*1CU~^TCSjTNM}am=KAfmBk%MH{ptaMkZpQmikfawfz?amge3ohqY9Ai)P>h&!%f~qo>|y)P{I-_Cy{(b z>Xa9Ki6r$dMX~CpzoQrLP+n+8_G?6|e2fqbyJD2;mCw$TrE8v=}OTN}uIs3|WWyNhQLo#DL-^B=H?Y?#+J4 zX!&UfiCyw>YsP<4QPVXWp5gdCy0ae)YFO>p#(J%I+Iv;67Or;_JD+CHO{&p*Ke7mE zZ1?K`12W>>&nOIffIV1~&O+UBN0D(zz8qQV;0AZjEzh%!jV=s5a4ZF*v z+c|wkI|zap!PTG>RM9JEnP|1ab};)uP;th;9{y8X6ELS&0cS$KNn>n0b2hil?Z--wVKG<1Hx)4MjQEWvCs-l4o9sd;de?@J5ug`D8}@{CL+r-+&kj*2bc?(^!weQ=9PGP?c6Qm~#JXL(w*sdE?0bxa z*73WCVb7b~c=@-~@siDoDK>Q)aUmji1j~iTft3fuHTfJ**WSU{8>NRR(=M@~C%R6e z+g%d1f5R^w67yWPHl0cPTX%VF z4oj20`wwZ&uB6f{2#`1d5^&oJU$4C9`dQ5Smm)dt`IYn+1s`CX{~7-?;rRi!O&gm~uRul{@YUd8QkQ{csGbaqZUy021QA! z6LJQ$)W_hrG349w0$O3iMc2|${T-_dy?5xMTr`GC40hU-xsWtW;9ZM61$qs`@7)hM z)2g+m;3vY3s(uq5VOh|M1302;0ib?b)`A)+N(Ex&1yw7ldOwkp+)HU=_l~{+nBZRs z#v-hiHCoj*8|T}d{eI1&Yi`GFAkf)E8)nf!eiKFO(c~P=zVK(#5CAhs9^=i#&&j>O zChGLOgW^=bnz19Ao|nt+OI-Hw^K%T%c!LI_G8Z551l*aT2iB^XcUObls`1uY_!8pd zW-8;wh==vKNzmn^-x~;UiI~e^sojJSBx@7El0h;LZLap>6YGpN6EsENSBCHsQ`S{@ zwo;J*Q$4hNI@m&&3kkQ01^401@@8<)xV!u>YSSi}!cex>CvONL(1@5zKv zdOhFY{O6nYxRqo!nq>p_j3Ifap|T(o;ZR(?N+Y{85^u<|T~)S~LfL---`+aUn;f#M zA#{m-i$@WHHOHB1>)9tYii^W+-HGNcpX)?d5QPP*eUv+EE5D_5RfmZ}^*El_Y^nfl z^jNzW>0n%GO=IJsX=u$PgQc@|4J1XGNCD99Vp8N_<8NR7kDHZJ@%U2cZy08W=Iejb zlF}A*eaGcpV{6QRgwl>d!|98g_;YhJ()y6R*@ld5T&4+>-%i5B!npJ1`Y8Ss0&NaI zrP(pol1dKCSOcZHe^$*?EHt_iv-?NPj$|YYYF@psvX#1_k#tq(?5dlv?_dpnCS+-= z@zEJ^B(y^9&I>;U2@-e7RA5v8ifU`Y9OLctdM&>WQD@4r()-8!PlYdDJWJC#>liG3 zFh}0@hzUmJtl%vLiGjF<={G$JO)$P_^w7Mad|k2vtE=r(-^H){NL+GKUFFP7jvWFq z0@@%Go{&`(ZKiTIX=h_)Xr}i+1iA{}3f)GzxwM?Y4EzvG&o6wtx_LNA%4Ic*|L{1{ zAg^$P@y%qz4KKH*Qxfs+KN*YWZ1K8xa-DgZ75iq}rRjM+!e~Gp{Kx=d?$n&ety)!_ z%k$e(;7`SgtQx34v&MfVM1FcI>-=0%pg(Eq9y_0|bWf0T^a@wiEFwl=5e()|I))K` z4k-^9LnZP^r}!x7kW_`>|4=5v8O4B`YZLaG}yjXpQHD=Az1Z^a>IVFf+I4nUoMtF$u)Z+@7@)O|H^v}H(&8gSkw&$V95ed8L?-TddU>Tw?`y2!#o1WRBlE+6y1ToFGw)trBKd9sW-x@e z4?RlB!1{WX2UnPk0cmLkIn=caj=x5k#jwP=)OcqP^(xg&}#r`ZupL5pi8L_^91b72vC5A9L&{HJNc;BHWK%m< zOO`GM+of#qrsy_GHl~4ytmTpf6wJf1XC@8An7HcS{)ypiV{4UK zS3V8uq-#$F@wPF3j6?H}=XR1Jq_)Md;^AHqEum#4p#Ix~B8%6Hm`Ac* z1N4G_z-HXhqTtGM$=khjCf$2FZS(@-{W=B6V$)(8&tlHCrQ=$R?CEwxv6tCWATmC@JLGq7& zC1{>Qg3b7&3(vy_78}pP2hIHym))MTdCyMEFh=d0hTxYyB(RaHI^UdoO5uQ}ZOXsq zeBg;^<0jlW{RWLOHEEUe$lr!*0_15Z#|s;W>zv_~JCCw0dyof3nX*c4Y0eX8Q62D1 z=JC=@uQPgyWG+#T1eUg$zb3-bE1a##@#Cs$r-sf8<4$gP!alv>ylA$(eAWAZHgR~Z zI#yjI_4qpGa39`!UtlZ@q0-Yp)2ZCu^y?56zh6k6H*{BW^lfs=eFr>b`aA8MTRZJn zU82=|8?MS33Zr5|l$_sFk>emrP}O*-u$m6A;XQN}_k#A$Mz5Tg2frRgk>a~2i8MKn z?G_cm3-}m9;&GRl+GEGjUA0dmxZuYRY8f5VuURcgn~p(Zk>&o5N-tB%#HbL<4z+41 zU)G?WK^RS6&1mW0W(;A8#NKX<554jMssWk~Up=l8KCipN3a+5t0n6atRs}Ej9ada@ zJbg_n6DnV|2GQNVnQZ~QkIGG^;OV)cuQzef=UqXmEAh7 zs#(l!=Tz*mVPje9D|4GZQ=^@m5Xi`_!BAff|FyecIr_N;4tuX}Tse3-1x@7$Qo7fX;iBNgOEa#cdO2BO7}Y^RwNd1 z=A)$4mcxeApiB1fXz8Dbh7iBHysXh-06b0(o}LjOp8*eMJqriqz?ab0BpQVtUKnb< z1`z;z;e|*`3z3{_j_y+DYP9b69`aeizest6%|86JJ0R2X_URop2j1pJlFEkyhMi)r z{eF5R*uUmZG~+@~AvrO57wK%H(3Feq*xcS*2bvxVR2tN@w+=9|B#%KR>jp2Bi>_G| zQ^SBN9m5A*+MRH87TCz3U%JrZxb*d^ z?FepMyeUHP^BIlo!->xm zr7*76Wb?U)GMJkfLi5u$w+W`aFl>H113x#@`PE9IHwddK@7LBZf??ibLh!m(DY{+_ z*u{^x4+JH*c^|x(tBSR&Ez7No4c8sBt(Z2OKwa~xiF%#n1tV##lU&!ID3b2>P*fg} z+C2D>4iKPP6=W46DnBaW7oN%W%O+db&GkV~HPN%hD7tqdM?MGU3SD3rhv%-|xa3UHQ zY>Wi(J5LTz+=$wO9DPpWtm-vM^XG5m{L%GJ=B8^@fu2Z2Jkj+_eSe6(xrpT+_0Ghv zqthsV(?3J?4$T_t6?sF95s0eeD2tc&T*s#ek8{3Y z*P-y1&dEkQS3KwSKpbw5Ps;7g=Qs9EE#u3-=~@x3WRBvO)*Qr1`NzrIg!f4zQH%Dv zs`6XXv*7aZq_mB^lD(3!2r$KmnBl>}$36|1lkjhVkZ`iQU zW!R~;!`c0UDB$}VzP6@~0{OSX8+t8qmcl8N#0cAj)3BnzlBdZ|+mnn$VE5P1p!KDu zo`k?-d&-Dc{Mf2yL&{xGL9gXax2U_)TTxadGy!_b z0#iwHi| zc88Nkk>36LokYJ}cyAe0Nf@7-AFy*gxFx`E$Jf^!uvlh;QbLG~44s*E@(G6!Qamtn zLXFiHp|l18ypBe#IwyxkAW8}GFc9_Wn~6USZ3~KwTK=ut%A}8@%zd~&xl>1`;w)bg z#S`-0^8?T`Vw{XX;8~k_;s=b3G1#W)BL_~u0KroZz1XsE$3b%W^z)ODGe__{8z?d| zGH`w$0*+cc#AC+?pOEqj3NxfJv$DuQ$zwro&4Yl^Bw%$y!`_Q&TA|%9im*BR;ash0} zj$zn>Q}oZZz!Jj91Kg4f_GByCZ@SP{g=!jTpop7bb-OdCkyxJ%DvYzC;TA<0@gi(5 zqg|;_5DsrQx$qTpTU5rEU=r05A!dnY7!FXHN zRL4OI&j!UJ)O+`-Y3v@^%RXq-=Ro-g1D$wYz)Z za?e|bPF<*eT<&fnvlp!~I^LJeNwc)?Da`hmu8Gr1dm=GC=I_vCUERgX>H-+2`MG7k zqCnV+d8yaiiztW7|37+6_2ajH7gLM9n$3lDNj!$&6-nF;N|0Fg!Mb9>6?osh_c<#% zp|Ov#ayf~xv%vEn*guCgYfK03I%GN|t6=N-`x8Tu1=2-#gnyM7^79&ZPelhKdwKk@ zWFvhdDp~z2{k8wB9%EC4Fy{`g{FpHdsmilh>B2n37u{*??&$l&ek&&a+p}fT;E-m^ z=Jmo#WGp0@Mpj$LpOEX~d2Fkj+lQs&A%3LxDT}q--f$Q&bxluGe=F$Gu_*4F0cFGt zOR@reAq!l#JmFlZ@w$d*!1=N^ft7G6Fc$Oe-H;d-C2SD<+f=~=zcZ3Ezj%Z~2&(yh z((fr*YliH%d49k5(OO#15oo)8FK=<%eM}adQpKZQ7IXB;vgi5cio=ccYH1W_p9yAL zXK!oVH(8%*{lnE#RVgpwY-&5qS`(}Q$y53wx;^8gM#5O-r7w??huZJr;!90HsBuM@ zLyx5$6uB#U!AC9j2({(T2rqk)llx5&u?y^d7)z-3j?1ZqyY4vw<&)X=TZGApZ`6wK zAx#DWmt8{Vzb?-K^^=6}y2VQPM2XkNYHNfEIYZA)hjUtH)+;hY-+k=6Csr~`&g*DK z$p#wb?rpDqXllz-vr^(Lb(*J|bt#I)B%Ti*KXJLd4mrdSjAPZS^>(g4F9o+R*4&9j zRuQpBtjCErJhZxq7`>l3{>5&gMwj1|#X7AM391`Y@cLYrBk270N$rZL%&>FlVpOQq zoJN~0yD{NkWHjra^Y+{{n>RLmp4!WgSA$51tz@*(kzAvWX?z!uLIEc^nZQ+9{3xv@ zi~F&5pDcGNzz=Hb?n(G+NMQ3(5|UYP#$y`5$SVk58ko_k(^f9x5tM`5|826 ztZn4mYPrDgBy?T55=8;aEfkS}&wsY&3UvT`Is62CU}R=y0&--5t#+nOGxiWFqkh-F zotmMOlQM0m9OhT1`{(By72Mzpw@BdcBJ_tRB+wfrz7}RoV4W>M+0tfU2a}!61$B|2 zth!bBiGgeGprV_SQ-6mZNo%}MT5wEM1GSCB_Ktf^%Mt7zdQjIVpa)kkj3^Hcx-AhEJ+APILC`sI#fT?wgcC(nRQ<3 zdK?--lTuYbuXHm=KN9OF9SP+7#b#nlA+lt;`iDPQPhxNzq+L+IxKey%<+^S%Ia#(r zGVFCYUzyE2<&uSGwgq}5x%|_T_OwQO7>WsL@6uB=vr#70Ms*O=4+Ct9^-DWP79^Mr zG)LtxP_m51y!-ZXLLdzF#c-7*#8QUD!C#<6TIB!Oc@gJ+Fe0bI7&>9i*=!aBb$s}7P!((^WN~>2)nWd9@o+Q%3Y^p`A}C^*l_X>^?(F!#x17&mVVlY zR`QI^8*nGZ91?>+IM|d1jhovU_I|&vKHs6w?F8G%by%DUN)g;N-wp?}QCz^$K~dde z7sTPNW&TNW2F*B<^tsjdj+~Uy;nz5_mJG~^e}ZkhN%{2E%7{-#ixOazT^YLGA7@fB;FF76U3&!Jd) zAUHF|QtzZFm9Dr7u?LN(lAFj6deAB+jYPbk3(KbRTZ(lqRpl?&_dg@KUvgG9M+jsV z&dY9yKNj=G5s;elR1SwQAmGxjqBkSl*H5F;B@FgHL+G>T2Atmop1cW&@238O*GN67 z2l6{jHJUH^m&ig;o)tf>1Wjtr6dx@;@PU%GPcIjmro)t-XCCq9!&R%wR$R$nIb3iK zU9H)759EBko4+40`cn^%e1ZEo2v5{RX8xq{uw-N9u6AYk-LxNZLiZ-_XHD5dJtyWdq!5RPbw74{(dx9R z#*bq*&M{!2xYSAO`4#T2I2y@^qp8owV)wvBkW=seX8Oxb5N`G0Q9@$RE9mA~x2vGUSOBapi#r9h_|pr zE{V$cQ7l4JTk^+tUvuqZY)m>PQM-`v?q98LGtHd-j$5TFQers-5?Xo)-PbXt1Pu;g zPJ*6c_4F6(D=~mogjjI=B{%b=h^7we2o`uE0f*;! zooXg`z9kq?#%jGx(JMDcOl;8Y-*fT^F~^n%?6)es3&{M0gpc8l{{TlC2uS+|B9PX@ z8kGRnTPB$|TO7aKxcivDsvr`&+@PAUP*6p$hc?HeY9tcL7HOwz)B6G6hN!fQPX^U6 zzK0ruK>~beU?RwI_%MnFXAQOd_i})le5SI#;RgZ(#7s3@5K{puF!0BcVe5I#Ic}vo zZO9;p23W2!778d~uNEn}V!{Vc;}~FcDwcY^yV-*#mh@eDu!=rAvu?00c_;Q$h4|i} zjMs4WhOrI>-1fciePbJwu|eo+=vo|Fb&NWJ?mLa#i#CjT%KSuTI;j<_<^mh6DD0xD z(w?ml9A#=U9Q;3k^9xemsVP$PAuRi83FokOtCE0(U&NycP8P8O*Lb24$& zxLT15!=RIAjXNn3v_?_FPjD8Mbb*g`a5^P2u!`l#{F8cME{yUgC z>{lj=)N6i2AddH&d=Ye67N!=-j+A})kX^sQ+5 zIT-Pr9NNS<4rKlq0$mUoPqJr3S~O~}8Uzl3&CtdkNR%8z%SaI=SRp$iy0- zTquu_R&&K4^ih>ePDYSfvaJN{UZFZ3qmjI8uaWGZPh+jz?A>0PaAI{fm__fnc5yu@ zMcXk*j`70wv2s|x6cQkT5{_8@PwiVfhmTmu$WP_!F|MJIo%=WOC#GXCM-HN$ECY2` z9fZC#*c|SO~x0fJdHtTIW_r6HNOkw<;dm7#R$u?)ik}OCvzZC&^n{9Zwip{ z6x!%mrbM|q|Eq?)biPON@?6WdR6}asVNqcpqD}8O$8h=^onX33H%M~o@uN1y5tqDO z>VQ{Sr~t25$Qm_%HS;`X@q)fX>*Ly&t&`A{^i+b-c5d6eS`XOi4RA|>y2`!^dodT} z7Ksv^-S%!;Htvl7JUI1v!g^1A$tAwo8XG#K%XAdnzK;)ZU=_Zru*QD`IJuAXMwtM3_wwqpcGHe&0CpU; z;sJ_8a{A<9sk-(U%VHI4j?1dG6={#lWCI>H6cU6lrpzTlb|CRHA&!k|Qltu9213Sx z2^QK%a~wgY81{eeKo4uQY%>mhTKYaU15}3sr6{0q zH+uDqY8kXOukxuXD7hhSlF+d@Q^MvnWSm(h{(6d;^73~L`+v3U{dY5A_Qvl2I^+Zh z3I3GQR;oosP+mv@OG7HX$XA628;6G=SsO>mF&c3ogg%M#+bV&C$kKed_qO9ANy0JD zE`;|>n%F~Qmmkg-?nKy+@+pmD7==1}Z`;A_PNWOO%E5o?bFmKtOpSG8`qy_rP3GN; zGiYJNCFVm{N*fH9#yTM~aEZ zx&=Bu0y2>8QK$2*Q?N@2#}mw41|e9Y!))>Y>Pz%On`MbTHul)0)r^bd)xgO`Qb5p) z6V|q`88XW+XJ*3_lW-EsYN_&x7@2A6(P=0_qr9i)U|73(O3ub?4S-e#bj&DQs z>&vy!CM2K)U(|DUsow)*eYZ*T%dYP5d5eg9>A6&KQfdBaky!ud)cY`7|A~D@Br6@F z&n4m@jHWlXEP+Js}^MCn@Ri|NQq z^W$ zn`YldtU+FoUv`U=p6xp?Kd7oMz?FSX$EfPym3vy^hqTN-{w4Xx9?_P@)FRNG#dh*8 ziH}hk;zD(No|5~0jOp(@b${{q2%*E^Q?JNF1shA=nz5VM8h@(?b@muJQ@9dZ+|!P| z!1o_+?@S>5oA4Hw!ry<2h_=g?pCc~YA3kCA%ijNv{&Vi@J;%Y*Ez}Y_QHbN(2l7`2X;$n0WFCy!n zp6jwHkXMqA)WKkc3@QDA#qquP*K3@=6qGB4@zYVp5DMP| zP!T~B>{ya1Ed#hfx5-7?#fYI)5-7H?cfVUi#%Ud;_L@hT>(vOcko(>?K-Uj$eCuN?-6P~y*_=gw&Bo@+5?XGzaF$W$YrMnaJU4>_YF#J_r#d3NRYu<7Lb|^VnAki(#Z*5*2{gR7t4XxRM|Ru zEE~JG_dE3;zoA}jb@kq*R698NfkI6`foFGm1jZ6=8o0mV9Ic^4B!6n=O9dpQ|E|Hb z1(`+$jGo}QMJFXwIkkfL07gKV*$5Z9a>=@K2@g;a^3He=E!?m}K><4{qAS-uxPad~ zRaze32wD2A8VqQ~|FWro4+M7w;kUHD`y^+Xx&pIwbtYn1X>8*AkA7<#^tmBEo!tpK z?O(B)A7)RQ?Wa;h{fd#d*Za|R781p&J&k})Zb>X)_ANGwbf#B1FWuW1M|V03kyyhHUIR8Rp#XJIAn zIph^tnrhVp2*2qudB74FKu#<*y4~$EeXx%4?NLxK-8eno4iUj(S+qABKu8CfNn;Wq z3SkGhj*brL@C(|xVuV>WqK4?1s7|?1rUA;LNTiVM>WSj31okT^pS*=Seep5A(y~WV zql?URG)CNYH>g%{C5uPnjrTZC^V5>V#2v>WyM2kdYR1(8iZ?~ zs!66v+o?2C*Nnq2hL=ez>IL5im)fUqQ_MpYZ5#fs)N1$=5QIYSAlCsPV_?v2LU89e zvUOzTuu;R-C}3a;G%`X}ckgo`|6;l0 z7y#(yrO;f^r9{niYsA;rFwIzkMnc6GRveDc`X@~oOg;a2i-`{O=B1%*B3pDWp&+4^ z8I}#8Pb0h8ID3#??t(K1RP*jthbcEXD{&aS-Mf>~b5{z(vMilDV6FVHVh{3l>_HOE0By?2r0%=;4Ck zYj68k{kfC!9Jcj|Ro(rGYrAHI4dsh4R@aJwpM-$MsyM`FhJ=7dpJw}BN7!g{b$*{J zn?Vn_RG80PN9F5FHfs0IT*D!m&iOr+16B83$v_QfN(7nwP;3$NU0; zI7~D>w)N^`wCg)9Eu2FSd$4W)FUV-nEtorxc}Z@j!WyXJZ8dgbS_MP%4ZZK2(3b77 zyWm;7iuT5_Pk(0Vwy{$8_+KuvL&_B>nA#fRV@~igF{!2#zDZr+j)m2i;)^ZS%b~^X z>`d|CvfCy_Oj{E$ob)U#u!5jAbMgXDATVg2#6Qpjc9x6$f#xm03Uq<^msTx$RFNKl zBM9VfGQhI`+vx!S9|I$!kQnux>oN3+Om2hWtXHS_k`#(U%{OCQ37t%R$qZw$HKufm zVL0$)0e0c*J~p|w8KNG(+%qf?m;$p_`MvPioFb%Cv(CYVg`doyUGikC!CE*Wc|@~U zO&DJ3Ci$Z*-~g$IlodA~F^nSv5CPB?ErjxZ=z#Cd1AOP^MdXk{ z8}9E12Pk0aY17R#+G=TjONT=Ivq*)>i=D;)=tE&l4E4`` zKSTNlmjIb0frmDI%Kh)r_7_=8uoM?3Gc(ty5mDya-Fxrog2R1vrc4U&z}fN;A%J&I z(P|Y=W~^*Fy%fimpd%?45u1rIKbp=tI<7xj z`xD!?)yB4(2943!w#^9|G`7{av5kg}?Z&pP_x$d??^?5FC4bFia?YOp-TQey4`-!m zd|g)D1BoQ3X_2xdf_MV9Y&?Q&t)D(ie5P6%TO5l=QldGC!Ic`~A37Xohg7gwU6q!T z;9RjaJM<8kmXm)_Y&5SlhUS|c2eF~1XlMuVXve>j@0)F+2VqR$he^zsljz^(O5tj3@H~N=S|E-=4%FWT zKt>_5vm0xyW%u<4;CjNu3EDH`c%WYHA3WtX=$b6c%8Zgjb!Xr?lb>GQYZb%{N#*7@ zV#@Ai9_bhX&)`ar;=jf}G0c{u_AkWDWI+iz^}ocD^%!#6{gwTaKINXh zfS<)mfoBHidr1K&Jhp`)oMJXP6B8$D01pvJ$Y}>vXTvGWPQOWm2)W(^vXM;SfL>-b z9qNeT`tM!1eCy)^L?6iG2R=`BX%02{AJ)4m~dB)Rd!-YHyHAmq8Ar zy5PSb>cIuA8)uiB)e8YR7eYcd2YokG_53;gmf_Q`(TpWx5=0fW3<)M9V0$?jU}`}s zMm%ed&L{_#kMwie5wY*(Wrx)qgx}W69I2bR zHoQtU9`4w*JfkKnQ`5~x*bL3Jx<<3uX(KTl&o0B}e2RLP%b;}Eg?;qY1(<$AB$A{f zCC#_|YBKwQvgkkfYdjP~g85Gru%>)H#s0V=3kd7>f6(aoxFw)yu!NML3*?j)uczZ% zF<(T`cpR2@sDDjc#+b#_Evc5F9?EKDoZ-v+i#*OxB}GM0j!z|7(hM9sFVFrnGkm;s z_bsv*0Af4DNc%vs)W7?ipoX=WFP}O!M}I$7_&amJIr(kQvW5(+3>R>_58;;$hI55- zT1<&Z9iI~z?2)GlRWID-cpQU$wR+2TnLzdUb05Nsc#1>M+71`{HO`fEXS(EW{}>F3 zY0>fJ$=x#fsxxZ68v{Y45TsLi!E+W(J^JW+@=7`4bzI=A(I%zAarV?7xNf00vtiAj z`&dbj_zF16{n?UazLi_HOiXC(xZ4`o3hKR-%ajy2l?}Qmz%B58N!JgC;tou-i|bFI z#`kt|3S7$+X=meURrfifUAY_hDqu~dd6QDPRJVah>U@@I-0$2vc;Wvb0{A(R$p_cg zvdza}7;$BR zB-?=8U>O|Ybn_(1{*?9~(4@&u)$te}33KbL9SwgFV=`B7r!VXwtr%mL8bYd7@!V<^ z*AAW+AQ>6giq3LsGU5VDtN%9Q_*DFekFGZui)ar^wu)SNqX1WsZ{7EU#J!oUmS3PR z|Kg8R|CVD<*aO*AlYCt{Pp*ULoS{$Mz^H~nzMVF}PO3Z`0bV8qL@EWi?E}LvxB8@# zX+Hba^k^7#PIc?(8W;rc(0|@|{moG%Q)^1xO04)>ywV$9LMkyqhBR-9PK`~8kOjoH;e>#2_sP zbBKrp2wpO!bQfdm=Q**s5|As3t-P1ltEm)<^R7d8Itpmi)|9DNA<3E)rf$<=!t;7E z2kG0R|2#x#8&kwS?|v%3&7o!1?si31yhv;>-~5ZOz&oyXi4!tJG|a%we4Zgk7KCLG zy{oy5O%RL)qbKFQh=5N;<5b3N7kZ&W8G*Pt=-lIwS4Phh;U9PO1a86{BTkQvUsLx0 zJu%Dy$(!IfQrp;H6%=v7vt7F+lrySp-h(U%H>S-U#%v(y>#aVX#qH~ac)S^b^c`3! z){dsY#rse51smw@%e8&LB!B%8Nj@RRQ7)VZ?5B8QoYn?AohUyfSgJVaZ`7XW?1Y*S z=-%j!ZLXTu@9>w@67p}Kpx}y4@P|}Vys!ElV#$hxuQ*dd${6A739LV5_!VVWp;?7g zp}xdZ(SPI4occk|B~x^EOw>p0?0^Lj*y`cx-kFA`A64GxH`#8)PzOERQ*+I@DECPG zm$hd$CYa|F9bMe>QuIU!xGXXc&aeDn;_7ZCaxJtH$NW_#{|3BRPzii}-qamZK*`+D z?1vY&sHVBsgu!})VMJyB$#y9+DYE#GN}t+AeBthL( zsmHpr_vna0Ust5>WU=~c6fnX7j^Vkz>g_oaRG(z7&r+LSysHHgU&gKyON^q2>U2F1 z#%PJ64o1fWH1y43Exfci2rxV2-R#n@9Q@e5MgV>$&7`7B2UnQXzO6Xl#8ZbE>S!m; zGeeH*+6VrAgRNja6KJm0ffW@(MH&?Z8!t}+y~_L5^B&X>f}U-!kc1auglH@=Ii~jgyZ@Bs!#eIg;Qh86cziVU;Ete>q=oVZ2E6 zhgEMe-zub}g4-twBXSQ@H4DAqDU?s?D>j&1%bEh6zj6=7JgN`e9wzjk4SfDv$`cDN z5^^6{F<1Co_Tntl1PhB3FLBL`3aESlGc%D15D5k17ckG`Wvs2Q12T9(b5vAx2r}sw z**rfN<5`KX5HD+OlU&?u%aZ@nhTWOmRR=A?r0P&>iS85sD=bW>Bj7X6TvigSewgsVQ$cPuIHssc*4aDzmF5kJhW}C)#`95KyJ)i+t5@7WOP(uF$ zR{sJdm`?G&@8#vPAYcShsr7qCpB25p6iQZphS3HYY{E=qvG+{rqFpH}S|z4`WjyG* zjMrep7&v%S_waSVe^85{yt>@1r+dSIqeSGbu?g9~n+$zN?;Cv0Nuoc zs?S<@<<2F>(7GN%*wLc+-jfL`zO~V?z!{sV_1x1HwqqafaF*=)JHyykFP>R zmhdyL^qFu`kj;2>KavY)?HLkjQ9fGQyjhklx;OaBq(P6dc_&|M5>ww zOgk-25eTGKS&NZZ%(PRynLg}do;$LHylP-bopWuy%0Zv?j%oYRy*|;B*_z;3*=UuI zuauyXgP8MxYz9*dJ*YnBC?6$Qd$ccO~8H!kxMz{H8J~avI5~9?!}aPi9|YiK!WgleBprF9u)K zVA-!fmm=FQb>_gjw0&R@LlP^_%q?oRGu;fZ!VJNqhTzsUpfGZ=eyv7-zw+qr(_rc9 z4R{H7Cwkuyc|`+Ax}>@G_N*vEJw+&J3N28}?8~roj=zGJoqOgrm2FLl;nrFPRv5N1 z-3p2-R4c0O7LDtdw{Lf$HBwU_j|Vh7@2+WpbEuP(6UDM7F`GQp`NahZ86})##BcJ_ zzkx?$u(F9piIfoP9`kjIers-t27OtyJX#wTdR$>NCs#~+Q}YRxx0x}L)*cZra@ACo zs8>T-Bn`HCD_YGbl_~$?8T*np*s8W&^{ZZWPP0m+>`ubru}xO+nZ${;4S!gL*Fgpn zg59V@5#ckwqJjFcDDOcWkSu?&8~;Hbb-5OYG2BJy?mMFPKvcNV*lj-!k)Gxpyd2yi zGmzj14cR6VyC1yK=AR$^@Uyr>Vy{m5^GL{p1CcA$=I&Z;4?o%zfm<);qX{BFHTrEjW|4Z!QAinp}1vHpVXO2yp zK!njKt#lx3GzQv>(4bQfr##ST_BprqpWov;C4qJTj9?T-`~F;Y9OF8zXz7eGp zPu)N1ody!a#YYEcixAvM4v~X@ZSShnip#%t#vRm(8uhvGrKYEeSHhXslyU{luftI) zwfFGeT2`Jnm|8-#Wk~8SOP(rszy(j`eU_zp~CIEH|_c^h8Y({cJVyUdG z?48qh)CZp2AJ$@@TrlEIHEyU0Fbl=7OoQ!ZrOr@#al}@c2cz9AmIfgS!Kdd^)LOsz z?Ij@H)lZmGGUcz6XNxHr9!+8__T!C_8y;sorBrt>{HMlXHcd-1NL&*F0Nq4m5JS-q=Q6tvuWB#@l zEC)|9`Y93GvWSgpT(qEQW?`BFck9xg;S zH{NgQd|xjSn%i|w&(9q_JYxHdVx2Nr6)<*K4d-Z1!KPnUscSFQCa|v-9Zk_8o%!-) zIP~y=>RY>HSgTo_U8AS~@X?z8L(AWsSO9lH@6j;AO7RcAV>U@a!GFM|gdfUyf;T*( zIrg|P*x)KI6GbJieQ3L!ms4`=beYIKSX~_X&Ent3*)sV}jRlGbgsGSg{rGE0g7E6FZbmpmlpInNV{-{iqP-gA{l#R=1*NOWxC`gDA^b-aK&wWkY zl1qquDsP38QW3E%CmQ(|26D=o2%|u^JW|R@;SDHU!*w`O**QcJ_jDB;86s zc`>|XyK)~ipU+-h6ZoACXZ%hHwg@UuSY*gtU3Cv&CY{k$WgkH+KH_*5>URsK_Fs<) z@KNA2b-&^B)6sd{okR2n8-K?RbvVfbN8LB805ZQte}Zf#a#ugUXuQc>lg8!E(`!h! zL2OeK_09^De-A?R&{3Up-?53<^YcO0)Y3SFkZF%?-&_B`7J${t{fIZ_zokM|RW*&x z%{{KX<)!1&&iOs89o=YL5$*w`#DDV9Unh=!em|=9{eSr5Cn)GL3iQiJ?x%LYO4Q?7taNgJKE z-EzLQtT*qH_TWo}C=8QEA3<_4C8PwxP(mq$C5L96W$H2n&B_J-Y5GaKc7-ASyy>ng z+(=Fc8}A{wpo5Vaf_tb`EJuVLkfp}wo^GqcTC=6E86o0#l9J%Jz8J|DQ+24g|SCV z&Vs%-hQ{mU{8LFFjkszvO7LH!@REfh))#|&7J&oHM zouG2#EcUk$b75YqGa7VT2JHNzJTYG7iG6aJ8fumcZ(D*lUGzV2S>TEU|HH01G`Mp_ zn2LTAb+G>UIL$!eW;`J&g0Xiw37l#YTn-(LE=5XbPQ{CO`94PSw zBMJZB`%TIMQh|~rF^)N1(bLlywm}h`x#LeXfRjI4&(m@!N@S=@T0PEUz(eQoPqvwN z+PT(}AgpNe;Pn<%KR2EbqhA?~0)gf_ROg;%(41}B#9PyoN70>=Mhm<-)(?3 zB@a=577b~dkHSF&ywd?6WbdTa-Tq8k@<0Tk^^dQs`BvHpUBUgsIg+PvWqA8gTc+I1 z@`Xt;bG0NaS4L$oV-bxN=!G^mf@w}sp93X8Ltu1gce@NnnTv9pU5gjZ?ZvU`1?HWA z`rVlr1U7SIOXuy_l2a-7!+o?_saejg`+MBXXw%$z*{@6mrFn2lQ)Nv9_nkRevUX4^ zu*KCVyllZMH25J#uOTr(bE!KBge6lxfua~wj6B7l5Ew{p31fs^2u$(sBt|XEbzQ!= zY@m6Dp{2{Pn3*nh-l45pLr$mX@j6!IA(_q>!F2Waf?MAwo>-hgr;)afUIM^7V;eFS zmbbD|6F*W8Rf_RSYQ~HWz)RPhqxE@+AvwfLFMs&8SxhEF*4)3i1a;S=Cg<`U5wl#W zTO@@~*$h&-{o>;7M z!4G7@hP8)|&dxu_ha*e_b8-u8O#6luf>nVAecwFHz7@K$?soy%L(AG4XbgV{0__DV z4ccHsL~s*0-t4e$J08{o)=dD`rwKgUPd73ZTP2u1L^beDbISBEDoqg%efb2%Dlb0j zL<|VB27oHR>ejM$#)=H3FgfAq?)~$k>xC4+55DCO0i&qB0UQMd#jDFH6G)?Q46=>x zKPRaM`BrYpI`E$N+c59XB_dms0dJ_IF*S#TQDOQXzYVrtUm;KK5G7Dnn#5*J-_%Z0 zvEd_InVVt$oyhBpxhveU^aLe3w2hS7zHSzFkHiK$8vmMRti{5$YDvMFd*sslgr0)H%Y z8QM35gXP^{a>j*Y3iVQKlm_u8@Qnt0W^=m}qh(uJ9nQf?+qAglo_&ECw;KiPbFT~9V}t8| zN*TCYW()rcmNbWt))zBpqiEk=p73TZ(? ztsQqliPeCT#%3aL;Ao-kV)5lzi;%^vAy=B9et_+#jcRrCXD=91BS7C|v#G|s?l>)A zka4Hd6J_$C{|Lk9k;Jvd%-5fFJ-ghK?cOKO74;?Nt%;z6{ zS&Cp1{ju=QajCReRPnNN7da0UJ`eD)tGhWe=o#f`q$^dl6cu(EmRay>#ZC;> zS0SEl03p0*YYX?|AmFX~@%`nZcBR5B%ebF22EPPDe$~jwJE%&h7|6j0p+&d%5a{r| zg8X=F{|L9A7E3w**%=9JxQVeoK1C#X)Sp!!B|#~r*LT=oBDM`i?rppiD;>wH(BV4w zr(_59H!sjyX^5^EX+EVa?{+qbEnHZ!=agR>_u86GVU(Kryn7P&X$A1T!AM67WY(0{ z;!HcOzCQ60b1$Nj5!0(5#@Qamr;Mzssnv@{=>Rrx`a@b1$NL-_dZ|Ek%YN(&j44n) zL{h=>2z*fv?dQ{5b3M%6p;esf(F!@WZKGr-Bv=U#G|drHR>sR9NL?f}?Ry(UlR|Fc z&`NC$Sx5U0XP;4$A{sX4-y1C4%f=v?bIcTYP$X##2o_~bGBJW$hdsalJ8S-w&3DO+ zAs&$HUdWNaYRv?k#fY$E^k$55-6arW%NuPNV_6!%cNGRzY}D^v56iK0w)&r)3TSk9 zcsGG>9>B6S7G?F5mro#Zt(tH9KcV0@_B0c}pwGQrRi=dE4|GR-RKxjB9v+?+fA{FF z|HXM{j>G1oXfoo}v0+H_d_z1;L2`}!!6;x*U8{9$e-!l(;l(X)7Li+SOV-B6B84x$W((@xV2&$s8~4S>@KhZ?|Rs zye0T6kEoeMQ6HCoe)ajWyEt*>>^EUjL4Tb(UHT(jbZ*h)# zK_dUQYGaz*WPcjF_Z#Mu5x$C$@*kG{b|f!cJvxDbFj|;@spSBi;QI_3GD3n*Q^EW! zmrv4jRb9HDN)cy#g_3coLMOki`caYvii)7b#dc33bbMrLW!34@ zHGDEYO`0+Zc=5nZ557hkYi;Zkfb~kpDvH8)xyL;HfY>}G2|4{d5xgeXhfLl0{m3K0 zA63HVpbN-{d4DB%d4m8RfM5=YHGaH3N+b*o2M)s3UEVPP?*{=3?~0c(zQ5`#u4L3c z|06=nAU3nHsP7VPOvmIwAV>1jnAp~L{<@00PreadR_^UkuTS7Z`Gv5F%1G#gOZJBvQ1RXMlrIkcpTF_*LfDRT1 zy@V3+pMSw(;d5p6MFd(&9MFl3El$i`J9Na$L%~dYiYA69rG|z~H>z?MpS>#W4W5`4 zo`)dwae2#AjX4%4PMqR;S7XN_7gDkaG)6K3dG9virgyvcA)7kb`aXu9k7=LNv}@LV zrT*0CZur=AsTl4_zj-(l()gr#dVn3C35#(s93Te+3+FAz!>glNDS)MG~5G zo0Odj6$1;rbqOB$^<@>7`2M9Z7*i1%oQ=x$mROZ55m-T{;jsm&9&H|b4o?DEu5%rn8AkE+hUr?X)hnpFDp zyU8@0SrgQTySKkbu))IuEyfx@qy_@*+EHjhejQS>y+!+Tv|+->{d$LgmXIdHP~}v< z%na7wlI%Y}2Ald_)7!Gwojo|?MNi+EHOV#^aND=>-(bb@JQ^?cYyLrd)-Hs_RQ77ErV| zth&8m@up*Ml)L|;DKP&k7mvTAJA+0=y(IPjhIufkO(N>z0=P%r(uf$TsU zT%={>M&*CwY^huvnIml9oMmREy($2LfW8`_I-$ew z@B$ntNC?lTyU&2)_s;uAl}?_Gz}B!)zk8<`x%eW})B~LF$J#^MAke;pBLX7=yU4Cm zfnl@0?;Ru{Dp14%1aKlR%acys?P7}(jHxK$RFE8$#v?TqUbBxBG^Bi4+#1a;3X|ah zrLQ)=TXvA}@WBGk;6t0qYP0$nQ4BN}w zqW$y^%EkXZo(V)nC;y4`(=7qbhN^4pG5p`O5<+o(MZSQs!TKqU`PQgJJMneQKxnMS zGt9mzlW?dE$v5?)Ok|-x_Y0E*k_!xcV(P1KBbwe_71>j-xvG8wvO5RCE@+u@ZXTD92-t%91kr2V7s0mYs@SIb=ZCo(!G5a6 zGDntuuRd~rp7vtzs~P#T|FGBNIhG%&+%H$nYmhN0ZtNGD7U16jNBe-M)PO&$%@?B7 zqYAGHOq4U?y8^GXB5znZLO!8gWRct@eRZ|E-G1B(=Nik!#-|p8W$r4cUV!T!Pqum1 zHrJ)JlcKq&6e4Sep&lF>9nYupo*_Xj0aIegfWG1WxnT{n0RxI-P}!QWc24yth!Fpb zI^4WVX3By)A0h~!QELJ9@A+z7LD}szvZdBdLW5*U9t;P%`J6ME9IjCI$yKQtJrXNMg0YuCtr$pC zL1GNPi=_zIL@z7T@s#8bu@a+uK}z#H1)Hy8-zB<~k)On(P0)E0y>(<)S@ChCtcN~s zqU!e0#iINfpDc8Dx?Y_twi0ml{1<-~q>HJRn({dZQ&BXC+&zu-;abaLX`J6E_R7+2 zY+Z51TC%E|$HlIar4E(xY?jzR*~On&+}q1>hl<^#$QWMTJt70gGmG^~e<&A}(<2y& zA*Rf3|0PY-D2zcO#QZY^6M6+ZY1;RySh^-VX+DORTxZkgeqKI32`#pg;k+m$8F;X? zmsiJdgHAK_pJVlcg>^GcLEh{ymoy$xvAzTqbz|V=YG2b?aqGcWLaD;ZCc7FTfq}OY z50Lo1@)#b3%$W#&b+Y^93d2S8z=JCaR0TwmxIw5AEd~9VaKLkj$At*sp#A19XW#(1 z1+>T0^citI-;TMYgXI7WY4`hl^%RXL|b&6R2WK%YP0Z3s)6ySjADUAc1P z1&Oggt*CRnrN{y;Cb_+2$P_vB*3n|M0is_9?Ab4-+eEt>6BCREO%@C*gwSwLUPHu? z%vGKLzHx7Fv4JUJKfnNN)HTAFLb+vjY8EkU)dom@aw*3SJeGtqKLH7v-lEY@3=vPhpZM#;Z@@VMx(3yF^bb@$cReGU-ti`Pe%K0qXuNf*ZYB)-w zkgc6el>f$EQQOioesuSwrfyuvJ!lQwx56?I`zRv`u*o4013oltxf2k<1FBFA z2&A|x==ugE3O~TcZd3#h~K32cU;yjBZr$8b0 zU+TL~poRrc{V1**9)$$6PD){$^Y|0$0m_r|^3QU!AzCirObj&@mU^P?0)13RCPL(V zI>`Ru^uN(LPK>^`^fDv#Bt8T?miVDa{6+$0_TH*)h;?p@C(f~wCn^Kl5~kdz+Fz(% z&!3fgykd{O49b>b%fy4i$|tg@Wg(F6m09ME7aok@rb4pFOtUe9Wm7PK19A@|?0X&D zAW2+PO)61kvh(k5E*H`1<6T$oq~+)tF6lLAZO^Ps7c2lF6k9 z|9>wB)dbW(MUa_YcV5%P7YXH#$?p(j;B8=@jflr*2VI)0P#hPzp*kXHr|3=6!P@z0 zS{=AD^B%Bc3sLAB7ONEwgyJ z4Cf9i1B+%UbTn|^yi7-=I28!UBJ}-*V#|KQE05AWci6yp^!@>@xHyehHogtLn!|!q z9=`t=2@%QsQPRDzYUmf~hqDsR=eFm;)z1<6i#2A`H`J?Z2>i>dt`6U=flH!rKY^-6 zPP#!XUrb)kF-P=j&1Q4wfLOSsDX+YC)zd8Shu$!shGtn&>wWbV6hUN;|9DSOkH|4G z*Em)Mp{Ls<)J|H~CnU+(lxvCgbk{}UYyN`vwEEv#4&gbG#l9L}=RB()D6D9d?Lx{o zl?U-Hkso;8H1Z5C0w?8>2UcvkJ+HQ5P+x*W7!;^hq#^`)iBTT|-tPi7176M?0Qti= zebE8#=1-;jT`0th0dY9)Lgf%5WBEb@)o7ubxud2wXyc9Ve19ca1-k8OB$XIV$SV9A z&jvKqG__{f>%7YR>Vs4Zt<+$RllI^lpc~0q#HIS^bBZ}fe9%Towa#pk@^F6gXrf9b zbr|Bqds%fd$g$ZZHQ2umUDXPdH(Ls=R%09=)_rt#SIu-d(c48{`}c6mx>5h2c;s)y zhHzGtA2QOUo>5NZH;nF5Us)n^XHh@bd08jBmz$g=LS!d+yG1;jFYb+S0MeBJ{)hi4o^3MmfVwV)mKx;hfiLD z?kOeURSboxwQBPO@%@!_2wvS}D6>mt{R>(=3ze;4TCJVk?4qaVt9{Ndwrz=xsR^5D zO6vvw0Z{<=V`1@lz6HT2YlLksifHpac=F}fPh^j3FO-#wl!A9tMr4O0AsRg2=c|&I zHvi+T9Ssc)er{uW8j?&itwQOUJ|XT|*oPOmX&t~Lapl;5cE$umwz>ccg3a@N*wwRi zlL8gQ96_(2qbIUav(V-XbH-G8uChDf9j4jVR=GtX@io_km`qklrhVBIFqzkNhWh5L z;IMWd>hQprh?X2ViIU8ef{~Ai1i#~Q}o)f-5bxoh6;xIuw zj!~!>=^e!E72g2GXEL17?5>47>><0$CF|bql63}*IfAhdR%{hKg+LE#xY@tMsT6b< zjn3FLzVM?!Njl0WFI>U&4YzG)-@_($j+~}@3zIGATi~BPg&V;q#>WmLuL{EUyX3@j zTqndgDO;5M&TP?Lq&W19fj?5N|{B8VxPO;j_hY_6GSZZXa_{+ z+fSC`1fn)Z@qQA%()0-k&@`D@Ei>FJOGHrC(TdwYyjEyu$<}$^ zJ2lh=y(disLj0F-1Vko{4lsGsn>`hhh(`M{S5birFbUa&bMp6FdKvrxmr;P z8^>F=aB*6#?~{~9G^U}JK4{e481=Myv^@7gJ{dS$6g&TdY%Ayk>29#Ve3@rR-m zmXmDw{r1rqBCi#W3U0}w@!Uvke54$1V@ABoeJiethaSJ5O}?zI<7cXSZXH{UhYc-9 zA${kA!yE5bP4-n!`mI(e>9$(5@Vlls6$8YjOCuU}niX#;YTi5E?!mii&zdd2{r2mt zoSYF2vtf?1C)zKJBuPiY+w|Cjh>+<+AB+3iK2M@W>aOcc>+mDb2EAFlxRZ~2BC^eRK+~KF?7{lv%I`Ajlg%*$0%Wx}_v}6%#IdX^O3R<0 z0;rJfV@FD+4&UN)SKAaBwg#kF9NoM6e3Rx-N(R4sU9ie8+486?^ITGNb2qF#`gQ}i z`425Cx_Nod)UuJ61e|ol9jW59JYxg_mWPImbChlO@RAe>e9vNa7HR4o`KCAs@@rd? zC-K2i3YYENz(BAQH85h|++VZN)z5-3i+6>g#!^jz+TVl!1{LZQ%o&vyD)XB`$L-(= ze9`qpnCttDz`YYfV;%8>Z=z_z))kAdX|E~qGw7P=tZQ(gt@N_EdL@oasg*Pb_>hU66#Zbj$XOm0J zlBKU|pc`!ZAC*VIg^f!J_#9>7C)!-Y5mkGnEWye-|G&l<$j1bzWLFUP+!G4+#3O_a^i)M zCH%n8^o#v*cxDtD=JI~?@NC9Tt8jhOca==gm^OAK4Dm8-+g}IRL~LB5As`EhYM;;K zpR|aOn(oC#?OlQ3z0j@oj=703xm-%lU8|vof9Q{*39$*Ju9tHfKt~MT=Hsufs=5S3 ztq4H%rElHjC1bPW0UF8CI$*znNmTjn2WTCDphytcMmdiBCqj7>*KF8T#z}EmYu*Bh zJaK%A!KuD0@Qxr={O(Z)K$3ab=)RtM0p>)Yo;dhSr+)JcM<*`?%3j`R%ovolG}szT zds&7N*GQo2-5E}#<2^<5ToM5znE=YAT-kY-AVCX4NoxKfPIB*C7L2T_@e)s8pEI92+BeNGr(*6$K+boE63oUL9c!(x6(yphrZP2{?s`~Hlc z5O}s^Men0}SudH4zcQSmOv(;2ll)d5{b!7qG}hD8^YSpsES+sK(kIHEn@AU!4iid& zbY#p#w+~H73o@;M_pE>=hwh-AY*cG5J?o#$g6Uo5JN4W{I4w25ilckg;#bj@=>)e{ zgW&awa-iuN&CIm5Mw+a?Xlg^9Tt5ES;p~L1Y%jd|S3r}DigOBOCGyp^g{K5e>(^T8 zX!J8hHXqO?=}<+>pQw=#Fo_-=me3c(Ofey+A5z%*tgJOjQJEeNHLG?tYxX@xQS=eE z_;KJm@FiFrMs79Zq-{rs&f6f42Zj6<<9`b(92&%69nq8K;cEuQFEl-NC0qzoB?8dz z_7@=~8012bTiEYPX0m90n;zV)H5;&Sj*ed z&%fkUmku$gw@^XfCz+XhBs4h}lWH2(kSO4t2bx*BVG5Y&jUO?ac0%0OneYnV)+c37 zUra(PxTuneg4KGaeui1xHr1iebD5P0tM-IO@j+_Ze>9ocAD9uVQ103eCR$^Me=q;6 zBy6_sq}zX}+?o39p1O2S?t4~bgQ$&kzq4U2eYRQx{@4VDxts5T&8H;rs4$$%Bk%;_-?DjU?d;<7)K{yvghGLnJubJ;xt0-K!ZqFFbr5Qdwx zW4OmcM}qd+6)Y%$$O;}r+_WVn>B-%tY;yunP+J zBHf;J=fzh({onpJ432NJoGM|OTxBSZB=USyE2j=sSZis(KSY%S#9k<56bza9gVjtO z->VXl%}d8f3ylL_VzebYDY-;!YZ)2AAfSsOZZ@u(R|84v^oc$mD+cuTtuYBd?Q)zl zGmG|tY08NenGB4iomg0X3MUAwBPrq~Lozd)Te{i?TL>C+t>b94o_a8%2$+#Yt}%wUNWRYxW#o4=jW~Z2c$^M^{$nu}B)@suqI_*_ zAINDvi_4X@%FoNS@X%5EP#THuiAU}1T$y_5bWY@1`%8-_`+p*c=VMt zpMERrszB)*#bflD_ovYP+aSAK8?APHdnJs3O-iUumlX7S#(ub12M>FK{}N(9?jtC< zA;*M%DQLy%Ahs$g$&@C;ROaEe#}2~tisuqJe0%E*8zVa?z?Thnks8DKG|<@3ar^rE z&&zc0%^N#HklYN)OG~Z$JNKt=xm9Hflgfnb$jSfm;eQ9HFIzlCH|nT3Dqk>(t`)Lw zeM5&T9VU5^&om8CsdM7j%dFWrYqI~h^OWVX2`u>%l}gDEV5kTrQ?eR+4aanJQSyv>OZ_7&$q?lw9De!@R1)MwE~naicBX@_XS8A~ zN?uqREc)clho~q|tzQH|^^n&29&K_nYdZQrJuO_Ue)?fFZRej7jkZ%w4tBL4`?v4! zdd^f&u%{W|3!&(Rm6yYMvZMC3MX0UE9O06G8R8^ErIU>dM4HbouuZ2YFPS7A$hTgj zf;&(32cGY*eEMC!5##PBi@5X0?08X`2p=~aA1JvWC6iYM?>85YOBd6hF<{SwnEI0I ze(yGzNClQX^tx3}`bV?z;IKA8-h209;~4FBI$MNRWpJoh8+qn1oIkAI5#SF5!c&#v#OQoh_RQj_u^mcu>CTq(3a(zdt-a)N&E6w(e_b9q@CxLd6lf zaZ2IKDv+zk(cXLlhq!QcX-@Eb8;Cp%XQwmijrjA`xfjC>onx?nlOnj$Q1urC-oXL6 z>DUmAq3AJY+Al^5vxtg*O>qV(m@$e%haaenxpR|z(#c;}YjIsdX?N(X1yRCn>}ML? zuou5=OtgjmJ=3eC5I@4tz!tu2j=9Y6QS9PzRbZWb(d5dcUoB!~ak?=1QeRsgqT3Q= zqhoRn^M%qgX0WBHmzVXJ{palb=(7H>Q^@(K&SKjq{4w@>JiOG$yXt`GjgR+$zi*;< zhN|eo zCNTY}%p#ldkWPWzb{-_h0p&pK=+ae#@~;a;GhgpBxp^N_I2?n^ACHaB-rVk2s`HBt zBYbe=4HEze&9cyXpz(pgf-KlAm{P_ta|Py?Vu&1|5RdBap|vxn96_I$12Vs$wR3Sq zOlD-lqJ-M~dU1CRJs6v#$Zhk+Xmw6sp+N^9Tea@dmADr(l#%jp_4eEQwUs=|gpnn> zM+{w^a5c#o$>U24T)LER1>X+9yN69qC)~S>+{255rf0r-vF;+b(IXFrypfID9aogA zwn?lKY`Erg*^W2TYO_d@rx-Rt6%4ensRWxa(7o<9Kkp$UxXI%`XVo(PszLp7?PfUm zUMO!)tb9%05&?_Wn!I>}5OZ#J87uV3?(W|N3;b*UVYr{LlXxseN#nSDpUIMhXPOD> zB;GnIvwG}60FQSQrFrOArv8SKFs!H(IoOHV2@gE{lITJs=P}F2TUTCf0z=1LY`F9; zO6On3JFs}GGD5$abN9|(fq&gj^6^(@>7|#OgUQZckM8X-7)EiGgu7V~amC1=q!I8# z|7bK{svC;->f!?P0?^pw^GUUnpC1bPR?7x}Fd#1qdFvwu_M1ZqNT@GR`o6aqqEX`w zV!uMlM`d;ObvJn@6L@avCENFScg{UO=lnAJGnDHa)b|d~%=7?=VSVOVaV~>E`CU6l zZm-V{X)O_R`92bgY_+aN#LjVk>lLR(H}EXaErTu;$o11gy2rddxdGb2z$73ba{L@& zzgP3y;QXCxmVxeOOSj8E2KMHOWCBZ@ElFqHeHZPYyQ}AYr>>}sm@0?{^DcZA#IY)J zHu|`N#4(;N-B3jUW$QmvUTMA;u~f323aeH7TAN0x5Q}kgLZmTDe0o)6g`ucT>aB(# zwQSzo$dt~ovKfi*S$iPoAp}E_Hi&r>|Awxvw-apVny1BrNV==nhPpGjlR-N0b6`Qm zvfq9F;*8MDbfEiFIbyI3B2_C7!^u9i%n0n(^1N;CseYo=*IE*AKTHTRp#-f=*BRs| z0w{Cjg6Rauq0vzi&=qdV6KM}L%iphYNd(vXRA~sU$Tg6P@HfuRHE8%N1n*lr!ST0! zSL=Q0?#=Lv$S5MWe)Hre;Ci1SlN=rORjQoWD2^sOrdFo_yAPd@W($SE3bGT8a!cbo z-HpYEMjC(p_VZiTuX@hqj>@#(0OAIY|4rrwfOG9qcFa=iK@b1U18{%;`~6SA+giZY z1AcgYR;oF2LV!8EC5}HH?HEpt>Pfz}TqT!&!^4Bg@`K2P; zJHO$X+56t>Uh7&7$1mnPOR>b=As9!z@kkxcrscgY@4X3z@<@W2*_R}=q>@~t?jaE1 z)|vNd^K8PVE-?DN;wVf}U@_>x1$7(*6uiBNkwMwg*xC$DtY1ItY7edkVU8v5HU*WYR$^_<_!pPF#SUH~cTTf(4aT$sY6dEYaF53G z?_e57{@(ciBd9&qglp9xS@$)&4Z%59VXSUm4AuBV+3KlrLE+mhJadC&Wn_jcN#~$; zgOlPk%9>w>*wDH%9(CeN6#Ds~8Y2iXagd^5kfcYJo&7i!n%E7;u ziabAqg;g>>RuHt#QPN>ak|SAB``+G&d!C+IyzVxQTzJn#M^!N}Vv~?r0mEWf>_5AV z>9Ssww{yv&`8b>LQd!Ypzx7XLYqk47ppp7tvqApO^wyBZ*>DduY~=bxuj-mun*=eE z6ydjx;fsG@v)<(jZ0%jLbUr4@FOG>k-T~vGFCH`(p}@?48xQO>3`22@%Lpq+Ttv$c z!a%&!HIQm%Gx(EJ`WsGNe)TWeWWO>Bl9`;ooM8+bn`F9)5f{u%7}mrX`&i5|Gi{3~ z0`wH0#HQ;nBr0Tl5m88DKo{>j?6$UxONeSoFSDC#lT(lKBUKUuwSYXBkDQ|~N0dJ1 z%FsoNX#F7$oWQr|SHmzK>Ap0#_d+27IAF=OkCy1S6{eu6?^yDMCaqLC!7N?~Sa@>0 z$|ej-V~&IcA0;>NZJY^Xt57uiw`D% zlr0m)PlT|c7Ptd52f7{wm+(-KvTZ^wFcVZ*>zzkR()J*jm`JLlqyKJ0$fG_~##NjI z9b)i#+J?-gJDZ)~y`FFBJ+qmnXFMUTDc=)@Y?}H7W>y@(kLtu$J@B-xl>Y$l1`V>C zNh5uKKwrtt-Q9a7`fq}@8xTiYc($U1HbC9gE+;v7JsW;=}!DbgW` zH(>HPgl)q%D93P;OYW-d+$3~%;cj`0Q>=EPBx_u=5?mb$+=~NMcH{-$ z_5JEDlvqZR8Ah}0g?rW&qL5~ikVBwCRsdXCu^xZWKSszw>rp?51;dgVg$#^uIdmOug>G;ces(0#sZ<>1HcJQ*u`Au)D0J z;w?Q?H$jfSg2dt`zC@9$7nqE9{tdnU+b>6}9fy8N`;Y!?nIP8_%*>>zJRQZYRl-pp z8eqy*(;?Vo?i-!><4o@h@%!a4>DA#Kq5M466UOR*AVB2D8^i~n*o+wYiAD3f4`v@O zv=vDy#p{<9=t^g>df1%q@ZM)?WLh8VV*MPthG(sTh~<7y;oi5LJ2$Kgqo1YIaD(0C zSXju>v?E5o-;IcQ43{GgR{s!s6{ne<5x0D@bY|GRsDUaWMTRk__6vyJI;e|F_l8>% zYK9-3Z+U(nwC)9ZbZ_E@5T)ik=bcntWi-y;M6Z-tqP3rW00Vj1D#*%o6La4MNRy6W z%E-x8aEGN)b09@-$en;g!hH#qRIX^$I)>_d;Y<+~`#9E;a6ubtJ>uSPqdBaOp1g9O z5BcPn^LJ5_znF-VBh}C*drraO%j6`Ow%Z7o&0XZf^Dd#ooPPaDOe$4CdPGa?uznYS z#_J#NrlwUhOdvMsyE?BOb$646b*0^pWw|8qN8Q_>>{lLc zj1LCh`s}PX+wZFfY#rf2vb>G$zz5l81+PPwCG~w^s6?DftwCu!?n~JB4EFT7WvV{S(mxW{n;n_uz-n!Rj;I$vdY4}CvXscwRB2zNOY*Gy5~G_FC9V!a zKKneo@S41_%3I_wbMG@@GwuBh2q4YwEvuhr$gB2eHAK&iiZ+$*3%*&PpE7B z<=CnbV4v6j^IvlR%C<0>AivbcNeiT!hq{hu3>f3*R1=i4;amAoZK9_~NjAW#D@vV` z@4C&a=;O~-&Cc;tzh0Q=zh`@bPxc5@;7eOz=zmhc-M?kS%-7vrC`eS{^c8x26D`~3 zlA;AtrlKky6%4Ty@LX(}0wKVH!SCC@q7(ww?Wtp5c1

{hIhekUCRV1xjY-=@x)S z6=6$VBX;3F!1lxR;3T@|mkSKg!%6!l0mLBkl~Mpr;+f>0(~ ztd(slq4V87!B$rQDkHkI4dUdYK;}OI-9J=zFT4tI4L>s%JMkd4uM9D$O7K9 z@2cYF#x2KT29T_d6zUU0lWZ!lAMLxQc{ObdsfIXEqQIA)FR?BeEO@}bU;YPM4!2Rs zn7=yLK)a+fa(@11LpF-RE-_biv9#vT>y__f6RQ9DGfMbD`oPCi&-- z%yib1c@n_-HD8=uKKqOEnyC)Hyw#2g3_L5E~Uqi`~ggyZB@-u$n>QVo*b?^qCJCqOL`B$xe&b*Ci44x_xn|UU*j@7@3bQE(t=f zjZSlgt5eZ%Z~Sg2l%@Bj3B~OP?JIyx2nuQy@>>W)u1vvAdA@)2jPQrv>rLCX>4rTl zS-(gQzK<$}-_t?*qwvSWhnT>mERzTh9ZUmOIcEwcjyXT&BHAu^_sQvZ50BZ*;_F<3 zLr#R(G^}s-&a->Kvv;gpqowuVK%ROzanY-jfWQ)?rK*Yy&{MM=k$OZig1op20avK_ zryjGwpB8^Mw;PDnI+WKwC;In}tTj}@m-O_WJqHNC@r1+`^%stwm!AE_Qcp~|MEpAv zO{-yr=P$T9dh?G(P%w8E+qQQZyLH~Xf{cZF?&`DI2t+5XH~xXGZYo=;+!R8>b{knE z)x}T&pcfO!P2LxSF1S~&BtYY&TZ)A}?PG;vor!}ogAPYpL8Vkp4uPBXE8=t6(NOg= zWBAGM=3pozIOgH^=>vGjo{AhSt4n%6Rhz=n$p2_*Fq7Px+`MKG225Ndr-~S7wo+vBYlOykU$svuU5* z9M;4z{_#HB>FRpDw_rcii=n~CJcx}75GH^F7bb+6l$=tt%`gaW@Gq2&c3c|91RqHs zk;lmpyn9bFW9S!+M;aKCGz6|o&^$k|CgQjBL^u6Xb{*iiGLD;Vv_5opL90+FPNv0b z5uZk~F`B;cLOWfzD_4x~X_2X5DQ>}enUAdgwPSiwjXpk(X&Q96y+!P;%EG@qr$&$; z$4;!zijin7I)I}5M?Y+l&e9{jFAJpnB3?0KW|Qv-q(78yJ?`5x83!aH#+LByBp;5^ zq;l@qbC{G%Mh!3?lXOA<_G0@SH7R}GEg6|-{}D*+feM|Zlt1V6(vjbm;(h8R`Jwot zhng_*urs4Pr&8REp_MJXzP5GqIi;nQPUaw~%wKg?beyoPiNkzr!kZ?F-NsoXCWa_b zwG<>B)BLS&gJ5Y-dx%YmzHmPT^5E_;pKRJEBL-nYPCw?R`xik7;w$FNGt}sPFCB8? z?!>V4^qs#Fbz$32OWBWLj>54Rc3qk(YS!qZ_`*b%xIU;1dN^(M3>(OLy`S=xO~HGQ z@sh+pK7tdjuFuitEe9;uc21t>;=CgUMWfl+DB~z2v0TS^8KqF>>9*EQ^ovBdM%)}G zm+G6%oSsDEB-5td*M})TpLG7ncWEdRj-8B!oP7IXE`foe6SR8!1KP-Do&2ElJ)(z; z`<_hxlArJ+F1JT46MM(#@gT}W?-7-GwEdihP1(W{$cBt@BE%$-s2bv8Xz%J8SoQp3 zcqYyY_LEFYD8-g3G~d=4{D=b`w^M0YN^_|{b%$GXoMcsv_)ZZxv@5td;$gc0k^f*$ zD|%ED3>3SoFL0=m$Zq!X9=+*OkkWHFfd!caYNSuBv&%-UeyF;9m_@xkayMQ=o;e?k9yRS};& zeD23LQ{JspNfdf=y9Qx|DDK+CJ$o2rd>CNg-rK?9=?o6n|CpXg8I8*ykC0i{oXPbP z$Hdr+RLR=v=!|K!!ACfKbNGzzCJ!Pb@s&G5MXZAN8_sB~LD!FOSK12KM$uX@3E^#z zd;xVckaC%@qgCeoEbWu_{`uyR6t+~)4fLDXw}6EIxS@fsU_1>Gy=B6r1?;EgH7 z9pUfl!@qolb=EB?)BTJb1&W)J`lvOecQ5?m8PL^-IC%8^j5Rbm$f8fXx4SXqRPB;m z;q&CI#luPt4lUtzgOOg$VK9O<6zWpB1dO6};=Jn)@#Jp~+i=AQ(b_#x*A;6uZES|m z$w@sZ3(hKQ2m)y2?y1laY%QIr(2h5gN-b_SN@r!I)_1#t#yMQ6g=U>wk|N+Ow=1V#JsIl~c2 zGdVX!Xa3Qf8`&J_55{GEPaRwv{Mv?85l%~-6s`%KAA5t9pfT)pwz=sqh;DQAlKP(g zf+Z^8Ee$X&kb~M-awID~S+vB>Sc-{KS#I{PJ;UswnXz_rvtjoa*BPN@A9=>4gpaf( zssBts7kAx5IFmpEltQiRgrG+9KVE6~b6Qku{zx5gL83bl2Gis91j|)6WJU#n3w_h$ zjsD76D|3KO!(pDLmR7R5E-d`T5L(rtd(V!iLnc3dT$DL0IWuze@wGG&CjcN1(zu z40~RYBfv01Ps1#1@`S7QpA08jg#USsR(`I#8V?w}{$cd@wbV!LETMZM7CQQuxx760J-`qKMGSX*1`{BRk>R&PLq^f%eFG2hD?YqG#0`r%YUY&Z zLkZo-)VP@YxP3Yz;o{O2H!)$m6lJAK4;j#T`W!5qSald@{D#K4bn`o)O9J8Bl$=eY zPDCv$Oz9|psE`IFMsqHXI(wI`hfZu%0o-Sm*APSjwdm!c|yr;q<^TDD@nY`DY90m=eDuxo%n467B^niS^qM3kM>6^O)Aszsz!2A=nVjruasSl zA|z}wW1T7#u_tX4j+2wxnzN@|KARJZt(jymQw$P$O2qGMt1#5oyYm+DYrQYu@cXu{ zQ(}>)K{IGt7;>xOBaQAW5-?Mmn*!pc?cx?0q^t%ng$u9M)C>Lm8zAb@-*Xg7E} zOvc%rW!a(l%l%Rj^8{Qw=94&EI|@GA9Z4e^xCl$Nzn~%&&A_4mHhKZ5MJv(?nu3^Uc-=&D)-$0erNhH@Yle#U;<&q?*}gp zCux^w3>Erhnb!c!6``X=V;7%9;h@N_gsbkkdWKrjeH?To zE`1)KeQ%RcDYPW0a`IX`daGsW_W&zr5OMwdM2K zf5^gQ>F4(4!6@hz^C!T+YoHQNcG7k6#Fox}k>e!QAhCd+LqYbK9KC2dk_gpJ>4j&i z8SXN(i-zR^Q&w@{NQ2rkJ$#mvW`r7<)*1GTnf0N5bj z&1AX(MQ(YhU+wLziw*ZR-e?yL$$dBW4;#CiX|n!$?P&8CY{btMAYzn z%An@fmeRp_RP0BtSv!WnNVkrWbUm?5L5|jKYn68{ZbS|!4l-{E1)Z8}s_-6NW?tV$ zoSVc3ruvihx%kT1b^iU;Zk`JJ3Z04^0#XLPFq~?g;~jclH*G@P*|5B;egtbC_o3aHOs!`bZCceq%E3L_kmAbmm0V)uzihka|yMR)x-^ulJ&;mrWOPKhV zIoUs(bbQJGkjU8d@{;1L);d_hi@Eyi?h&|>C``ABc%&S|qHCSlS;Nw7`@9xP-9>)A zgRN_qJtq!FRYrErGs(6H?=Ey5SkjQSMdT9t1mGmI`6YBC|FZznQl1{!rHtT$3D;JS zXB{#gP)vtWxl335hoKv0`__rcK!BTD_?Z=WJ+-i;jX@gN7!WMAj=8=vfpoL~T`+v< zB4$SF07cep&=&HVACr6x7>gdm=KVqaKqo255AVP3M~o0E{)Lub ztf00A;?DN;42O(~`oi8J1AA9qo}Pzc-mQ8_e;|u@z)-={?eS-b{-`RR;O*rFK-4}Q zw)kU}?;j3%Tn|Dt4$l~fzg_9fwQMWia$%AWLiaw+6S!K?DZZ}GDUBqfzOKA&MYgGs zB>mA4^EmVvvx`p{+D>5FMB;(N{Tpe9CpRAZJ3(#aGX;R<*(x3f%u43K!%JkfvAMCc znXUEsIByg(f;tUh7Wlux8l}S3ZEt}09a=_W8F{Jc{uY?TL!5GYF7a`YIzdt#MCd3~SFZ z?M#?na`tDRl?L3GWhmc+H`gLj;`Vuj+f5JS>uBoM*8KHtK8=+SzKk%@g&;mgy~QWa zQ^Y$-7(T_|dV_7>$J_BrEi?lt#W74>UTvnKr~?*RR<5|So}SsM8b7rBo7943AsrgUTU(7 zhj-KzC%F~o=s=b3K{2tIw~_junk>Y+Vhd{1?Rw?AVhQ@$6Bn3Ru`5AC9ECX8p2jx$ zTUp*)CixgaSD*%HU&+>|N*c|iNFIbc2bf%8{)eY)E#q7Og+pNQ$(xbfs?v5gF_G{_ zlG9iNJ16_DE<|Zer(9CC)5Td3_M^M4&y_CHq|vM9dR=) zaTtUNE;;{k=(UXe&z6sJ1e@)2a5pwKb|6yRe;NVgQ}eGfj>A^D%nzKR2xR}6N5<5y zXc;54QTrzAx+M_o*-0FK6D$1j^yT$!`$Mqud+HxM7jWv8@dJsarV?UhM-5K8Hi;1j zg(eU&!oUo?yc=E#s{x1YliN0%wsrq>ICerp?o)Ruuh&+?wtK#d7Wi}ndFA#FdQy_` z;EveB&+U0bdvrkJqw_V|<2X?4FQ7*1m%tgUYUn1BCh z+q-&}l-r^5k|}Bl=p0sbCDImKSA9%>@FkfrypR#{TINW0(JJPf2(q?o2RK{P2`NX% z-Xuzr;M8z_v-Dd@Km-4Bk!R#DeE$cHt@U|-}) zO0FdbADqO?wyKoM?^AxCxZFDFP;0pPJCPafoX1hE8_x zdxU7M61HEmpx%yrFc^;-{qeS(8Y}mfvpQ$DFt=^8*Uv1QYu+CDsmEyl&bS*=e@K5B zNtp_3od{pHuH+e!g3<4FR0wosG+bkKqp(GO&R~=25~qDV|K1COxoh7xSWTa=Dho+< z7+a=Gss6PZ0g(!V&Ni8PKF;|?o(=?NAiwSbPhWVEu4NvG*Zlb}rBgP+BMK>@AVUV! zap&n@4;_kcOL0^1a;aHTu53GcQ1$qZ$=E%o9-1(S)dC}BgX;ULH3kBtf%2r>U}h12_i(K{T(6({9vf;|%l?UW6vGWA)%$CMpAPqQ7@#{L0s$yh#V$zei7 zYv0N*;C~ORly7L3#f?7#HP33y@6bR%s}bvk(tfO#|;8v@JruF*eUKp{bF>)35=uI9aCQfP|(*kj`#|CiD5Ks`K?HO>d!pa0~%@{|sd0L}C=&x(rY z<9{6W0wc3M@LM+CBb4}LNQz784o%egRh!+IxX~?eh5iSW7$p#2h;RPShTRkq; z1;m*&4JQYuQt5A|e$KBG`Rsz)77hmW>vvgBjV|fKgojaaz2?J*=((S<`b^<2hZMin3zU`dj^QUo1Wiav@z+VjA(Y8cN586G z2Nu2x94uXLPVt$k56h*(ea)<*Q+vMRt|!Fl)9s?(`uwE6FI6KDW58z7G6xro-QQxD zJ4EkN3W8u4eyL_8oNryxWocaY{r*8I|uLXxc>Xw(L?j16r|P@NZFUm zP~z_R%gQV}(1QHstI>bcAGjB6F|&63shLW}3Qw)PL6D(yW{ef}D3Yhd1ZTzR$Vvm_ z9qhCZvkVM%2$kmkL5#Yw_$1-4hf|Oxh;PIuJe>tRuO(R(e&{HLd~CQxEv`tjTdDlS z0fXe{Qb9Xf(Wg&jeD}!gV_$y~E!aNJz=13@;rlAt3oEq}*e{u7^)R@CnsFSENaZ+B?t$dSQA0SqsS4@nB z)mIw@1V`(6EO3KW*?YF?JUB02enlKKJH{HNjd6oF;$8NKYoO}Ud!3Htd+MC}@-Ar@*_a!$rx&{MSa1Qc?yhApJ!)9b;k+RR0 zqJ|DZYgQy-*8xc6Jd6tcP_#f;-(2Pas|ywlg2@vX$73~$GS!c2cp#~){Wx{^Vr zmq5QKq2!ry=0jD?ZH|}?J(qDd`mK2Z9h|wHN6nKP6r+u16|GzRIid^p#I`HccHLwrb z1cr8USDg;w5I=ux`uU{kwEJ)Xe|@dHF5n*2aXstHDd~=jYI^TKg-c_cV-6xJ1#RZXs4X zPlCUclpN+HwZd=5i<5p5fC{55tKTn?1oxrXg4@J!dCjl__NU)+R(UK!)g{YG`b^o* zWs|s5>tT|7JcWv=xs|hX>4eG;c!eSU%uuzN$yU&5q5V>Dv|RqU^^`XS$4s*DYL{3H z*F?+&T@}k#%-XnP8oU?i+J}_vEOejD#y{le$M(7t?F&cZ zO4Qcal{5h)YZH^k3RSz5RVkQhG+NH>)082>i|3f0h2u42Z+*O{zRZ5?DSxy@TG8&F zsyWF?_(bxWHtM`rw9^){0{U4sX)oHx<*$%c67cAtfOQ;BDRc=G-G#tKz=SKCG%^Y7 zZ>}&I&~P`Zg72T;ww7;KJmOEPpkcvbBtx$sDm>@_8>i_{uJooEQ?YL*2@#$A`_wQ3 zW|?@uDg~+v$yhSbec8D2A(9Nedo!60c^7@$3W^NMpe{)$qph%ks*zN&gaTk{T02nA1`9uTA?yA z``siwZz-D-NM1>zex%NALGXv8Cr`=abY)3{rTFB6xkOBi{+GVV0Z#oC-ho=hlNTg) z#p=MV?b=`AeeU0+&g2#pTL^-J-)DW@IH>|y0*$;I*@D+*))hoI#q*uh=`#zZ_2 zKH0qFbs73#qze(m+82DLsVWl-h7{E1zm%09OH9+MxCOwFHxoOb?*E%UiVq#9b0h#y=iKDIuGut)9_E%F(&Pg=D0mQMVW8Lq)j)O6{vy}5gkje^K4o*4Jn>;K2NjMFYRr{5fd1Zh#fUfYJvUhpFsoI-I!t%E$PdbB=JU6`paGFW~j-?|( zMOL#qkLdflrb7N+b*ilw_eekM+r(0$gS~1gCMZWn;^NnlPl5yVa-t`E&TdyeDnE9T zUhusyjD3rd`vrO9?`ekRlMxx!Im;LZk#5b{WqNU9pr&cLOTMp^AO&sm@`$qk&~j}2 zr>gYwRxuJx=iYZh)$AC-`_(Pr5sN8ZFSqGazOx@|ascm^FJkehPHY1@jjB-!42ub8 zy<%&x0ApZx@Prk$J&*kh%TQ^L9&5d8%_@ zV1k7XgbsX0P6g57=PhBV*j)2+b4}XTH4=y@P>lu4bsOJ{7gRDY;FWvu<|ukGvYr%o{c~={I$QK|XZ4&nS{_Bo z%pAcTLsRm=>QaII-2JhkEn!^X`b}Zj0kTN!ndG+yH%zd;%9HKNw@bwX6@_(Wn-T8y zb~`EkZKgMkK?Mp9vM9z?1O2^IKfERNyYQMf(~E>J22@?%1>-65tG`ITp~R@td8;T@ z#7f+(PTzzKny`2;q{C5LO#aKPx7 z@XE+0AH~M(ZNS<`Ilo-jd9|(Yo)jx39x+&na+4_Q@|S8Pk&A5l36+9dp1e>fKQbt< zi)^i_f~r?^QR-@+#x2AY%u{gW**Zk4$(u9{CMxi?Ot`fX(ff z6@!ReMClMGCaxd&LJn~npc2UhPlVuT;e)4Wr#pl5E^GYExMqi`fA|Pl+<8M~{}=*k z{3R!4&L!;;YpB!gaBVM!siEk(EsmR@4eoi*ho<{a(S-kS?;iUzG60AOr~s=wwBNu~ zmR)7TKU#(Cu0LlMtF8yl;Xj%T+PrEDS1qIjM1&|LMLg?5yZ6Y8uWjx=nJ{sg75^Iz zl=64%a#XmuxO1A1QzfS1Hb(;2P}(J)4dL-VY+oszvCX|nCu=vf=6uk90YWdV+HO(c^%Q=x^B zru>h{HSxEKaccbn7Ouy%&XBqZnclTsMelQ)=hhRTh&XX7!1qQk6Ti}&Gj@G#i%^}BP) z`NrVq5;ftjC{e$4hI)fE6{O8s_>6Xqu^F>S=dqQR*lym_WYy@9b22WcmW}p!t^A(< z^$r@_u~i#g;r<#grZ=ypD@2~nFk%F%trv%k*)GKKJx%gD1@ndPpU`?ecIR2a&{7#= z!fEc0105ta!s+VYo~@75RjO9igF?=oCi5*{3mB?2>rr=CT@4MdZa8&|AM#i-Lpr9b zN?0`de?4Fns?afrI4pC53@&D0bv-it6mvlmWZ|Ix40_`!FR1=Y0RARE9qtT$=JknA ziCf*7WXAGytp}gQjZi$y`+DGuQ^wIM&(^7t--ubZjY`i#2WG+9u`L;)Kwg&-0^Rr? ze8s;qc(xck-^8d6M5Bh1*9N0*dv5C0N7jm3N57S3k5lJYvdPX=crCJw{H`s>@L(|J!qNMz`H|`Ft^kz+c z#ev?Ta|$yv@7YRgO$ly%1CWWjL^1#(HMjRQDGBv+DvS;fAO(wl$&&&nPBztOc^e54 zxjZ;iLTxh2_8z=3PL8^bKmwQVk7ONXI&=JxdoCx2a7}Iu00RSsq_dQEy`O|=Lq-g9 zg)CPx5;9bqA(Nh_b*vqg!*s6lr4XzukQyrfzg_@ugBJ7kQQ6eQBbfK=BjFu9Scs&= zhP!k(-k+`K=B~x3+_0vb(Oq*P%f0Yg<@WKoJL8t{m4l2b_h=36n6|Fg3VijRy_GC| z`au!SkRZfXA_12#-&m-VVrXn}$4bITlGB~T=Wu~eYUkhL{GtY9xE^j>Z65~|>^;Nz zo1bm!!x%jG zWN8h|jUPwOaWjE?Y93GMdJnI=m1ArsAOsCVP~o6cu*qm9DMHWj!a|3Y)C#-yspo9X z1m7aXHHS5B57XB0O2tqrSNGE2)5qKrLyS93yND#54N_D|Z>Xquc|{^#6OcwkSt*JE zrz5DMu-s-;Xs&KiPEdIAm{dkATZWL889M;vK$;woViKlK8S{j<3l?18yVY!J*#7!n zc7YZ;?nFGF!*naW_zmQ2s^Xv4bumxAPR$z01FTW-K%`+LRJ zLW@gmpo6}<^s=ju9NNf_ePAbgVpv7-BEa~u_YqAEx(0s)vgh-h!<&-c zhyT^1)bqCkneG!Qo0u`hH8C@x=yF4mXo9=|9oX!~xOsbbmoHAWmV{-YrAj5WUs@VX za&Ow6F6pQjH7Lp(a4MKV6 z;fUi9k=(CrZ--74@zHX~=HW=;As{7(s>cD?u&s`fw8A?Ggc5MJBXBr9c!|mm#NTq z3GH7xK=WJbrplAslcYy?c8zrQ&UKKAp!3+@{4VYcwe-2D$~d{W=kJSr9<6)Ito!$TEC!kdJ8JT#7{tN2i#fd8yK3ndB%ft z`tjYTI5J8k{a6qvB-zcvOXGgo8R|N2-6oZ7f9EA_oDroVujMd8ulX|~#aPWYXhBoH zk>Qw8Y?pqO@;v#wvOA99Vtbn~rMH#9LGAn67OC4%4|hBJZ5!x0fVL%`zyk#;MNZ`$ z*eyV(ts;Ht93#(zQHZAkmDBE+w}&9i4*xE16~wyMn<*GBa`ke(6Rnfg_I* zt}~?~JrBCR-4w4djAwEX&!kiFWOr=6vJ9VrEZ-v{5LT(?LR8kza7(2{w^B=FA1(QJ zPvxVTQNeVD*T2hhp;z4Hz2XD;5xE2t@KXp>D-^jq+ohB8Ao(U0>)-z-+k%=_p<6wA83`k6F9(4en_3PQqF%55CpAP%sxo?OSk$UqY{CLP{6K6sZd3>R5M!_K>kQ|R zYXm1S#v!n}w|kBl-5ZT-=IkOWHi$2ry7n}Hus9U|D+1gbj`E5kE#JKBBd#lPRMHfF z7L_#5;Lk7B<73*WRQo7gaQ);nGZF%XHD0N~mmbbTw0#WsGqnvJ1R%_LOIx>P0y;## zy}c$q$$+ms-F@{PHfvQPBBsp>$2B|Aa!?J_HMQ>AsDPFtXX2C)ab$gRNhE@WkV5mI zCZMp4A-}YQJCFut5PmY5$WIz+!f(jLun*(XgO{kU!#LB5=pKPB+Hz{jQ((_4HPOrb zDyJ~HFstA;o0`#;XsFW;b|~x1n(}|WdNzHDjuKFtP_J%`~Rrr|=|p+6bcYpEj) z_IEl=W<12;mWib#wb#Xis6&@?B#c$+%UxiR!3SDK#sxn%?>LCu?sF~aRm~Hu-f}hw zyEFoVbQy<(M5DDW#(JfczXzIFmRE1m`^~U4|mDLzJX!5!Lazy*(%CrDWLiw}B zQ@QlqUzPB59|!k;30g(QFwaKN|CSVPHJ44Y?L{dtGuM|VH-&y zIR^J%oPM}2AdKas9klB;+ra)V<%npr%x)}^^}|TcH#}7&3`*8HyY?!xWL;s4d(i%? z;gHwOiEo$x3$hzC?=*q8VIm$>%xlgjw;g!A=56 zqImSjiFBhKJcv#tzwY+91&uGB#nUb_M_i#|!BlQ?8)OwI4D3dCF7XH>MK3pesc? zw_t3oleq3_3BOvwbiW6ZmmIf)3EU@&?e&K0j@PlcNJ$WwH>7!>{nFQ|^?_DWXSH+r z?`-X{2fs`=^n;-v%4dx&#v`*UDU5}kOuue&p~1U|NcMKg4+7zGkz#u9E#(vsV@;Hb zMr`h$@y-FCI2B~)-$;ZGCPd*Tm$Q%Fc@5ha5cl6fx5No=3DvPS)t>C!lD@vaaTX0v zNpe{puplXfiXI+|;2kr79u0YHUWY0TT~>dfqcRAFBQc#4o(3DMHfscF{t!hGSmFO@Lq-!Q}sL|f?8>=3$*2*@-T{hWCZ}G2q zaL;!@3sbaiA@wKChEI&AFN)O$9p7gQ3J0{Y%_5B`@%=wXkovTM>|_$%3o9Q#DW2Ht zIxVN6+9;_W;OYUi)?Bt<3l;p{(=y}PeGtu7p!{OpRid%?>?yny@6|)fqc(K z86GUZ)PZ$tBEMN>D~7Gb5dci7)t~Z2R8XlhX$Yu+jusLJJ+E|5t+#U(Mp$RIZ`XAu zROq5j2%{xi!l+Yt=;_JVH9obJaAI&rf&LH)n(0c(U6!b9!(*~pdnM(vOYj#lZ<@?s?Pe&H@tPe9x_dp0?;PzObHg z#5Vzbj|XV+Oh4v4zP{_o^^yjno3Pw{r#QPt*-kg?ske2vR{^TWbH~mwLB)5VlcYnx7-MwVEN3f5kLj7(cgVr z#L4URf}{CGn;vrx*A|pVmvel0TIy4zlVe1Ws=J-q$&syWoWwtXpq8BFEz&QrZTt`r zp;c$Nd;P|x2`=!>Ea?d8QQrqr{T2)5PT{@}z2fOR7T|88*N49N9uK?^o|QV3p!s4D zd*>!gHV&|n`RwX={-PBvDO+k5Ar&gBe1%hRq@xf}MZUZF?`V_{T(|x49dd=bjU{i* zFrp?ke{vZP1_?;MTWIfJU|k5PVs%y(Y8j+I#=pPF@&0SIJIZHQ8Po?xZwW}002S%z9`B47J!gv zDHC!y96W8_{$*y2>oqPeF0k2bFwe6$GE4yP*GLjpN8 zlgs-)lxo&W`dnGq1fC0~{Q)NQnHl3C&70oaiifIrbzRsos+BfqFp%!GWfl%p%b5|& zGmZXgNvW{s`fk=Ve$zpFdWqw)y)Zhl`pQNdb}_4-T53j`yBvcoZ1@AoGvQbUCSa-# zC^v~jNaUqXB({Vk3N%?DkvOb!&Y=Nj;CXH!W{f;vCWedDu(yyc&lVS#?L)(_#>IqW4HeM%%&s2qfp~}k5cpl?}OFO90kmC4Blu!tcmQ*Dk4>Db)e=+wFM_sXq`ukq zGvM`ru&_2C+LQRVs zcAjUV#D_eT>gF_bQ_~j> z&x(h67zy*?JzhV1g2&(f2l6nY%o(H}cv7Sz#pI(>drZqRmi7z*;hegHX98OZIMBQ) zIx=R74CxgSX1mAgvejoVU6udHcq)JC`CogE`kHTbt=oD|H7#@*n6-TJ-;4OE9_1xt z;<3_P*Ry?Bbk@X(R0H44X2>`mXK(avA4T+Gv`RL@-@VRgU<5j~aR>fA$#W z-aEc}x{G69qJxMlqQU_kReeAs0^qg9Z5`CnWAV~v{!K8aV=#;W@j?DCa{;Bg4t8%E z25_12+mm1M?$v8-R!JJ^fsr|@$`ros82 z*aZ^q+`T}_2jppo1aa<3O79%Cw`#b+fPny_BE|(~5Lv}e#UmDRta3+Whds*-?ST)6 zPU*2`JX9VNiG)JO7i5h9aFLp-B;D)Vj@FePBE6>tdNW7zK)}h0uzUX&Z(cmZ!^htM zOvub$GJs)tsy6-Wd2HSNHu9#&iyyjf!<@q~-1>}<<yZX4I4E+8K?0@Zl3Wo-zJ z+IlE(Iv(}EtIq;hmQ@jJ_gEs%@iv}la}hpPlz$lQ)oij_TeLGga&;0P;|jwRQ3kd$ zyS+E?7$U`NGIu~SXL7FNwb}LAYw_o$eU57tjj8iI*ZaeBj?Y!n?6Ydv=y`hc-TGqZ z;ZF0cQHl(S5`@&kXBMY^N$e@h3`@t?pWRqO9(~<79$7jJfCy$XJ;745jQtC7{;M#gt%U>B~^YL1>fcxQJ9E8R(eFE+7a}^SZmbQqT~!_Qllz4 zz4O$a^5%$yh)1LhjB3xJb&LoG;x zGfl?%JGGtw$_os$~HSTlZvEg8mcdw7^E z*Z87(ru2K9*bRgn&aJ2^Masz)Muy0Z1OkRZz7zJ$uOS$0O^)eImd-{mPZA~c&0Kpu z+rHapwH7U@HfR;vP>4h6!8$3x=ZuJrZ{ZX6zT0&6o;UdXJNeXNI9nrb=s(`m@G^N| zbDzKC?!#`FW7& zqG5mxjOVbNx<4}GBSj|6TvedgkEY1jFf7z zIU=eZgUL1mzK&J$n1Uvs3~7*0sTzQUR#XX=<%03uNP<1BiBj8P9%ffwNplra0$x1% z2}2t2`NKyjJRoZpi40qna;`?D9v3a0u@8OTUrUN}k8dL%kI(+2cP#O>{uxWS&VJ5W z9J476i};$T8V#%Lsk9N_mC|tZ`Jcbo>s21fg>KAM4{7Hcb%jRea@Sym?Bmvm7}vT9 z$}kS;kBdAm8mW#Ay>WfwngSA0Dby!xmxhG>v`4mxI<`h^$F$h5MVxb7H!J6`q?0VI zZ;w^%tTVF*FO)DpR$Wj^oGj2Hi^`G>GrAG0$f{}(3B0zT)g&ZE6*5dBoHSQO{0g-BO&xs zD8-GqZgfOON<%|GH8L|ecu=u8YdZJt`WpNF9_#T$()0;fZ`Me|sHIE_k{S1$ChFcc zhGg5%c%BHMBf1!?2O8WsZgoj3owSDXSo*A|NBKE9-f&v5Ig)Ba#{XcAyR4Qql-?ma zSTQGF18H?HAckWSK5n{%1%V`U$^qKUia}`*xJ@p^?=H!~e$RVdpwYn=97adD zb%8h8ed*tpC!dU@pRPZ+*o+s0EMutYsIB z9iDz!_jJkFA@8ojx2}aKMR9Gd2~~V&LnAEpl7>O*qglg(-dG{4q(I1dH^Y^0^h}qL z(tuSO0g`eAg(bQ(Q4(Pm(pS|CDxTP!k+Vc`=A3bub~qdkm<|*6`#tuDgLH_@8HfE& zpRIe!kmg6o7yzUpY09dk?2H7g$CWA#1LeUhT zAq^M?@jTNYQCU%FrqqH~18Am5nDT7iRqxsy_OEt=);&mON?^od`Wyr+fh&k&R$Qm6 zuSz8;z2{=!#uWV&=*Z59)lFSRU8&ELfYt5iQWOnF^yvp4Apb9WHdVFpU3>fly&=i;4j^~j^B-N-gW#T z#kwkRy5yFc_HSH0Z?!SRwXAe}i+8wtUT*|l0%wsg_58=^OMY+HK7L=WW93rrjl8j? z3z<`WW|S#${4q_)-rLRxzQ1-YDYo)HhD0SMSHzd(BS`pVQAN!Fr?KETz9pLL#}hAk zm#mp6S5@Ka_alzU6muJ|P2A^@#Zhu{a^mkABLD05FFHGF7>&{fjK9^0Zy#SVL#5UT z9|qL4X{&E4QJ`g(dUX4FR@pL1Cc(`PyZsIJ`vVTU8=z#Y$I6Zr8UO6>zy10%3JCWe+y|h}MgY=jgd1#T@8}JtOE~$@T>Z1+yn5v_I^zG#70>i- z-&vMN)d3)9;yBwVj{`)L){$)2~ObGx*OI$*h=;)PZm~OoAy*q*0B6@ArABOjew?T}ygaKb|EW$=AgU zP+9S9e7>JwR;;T=)37#L@z=4kGL~TAgYyI1)I85P>~`4i_g>TAYKhMCjB%{BK)2g1 z&Q7;juQwRS^%4G?=NZ#9$vh3KmKqqKOiOrCtYr!S>WFf^PBRri$2~EKglG5IrKmwT z^Xx`42E6+`$bvP6rlx6+>9EJ(9?pt_H`mL42|WBLbL{#?fdm`wNRVyO+F zOQHKscJ9Z9#(O@wbdGvVM6e)|>c9fA25ltK{UCuZ$r>ksG^4|QmL~y_G6&uzN)C%O z<4fSA^HnTd*P674hwiPNPe2`n@Ju^fAH*|(VBAMNIfou_K7%Y ziwCu(nEBM`Xn%ZtGLn9}{_rxzCYhh5J3MyJhpx!rY#g#Y}6#Q( z!U}*4YsNx=rrfOb*;xT5F|d-*QQbeTYik<_sf|Pk3IkD7qgM7(l+mPu#sL%v#1Y6g zdPna703ZNKL_t(roI(KK`dUJ2${v8lNNsi8N&#q)`-PU|oQRE_VRiTF+Vtm+ASp%i zC)OrLYZSbH^Bb=3oa5}`GfYO0Ha}E4ZqJOZTPWBR>9`U8Rx;pNX<`n0ixxyUxCy+Z zKR*`j+k%~FXgK!FI&Jti+a5}pgy?J{r?(cs)bn1SSI>NE=3_d|$6mJqsU?NX=ujFB zw2Ivl&|U&|@o#Yqb>3!rVLkt?vdbfGj4 z?ml1k#*-3TrORI4sr-#;&Q$9*Oa|z%<_)sHlI$u zm}AWi0roepZW&vunBIzb=0FuNYj`Mur1_H0E9rSIEK2%3&A8d`uv)EfetIf0A{Q_X zc=hTP{_)R$;AA~wl_Y)suoowreRrBCOnJgQS(6S~C!Qyqo}S>#2VaU}E6h*EPYDGY zm6`^Z3%)l-|6$LgbHJQlnc+3%5a^0oFvC%|*_3c|bB*iwS5i|uI5CZeYt37e$8~+J z{voT8&{Du1&*^%5O>pL;PQLA2v{6YqHvA{l^i*rgRE)1Wy-Tza2;j_4Yklp-if!S) zFDZsh()5z&9o{^Df{XK0Y|idtpY^`fp2LV&Z^M`$d-Z3$e|E&jAN!v8oIb)Ub#khI zc8`(!pL+-VZ5T2BooV@Re|+`wOmI}hnQi2iU~1#~Jpetr%B7{>wI?LB}P z+wF<-tMz(~an$BQ-hfn|1s#VOUuaOHbD$ezBG#vlT{aa!v%3E=icHeVm174m{m{Rhd4HD(d7+0$f zFGfd0MY47sIm#3lF-!EVL~dIUg{_71jE>)bNRGw%^;muhclQ|8V2WX70Pd_VS~9L; z@EY{dl%z8KmB`Bk`nyxrw|e~jN7pAK>8I<1mjMA*CTRZD$S~po>Aj-%Spkkc>_doUe(CKTo4s}HgM1W6u2t~ zRr#~~1VAb?S0Ny`lW}GJj@4p`59b;w1QEveR{;XyUbGC)buCqJ9QBcmdGIG{zNZS3G!ZRg$vI4}MC1Nvkmeh4HrfG5jG|e;eJY(J+aG3VkANIJqxdylJ?f={epqV@(9&2__W{Xbl961Hsg#M1#*)JbMvlN{9Lc5`khu zm?52vWwyv!1oxozd8EM$n{0PugBfIMz>?4@8_XgzG?04}6D7YZY!C`IK&xL)rQ%LN*IRmNx)?4cD@%i%1gvzg$E(&X2f3IuC z=<9_3nXBb16xMzTG)E(4{eG|1FDY96JLBKlcd{FdY|W!FGo|*KOXCMyN>G(AHf9^Y zyw28iLBZ^okb}R;j8J1np%P}|fGO1E042hN3Su;BjX)UyPuAY5y0O@_qF3V(304^Dn28?Rd6y8(Zps9=pi3SD3!h<}bMkP=pG1}!K zB}l9pUD;2_Trf}4kOQS4=NX6H9*1edG#zlW+hM=kVVY;0pPk{aU;hY>)qkxnV@szR#YaFBT_aBjbfPlG(+Z38;kJgL@cE=hgPcp{qgHk%H2Uz4zDhez zLooV7RdT~QYh;q{!zuxJcZsJz|A;TY{u{>AJ4*NZHmil#DTWa{_6qZ#y^LoWPv{L1 zk(YjmuiSRsW{_L@yD76K7g~k6om>CRW^KE*@OgZsBKx7s`HL#i#;0wp^4|74{TO>J zT<2*9RzlU$?dKBY`SF@W!)ugB{XKDg;@@26D<&80Be-<8KWMr=D&``CKUGEmRn~sU zIND#g$y$k)Z2#8Fch);>wp?1HxYb>(Q>%u$L(Vu%lSGJWL#2{4@-%@`!Zb}_maMh) zYK612bF5b@Y)&>fIXUq;4QY_FRV8~ABr{{4rFkB>4dzKiC?r_}%uuBTBF7+&my#OW zi|GYg(#$4Ggy0wwe!|K}&B;@-j_HM}6cBm0^r3U28f_6*xj`f{W}0S*ge}Nr#<&_W zu0|ZL7~?>`3v99ltzp*IeTfcBsm`%s7*+q!^Q*YWbqC}B9fpte6ZMsdUm4J5Ns8~u z#!EHIQ^yJ-Y1Rtan*>Xv*K$gJ5UMO8)veG43~&+s!y1Gk@FX8USeo#v6e;>lP7u9F zqm7vvY0x^LhFQAjnPNybf7YxD26z}j)CLztJ;UbG$j^l{YCNY9DetNczt~FMnSpqL zN8g66Kg26~e7cBxEtrg@Uqvks7vU97b{frL4XUxkV) z#VjvtLA0$2OmQYvKvZc9sgg;iqk>S42U_3M8MsDH!UQZ!{ZB5l)&WvO=wZ_0U~meD@#!18Kd*w4d?$z0dK@ z{d?hqmC{$&lCB+(!N zk1F7%W)G>6&(52bQIPqv@26zOi}7O^66SdVXNd$J#=){LoxWQ7C74p$C~_$w#q$e| zcxCOjte}rg_}lkQ^$b8#6cVK)4h7$BUR@+lN*Xz(QPAwhB{487CxPj|M~)WV!%`qA zP7DA73@MG6_V4lZ$&YyWm+!GXzi>Ef>k*AbHWebPPdS8jYynMgxU$aRw!T$yGTMj& zI{_LWEXxp$l@>Q#oS)QjnF8Je$pGwpOqB+z@vr5V(Fm!ZgnucFEBU?k>VN<97jp&E zJy34;7I4~UMg@ed1?U$*oLx%>#(oSf@2;t`@tLwd(HqZ@Dqg9pPaT!#Xk-<2ki(gX zAg>?)ZAxlm+@#`rwj^JD!NQo2o=?iR)Yw$0MrlTc*17|WeV5#T236Qfc&8{0GHVUK zQ9iB403z?)9!tZpI>^8ShD3m7HJGwY%8zAijI60@#Ed*o$R(o`OQ95F<-9-Ou-mEA ztzbGFFwHZj!yeOgfYh><|FRh(RX!4CH82X;e*OLp-aUVgufO>lzWDM>Ow$3Y^$Op8 z`&azG`yI-Bz;?BAndb^Hl>aeAQR?>K>hcmO1*hj*sa?u-kL8RA-%B8|uoF;-J<`_< zf1*H|!o=X5g$1X$c0egJEE=3t)10RnyZs*5*VmX2d#uJJ4#=rs99Kw#ws@e*6$nWk zYV1mNi@8{NHz}Q11iR5=4m_tYt0Zf0#3Xe2LV8PSEbWOHX+%a1X+Xk&k{LHwSC~0t^fSupKMaqr$e z3HBghHLkJQtbG4$e`AIUX_lJF@g+k_gH=iJqEvJ$Fq>p;*ku`2zyNVpmBL6|yc}1= zVz81SriW=1_1e)iOS?;FHgeoWWf^f9irV8JF6xh)@2tmgw^*5+j? zVsOpmAix4QRU6Uu%E741TGA)A=Q1{c>#=V8?1tBI;dt4|?n!GrNr`@KeL+Wqo*G#b^P?R^y_ zS(77qW|a$(Ii*I}3a2v$QlBSAJb4BI;9NZQ8f^EO$IyIHYkV( z%>Y)d8>?f|b+gZ<9%J;hXjF(XM*}lN7y*wigo3dGF_@REop_7XVap{0EKGMg955aB z*zb3k=8OTXAV<;;b19|p|dIiU<0Im>!(#sT@} zJ>I^2ipSr6k3$A>p7HSELtMRki|e;4)r*9`p zp#jtNftC%+T*aVTs0u?;Z<$4h8jw}rsWWy1d88n%pdgW?)z?~e4T+)MB<8s<4Z7EUErtA2bvoitIs5R1PV@M}Q z=DJ=>Kwi~Yk0uktG-DvbVSkOwH_vf)z6E2@u_jnOBiPAnfB}^MXxHSrH}t@P>ivO-x8v!b@#n6n ztQcUm&wHcAk%G=pdZ;wkDx6pZZoMoqBYZoHR*t1qjkHk~#4lMvd1|~|@^76_l?nB4 zboB zT-->S=NX6T;KoywB8rBtCCBw8mXat50Etse$bG=T1#-@6?XF=QFdb&Rc=`+O+&RbQ zWP@ow;N)b3ufBYMAAk4(tJPZ4v5jWI()RVF4m+HlZLwOdq_GkW zT8)GtbveTU*C`}2?4i#lS#Js&PqL;+AkP{>VsSvu+3RnYlEFE9RH`Z5M66wc;o?PT z!(+f2M}e(<(sST-LxWNzH7vz3Ep*MzITEeYC}<%@p5I^_)AcvJ1`IG#8Qg9>_WS-ISo5=C{blUH8?M|(ReW9GkK(X-GhqH>St9imai8K zmiApF&7KL;@!e&<;Q1PJt2{blP~}Z3nr%uUTZ)v&)IEUy%}Snt2>bmWTr!3<0!7y7 zWV6Lvm=PABBKV$)VieLEj%u*A{dV1+89!-A^~VYE()o3Dv=^e3@7RJ(xnoY2|ycEFuOt*%<0Nm?4?tStWHIi$ddL zkUf%4^73es02iB+(T|pQVuU;DSQM|3nU>JC-TqU#~0`cxrI zLh&jsI~-gMoNc+TfXTz(`uE%K)h5&Oc)3?f8n_*!EE|ENUe(J`7#}AJc8mJ{mT&&~ z>ywf6)AhlNfxvW+0iXTcdl>9<10gYe@z@(7!itMUnH)dkNYHX%U<_EzO*=&L9{E|G zAAwnafT|)Z2RJqiLHJu#g5XVQs<5i7W?;ZCWsaP)DoucUtqhdgoLE4;*F|ZVhz!Rf zJk1zp3@TYeiBuU*(&r~Le2{f?RYu4)#ho=$XFeRj^MpJdkmng?&d6oPJk46?M{0N$ zO()1DgIEu-qkEJy94=J&AJ|=qts7_U}5Z+E<{oreLBwO+pZ_ZSIT=U)PV&{)76E3&q7?n;=8h#5WeCCC-FW5!CWKpF;b zXfrU>5GEt`W?d`}JC~29Kp1Z;1mvmYUyU&4>kUC;L=o zuT7UKzpfZFe!s=AwqvDnV(9`Wb_oMt2gXPRm#?4U-FoTXa0WT8a?S{8xc zL1>iorFpl8-WVKGjc1N&sXC#T=4G;8@OYKsHi!P_sQcKzhMgz@X%GXJciGOfr+jmL znHtI3b7JG^8?(l-3TfB%NQz&ZXt9*QYUG^f*$tsqHp_Yf9JI^41;v0FX&A8Giqj~i zgp-pKTwGkBlnfYub$lv3r4$w!Q>;Wsz`G64sK&Lbe}%mv0$8)=2)-Aj1{*FCoFF_W zSLiHIPu|5EtU`owkhK2H3@Tioqxe(iPz|KUFM9)!@gjCQ5iI1Hd&ROBs&keZILuO- zV6_@OK*J(QNi+N+#)x_^g9BYgKBVjD=fP-PbySlFw(h!4$#8sk4wwU?=lZusZ$W*Y zWoMDg+REeY%-Igxnu0W{H+q!~8!N80ay)ENszJUweN;&c6MyK=4;c=zxeisowE5ZE z2_)B<5P3F_2*98}gnjAxeO#l4SNWR3_t)v&*2!qz@U^Ky;aTx~$eyTd_p&%AZ0+Jo#}7CG%S)zR30<@#hK{d9fs@&nJ@crSX7MGu^o0p9X= zylzLwi+e$_3@lYXxCTV34B9vZfZC_(B?r2{;o*L=q8c3Mi~_boC}x z0|mh5aTdv;!Y;f+BW=v<o|4;SfH6OMzjt{dnz=a^AL zGL^xX%7no(jsi*Lw*t*6C{;*={o#P$pZtoyZ_lwB2jqFey}S4D;L9)Z?6;qBXE>7x zCsu{kjX#9JQ&+gkQSOw}Vi7WCpe9&)2c?9pk!UEYbXZCWDkv6XM?GH#t_`p!Sjs>G z52j>`5HV0bCNm7RG@7*DOg+0sMRrDYAN1H*9YrQJL{q}JTH(d>SNP$FAF$b+V7ocN zIIi&7y*s$LIForZ0M0rt21B}J!hzQ^$Opld=6dXnu7cOIQXkBK1qFLWfv}b3D1OE& zpK$@6XS{m$E0_zuc=$Ck#5us47{y1%Lntp;Qex|SA|G_VAy^PGPQUw0rx>1x`NZu5MTiKbN4zX`&$Mjml5YaS|mVj;aqlyn-MxqX zG-173w9%;Ux&hVZ<;dpaA2LFb*rQD)c<)cc7$QvPT}P#(^QF zYRm}la}GdNfvH9uSw`u)oMjJ@@XIg1;^oU%xHvz@FpN0au5j<(J#027Uf;YLYT7g1 zp1JxNGrK{52`3V$QS6MbIL4F0Ix4SQr7tOtgw^4r0V4?0{szyU{Ddzl;q30`0%?jV z@$C4o-=A1E=C*F{f28Cs$%6mt6?y(`@95WmX$(ty)GOTpj^^Id&wuT5J`1SRM~pbe zgH3)jS6U;}A#fZ;b=$tl-z|a^u!uOv5MU6ez*YN;{azh;GybKuh=vB&EA)RQGQMW4 zF`L6om z;()G^=^8o+i-Kn@9by@m$v!LMEV3-Dtn!meUFU(!p=7jJu~AQVL=+5n0>DgvAgjfR zipZoN0-@vyWuAc52`so{HLiT`M9+XX8Iqw1rik*fmRyoQiz7?)1cQ*CodU%t5qCL0 zf~)CI$KeSKzVLHWOqo zBhV~?Ny^lCR4g&HM;R;tt3ZMf%pu#Hi%?^^HntUt^~mXDCDQ8E^ILgb9cwY1q0e=b zxxP=Fbg@op9apd4G&(_$-!Ak2jq8(<^waght9py5@~@yA`hDT|NVL)@NDg>k+sE#$ zznT%@_<8XF^xyS6mAMr_YKu98Z2@;QSi+b$#RF(R$1e3jdAE1hmpTwhsu+mC5W$#W z1*{cVkqT>zgh_Rrl5VVqDor<>rwRMR0bDXrfRd%MV#x)&n`@Lj>0Am*nS{BhA+#{7 z5mEu6*L%_NKm~$Fa}}=z$1G8vglKRB!iu}XE)iy=-ZNc$utvNdd)`ffvd2|G0~csS zRGS!yRkjQO5ILwM6@W(nv1VfC3^V3MgTE-k5&_IeBJ6dn z$vZw<{aaGnBQNakM~ITjd3M1;lrTikrU9eG-~x=RHLk9A`0J`~zEvA$_6=}^nA zv@*y6H;ONroFi4lAmgvio9rf)Z)$|KFGe5-`;*dK1?TK?hYJiJszv9LB_6y?n5(P(+-cvLAfHrQYoMl~qdG8itDi&4uEtP)|` zU*XN~zuiGU% zvF#fcargd@yEyzOzuS5kkCrX%*G9fmN)42Va#dMdofmq!f`CXDOqr8PC8({USnL1DD#AoB1VmM+)Jf% zH(+VWA01O+_Fe|IZX$D2Ltn1*L^@Vxl~jRb)q_=e*E*fHmlZPxz)-og$|qL6!t0&G zjFU3K+8m7CFvt)mvgl61@MtCP>??le3Dub@>sF}hcSY%yVLVQ1n2J+Y_tpw6FuWAO zQUozfR}bgBF`9R}f~~dCgtdkZc8k2|G5kgFh@4tr6`A<;F`vAuwE#ym+1JG4GeF0(MOTrkZCfQuN3 zH0>m*x0oT(JqaY8Y|YUIU?g}wCIUdCDjg&WLtyO+POO${^sJc&jZ{I9-z+sijG?yw z6qI6T;=2W9wlPblWI%6IeH89Evv)Z3J8(1WZDNqHW3#+F7I|$Q8LgTo`w4d;g zfBXYPgzvxq9(T@9K^NzE@a276Uftl`+jqFWzQ%7)pCKi}>Dd++=jS-zo?u*!S}fk8 zx8VYfm@uTly`gb!K*zO+rG6iy*wQQAnqpv309-us&VUVvwJcinJLd^cfBP8^ACK5< zKSRz^2S`8-sg0oRN^3M*kzd{Os?gL1Rc7=v+NhDfEub+vlSj#+^oCV7U!eP$0-bcV zk%Mx$WL#~p_H5IL6sJy+y38#%qKiOA=1VAMbpi|S&}z92i?s-SUe`ZWevnk&QC)n&Jf`Rod_EFssm5!ql~|ZC ztX6pQ_AP$>^;bN2a35cP^9V$Y^E)T_>d{xYynK(#%eT0?y2AU*_ZZTEJ9jT|c6Nr7 zleNk%hBXwFfhDI$S%=)5TQ^7sjFDW?BcV^Nv7Mlf550%$k#kw)`=fXg%oq}3e|?3g zKmC9&zxg|8a|&cOAO+San}}zZjDzvI)u^c(QZa&jX7r1IouaIXN_32nj7^Gq!)PC& zADvFk`@1p6XZ3aJnkb(r2LrBOdiI~Wgd_+SEoz@xZAniX*8Ov=3Hh7p0OnM%OSZ|B z_UgP(s67Dc8UYozwGP!KgJ(;tw!P(OFM8uh{JtAW^|ewDl#$uWj2JJpXl@I7Am`Wd zjLh0OKBa_to^f+?<3`JvIv;hjd7dRTe!T{WaI)Fp?CcEZ=jRy55r@OU$2JT@Ll<@q zEZWpQi}Ng*CF_o=Q>#YNTiy8Nk$O=4=BeLiFyp%Sf_Ygp(-?-~E&X3jt{}7#&xQ|$ zP1nZ1c3H*%lxzx$M916NHOvO~PTq!N$z&p+dbi%Gb7E3Hq*xV-`@vFfz@973lrr|y z9{XvBbBl~+#>vSEhG9fL?153~pESxb1h{y>2&(+5=Thn31hTDhF=KCSE@|&=)=25N zm<%U%8m9h?R1jRupjUm8ossruG& zPmNaQ6dlVD*D5&1KIZylB>i;#@kIv4(-E`tTNXf#@ON%f8swusQUuNv;?)DiC6BWo z#;O6=zo7?Rrp%hBftuP|&h7P*qWwvm?Ha=t1|unl3doZf>!!m2`@;@7ACM1HIGxqg zTFL})!L;9Fo+po-%q(ebB>IF$eVQRPc}NUNmqbcH()7!eVd2xT!ENk%?+>N=m8LR8~({(TG5AE|Nsi zDa^>auk1n}zIP36FuSM71toxy2oo}fVTGHkOT2pd0uLU4EdT?+iKV&rajiH z6OZn#&4G#=GKm!O8UuDqKmkFzkh*|mi7*vv;Uk(ar65!7&S|NzMyGa}!fALn$q z)1hEoZ*Xzv4o=U`@Z!ZwTwPt_Fip68{~qgcz{UAF&d$zpw%uS{t-uVgLB+a1gO(() zrHw_(ZPqc`R_+UF@uVhxTO>*q&{1V2rQ`}i85k2VUESc>Pe0 z+%Y4hoRJ7p>pI6h6ft3Ez6FBJ7KPL{i-`LznF0e+f=7IZ(vB$F9FJK3&iR1(>IRdR zOR+tl4}0Wkhg>G)X-3iXI?hsmQeTLy#z^D&gDiqJ{8oO!i~%f;9TJetgGCS6Oe8v_ z3+ka*C}Dj884na#l_vbQeSgA;LgPv z9zJ@6Uw`=tt1@CUj%s9+RCg2t4XG-+PH(z5R1LsU50wbvgjrMPO>q`B?%FiQl>E$^ zT-K>!7+i}5bJivz*04k!NTxR_tyf+U&q<7er#fa%I##$rR-(k!Nd&^U+TiNy3jh4! zM{Lhd@$KKg1p|2g;stK5Z;;Z6&1QqozxV?0udeat^=s^QH<)?kVZL) zfXg?pkcJUoe)BhQTB$QzXbm`SLJ|2^460^)i04nvWAXPb8_*d*4tPnTyg6yzNoBC(YAxlU z)W}&NnFG>6UTQ#3vy@NCrJ!i$faoMyqCv+2X&{WN6*ij<&d<*=9VCKuv)MSWh(`AH zdhK*jYbdI*L!-^*&%%hBI{mU5TGP|goh7~A^#a8)hIfmeIVr_Np8j3;OPyCSfQ0IK zvS0_YG3j^HFo;2wO&?+Vf3Rjr5fyI=WF$pUqq-ARn!=_}okw~LhbI}@? zVy3s!RJo{;GYKy%1TPt~pZ2oGMGQsbdV`ckm}8bzt|5s&npD=Kh`wYvy{Q9Vw7)_Q zpW9kkaFJ)|REI?B_5db#SocBkZ`;GnHNeX6Kq^1ADQ?F{mGBx&4AnDaoaE1DyQkC& zaL~q7dh*23O-bQP-G5>T4pmHS5y^EddIMDhq~TFNxyD=7+3dV4JjZEC-(&RXM%oA( zIKd;J-65=F27r=0qpuVM=bEk*;dm{bD&g48bb{E2W7!xE^wFeC_f{Nae6`IQHoOse zhhuNl02_OLTt8+Gk;ET&eKL}My8hs5J(#Az^jGgKt%jPGQ2nXl5IT5VxVL|<{p~hz z*%z5_-)DzQ-5$ zPh!MGLSlJ_L@Z>0k}F<`2m^6#WK9Gl^CBe`ta`wWxvI~T)ss@xP@A;2p%+1iGH4rLo(qp)k%b4e7Nr;yiYf>NDXoywh#!9X7oNX-g}?v(Zx~X-k2HN_bYyL` zbexH8+qRR5ZF6E<9b+c8GqE}0#I|kQ6QkpN{eJh}zx|`T*R#%f_TE*stG-^*Y-CnR zke`oEc3ePEpHmOf&H1Ce!OrG?Q}NjoW?tYY-thov%6j+X6(l4@(327%QkkpQBGiF6qvqD7N8|kR(B0^ zN*7a*QyUYxDQfZ1D|~hE?W|BrlEbVR>OVnB)rEXD*AVL;DSK`^kWaS6&nchSttH?0 z&kN<%oz7Zp37Bukl#p_{iD5s*#6CnV{kZi0;;Y^{?zO<&tpS5GhMY^eBJb^OBKzN` z`b_UeEh;>fo4*MUzz#CDxr6+=TsrMMz<+S=;(ZHBMNR~b&iJfrL)A*$p+l)FYlseC z7`SfrdL`v@Aq4%J%-~=f6_+ra+H_} zd;_*t$#>dLL8%I*=n-MiL-NnqXtI9W`{zo?(f=R})+ zwOstG*;C#oQtm@gwyRZAkQDs3%ge)77P=ADRs3cmQ>~rt!!J+$u?`D@Z@EOsu%He{ zR!Ype#{6st)T>X>fj*K=-ihJea@-1ni}>V>p=hQ_igU7COqY!QTBkaxTOTmb@v(}L zSCWdgxzK=$f2-oV{JX^0XNU3Dm+M60Xb=nziZ&UdYvt7t_P`g0K>ybw8TW8 z$_PD&O_dw}*-2oGAQ&DK9rlJ;1;NC^-QHBb3Uy=#EhBSvYBB_hDq}!GELo_HVY0!4 zXzf2ek)!DSlbs_O_1i^<=J+|(#H2ttybr&ZqnuGY0QFJR$)2dL?E+lZc2nFNu@TC= z81u?%=(IXa#E?N=-^p7VT!#ZUb~|UZ?{{p4l10NMqcHx&10{A&nf0;W9xVa1{5oFR z{bby)eSiwQgY}@YsoQo@aAQ{T%m8BEEzzCfLP@+u`X3(Q8%NHJPqSKOsd?oU5(Db| zAJ*Myvr{?X3YvQ!h=>%{v2re7gl|gkS4lrO16YWS0<|j`|Gel2B~ot|p$o;pb%1<> zUu#KJN{NQW`dcEcVg|mc^mAHe=j58M8-`B&M1qI6KoZj)7N4aSTsIMij^@arw84?Y z(t!_Q5u0zcK#FSIDMZ}toGj(nCA&H0V-myN$dzJgh3vxoh1+pQd!eIVMn@F`1CJKV zdiSrp*R|e-qe#{(+7}JVj_X`?;G5zX8Gg2Ia=TyO9$k#{JOD!q5gHhH zbQ>OTaDFx{Vz8&TE&@fb4x;4?uI(=0@TLDG>Kr*mC3p$KBZ%-pcso8+FsSPhVH7;X z37lG{lHh|&3H)&sx$jQ`xq>f9fgcwwq;k(YUl)NtbZT#p(v3|ULHB@v$ixK0`^`a5 z-Fh{MvpS)@k112mGsQ*ke%oki4g3-=wdsFc0{x0kp@ra<)=ab+{*qc@rXXrPr zjh7X}>NZ_n^mtY75bbVy)b$4659q?;-DyIIN5U=7#5|5R9xf|@?A#NV!ET=XJ=-=B zDD2!*+3suFVsj-miUL}$h!^r>9XCaQ3kH%PaJnrm&*aIcs2;&nS>HpL%g4%w>GH&^ z1m|<>Ts1sa?Mq=Ez)PhNP6Rp!=nkM$J$|*NA-0)S(tVxK7DSs#;5{*&Y(<2M1-y9D zH#x*mTChRf{oNnEB#wghm_SispDKDL0QRcBJK^0>V+Vv{(zp5J?CDZ zu3^?*3)bI7Ch*C$`iN=ozckca>8SpMky@Rz64mkXC1UDKEw`?1fe-}++tSJqq=rV7 zSo9^~xpB;mCl^YUxkmW}T3PhXJu5A&RW)|nKPtyDBmwUrb9?X|f1sCO;3wgK$#ppb zd3*cQR;_qeF$Zu)ouHlPbe>g^oEH=zk#!;e{(iyo?6eaY?$rH)fA7~T$g$nsHF$L7 z+v(51ezL!hXjN9WnrqMc8v_0>OuM;G!BFuNPh_D@4%;^%9<^zLRA%1<`>Iz&5F4A3 zkZ;tZW$1kekZr*Ba7EL>#dSj6*GwXi#m1*K70+}h+ct*PM?j0V{(18G1%2kCr-xG8 z2hf1I7g%jTV)pSBWq{`L!>{$|0-cZL9WU5y&9@4?IINC|Zp$c_R4_kL(I6B)4pDxK z!vosSA>zCv9`NJMX;J;3n?GR$Nc9F@yVKqG(Ls{|Tp7)Daq|z|3NUU&YY&qv!L-*x zuNSfoe*wK>Y)NqxT6PuwLJVQeFm-OzaTE@*X{Y>G7>TFS60_}TAx)Kl)u$p;-h6y5 z2med|yA~+BYD+0H@}c9Fxy&*2)I@IHzAY}-mPBRIA-gA@`ZB4 z8=p30jZk)6u8F~#?H4e$Pcu6v(-tB9*H2K?QQ`?FDbAeT@&$%2`ib$k_UC#dfA=`> z!^}i^$8ld>+3q3_7>|>D-W-V$aY%*H7-L!acI)Ph25W(tw8{M$YAJd~_GJ6`!`u)Z zN6BsNR+)uSQWD-@X!Vz39@&wUK?J|DxTJ%ZaB8JYU&2#hDkGar<1+fNLZZMkei+(t zRjUfgzjA!jtQQnPYDend91{9!ajc2^sT>; z%Doly`ycqpr&;E%f#WPnO7v@^p8l(IbT8!<-w|@DmZ=6_p%GWBP{z^%3eG!$$X#l)Lnp9G+DAP=PcL$7EGoqC!AU6;DJ)r zBGp?`nv3qGfFOz*(Ck@(aoC?p~)DJXFX8gf=RLa@=~$vmSwQc%7&7nqaV7z0J3(7;U z-?(H|!~g*&H&)rQ%nCa=)H-}?RAn{6|X@^i>=o|2MX#iFyR-!c^XF9`=CpQ&)6gZ=^AN`?gmulLZ=+;Uu!+msT#=<>& zPWp`7`)nnliIxDaaUhvtTpNK;G&p*h3j|(sKo=NSZ7f$LvJwAU_iP59YCvc)q#(3k&BGQr zULwqybj94^?nrC!-mM@H$AMfqC`aCge6tid8yC-n@MikX_O3CV96r+b@7`Z%{-L6@ zrsmrGH?QUu{EFuvo`bl~|I{uJC%VRt)_LPvyZyrdbC0R2B|c!aO3D6D=>GnC!2%-b zKmaSY8}sP>Pc`;jK|ly7sCUU0It5gGfxQ1vTD^b}|7khR+0*tn&9es*SZ8|wv()HA za=+({HWjwB301rKJcp;rLK0Pj^yfnUeMSFRHNqJYyoDv4$X1df*CJu0js?~#!v~}K z4{Iby$WCG$qu7?07E!7{LF)bPo(1$MAa%c83H%4cgM>IBi>Ot5<(r4K>rp)K_eZn; z?*6Jr{CEMH zvhp&&)EL#Zr9?7wiz_lfgKQg}E0nv0h(`U5s)&hLg;ORdW_SK44BSn47ib&+73}N@ z6h@92Z%hsJm-!LXBmF{zB(P05aQvN;yk4p8 zYHTdd0)N|?Z`*ba3o3&~C9az59Wmj5^&8jqdDN4zXS{i8LSJQ8R-n^o&cN%)BA_G} z^n0GAQ1}yOpKEE3eqh^(yeSp9w(0X?GhLD$En!?`AY%iCJF1myO1U_1+@7ZS+?sv0 zVx+@EM~VDku&O>IkDFCX;js#fj3pF;T<)%{BF;#l9F$_GrmP>2B7u#w;sM52)?|?R zj}i9j|Fi%xEp>cs7u!`i_9$iHE_(m&0Bcz8faaP z^~R-Nw8(6@C!+2x5(Yt@0n6J1B`3IsAYO*jW+A!>LEtVBwCprh^a{F1R14T!vFP`+^RABtZxW_MU zC*TEd5c&YDIH~U*Tt;oB3Uk<2<~Q@qD8TiGENqt1bql_=YHt`*nTKCqt95xn&51nm z8!N`Q7%4ES22Ny-v?w5_Py5&jqV|-IAo}NIJFJw7*Jt`A5~4!9lmSirlJU*U0@&-u^|; z2NB2*-{9tkC9n_W>lIJr{Q+Z{f))8ED8%Gfw3M6UE$CV|Fxc!H$`Js8EN2zCY{?KI z<+wq?1E7~KIcRjtG5jMSeqn**A5Z|c-s{T1q(jJM7UbgwGDkwTtk^mmEH*6{N0}PI^S{ScCFB6Zjr<`Gg2+=ZL^||0x6n+&$3MIC^?N-^lwt z-k|0Fk?IWmA_l257_N4{AW%qz2ahF!UX(>X5Edxs;LVbhN)LE<=Zb1?K7c#&d!H%A zeYgs2~U&nxIXy9yfy^WLsU zt|d)a%&KRa0g|7$*S&GMD2#NF)3xAE=oWUC7Z&-xvfwC1DN zci(iD-9|fIwh61xx@uGrW4pu3HasRb~qRVLm22l?=RW%?k3xFy*0QL{7zRQJ#>_a^!BchP!8( zi6tGo)#fYz)zOdy3$!x>%uqUICFQHmxfC}EMDRrz69d*0UBpaH!{yg>HDmW_U4mV- zfUiq9;hryO>s1pGB4;0;uv%h~{;&6*FB+pB0POd^wI?W=3#|Esy6x^Wdj{E1h_^)^Crg(KH8Pr4@Y9+ zL|w`PJ17$J#=F7Do1x9ke{PL4rHydQmgeA_2uE?`Bo*Vy%Du?3o@~QE3%yb4^(lL0 z8kh?&$)@dW+_pObGg&-NFApyW!Y_vy*%#ig4{(6oiD&QUhXv)#MXs!=Fi?QccDL`q zp6ghn)yycz#L*En$@XPoXo>|N$cy`gPvm_ccF_ZgIBL^05fWC2GVZCstsoZA@uz=NJd>qvQLf)NB5Pd3P;WibcX~vsNu;#5 zTx2}nJ#x+rs4AlNhM~;ipPH7+88IIF{rOogzn(vUYX`QFv5%*DkTMIt3o<2N<4Yp? zZ$%ok9~@kVM$W||h&kbnfd`Mf^}w z*7NNQ?+l5Y0G4v~iQVe@MWp1aUe{g%?UvHIN~hUnk8xw>Q9S4#)=Mz6x2{HNlhSiu zsx){ucKDNQyo0jq0<#1aOy6q>vb_@HJ?v|@>zhgzXlwa0a8+$%%G`EUG5^B)_;%4= zs@ftr7@tt$x3?@gT>JWzI3a{r$z_hnj3BvJ5)e5;Z)-SwFZD$=VL!t#IwkzB?EkN5 zv}eq#yD7Pm3-lovl162Sd=<*%du#UVH2)!hv%+tc%TSOSp_Z`6)@ z1?f82x6}{z;RcfhB~fB+&&n%hpmX*%tSM$j@NmdVE9yU!$8hShb1g1D>gMwr+&Nki zg>DAXW6la8NWAh`)<7LQDZ?!U$YoSxIz$&~;dcCIl(T!|M{@~T!YYq;8>DSBiZ7XQjbR$Z-8++ zovm)maqK=DR9t=f33F=`X-!%?JNHjdBS2mQ2vX~ojU|`NKP}BVnSYF2#w^pJs zFRy8j69~X2pRs2Y_VD%|4Cpaq2hpRc0|I7@lDQmNOD@^JAO+$tG@g9qOJ@{3s(?XM z8N{-|{fBkGR612t_Dq-%J))>)IHqTqUyhd;h=sj-C(>C)*#{hZ${dJBMn)KMPn@Z6h+l>J58fY`XyWsdt)Tzhdj+Q)o}-{CWWx#-%M}40 zb{UxmTGK2}(miS-Q`?s+lWTY78i=LMlAgYV->%Gn#dkMlggf%6H#_khd^;53++A5}nvK7o=gs^oewwu2tekg=%UMa~G3)GjFh) ze)W^7EMf|M`vV*@J*`kMyGfIwz<5zUhz}4NeBodpX}88gjGEs=o4%3YhG~{-S03^7 z&c^Ytj(4F9ukWrUCLu=a!8;lCrQ=@oa91RNUGs@*Vl8spOlU$z(ZGFd#&A7MIi48{Q>VGty4T6^6wo_9yCy{!={37vDGPB)G zqIC1ii~Cpmb_3zRtz$Wit75AjhjO6y_9^^DU9%D}K#3M3;_Hu+6cG3^CJ#_@PsE5Z zaqh$GWU#;EaZ!2P0n*L1@&RB>PW*ve04Y>gDmP>&sq~`}ME2{jcDH2U5H}VWsQjhA1`8k(zkzwMTe!)jf>MWD zrMfCG7?Fb_&G)AP-p8>78!;uP_xfTQc*$818W>UNgc5$aOLbx*Ut~kFEU9V|=U}`n(6T32AKXgu zbR*&;IlMYT0pbi4`XXX0`1WL&gggNI%F#Ksoig6phvqmWe^jgWpQAim-f;T?~l5Pn;V9*B5)8$S7b ziY+9Q!o#{7*XSAWMw$OE1+#kj^siYT*;4xX1DWKMFU3J4ng_~@kvPf51q|b3 z6e2AxErPFy80VGyRkhuPpgD;7l!#cs8z zrpEE*PNb)FjptBzdShj$VdGlmcZy&#{o1gOrNy+XtAsB0p=6wxb*OzBEEq1L(!Bg_ z{di-H_H`>hhCSheRU0ma;844=wE!2i*X*ykcHC;3+M)UgcZm$*plBdnn}hYn(3(K| z^zH7L+h~=H;$FX)!FiBpj>_IBak-CW?%0?o9`WS`hH!>k!zEWHxBAW&m)gwvTQL9Fb{BySY7Zj&XyzPNahvXkvQo*3G?QlKFJt5SSP3oC6&&Y01qxqAnvy_Wy zw;F8%xr@Dn}^{gZ#>xqqOPOq4taw)`c`4H z;f>+2Z^pV(``lZNu^TxiH@4E<-nU)?ieG+<2#CP;x@LD6^^J8H=0K)^Dom^};eHK= ziRtLLDFtkl;~ZdU3<E;u`}N4Fb_!p}zDd=BJmj_R>G-MBGE zO+(cs_3=t-7P-4h>InqNE15Wl`7vwvp zfvdLx$;^^(l^5H)npQvG9(wgi(kfqWjZ9)9-}}u1b!yp;@@m}d-mG;1aeb5ziaSTI z#FQVOugU2Ub`5Q`yDLcCa|O34r9gC%_!$BRbiJ)<08VR1_^{-8T^thkwSNS9I+6x= zbnd%g7tG5MNq!@} zYU@p_YaydHeYCPA)Rf=T@$?DbkfGd|RxNXs!q~{T$`-Ux|6#j03q8=(>iM_C!)p!E z#KGd)@rm@92x+8y$gBt8S?4cmlpYC%esv7y531%3(3kt zy6_meyo@TWJ8ZMy&T{kZFzwnlagbW!bBy~F_tpm{e2svo!U#;!h|vN`%j-QIC*VV9N@=4u>&7@`V$ z_2f0vQUGYZ%4<_mYwn~A!!o~nCaa_*p~LCd{xzM0@HTWCksK90-H zgJWQcCmo+><`5?hKt$Tsi@`WZkf7OaDIKu?HM7LUQRG<#mxP9d`Yo)fOua}uMKy4L z7tckNE}!aJmBz^O19;Fe(ZZ$8(1ALDg2Gz zdi}#V54FnP{R%0;WTOZ%+Wpc`V{9b1Tf&>EThE9du8K0L2-hC)@V*Y=Y9kTZRox5C zr8dPjE{%*BBWe|Z5GQHXLr|ej#!9QP0~c3ac8y3&{pacX^hU(3ku4-3bd)?2&nL{k zzoZRnB(f(a5S|O#4lkVP5<6~t*mLsV}< zKbX8AUyz@A(kmCEL#d*Vz;Udss$29c+X!!@MM>(zfp0=tQ&RLRIFcz}Z}v)fBy`qz z8b7?7;O@|uLuHY1Tu=*N7EZ?U%b5t5i^*Vgpw1oUJm_Z1*l-)1Wzg+K9#q)CSY`j3 z#9$L|;K1z`fyGR>P5(gx+D;%reULRDfypepxKXd#5NFdEqHz~%XIYoEu3p`4|8dJE z?*5LCDu&xQ3saVu%AY;(>1jv4eTxyd*S)$Vh8^zGm=kJt$jpd z@62JJ=OxqGuhR2Ge)wjpAm%h2Kx0*N)h3ripvwv2>a}vKG>qhZyIoBxiY#FPQqTOmJ zG*??bw4nRt79BFFcUMWtAlEyK7b^a_!v`*I)1I$iT?0zd<}@q(64+P5sEewTjd5_b zOA>!IvK(q*=gpGc0;9+-qYs1+^2Ox5v>1Rvb{clIxU%$<{1Cj;9{wW!R6G=?Q>i}l zxS!Sfx?cg3o&i_#IuV)gx?dy`E728diE)YOSKbf{_e%2vQ%HcfdC0-5&Sn~}_+v{w zUrHkL!m|u#zRG_S)oWk;rXP>6R_@`HNr+9_cMa&{*QN7nix=2K`kG_l^Do*zIr+g! z!u>=-!$&j@87G_#8)Q57D&QXGjJekm9N0al0a4%K`P_3r086Lazbx$N0$PO5@JEo_ z%U=cRrW?#lucX{f573ZsyRDuEO(LA#pfkDV2s9sJdi%)zaGWt`FSz7KMo#+&^rcRw z+dW%PTeBZF6)s~eBP1qP*XG(50TZ;)R7nE`AalA70chsZEp+eJCT7~&x_$`fnS!=k zognhHK?^7tV}mXF6~y)-7Aqc1Z#8>c8!aIE8X(vt#4ETzwqVuidytt{czDuCmn03&!M&f=ZbJDcBUZm=f3vN=!X=p-O@|$0 zd~{|;scmNVV8+jz+Hwoj@O#~WV6_%hBXp>S{_1Ba_w%qEj=MMM7B^O3i~E3UZ&KEs zj~~K)nqGJz=2fb_^&$8&TrYGj&TrhL5DhDZF9i$M`gWPOBrs!I&2)^wy}<-R-a7rB zP!~Mw<1+$C)R~v!A=SEK22S&*tZxOcw$#J?uXhUGtego`d;-MHD4W_GQb*LE zIjF|7Rf?4!8k_32?AKbDBy-JTEI_Kt?AbrnD;qakF(2JOnzri~{p5Q6x2_4++6CUWFxA)^t+}=h? zAWRSaNEF&)-=&yjY(-{Tv`AGOT&J`vRYqDYcfA(ko}f*_lvM7~mJHVeNd9O&4&k7< zWSt9>iKgoP@S#X$yA}$U4$saeJh*iy3O=Y=X$iu_b0c~#X3gZn1oS!XxB%QD*+3(S zsx~w?2id%$`GW84ER`8#9@(HZy-QL%vH9Gmp1>|95g652yIPrF-ASbpqSY+h;~K&@ zs}R#s;-d%_II%L14CiVU#=1g)Rz?NZH)|{%@lMtov0DB4+%> z`n;;xzp?1?6zN&Xx)^%`ItOU~gaq3?%v*wk2G4k8tgzt-`)1wqwW(}a`itB5tLt5Myd9^-fAM!cIgo@0{k@B6z1C%vBrnc9ztX@2=+z^=}m;J zXs`wja2%3VomFt3yJslIpd1eh zGzgBgF+*|bR#uYF+*`}bnM~C+E4m{jcj=xOT)zEPni_dO4#YvUD{9UhDFs)#fj2YHPfo#>m{M89NKeQt%h%(>~V@kRZc)|K+jcQV@yaW;HNc z>$^~6CQzvEcKtXIAC#9~;5-Bjdv**^gxwx3d6|EO|DP6sOF2*20!LIL#-ee1)&uG7 zBMyfpH`xN(IPfEiaUx^t*f{0(VVRQ4$grF7&0tEZ&6$bDFgNg37u$jzI#7o^Q6zd zBT+|&VB=&+Q*l5Xxp>*^U)6;Rs!})VKPWr25dsH3Op)+6@X6f1O!$#U60yrCb zJdDe~vggkbS5g}ClVf2q@voK`;a(S)ISAy);<@&IeC3iI0ma5C% z_D}SEk3jABrGo%tJ5p6fFyqp^T0x*@>^{Ar$t(Mczo5rExrM2kBhw+M%nfmB$?kfA zH;@++8Gc4AfdfTbwll|iW0h$w=S~)#i(TgNOMZYyokwc$LX3htfm2A#S0yVmE|*p)8W96mX0P$%Yeu(PE!#p@%Ao0Y5p2QdtVkbqvP@5at0 zZpAPT=YEf_*Vle5A5{_NJx{Mqd*bdt5iUCdiMG5-=KgNF%#Mf6@+Rl00K@vU*jllK{-!azye5v9S|0d43^HX&W0^H~ur06slSGFF!$A-P_|! z0qzZ=i6L?+U{-H3T-ecF!lftZHcuKVETDBgj)vA0+UpAyub9roahc+p%B`gT9$Xk! zR7ACHM`b|(B)I-Hp?7kAe2jlB)VP-Y5il||#J4?Q+x3Gz6O@8EdY@gCY}Vd<1R^3{ z?3Hq@QY^57>?h2r=^Wp-em5?734T44h>{!ef;owNq%INhc4bkq)3&)5>MhZ1M_!9d^wz>p-BY$iklZ3X&9?=6RwR9Z4FOdLl4%Nrk z&>UJ7dn`f@SOVH^c%t6VH=~${`R+ANGKeRaLeWSFx3<}kxh26Qa@^j}wR`q=zCL#7 zqC!B2?&{|~=uSS=bKYK9$q=Q`x(J#$@?+S@d%u*KxmCleW1TSE>G+lz9~E*3;k{H zSjNnkVTt_dmeiz)$%u@6gT0(Z^l2UGnq#SF&7x93XB_aAU9iQQ+fgu`2!t08A|yqy zEJbU-^ICy!gR^-!$L70+=m~z;r+}OT%yL>W>}FvKEi}szJO)kci4%j-)Xp8YGmDV> zo^@UXTt1qxjtXs?bzM@36+zF=SooEG&H%$1fAS$Ca7@=eFr0qBdYywO8*5aEF3UnbtyWtOMJpf4W>0Ia$DvLuVs#!ArUE8}Zx?6nGM?=A(d>q(yO} z-foy)K*#Bqc+SVjlYqI``lE<8T|g;#QA?ERReZ71(Ki$p($e2m7FXKcF^(KV>l#Vf z3Wl!M8q)NQE$g-q?=clTMNB$i^IOKC{Z3?cVjeY}S%Lovp-FpA!uadA;0)mTh782_D~P8}+jE<-XR2tX{%f4-KGEo= z(Esp}tG#{g>QFB8_4x9?81WtV+R*tVuccsaCpuX`IBcA}BcY+st;SKyunY84!%9z3N-ofGJ=jGi!KK@UU5mjiypX2J| zGY-1&lgEC7a6;orJ{@9bH{Xf17pkcM61Arz%BPzf+?C6<%O^sjDZr}%IcV3LNfpmf zUN;pzXF=w0*0W=%E$(AGNmrgL6K239#7!;1w8hRQD~+1>KsSvoYswpVmE&A&!RJ7s zd3xVz(vl2;{Tl+{;h~so^?;usW*jyVY}muh&<9`fkH%Pa=;X>ivf2BQP2Ak%gYc;K;O_1v~Jq{@rDz4ovxJO3S+vw z5^}r_<8i0=EnPgZkb=942sKGGHQ^3Jj~(T&W)Tfm6#t}`AW>Vt8MN8Fo)}fDWu#*^ zKYXP7M0!GgG_!CoXWmj|oAVgN6~%Uzl6LP_n#aVky8^hfxq;ChviKS#6C3iXh{Q{w zLx7m3mVxnh)OG{*P7}ncK7!$HKhgn{jV*;Pc@BvP?!c)am0RVT@_BwRm^dh0R80m& zTz3UjlO44g5bF$>Z8qY7PTRp;3e;Q|k74)s9Cy{E6YvHnAPqFM1BiQQrJQjCWyEbq z=dw&h9l1_FK4MMtfd-R)&&HxkhI1eELcw3l;_%_P+4{2{Ob%IlIY0DLaqTMXWLY-C zAbb=L)*QVyw|%lNbQrO#SL~QsSag|j?75R(60GlCIXjl%)eOeb@|G?_fh+n%-xL6)C3X zU0UPc^jGxL`4e0&=~~4IadMP9C(k^)_CK3!(6e@n@cC%`mAZ6}ZN~x9^D0_`(qqbK5s=g5 zkx`2GU##-F4i68DS0WMfF4XyA96CwtKJ-e zL>@@Kfuf|8p`or-g`~Kl%8Q~je}utZ9PGf0yeYGD!p{RXa0uKkO$rhOw4!V-s=d>U zHrFR2tDQ1I@Si7Jh26SO&owa(XE@{To6hN%Xv$q$LC;(Tjp}maR+U3Yb023U(Tpca z0V=m5!o9UjVeY8naq^e}; zTF2?U_5sY-e=~FJLh&gT(OBt%gj~)d<{dFn!2j5`vaPr@(=aX!@I#Tgu(t^c_1ls9 zz-No9J2uFgUDUy7bBHFlQe&Z=fY(n!$I?4gt17H!rB3%caz$NlOPdxy@ZsawUT9;* zo*Trp_WZQr6spYJJ?`!F@1$~|qnjhV_xIlQN6K5>7GAgb=Th}++x4V6i>&*zH*4~Z_4Ldvrh6b!zikS+f|2zdi z($JAmSd`XQp8?R0dJV(Vo4-a9Na)@v0dEUJ;h?wwgVVINSHM>%%kB0;)s0$*Ou-}6 z1D%~wUk+n#&AAci1laSE+xuVG@sZE{S{&pZUF%ei`O;5t1bG32?w+C>o|uv#c10Nk zgo&>FvyLU3@f~17moe*~%Z<#kN;z|`{5@{)EbW??TloYQJt;1~0rRPrB}O9|Z=Z%F znu~eb*4QkF);siO?TpwG_Tc7r@|K@PRsY=_MQ+Ro)KpegVFf-9q$`xE=LWuJgKFcs zr{u;FV;arm2?qBC7thMd=4L1L1beB+l%KGLnlf#)pkr_MMG=o6MS~AV-2Br(Gd01P zN^M4Oo&|Y&&ODusHBTiC&SUu zj0B&!;F2YFbG#R&uO)8Joi2Yab5beinPFJTI(1j=2z%Q69a?3Z<1U%L4^pOYoA;C! zB|p1oEnFT6hwD$4M^z|j3fowxLL$LI; zs=}r$B^Unj@u97!g7nf6+Zj{50wOds(JD3pGxpq89b1D|n38>adt~=7F{NwuI*cw? zdQnVAe8U>`ADWtMIZD={6pnw6c6U*;;BcDfIu$8)gJ6&Eb!)Zzy_PSqh~U-A}$Xu|tj8dhh( z2NOtka(6gpMl8s?_xh^WVA8qwyeD2+Y3|`RVcYbdtgK-)bEXt@G~*4$-)v&G#luH4 zOHW6lRw+b}gbD0hbCdnmHfj#oA)qL}nJv^Ob@9$HPB{*}p2r-7Tf_*vk`<0+faTkm zXI?zwpS=wbQy&nz4>^Y|j>Lw~19I;#TXyb5zHS3=m$Z$4#QfmTncJAnZMIvheX7>B z>;60d8AaU$4Gau?OR{ZuUQ8TDq;K2t&~l&R?#~?8*tGF+28moBphpv|0+`%_^3PlQ)B*6fPDt>LR5zU#dAb7`0t$f zZrF;M%LzaBJ>O%oWsmNj00}sD-f46FS1R^$8>9qOkP0oEUokVQQPeS%SSokKk6%ED zU#2lC5#A&m^@7wPqwU6RD&FJ6)^mqJx-05`yUaW9RW_$EA`}j?e*vkpOKp2bJZfe* z&|Rcm<0Vfb5^PD1c{#mVVa1j^Z@pucB#!G>ZX=bJ08c_&di=G+r$79xYk4G$Oph|6 zfxwFu82=C)Be^vkc~?7|X8rYMvWY0((&RHjP^WV7Ac$;*nQ}QIypD3FcQ35=|7bd^ zusFLYS>x`(-QC??f;$0%YjAgm0KtPpa2nSj0fM`0Ah=sYkj7o+`_GxV1RlCCTK3wt zs@|e2Y3Vp3N59i}r;kgXtk|%!n)1t)=a#sz4 z4mY+LYJ%gx zYZdS*+wZ%ab4^HE?DbVw3nEVT3K%(WX)&en4#y^9tfnElFt1JuQC)=Kk5RHh!dR`MSw4 zx{ROilQ%tyKGes?L2R-+k2b2{n)hSD<8TQ*58Y~z>LN-@b#W=w&m>pK%#OONh=IcvqN8v}5`-LDq@4mlu zuZyAtZtP;;yzXF-U%-HKSIh|v^G7@CFXqPzfZF9MVL4q@5|H7kzYP~&i$M`~(P7O~rVG&I z*c)=1^_pg~GVqOZe+G6Hk24(ap<;S9SI$g-UkHk)@I=M%n z=cIG1P3uad3E(e#LyIq(WCOk}j~(eFe_pw^|AYCIgS>7)F-Kz|m>|_#v`M&5p&L%D z5_A&|V`1n!Ow0&)PQAvam`F(rz9U8$Fq<-(=EA!S2on8V=|yTC6H(3O*nO5xf?~q3 ztl7Emc^7-XQGXu<>SbV(K#p_%7e(zu0Yc^yg8CQp1#hM=`wS8o!!;#F=wAEA-)a7q z9*dzgCPI>q%dno4-O+*s%JuS=JEHD`{M{TW(MeY{B?1`k&dEXd>k2-9Bu2KS(@c5a zx(Ii!f@Xz0riUS+!XISVYreQtd)UgIUv9T!Xdm|dMs?sPJfs%|fq{aziJ}j)NtREo zJLD@Nb)u<$g+y+fsR!`%6O772tgDcF!0&6k6!`WCZgyfh;V(I1CR1E$snHV%doss~ zqn7#rP3(XU2HW<9W;AR;NNlc!I?giw+T#_Y*#K|2_%L8^4^l{K``u;DpVzqQ$T$&R zRnsS_t2YU5+Lz=^m6qh++uxT`dDL?AFphR*y-Plp(~KHx(9xy8ftgl@(jtAP@?G{~ z+f*igKR7_AN2N3cv{zQZoo?3EZcSXQcr6M(PPH}4&EIJkGX^uokyeZPEH-SMjW&fB zV})|WX};k!9d+U+jycM&#nQO&pz_mTLWN^y&2~E-8AcB@t)1&TwF;uGZ6ppHgzpUu z^yV>XD$+CgMhoZ4J`F;frPdXBo*mCD*b&v+ZItU|kclxcU^G&LPfv4Qy8VXcF0p6w z#XufpTitINtu9;heiJ*F*Z`&`q`#>=8W6w#`VZN3*)(msdU-|grDRAH%w((DQU}P< zOO`mu>`R1E{3NM)<<;^$tw3l0u$ThFAy3NF@YiTNnDn16g(Ly08CmNmicyb|ojxvn zWw0ZKqB9JZ9EQB$WGzPuyh<)Ze}|kN?j(w)7jza=Y|6CP%hRWx!;trh86hzdRScUB zNe?O!-SGi`U*A#nkSFcnhapTkj|5NGDi^KnBQMKuHpFtrm4OKdgNmb_P@;9H$%|WO z+;Dzg?6RpCVak>;oM2jeH3X&Mj;+iO8)V>m#3HSr90Qgi+5ju6K+_w+&57Ko=UT3+ ze_XS$ceIoh&|6++PZ3y71CmSCXgK)Y_z9P@E%{YHG?ug%mzF&9`fOn))3R}al4KAx z+vJz}rB5rfOM(+SKw2P$j-dLn?W}h(eyUP+il}-|VZ~S8t#w zv8hw3T-jl=pzWz)q+tWX^G!`ggx_RO)#f8o3FqRtgUo|x`4-YG);Kt3 z?ET0qp%qEuvNsw9tOp=Q+bgYX5e{DCj|Bl;S>u-Wt!<1f)XeN9<S@$s>>Fa|IdA|>tA&_{X+VqN-nidH@8&xMdVo^skB0lGmAtR6Lrfy>u<^EEahzzdW*?)M^J6;o+Wd-j@nO_;lLLkf+Nw+~4XC*y*jO~*)ZFMv=?)dT4dRT#Zii}WYSOl>^T)hE;NqxuoZ69690tyS zKG|c~@CQE?!&Rdqt{gV1oZaB8e;0^4z!XYqBkHe>#UL+;SO<7i`dht8imzZW#Wool-#ym*3+p>C{tVM4kGY`i_lT3cEEbJ-D4>OqP4ULH49 ztk+;pH| z`jT~QCB1a+_ww-JN7-I=y@`j12SB6iHvgR)24S3#W)`L(18$yxM5P$l)qQYtnj+ey zbNdy@-URZ~aIj7*!!_N?fceA(j}mB&ISh;@+B5#}l_N9|pC6}}`HWDbZUVYgtnEzS z4tDm`5$_jXJ$s#zNlTb7HiH2PYB~A()d@^$ng3X2Gg?UAZnxfmrmBM;cP|e-KLW&S zTUz@t&uDU1g^oZ22^HUu& z-{9b5@+E!np_tFe%uUbQq|)E3I`f_lv$DqWiaB;@;T1EJ<^(&6W>dQ!FIP)krI${h zSU&fm0QC$5VnBEcnwpzKZWVy>CbnEY^KQ79J2*(Tz{-l%$o#mCW zoZVg1iqYGqCrmFNded>dO)L22H22t%93-hmF1ml2Y8&`^Kmp_Gc(jV&-(8Jp$$&{d z>qYkLopfU8h+yz7-Z2M1$J$es07KlG{H{aHAYU^L-f5|E<8=A#zBvzk_!K);XAQBM z5z(J~TmwodF$lC*d#wqyLlo2^=YsUVmcFmwV-s6O+ps2CMz@$o7kc(>5?)b*pZ;Y? zyj?2W%>T%o0lYgjGuusoKJ5({L)m@b@6zrux2|7~Eq|1mi|4s<7SOD>k}Ot}0QYc! zb>8`YkzdT1tyad0iIJs~E;w6P>S65qq-Fa(YxkAw3BAj4R$_B`nW7I(rEr@ITVLBq z_LV1Y$P3+;VslSq?ynF((Izg{JXKtzk7qq>cvCIpx~~ZR+NzLMsm{ga z;r;Ev^kK>+_`{;3VgWKbg`R(v$p(wVJa7 zhJOQ8+l~_Vy+@fuFUN8I@M^ z$tp$hDdJVpi8eu0J*eH2boU#v#h}4{)+Z|!rWsGCuPw}_AJ^3fUOp~-YFDp(m3?74 z-ZmG75jgf08|EW?$caDxE!edrgIc^n2p)}kHp;4&b%qJD-$F=-rg#EJLokhDtG7GR zg9t+AvdJgU)*Oq^vdI6GWQPB)RL%K=HmE2COUf!|VAkYkRL`$b>g7am69Gb9A&|?T zKX0A0A%lV_?zAqn-bx_~LBglgIQ%)F<^31v9oV7vsj3az1=x`we;{#mkuIVpQwB$lk0ScvzOyk*pjK5Cva-ZBmQ~Q> z%0*70I3}Z7XJHEyJK~@DAxQ~4u{em9j$c9}wTzjUjQ>DIWSWk=@tqqRz7Zbyoml5| z;n~&Csl>EM9adEIh4Gatj|TUjG{z3^xI~j2ga;c#7S<_D;CLr;t|%2kB9nXoSR8{d z<4l2t*lX;Rx3adT}Yib1(gWRV7ZJ^;%n5=|}#!>_KE35}vmshSk)C zhtJw!-&`|MQNtT=qFRoB>S^t_uCcA1(d&V0t5U{FiqC|VAlXyEBpvXtJ;Qc;EKXE- z+%Ln!Jy0~Or^SH@M(_i8Sfs+?B4r$-xEU~w|7pq4rAsVGK2p{+;-)vCPh_Ra+ai|H z)7Pu^+OCi2WWH33|J8z?Xht{>cs>sgjyM5=-djPPGmz`Do6Lzd>EMk5* z$t4*1iz~Qv)xptoxP9>*5fK$y9u^8TZU3)X){ojv=a{B!_^RZc8-#S^85DEcK6uBc zpL+SXx?WI31dJ&0kh_;EqX@nsGsw8SY629m;p$IYyUE{HswVAzupx{##kbed^1bZP z#Mo>)wgKw%)l0a5%a&#a{7Cc&DFsL63CbiVvD}jGk*gyRqx57aUat&1Syj$^5pmFZ z$LdYz=5cg(t{4x0bZ0_je0^h0#+}}FA_1i~LiHP39>w>O#OS4_dXkLbv0Cf8y1Dhu z1mE!l-*;@y!T*cqda$j`ulR4hd`qJSJR%$Rx_@??xLyfgN8FUUBeV)-`r}>mW-KKz7Ib; zjaLhwgOCx-s|If0aCH`ovGYDeBf~zwicfcy6+778LBp*-lIa>~rCTpFTtAAoSpGH| zX4LNYXkc}V99IU z$as#omXy~jTh_+rYlKX8(uTA8Ja3xy7(fA9T3TB0Vtd&zCj}Jl#lrRZ@1_L8;Q0*sCLEzO_;O2hs=;C7Fv`=|xCN$z#A+5VsT}|Tb z?6O>^r&2}-XsRnJ5Bfe+i8fsW0W(u)u{mpeCubSA!noR#)|0u{j`!%B4mNTOA?4cx zL$USUK_gf7-IP3uEhnR68u=}oEB9Q-roWX(?lyz&R)Rv0M=-2+{ioP+HZrze-&%bk zk9}Z{EEU#go9GelY`vF$qa3Bx;35^+vHgUJ>@`oEsIm|i!9 zJQ3A*`$a}eh9qA+KVr2y!y$f+!5o#vcRuXfY`As*Y<`%(;d4NS0Hk#Vo=z!Da10Oi_7uQ>P|*1^bJrmig$L#S1cc z0_xXLah8>k<`8Ts*F@YuTASm9MR@xo0aJ`eJq}hLDQ>5wOs8Dt1>XYNps?hUJzRh8 zlUS~tlVn&6eJde;)~LE4xuw}PitbXsAOdPXC~KuK>N_#{)6yg4NCcJg1j4Sx9x(N} zab~v|945ZLE@CkWQ)Agb{f4qAB7IFl^(eyRM#kc43G$rsCDZv3>gNA!$Wu)@$Xq3A zWdPTueXb01fq&5?{zq2?e}orGaju*2{1#S{kx%gWJ!6yPES*!`(7@1ii5SLrVgGi9~BD=v{F+p zYv!ni3)?h_aG?xy$#WfDcx*enMF*5iq`KZMop@uDxini;#Te`>1zQ`!(yx6g!7ok5 zmcT=0$w@7Z6)}f_mZZ16@m7Ug{LS#oUmCedHoY{rgej<%(5c!DF@G(blZK~F$Dya< z!MkjAAAlv^g-nAVOBb-1Vi^ONdL5c_Tks@afg%DXiHAN+X-Wm8;FuNeS7;sPlS)%= zq;sUK*qX1wFS_#D27JTc>F%8IX%2fx^q>CUl8u1_R31RTGWj}-+|f~KzmxDYD45pT z1frhsC++h^cfv0FHndoC5s-6L3(*(lBHT)K7WD7I{{jPj{ZCO<_ivvhl6-zcp9Z0` z-mys6{pF4Sx&l^cADvMQv9#LJbRp)>RuV-B^|6~lpQsMvqK*Tb_tnuH4O;&e6Lwxz z8=VsJJS>g1!FUG#u%?g(;&2KCECpWA5-ll-`o@jey0oO@1sIO;bd95tG)4{%(ivGC zR-9VhNX1`oh^!6V0rJ3FtBc>|6&(Qq!NRR5Jh=nVp~?umsps=tCCh zd^z<1{%Y<7q?NdHRI*g;>vF+Y|9)(A?;PF{gM|;{h^`N){P@h9*4%=FCJz4oIQg4# z>pc?OG2+8Mp0LJe2K%z#mulXK78ot1MrFL@9_&56WEwIxw)N`8*%`4;JYQ~^Ksv3n z*i6~C?DpDr>2)uJy+6Zhpa%etTRVeqW6Njq;k#FZTybfo8D?1W#RH_*JpUWCw_Xk< zeBVxm7%(v|rXy8@XMmLE+2GHA(mN%O7KshB{A?W?8GnV#tH#5U%N%}Z%J3}&;BhXJ zp@d6e5+*Eln(T2Y3B2Fh50&I=;6}Ql93wb!caC9WHG@uAXOpvQe1_xQ5u*6c|C;{- z!doHx1@Dgqey{)dhLv=57wBj<=6G=)@0LPd1^!bs`-p*PP)ZrG+yD)q`#H2S;_FcK zLZf()9Lab2??;ev1$w3)MY^z_i`ePQFY8{;+UL4m+965P^JbWYL<*}v!eFWPTtJ&@ zBUK#ooN(^_5H};meZ?i32=8zCDq66rv)4C?3I=Iuazr54q2om%#bVh&%*1={vAjn< zs#wYUHU0hYqQH~at4ZKBG+-qF^3QObuI>!N1YbXC_Xyn1i(F^_L)(z?B)#<$t~a1> z#@QTOP3l}*q#XMCJX*H4_8IUe{W642`RC#^e0z(YbCz*zg~N@?3K&a9k|bh=G69?4 zP+uRHwZVU+i=8>DC4nUzu7d*rmIj=gdvhQK)(qv?&hO2yl9n`qtEsb?(qC(U+0sin z!x~sEIlFvf#mw;B$e0fJaTj~gipYAXjFwTh;^FGrJ8wJVcY8~b&4Kby>*!0aN1&jX zb?b_|M@O*}vAaX|WQNKi>Zm(=T^&$fbMWLpbY?T)y)=9JS=5|7ZzMV%(JcYxX9~0Z zYhsH-IQbE9M`Oz@5ZxXdplL6|X6T8wj`H|1nzb5SrL0XtWo*f*vZY#&H24*U&(EZB zyj$+ih-$yYS`XcF)SyqMoZ^zu+r_iQMN`3RybokkGo$o^zkQb7 z>kE3}c8I~n*4tXhe={KI(l06&+mDLWLn0j_mZ_^$mFM4HMp{CmZkXY_Q)Z;MX#Iuv zL`<1RYl)CRey-dxKA0xA*PfVH;#bQ<;#F*PA-Ke7gv*~BgoM@FgH!m?5=*s%9G-ff z_lXcJ4&mX1X1^F6t$jGJuZm3tS-M*;J1#!R2@w`F#A8OenZ48A@Rsm@P2EP%f$xp; zl);2*PJlEQ%{;JQF*{&WXfn~uW=4vMhrf5b2*C8Vd2XSZeWsL>X`-)rk~63MOHNp0 zCyA|PJoB`&43MAi#sZH<@9$T`YD=%u#?}8l--VjZC`x?Kk+qQpBaE^IzOt)IQ*?sl za% zQHGYQO@IQy3cDO#B!?GfA`+~g%Pf@3+rxyFi`O}TBe@5CeD}WQ==Avv9^$Ge)kaepS{Bo??O;s0aGIvHYx>T_`-^(;+jRk83}18AUnf{48Luuq8Pt2q z>3RIz{jiIgo7!8q0Hz!teuWm>^FG4k8AszXqX~Ln#uvbngh0-#d;fpR>UVQvne!c? zM?H2;EYF6{A60qC+>BY45>WxyD(U$aXFmiPIFMc!ww@s@`hucCge||eNIk<;>E}oL ziYm!rK_@13mu>@~_ttLECp7llD}_W(C>q(rX^|a9UVIm}-&}oT4Pp1Hf@E?1vn>{* z_;NFUW2kfjTpr(70_JT*689W0Dyuf9y=OK!kU}Y;v@&?f6IeeN<3A6)+-i2ZjNWy6 zPcpJ{v1U`ZnRoPVOfP=cor<2UsX7l(Oiq0KX2S`UTU+fgb}%-{u)_vy;hR>zPWQv$ zv~@=#E<>;P`b9qmLi^g6%r&#o>&hKOPrD;yrdyGdk?))h!P~6w_Z!BQ*_qeU1pg`S zwGaoi%>%Uoy7R4`q!q`ghzMBHQ^>Wb^{B^qlJ)z;QWSho`JewYUZs-AyzW7?O zf~T*v`kdmaN-Tt_JAbQ}eD79xa`QF@fF)ERZed}v^}eH!i(P&ezm!8{S>5IC5bCKn ziSN>Yh=^+xuL5-w>pH6JGFVbtKOT$46-&?aKFqwo&;;Ml zyvJ5gDBI`TSlE0BL+%XCmwX?y3NLuOVR#r*4~Bs{a$=3Z9g&OormZi3rkP?+TT0+x zNcOQpiepu>)^imUt#w;xhWQeFuNllA+VzSI={N11a>11+28+1uu3!<^ zGKH5Q3ns(S&AUwmT&*jyd{I}8hJvkC9bM$5M=hAjmT8ChOPcp8Gxwae1-i6?Y?J_H z-D=BE-Qb`&WVHo|V=zv@eEKA?eAa@t&U{F#`!lg|lFw(uq`nnkivYiMO}y)F5{oS! zbmW)OObfGg3ki|9C{QcsarF6&D;G8Zl9_h>%ZQ57S*yq5X|xJqog0}1YXd%07^gL= z8Kq{Y2vLEfXM8!umz7)RxQGFn=7eD@JvT~4Z90Wy&`QnRDSw3x>bN@_ci_X0Ht#KQ zm(w=hoQ+D^hnwl$REbxDW+vA_-){q;4*&`x=P&*z0T$rFan?5QyGkcLryM|HQwGbS zQ1N$@=~F~!y6~mUDHYPAmSSp=r>|}*_aLy} zCGVP08~ef}%YdiJ4M=RdKOfkqL&SuxM@!=_Yzz>FWMGJ@6XLs9R->{`f3e zkpk7wL)UR|pLTU|=qv(WW3R%pmZcjzx)H7G2xD#^4jaTp`Vb0$)YARTCV$ZBxOM@mrHD8V?a%hv(pbh{Co1Ky7!xmX!CiDp086kd_>_!U?SZ41O5;ayV)AJn5H?~i5a;le^PY*S6=EtN!x(?=J<$y+C74? zz7Y4a|3e~k-w2Xxz*~7{gMTjzgSqF^w7~L;MO?WD@0|#2Xy$2HN1%3g&w?#EtX%8C ztW$tlrm57i3}f8tVS<3eEFNZ?Gfz)Y|9t0WA1iJJ z7hvcFToWB$!`n0w#gFYs`p*lao@AGPvhy8EW4Aa_rV*g4tyy3bEoDS$R*idq*iU-s zd0*-=@7NeVRPhv)O#EF#+ejDHCn(HM7>!e& z`xRBrO?LKUtDRac1(DAf6k;sXTd-#d=(1Q)ZVhzuOqtb{H2vrUt=fZ3N}i_b|5d_8 zXnQ>R(%86u_D07d#Mc#S_rMYOn0(D)nfb5o25n@d{9-fpgFRZK=m4;(qdPmf#Sc}` zJxGI@IY=EeC!WBd=q|7n&MtKR3>11;38jCtQ_U?79gc{G3>Zc~V^Ul^sJaT){OV)k zF&vAOzdF9i<`Eo=9rITw0Dce|EwLFs@x)U7>1u^w%t_ z7*CoQN0W2aAaiv(y_*(MKwZO8|VntcN&s?H__cs|M(;lg{)9*yg zVmUe=Ch-G&@BRuIW)_`KUp{`SpKT%YcbM~HW0H|suik|1Y8~A+kC)DHn55@9ohr*> zvl(p!P|b8zV{me1$#(D{u`5xA!rr^0>UKr6(Hqgy09IXMOG~z{;b}Gd$;f!3x+UNr zT(*pMfxSKlaG}{fo*#h{1vV`;USB%Mjkk&&Vp^BnTE+v)%PZ(V1mh>L&R3x9HuDWj zKHi`~g@Vy2CyXt18OOe%;PmzOOceHP6IIiQ_e0~}xz)ygk-?@w%RFQx_keo6MiI{=3s7m7*j z-!n!XvXmC>d+OL_y2ou<>lZyeZpgM$tGt$ZP- zOhXBT{gZpoCYAFvmSh*G<~6XpLBl1GV;6d#ZND@vzo%}icyy#KylZ%W9|t3GA%)}o zc8B`063@I7s5uG~`t7|UiWx6}VwinDK(~&Wn5drJuZ9HZ=tj0UHJH=`E2Ogd znS-?{Ji%pC}trc1>pv|a(K{w7~qfino$g5oP3P5d35V* zs`Fpt)obxu*3fgC+I&0uom=IGpu5xDi>jC%1wKz6@&INU&ec8F5MZu~E@qtLC2CZ$ znM|-Dt)1I$DsCX`yCij^+TFxYcEiIXyq8W`{hX)N-~-}(gQeS zUBw4%Hu|3N*y{wo{K#m$%Z1l%E#npRB>w#eOV_|cxRSF#oy&C643{%UT{E4ITUAvS z%~p?Tdi%R0Tj>I&233HjB;jMgx`>ra0#CudXsHzQW4>x5W}Xl9m&Xa)g1y^Ep?uNc zSU|`8;T>I8H}^}-%h1J+jfsVKz)EZP!c}pls}Mn7*AIr~{`SVvuyXchK&Wc+DD_hD z4%v9X{m%cDp0AJqP^U4O4H={Dv0t?N029bg9vQSB74n=AG1NRiW z|JlmP#RB1M*`B&-HYRXFYA{Da)U7WBgnnI3lL< z7rPkzu|;X~hR{>_y_V?3QxfK?CS+KN*Dvh39zgyhOU?F+H_MIM!#_G2x3Lk57ENkM3t?% zUe$1-yF!}ei}zSi>YDe&DH3{%s0-OS*3s$P;jv-89bdwrdPR1lZ?xJmy&P13U0wWv z`_>?TAohuv#}Ryhjt5oKfXU#gcuc4zCK5aqpy*4qN=HkBJzlr>)`cEk79bMt&dXuB zp;pHnvBV5rg4@;N9O2(8pHGw)8Fsh5kA%qi zu?laF&@O}jbn|Nu%ZhFOwe7DV|Gzs;9Ca6C1^GKKQ}DSn8W{l>0B8yo>-0LgD!+my<1>^#FXxi?pvG#DiWhcnf_-cs6GSsJ#>k;5JwGU zDYvJbzCKc-%Ere%$TzN%KNN(dF%7UJiVM-h*dhL|NO8ro$(gQ;kurJ0rIvecfxbOs z*%a?<9-G~sj&Z|3ik8qXb;N)}Zt=6u2N=Dl?h$~!7aK14r{?xyI|7(FW*Q7@0dfX_ zwac5zoS?hAyZdQU+lIi z8~v~cxE-@Ue(H3x*vloxOFN?pdxoBj^&R{3uA%D*2#ih;6~+`eh?k!(63i@J7#5uo zTgk)oM#a!CNM7aA#PTAY$y$Hwk| zYg-S<#py~@-^yrXys!vFS8x(DV&DhYEb8V7c`4;JcW)A`PVYOc5~B7wo;uR4?NL$$+2-pnJ&lxoZ?<`;yrU$IUqYYk{gv(^-gK({O zIHZZi(ye2vs?4$xhH3th)83;b3NbcmiD&%dq&?wZ?~ySnZ#L5Rz>;?3e+AEokF2$( zx%KF?0&gUs=W(ZN#7e6OBC_5SLh=0k40tIA?Yj}zT7&B-}X0^P<|IZ6RV3>9Q=Vc5!5ni~(n4ohj2)P>qn4GA%CjH4r7>BN0+ zkV0PewQHQ6%?u7z$78uCSIT~phzw)W*rcx{waiH+b#+F zIw+2ON#R=^JZ-%>EqzAWjE?%?lfG0==W{I7$+BGgD-9Zk!=$_S8Vu+as0+9F1!4gR z5Tk8ufnhW5%AZ*?zgMN(%t|Md&TVluyJiWC6As(;(|HzyT1R|ENW8y%!01s9{XB_- z3-SznLy)>iJ~hKrhRWq`GpIF}c*hx6DU3tLpOD$tg|_6rndXs$)@`0G5aUy0si?ky zguDm5ocr_)-2TP8YD7xI4}8j2PRVbzBVOSZ%a4Q7=pXTSgPlbHSNbF36Qypp=JM_mYm%9ssA;NkNCAlTE(H}o$u+j@BShUI>fT;ca z-7ULhu&VI=>%v;!?oSM8c;qBB=obsKWUsQ;%iOQOKVipsJO2H0xOGDwE2Uqnvdlql zg=t?4&DLGA3|g;1jBT?I!Wq4^c!#m$zo*nkl678}GE;!>`B)+F<$E&69K(z{(8)eu zCPc8MD5pR>s@kvX1%;3JOKEHOLs@+c2W2BeXngCb@pw)8%=g+tsM@&}vQM6al5V=H zJJ~ZSk|I0Ef7W%7Q)WqeKS{bFRLU^|$=qRCU{O4qe@YG!6;v8@rJiE#Dj6`G_4v}p z8ljD`sxugXj9$;fn99|KH_L)q%CoF-Hb{5S#qc(?<)1dII891^7n4%Y)khcjBK$jRR>EC?ADKBSO zURxWmXox=O!_n34!xeI$;)UoDxQD87^ArCc{|&>ID8>BF!?H}7t^pp<4+2Ni7;xGPiaBxLr{d|?)Nm26tJ(ps* zsI?acgQvNyGaBv##f619Sl8?t^r{2un0L$OWT9ABBKBx)O5QaxHr#cAqg;KfCv_h5)m#pdTq-A*o`R*K_$ z*bg=Ua9iz#{VX+>^>w3xRr24Op^)Tk(oKW3?67c!PY^+mFj5ih!&SzQ`vv3CQN6m$ z+AlM1_$v>jrO*HHk>~@ohrWr5%DspOUJhC8Egk#6uI5}suqVFhj} zd&o1}rUecdj%kdos^<$3?VW|@TCIGeMV$Dyz@X#?bg9+h%wlL zwsUSau}j4G`z8tu@nl_J=iO`W5x{0vahtlxxRTfpuH7SGO?LZS-e$Xj*KCSSZZp_A z|8VN6sHuMlropdF-Ts#-2aYk1?i6tmu%{Fhdl%bKx^iG;BD@=jO;cab%Y?)pX2=6< zjTd7zvX8TxHQz>}?|vA?`@_gXdB_t3DH(Y&#NU3JmRrT|E3K~Yv_)cH1;n$ITbt_> z)rrTLnjYx(dzjY9B@#?f0ZS?JUaEpA8-M$lb)lXFy&1@K!LIRLIh` zT_{`0UMUjk4>})VqER@_E<|fiM&+d!nyy}1f!? zxLZ}?kuWFPU@C3Hb7}0qD5oUlX4A10)hH=7hOfjjPCA7`j)|WCz#U`H-h!9*${Ha1 z1Ju|}K7kLl2)*g0Lzg-K%4=2MXv~<~3Uv(?aK{lKshMh3)p#1=c(Xb1nc%+s6!V~R ztl*)2O?Y1EDS zVxxoL8_~ zG1G<0x_{&q4yvn}efwI9)p5jq_N#y&@#%=8zb^o&L zs}1$_v;7fk3C4haG6MARdY+k{u&E>~I%sRo6~i@__+w|_8xEp^!cjnU_m&jX?r%`t zB?5uVR`H22Dd{P|#Xf}O?%v#>5x8s?p0#sw=rkfZe{bl^m6~jEg4M{dCMx?2H-8Lg zyku^u%d6WmFt;OavmR<8TSYFn8%`Q8G3$a2*LsD+gYmZ!_@)H7pIEPHkxKGE|@?-8{ooZ zab%2MkplK5JfOiRDO8J*;aXOHI9~UkmU>{{`}5Wt+uJe4J9g7C?wPX)+Raap{9Cdw zLQF%UJj=Lz&S;y8+x55PWOTDxGCefHi}+G#2Dh?KV&w&h_ngU2e8P4c+6dW_e3X#q zk#l`lgsUjB8IF^6`U{8Ux9P^0&*H}jJvp1|cS!J@ykw#&Tq!$5Woh8#No7IjahO{3 zE1c=!U(pIBNjs2Ie^02lYxL$M1iy@<#J;9)^Q;EK$Hcz9w_@C-7rRrR*;Qcy7;<9` zvQ#|l#4Im5P){8W);x4r!(Ep*&G3b#vnM;m1F-K~AYKP&&g)h|?=Nt(cA4sn`E<2dspLtb`A) z8NyKDUD*7WqL)4@#B2XY)W{m#e+K0#G?}jTB|k}ALea2E?*9WYP2-`$aB|012U5~ zK$w+Wnkho!{ZSq0eCnZ`a8E0>x;4z_@Wc3e{T>(cASC|wVENC!Yc1+m;tc63)E|G^ zC#pP(OT@1TNBGNSI@`0JV+M-QjE@0NL5LdCgi($EI*h0l%#Rv+gU&lD9AdA0C~MJGP*^B}$s*?Pj$m)fpe91g z4_mJSez3{Bp`Q`yAe%B!PMu1lw4Y~P1)p!)AcA}R>`5{F`q5JHKpXA|Tk@oE zi#4qN$AR_oOn!K7-meQML^(ee*}g((Yu<>3PJzPNfX0jFQS7N5XoQ|hBJvf}RMzTO77>f6&jm`O zK+VE$SaTu^7eY(ftJc&xpjpC}QC%St3!$5#8(YPfrxPqjr*q~Ogt-BLo*bLirlnx@# zq{y7g)g~XK8RXO0+LJ;^+3V{r4tLpJco1uKD~bVf^{}J(z-C}rxUKfcZ{C5+xld%PG$t8S1R0JXz*Oc2gFvjq+Kk&Tu@T)SWuw~Rw>Q8YWTNB!=j#n$9w{*Vw6?R3O& z7a^Rq?6#5@6y+gMu3Oj>X}Q3>L>i_I||AD7TNu=t*6f zJdyU3Wb-d5hNw>`c=1nacfM?U9A^#RlX#qK#wL`;=Wgyr+(RtEyl>YWrl1Cl?Zh20 z_&-b(T{>Vu%CrhV9H0z89Y`b47;b27jmDIC!RmR4?)gtet2}`gU|BAtcm1RJJLMBL zXC$UOUmlo}P1jSuFC?~)ngW->bOKSf?vK^ruit#FTet3W+xM+`lQ*#lK()5lniO^q z&w1^G$fcc&P~Y~p5uwzR<1X(b6yu23A9M1qa>x9N9$ynWkMIP!t2li%JD8hX+i~mo+wzP4sB$kyV0-5s6^2XJo8RuNaZU_qaY0)}RZ8r~Q?Q!v77db` zR$qwY9s^_RCWHj}tyj@u;$@>t?x(LwOORjS5<9yMP9ReW@H|!U*#xif=@if zWkW`{hRkt=Y--U9V$!&AXWc+ur$TXRg)y@mIrQSwV)YSFj3ojwdfR{&AqPO4C=*Y?OZQSEX3GpBzutHOy~1a8087HVBU~>+9-3Rb1^m#LSe1?TW|*r(8II6rp% zsB*};3(feM>m}CxEA7=K9mv08gYV7T)u?CvGXnTQ>s^VO61PsIZ>lM&B=W-v8)D@k z7e(P;Ca3y|d|eVrW2mb#+|o%LjRod`=ui1^Gj#D=;MOZXYfBU6q(eTn(Y182zAIdF z@`$rIZShZ@NE1E+Zc51VJ@Hf`)V_*^>ug`Oz60k%%W@&)82LjXt$#k$WVOM6*#jY( zOD+`rW+Z~`fB9j2r%+Z4@20xdzD8__bNq!O&y!ggKEufw?e^KcDOU?ZkVD6*Na$}0 z42>nE-O+_bnC^Hcxg3A))^OQB90pE>(gWzh*XD!X2W03uPNecw1XAIE3GkN`1%pM? zCd2*d93JnRJ!r#TVVT7xO=??a{Z;4=H0udtYJ_H_EDT>31Uw$4Fu*AUu>~vAa>aa0 zf%?c&r9?{S2ns*SRmm6b|1Vr~5Dx$sOxBdWRDTafgtbQNZkRZDf0Xh@t!X#bAF7mT z%2p1_TE+_D2p4oE9JCBcCjqN_p0hM}5T8$TDd{n> zXhcJ$xVsSu4MbsF;-p+Eo|65l=E<@4?UA6ybwGWwn6uLqICs$8+D<#U66r4TBHN5y z2&0Gb^J6%Je_LIIJp)ItY|0?uiEx0E*nra-GLB)<8580*!5yF5Px`Q)D{+|@ zfb$2KSSYkPKbc_FML>Q?HpxyzN@~WQ2Z6`Uh8`x5k9;Utnq=&FsxHy&5F1othSA*VC57(ivfzRAliO5IG`?Ft72m z>gXIF74}LrUdn$8js{wGM0&BgA%HYDd)gNhDWRumL}g20%F+!8C4|};mI;#*E4qpf z7ua;FSw+O~7kJJ?D5e_J{_4l7@YRth4AnLDM~Rg0ByuCn=rLvfmla&8 z1ewGw8ABXr$FJYd!c3S^%I0&+V4{i(Yo+YQize;_&Ew1W6~t)3DGN^;Sro_WjKqyA zTzAK3dkRiPftLSe;8nIZ)5`Sc}orm-PJR$uBXgtOI~3<6zMiK zw!zOMNtV@q!ge!Z4|o9yp*~!*Wk=hU);wmJT=apYSj%;)^k?~un%nO`EDEy1pqq{9BuMuD$v zB*Olr2unz+lHWKR!DsEPcJ|>FR$ODJ$(st4DfQ1G5)Am`vUy8T{$zw+aNc(H7{0Mr zf#bg_=dZ?J;Xs7K`xt}~1r!D%v%Yh*y&Me@#dzgD87Z!kn~WXm`D)o5kpW5nI2%_j zs5KF~Bt@b|`ks>9Ea7){lSpQ3fc%H~#Pe+A?5%!6$koSSoK6$E)X|`){2iU?nyg>U z^k~$xVzsdelOraHNT^YG--~72>$BzvS5tkjm>MPA^2CN{!95J>@A=Kt6l;k=lS9ELw=SmJ(am6og9E(>a_MF~Vis7WE-? z>zOkU><%FBItu!qKDhXLGV`p++{z)wONP4>a9gqZz2wS{g(8`MHJlRDETP zHxd>S7#!YMbvBqzD6GX)gYrIxIPF>>FxV*i-Zu9O&Fi-(q!qk=NGL z75+q{D0j|0hh4-J9-#cb??%q83s6ZGafK0dfnj&5;&hqIX8#)7Nae_b{dDawOnR;a zvX35V%D$YvcN;w7m2kdmH5oq^CYdn4hc&iy=Pv2GvDg0znnU)v3|<;bFe1$VdE++n zGW?}%KcgJ#)Gw?F4*IMr1T#LdkFZ`4B|}4T0;0wNcZM|}>JbwEE4Mi-G;LH9@=MQu zu`K`j8~*d9U$68(FvkUZiV0U6@08tsMQX|1q_ebSr4q+aK*-IgT4Z=iI=;UxNW`G$ z^m?-_&IxGxtl|1nO{pq~Vbp<`ES}l+Rjbn+++?t;|t$+P=;Q%qe5t*Vb9d8H2 zKQ`gp6tkdJ4dd_mQvrTs2-C6`>OUAH-+9f6;tP~$0ETGOF?QG=V*6oSZ=`Sy&s*_S zCymte4OzPIB;laDbH>UWRn!nq^kIx0vM%isUgrO_0I^Bm@?j{cDy7JZ5X+X$K#GQ` z?B~UF&Tc+ojSN{b$zfE?HN4(u&OAB$K9U%A zzao^66@7!pAJ_9U{1Aq+?S9g!=P9&T3oEzzvAMz;3BduZ0eWFMmLV2_KuI-1S@eLk zo$a-|hXgV)wqR}9ALI=gW#?3j;3qnKJZgC;+gz%yCh$Gs1$8(vS99k=K+a`q=i@#P zmmora>Ve_BON_6gd)%wg2|Looj~~neJw0+2V|M6c?JqA?N-(S+WEm#>Dqy1B^+=FJ z{t6Wb%u6i3VOI}<`4vP=jV6*C|4aXCiZzYs&of_uOHJW;>4&{GK)teGf{Z5PgbtN< zL+PvdsDabFq55rDau9&PDivh}X2ax~7ongPLhD%EX3GN*iE-qT7Wq*bes%T*|2dnj zmn3Y#d$Y*k*z|-=)ml<~DA{19SvSgAn)(R88@EWdiL4~P8)2|1);C9qrN7Qs18(I- zQ%#chYbw9CHwK%tcOIs>{+1f8Hi{z;+`w`T$Uc4syxWKY8GBZdJPsIOOa z9i1yUH<6Z;Ktd`Ajw0v_fA=5L|8|OhjygOJA-_WQi@B-`j0Ryd5LK1(peo-^*Dt)( z(0}RuF@{fEd)oIXMd7BNRgBlJ{3zF8kNFaDv4zH~Y#+VLD`=W73|Ze5sdp}peQMnW ziX*w6Fj=*yZ?D42)oAE0iUCJtdgrNU-0?X&k%~; z4LXg^>YYiAs1Sl36zrSQ-_7MK6a7lY_IzdGGzfdGaIOp{6WXxSG%3JK^8dUel-u>m zg{t*Sp4YWdgPkp2iRvE;^YxURA_;AujusfrkS$+4kRBgs=veU{g(@sFf-?Bt(8s%+ zos3UqTy73ue~h1ofSYbuu!{fkDVTX~>qjf?mld_6`}uj{v|mwAPd0Idaf=3L!Oo>& zI@uJ9_Gr@)G%CCeDo7S$TVOWJin{qLJM-}T8_n-4a6N86{jap`_B=OHth@6aDL8CJ z(NnRP93+P@f)vNtO4Ow;wytoLM#s%J1jd6CPbm>DnaXm3%((BV3d!lgEfISaBy#vh zgL(FV&?JW+?&a&PVaA6IWj3fMQNd2>V}$jc1kXKeN;4_7sgBUS8~G_$vHYYXU;dh1 zJ!#;lx>i~|5WWuRYk%%{NCAXN{;%>w$8JvAjEoFtpm#v8cJ<8qpb6Zf!vu(@W5hXB z<*VLhWJY-fI-|;MTzq|Taz~5l)U=@F5spt?e&4X! zz;*xxr^6a59R{~L%)41yZa?WTJtkS;y9ub{|1uSG%fiKHp9!9bfsoQQX(2BWqlduS z=oqo|2n%bZFrIn@&Kq8S!J)hQ-r%R;i}4fP?carTuHIL3oXmir*XxQTyL@Caquw~K z-@gYW$k&lNj^*d~(oZ(&#;}QMp|8l(uyOG}YI48=@=08S87vBh%8qEHgZ0B}H}GV5 zk%^;O57YCm)%-o_OB6B8+9_j4jHT(DV8K#$%*reNbuZ;=Y|RnB!vDQYEH#cIz82A% zSFrQu+%M+bzobikl;B9RsXv1^mtFX8-gl?4w=zu>x_EALT*lQrfg${f0MTMh7g)Odo*w|pf0Wc8Esp#YrMe}m8JGH4Tiz@4%OquK zb0w>nT)BU?800^Df;fa3*x6X6P>nqr)T2aVq34Z}89+o^d~0$HOwJT=7=fQ%ltZ58 zvJbz*=3?!;z=S7V`VH|#3!1-j3R`1^Y7T>g5tbR`!A4_OyIVR~f%)0e<4^DzHW?M*A`{7ixXM*N9a+w)2a`Wb>sPQ4+Heo4w{e^wX z0a^CCgNY){sM2#9x*_1)>l5d-YA=cW)mp#A_ zMqZOQGKOC)U2-P7b?GUv#06cZtTGE!hB&*sBbl+|l_cRp$E}R9@7a}d9; z$uFJ*^vzB7V}P|}`-Z)7Cyv4D{__DIa5Dg#rXKzMR?*oDEBCRWmmY18L#oA`Jaks> zF<%UYm7xQ4>fu-{MrVhKRbqNjo5A4EdWmmA=nH2vY%)CvK4vtpV7GKa4I3CKEs!t}62qAR5D2jyHmZlE zopEfH)d(PHmd!UY$RSpT%yq3ZM^d$b0jU|0C({6OhPOJA6tQw)P|mL3yc zlJ!W9%PEX+ioP@>Pu<_hvwu^zP#!*w^tsqhx;UA63lmakm;RAyQf%HTxna&14vb5M zRk=Ao%V=-!8glHET13Nbc#@n=`t_4NVe1R;4B6XqePD!4A_;Ub`FC1@+eWc&R4oHB z(gwksQ#+zuaPNmhAQ+4+$EsX){f4!3`#Xeg4S^wix@Y^aq?>GKa!r|(_cuzY_3i2? zh|x|aLgyP=iFL3ADBNoF&W*lIJj&OEBgPHOLmcWYB_QJj`1O8-qAII{n!4k%j^!b; z5P~&^&WyCE0Y6OcL*-fIb4n`TwaJ3@cbIV!jOSZ+p#7i`Ysgcdn0g=A(5kE-Bn*>A z)4UCtkFJKbo^wqkd(;?^F@cKxShXf3&v+>Sa)fh>5~&`N(F{YT=(D`mNL`H>RC{bg z(t7P_2ojtY(ZaJVLKMsy>&MYz_^cK4CTd6J7oX4U+|(pQamT13X*bjww-U0-3$ti3 zTW#DK{#TnbYGV_oW*VkjyWxA(nVz>sUt0Re^yZ&D^=s*l@jFNxDR(quVKwW$gKz|F zg_)2;$Pf=bA6}Rx3nlZkn<;NRS?hd~l^W;jfhX&C!8A-pE)t{ad%QZ4E8L9yJTlya zDZOT;Fg<#6JxC&1cX>6}kn7~To>l$|1j@4_q%)a7va)DmqjKPr*B7D2WhKtrX4`XgJ?LJ2o==`CDd#n^#yED707-m4&oW zi$r<&PvENc4e-!gqPd{wlJ0>^QtD34CuSl?*4OD1rS_knd3hDpDL#GB^#8eje@VOs ztfN4DRPJOi5eS%D2k&~Nw>8oY40r^&3+d?0P7e;Cw6(Rb6Zn6_pefi`mjJ=u5;$A- z+)|64tnx*y_-P680w^db09aZnZxq1=+b2qw#MXX-{Y?$6-IgzB%=FCj`MjyuxV0^+ zIJfYM-tFQ39BH=q9Rqm!L{g3oI#Y9B5IdXb5L}n)E_S*H-T48JD=8GK7k^%nLyjr| zLt(=lqW4vm`L~}47V#5}L+k7KA_bB!Lkg6TEFKFZGch2hDl>jny?*HjuXjEevBAK5 zwik*3Cx4U!4u-!|&x#etD(z9|Gks{KSTd+zIWT6Uuebkf>=Wmb;}WE*;po~6F0f@J z`WG~My-+D6gmR5oTWb{3(VpZE2CD7cq$XaUoT93&egQ&o_WvCb93MMfA5BAl*JfPW z0E|$(-6aXR*JE)bKsx<(V(&XLNzX^pGoT+B44&J?W{@1`!lDm2g1kfOh+k#qqBEZ! z`XMh8d(gDiM2RO~|GE?4V!HUyix~W@tlcPV?8Z9{BliT)%A`>eac?gxCyg|AcFb<> zV;Q~;3$cdu&wfeG<_K-l6T2T=Ajr~&v?Da_%NYD5Q8?TrgI9ot2H8zV@4WONG*06Z z><{HS>gH!Rtq!~N(l7!(!8=LucA6gPGFP_9>i_=z=J?|u;!zXyuT~)MK^Rnc$P@yw z`yK|B1iXBFKo$BR5O0JNI}Exm=>0~V8_Ld@hp@CQC6i)lc zPJnwr;+BtQ6Eq5n^7S}vP;e76P80p@RH1{w_fK>Z+WLLF_vctEuBoMhQJ)DqH*q|= zhy8`aT7*8=V0XcGBoLVK9T&#;msStx7v$!uwo+KR!#ChRj_jNxvmF1fEA;6|Fe_w( zrqDoRTLydO{k`GC$T2(TeB;7*&mg9*FVjNbGcR{XgzSJf8^e!649;4U1gYW5wYu>4 zd_OZ)U422bZdg&L#D=+vEArElg3hxzF$QkE>*xL`?|)&WCfciOwc71nJtKF=EC5mv z@!%WQv88623>4Lub!S^WUza5QSA7KYbh(L`wE!^}Ol-saoW#33t`CCOu2cank!i3c z?RuTw{ZPUlfkQZLgZwPj15)eC8Ui=(nK$7^WMwFYb0CIlhHD;ku2Qg9COF0e$0z?k zZCn9FB_U#oo4Y*h^^9N9Lwi8J1^>sKF zazbmrnr~b?as2GX5vh1RQ(kSfeTd$lU&$OR;Sb2+)3;fwRpBb#0Pm?E}c_= z#A_{stvUzi=_Bh6cPwLXb=`IS^IV|#$>gJu!A&z20(LS$(El2w1Pq8htuD1#d7BvQ~tW0 z+I^Hu7vxfUAl2Rb{v<3(P6Nw_uApGr(t5)aM53{e6z?n3R|Arkr?&<5lhv4)e8TZl zMF4cHTtM9I+!HZ(4p%O4DKG?3nI)y$v1j$^5jK7URHYjm`?Yyca5orYIP#E*#g$3N z*h8vXxnf7ThbMMZ#mq4nGkQA5#(+7x-?lr_1I55ft&Mrb4k9%VI{Q29jo&NF9Es{;a!8ya{BAXh;=fk2%f_jt@9=JNF#ydLY z^%Yl>SJ7rU>Bv!6R4{fiY zWhDLV#W?OOB_m3=nGD4w62}lDo<-p|@ezx}89h9U2A&*~AYtHGKk)@7=Z4KoX8^Ii zu#9Rg`LtWJjI6Aza?{lNLa(f%0vygeJ|B=tila*=b4(eLA@duBlF^Q|GrsIuE-YYj zMp+ttYC#9`9Eh*|1S|Q+e|vYQ7AkGx%gFWT7=;%yhPny=vK{(Z+q8!i90%-6vvV_G z_`)FD%2FQkysk0u#=$A4s!M(^2u()!R(kr5cal3_Jk*b}MWI6}%IKP3NRKJV;$~~T zQ$?j1vZBK-d&$3et8bI8;63fPSGmu27l$(AKIVRhUI}1k>*g`EiNd1E$0vLxM%9Sy zsmK$m@#F+RXf4P2#l;WhqTp4}wqbkzuqR>jaTS2^NdDy^R4~ZTd5W1-LC5ZH@E__{ z#|0FmeE$x3>$x)9fBppSv3*N*>Wq0m7;8olf`x7&69;I?{QBgCPLO9hS)q}1Y~J%a z6Bn9j5~FgAp4QF&1*N-XEEWOq3_>6CEYb43dOhJsEQ`zioq&yS3cR! z#j(w@q2aeKX+UAptqIC4Gg7g)0S3oS({|-KN zq}^;Uu8!oEd#MqXZTBJ`D6tfg!dVH_b|T_i9?VgiXMo{+r9yIBdd`er@(F&lFxNg^ zuS7P{&N3)rLgI~?O*IOd8whwG{N7#fBw67eix+F*8NGSONZbmFCjFR3{ZV6Q-$tl! zWYCnbzIU+!NMJm@oj<^V|GY$o-`@i(Sr@>ym@j&F6#rCUoeB5Is&hYK++iRg zGa(E!toiBTkIz-`CPEKCxSiIp8o`RmVSr8kla*4N-5@O1z$=DZ|AsC=m} z5a~swYOamU+!PW-t9CCq>!Ry8i5DIqu~WB}&h*Qhx%~$o?FXkvnBZhGe#o$Yu69J} zo|eQh%!F1Ul{f66U;1%EQ>Csb9qw#GObElT931%;!AhhlRrCX8{rD4>_!qb_tni?k z@Su#@NQncd782F`KMgceA%9P?o@SMA!YWiC%I0lbMt}u)bE&<(l>IF=Rpa$}RAdAg z1?{(?@hc0xuaai&^}&=i4Bz02U-6Po$1_i;$!d6Z$%-l_T`2z!*lXao=_h6ISfVk44 zScvJNn+9O@|H$HZaU zkcIT8zlA*!7Ou*qV|aZmlFc&kHMJ6Yv@6dDv~>Heu{%b9Se=?0#!LQHXydTBIg*vf zlMa-ptL;%s35(RdSD;R5;&In;6XFO*3K)6mevSA$ZTamjf0??u-VIY#X35G)aVTnz z2~MXtBm^gBCX*xb*cX!beU(~8cgnvb*_h_$z3?E;yZp~}>d>IWBtF^;Bo6rjy#M0E zf2}LIW#6YNXl2G4iE<2LTOHI`D>icOw0S#&NQceE-C%a^yI**NUT|=oW`EQWHY>&Z zx`qAqhcRP6_e53{_Z804Byakh9XR&w5Fhal&*ZcGAV2J+@?mBW^V_>YS*RK1uCigP zWHOXY(uZ3~+>p~o!5|aSZ*}EU-cd8SnCTZWO-;9~*xwqD;k=n!PlDR_dF3{AVNqf_ zR{>)f-|m23_$w1)khRSUMFIM#$B044aF!CWUL6-0MX!=JIx}#?9iV(8Lp_LncTpFY z4&C^(jD_>|&hM$71Jbk<%bc~eimwRhu96v{z5g6B&!Agu$`(c`6_8#yU(wTXioAEQbdlXzqr4r_1yE=IIh zaCW|pOM|R(h+Hx=>bdJHQxccL3bjA8fte@w0S`@{Z?tjH4PUsXDB?n>xE32!omAw3jf@GMwhW`6q%lKsiD;Zj zn+3%v9M0)YU(W9G>+~;1X&X8CcYd`(B zq+7ovFZRF$x1JTo^?!_R<#5ZT{MHFYt+ot|7){nDwr^ZtploEn`}ml#*YK?HORr@( zLa!h#k9h+LR%S<7{m|(oU8Eb1yLRT$UWD}aZjU@@sVvYI-=M#&RG*I<;rtOuyO3pZwp%I})%G0L9#7@`MG-95 zx4B9D_`*n(Ad{O{iBZQPcwJo^E&@qR31O@rJ7RiaKI3|l%24-S(#}OQ{`9#ft45eq zych?gYM)}S6`c|x;Jq}K?tph*9!b-opx(BfrbOx^OM+{7%eHlRAl(g8OFx^{E%?qP zfreD3R5GVLDkTLyiOllROySIH)Nz@ti$P~`d9eyoeS=@ULc7-qVqB@^*ANBTxa>ZN zOk&~W_s>G>P}$ZIIoWrC$+W3icugU7taqNam)+JLs?mna%0y|4A-z2fW|zzJ+{IEH z&0i#@-5Xra;+^45Nu`GF_>*>$UbRRual7N(P^7N0#XdBMqV=t;lANYQq~-&vV% zp5W+?o%4OG;mV&`CqYiL?n$ifNC(%L3rS~tb8mB_)7f9q5W8UF*H z=O_%}S2Zr^X;MJ5e<@Uh&$z3n~ZP^8<)p|o3 zMR0Toj|SFqt`>P8m_Z1_p2XHeg-cVlUp5kJA`XU~a3gD=4h)Gjw4cwz_ z&LlRm&|pC@u8Ald_$r`Thl4V%YWGW(65-gr(bqC(`WGR+gFh7h#szYMjKas()l;%- z`tH(f`#Z^?F}mzc0t$<0DNrjYFFN zNRXEKFl<63t=ksOa{25m8jigrr_xlwteEGXPo=w2_pVJ zgQ{BgPSEYU5%`-PGeO-<2-;PD^H8^?&IYrr0uj? z6AZhpl;5afa#USInn!X&+3C;x&>bb{M0aq}NLz9m!D&nwsu9Y;T4P*-h?T2GCPLfmNq93l0D!)gtRvx z2&M=Bz4dUGz8vRbvWuP#*ud1DBG<>}@l)m&c!kA*)*EjWiyB5MeYLfX0!3yo-3z@) zAK#%ub%R^nEz}g02l$(vcbAa=PYZy|-ky3|-}@SOcN(|M02^)w8Cf49$IqArjUINs zwUH`0*>ZdqaEhh11H3IgY%izno%dbD{CpC{r$eC56YpQJ(l_CNe^}FdwQ_SKIq-Ua zlb)`&q9lOlkHf;k^55>iNhsh&GaHGgupCn}U#zOYX6o6wt~Y_lRAvx>BF7qC=$CMA zGpfv_L|gf5yKcWzYK#O$CT*NRzPqanZ~Vf|OOT{wJuO+M+%J-Rf3wp|6&l!|9j`7y z=y4_E?>tUh;w`4#TgIW|DR+}#J;sDlNLT#pSJ$DBzak&BTiqYvoaqrlDSF2%N45k; z!CpaQu1nVM?5#Om+&Rdt8}Vf$sL0h%-exq%R$S-5oujc#cy{?mp$cbSWXG7GDJRq= z+0c83dR!&q%zl;R-{6l1l<#kd@_u&q|5 zVt)QO)*(%Odz3FzgMM$8*(9uvAMElTAItbtG!cZ0YWD8eZQqBX)y5u&8p0ZM{Lh_F zMg+JXA?w6@S`BtJ^(XTmiZ4p^&_(cT>otEY8dJz_46Qvd)^(C36Q0+QD6`&8>R}iw z7WN0qKT^)rD^C}xM44l%blyHTm$3~|Sa|bh)((;K^xFzWY8*&i1J-j<_8x3Pr2ll> zme#G}F@saQ2omknhVh?%I`22+* z9xUG)ErfnxUiFIsp3ADOZVf-*U_5@RPPrlG*ESx)`sk>85H=aQ(h3bkyBS0|qmw3wR&oypa zBq9kNeY_;6XEUGJx+d$5Y9JlkF0Z>EJ!@NGVGWlr6R~kwkW13R$h6U^lLgyu0hDsR z2ED%MOrklseQyRXNtFe4Ls5R-#dEEU5M*$g2)ZubGmdV1;+X^Jh4YBojWo5GU=dWs zXtxgxO-+%Z?uv+sF58gLuq{w(zd}%xD(liek$?8Oo%|c^mc`1CkNeaOg35^cup0^b zxLUZ@?MZ~`=Z$;586|ZV){Sqw3VJ4yAlc*KgafK_aSK|cF`1VmplZs9mQF~vt0;_| zVh0FEi#&QCULXO_>DpWpWE*CS!R=n6PRW-p7eo;(KMjYLT z2PoUoef+Z)DT2+dEz{oZeQ!ZiJeV$E521J+nQzss`|ezq#1&6T+?Q~d3ESHS=I6f&U#r~tQ%lk2SH z;Qd+D>V<{u?dpkr$=3W=fz!3)K}9xs%h%?k*=@b_-F5rkFQ%X%*^D2SM)5;Gbd-;t z8%4y4MT&O*%FmlZON+_Ib0t z770Txp8U?e1iF59#$FvE(b%*+;o*xle%4Z38vDf5M*v?n(Be|U;iDNH60P++ks7>| zESV~zgo6ijuj%nF)`-1R@rq?5S=Gzz6K+N>*Qm2k9kO;s95h(d-SnDqhbisU7)c4D zxD9FfGZZp=^^-ReFG!~F{z~_9`~4yIHsy*u)NQbofAc)m&MHYdHWhXmQNF4gzjN;i z^AD=Sj=|1|;J8+%a_mj^4Z*A?q9#JKvZ&gU?|`SBq{5W($xovK#7pE4=srPlrz$@X z$1R?kv)n2u29>mDaPkgQ9mD@))9bS-&3*CmQ5SINJGM#8;BN;!ZBnrJ!AVL7F8WAz zdw6+8#KsV$}NMtXf3W4>J$VD*mS8DlLsc(l|N%_ z8Y4e%T+sbHo+)GX6n&bDZ4{RV#Fotvg@>(U(TmJntArpvW_x(Mu|CTgK^>>65_ z|Gp+P5I`B!E!*v6WAa#0vbxUb)U9%qu$|Dkh|6X%)U)+!Rb%ewKibnnDMxbsqU4X( zuq*@>LcX5yK78|6%WS#iDweyw;mBRINa|D6{@Fcu7Jl!yaPjxABg@PSAIuj`oqOrsV)(m6 zN#%(@ETJFgZ5YfLb0xN-GkVS;{6{yfvD)O33OvHV1tRu!_?kcE)1 zqw!Zrqb7N1!a}%8-Dgs04Y<&WA7X0F;i?UWJJ4s-2=uh|*k)Bk85FWFXLjPofAims zl$nlAe3osua%-juEQpHsxFfwaGAuxV90nkc*l zfbaJd^Rgpa=w&wU+l6QB;3SydN>D@u613GDlz7$iGIN$D4Ak|Rwix=|p=e+OI-cqk zwZA~}8pTItw2eEYB`a|vtm0y@OS83lUwnKnKowlSzCzXY`I;ry9p9}}ipQnt)Lk-l zJB;DPA5`)3SrH}Bc6AXYMWT=1!3Vtsy<-ObYYUQ*8qmZ#yTBpsc?te_t^YtQ!%8gG z&|#3*FdP`$m?^}9MV^j!y+&6MKR%^zqnDCE`;c?Y+#~6mV~xMAGxUY>j9|Pbh|ee}6Rb2uZij zMUXgbsH?ZPAi4HjwRgkeW>n-Iy*jk%EW$SFzle~K2_B4~u&^GomdbQnxj*L2acZ*mKEkkFEdYZ$1zXcE`w)TUr2kQvP2s%# zyMB#xqv!n=WAy&0-4%2PGw2&{!!CaQ7WL%a@e#f_i5NLl8|sOX%ff0pB&U%|@2Jd% zt=^G#yjHs~lh~_if{*Hs)%4h~Ie4G7!gtpZH!&z}qf{|G)s@2Sk5&31 zT&66uAdcH)<@PxlWyN~IJ?`T;6QYLg3+Jb!_~cc!)PRT!PrKy#>Pn3t{O+My3A5!?J0+WrbLd-GFrr}H2Dqyd@COYCA zWdH zIqsaga|oFD1it(|dr5H}ZFhZd0OIq&O+|s)kIeNe1-A zUBBKhg(n9q!yd3=SwUij_0R?s*d51Z?TU^YXCdxs$cC05s0D}84HpXbSnj8=wni!p zPj-OIEmA7J3{D=HV}biT7Sc_07eLdH)hOuxP}B2bd6FzzO+rSlNPk{fw#*hN$cKMR zbihr1`lm~@NI#2dEn~OFosjE~@>^|dAG2UKje{In|GuTy%g;9Q0f*P~Z$~MXGTbRq z^RGmsP5c2})%^M+G{_v(Y^d8xxsjBQG^JX}MS=p9= z)d|{YypN)Bi}=+mER#MpDFzt@4hiWSaWZ-jrP!en*mNY$&)nBcHDibdrzJ}KcrIvI|G4w_sXx~w! zON&3(1XDLC^5uEb) z>1DvKzzgV$+}+*PQW^yi-&|P0eT;K_H_qRZ zXvV?oI`UsE5v#jzN!1ELI0L2E`(sJ>R5 zsOFKG1$;`ErrWw7h2nuAy7!Cl+ra>LaLOBkKlg0+zF-uIOO#%j3L;6+^}KU%e%75# z4X4ZTyYUE4rssOx2Pmf7fR)(~&(1sRob>k|l2LEVgxH|%3(r6pqNzW*r52k8mqp&6 zK7`$D3NNW(wcxrtxQ!t6NdlHhXx;MC(}~x)_7ct=5oW2asav)g07>rmd}~ z=l^-^;TuWc1R@(VE!JcV>2kCZ>b9f_y&e0KHFwG2q4nKLPZT9Ll>ikKRs zhnBVc3ul(xl?J7gTIKTtnl)C9ppy3Mv>?sRkx>;6SO?DuD3^ulH7mJdAy z!-tUwOD&{9kQ~l~+GIFYpDhvVLko&s2*s>B)bUYE2tO^eugoNMz`|rIHJgdwCowJY zR&5X;>J2fK^v1eVaF%j%LEu05L1PcLpyyp!K|#Tt#R?Uj`c=G0u!@R`x3@Q()!?c7 z0O|WREK#D&@9ph+f^NP z)gAS%f5-eYiCx;DbfNCjndb3;p-e6;S_;Wl|Z>7DiNLlIR z@ak~~^GhMOKjmrsu0m2?k7TSB2*Jo9jThP*L|)+=|3~ znSO>tTzO}>T*O)dLg##3BbK*S-|nL;73Ttd0t`}kAij`M!$+6>#)|gNLb$j|6{zZ= z_%fv|yTurd?3IWIvq;&m1d^o=LxI8O@8h6CZYZP_b-wjr#W!u=hNKUFDCaZW=&Z!9 zgxzprZx<5#y*rD6+$YFem(xxiDb4cKAw**TH-wIm z)O-?Q9%+YK908ELrPZtZ(q9_)7Z`_VhK(@AoUXrG-&m;m&_OH**IRFmX zlc=!OWtR#gCV5ZH$Wh8XRf}Rz+G=hs4fSQ@!zCl#=ChbFH+!b}eU`FlNnG~V(&-R; z=J(+a2V6bSaif!Uu`0~d4%Z7&)=T}p#UVcdA^d!KV>pOMZcC>lx~$}QY||B{UMdvD zNVHmjVk9ZDlTcl{sw%u|s_VGq5lWy!G@~ec-OPu_N8CR=;_1n{Qm=;*qh#b^!0B{G zO4$wY*C4dt`#p)%rn0>^jNQ&bXU5Qc{a#0sn{55dU;bjznMtr&Z}9frTRc2IBBzAY z`Gj#;;pyoCkc5Bx^PiDY!e9RK7hGNKaXOtaO$lYHk-9z%7V$3vTwU#OdwcB!met|i zY_|CD;T`Vp@3CHQFbpGJUS6V+;Cj8r`D}9ga6F>841aidFei>0!7${El>_A zEBx}yFBr!aRx5Lyy?_5M?n69qdwYvv95G}|b*5u6XOcSnF>+bBeI_^M| zPYQ*U327Lx+ih?@O(^w@kDq?V+YcX*$I-{1aCi3>4__W^kFjpIgL_eU*26MgopQDr zo&5iv4C`gxi~w8^n%rj=9lLaZi{l`P8gL>KdWA&hvc|XoI8Bpvf%k}hekWih9M}|Z zzu#M$xj#%!8Jq3K$fi;v!n)L!<`-iVVJ(wRzMH{&33E-;WKQ_5p^L4x-OTkG!IooNyc9ziTAIiY3GB>q~D zC3-zutJRL|U+eY3C7s#NJ@rAakCyWhdTJ46x+F}$ri1>`W%fq6$3W?vK&g$WBZ_ME z1#=Q$f~Oqw(*m$|so%pei(^F;$Bk&2B0};CwnjyrIIKV^V2#Jf%XI>YH9Z@qFrky+ z84ylpgez7OavlI!2F=G$pYix)cFOT|#A;mO`|tmN+q>J?D>;cbyvz9c?|;YfbjFx7 zpcb_~c)16jStG|9reL;}Es*`h@*EbHX3rOTG3>(D-5#o7U2hVUltpl?q=Ilh@tiPS z7hXDoQI*y017i8)a5eQ_84}A{4cAueJjjWvgQK=%Yp?d@iBhKvUc{w)a_6 zFQ#|fgo@vjQPd4lX&6k+fzUZn+*U@duOj#=Q}8`PSQw41j)t20YZx!i^ju5De>(4x zu+&{&mn(KZVs%>|$Nt?uvOVGJ=(d=URBOeULLOC5yB~%Fa^6Jq;Z)5bLIT!9h9T@+ zpE5LE0mTA&1eW~(+7ik!CvWED!C!VXP%&9xRvNtdkU}(f^Wbx&7GUvPu71wAwpiE$ z{oi|nlRA9%d3pW4Jwe**hGk~!Qr7q1b14v{|4fg4m-dd~|4^#2e@T)yq43XN-$>GL z*RNhnBBmV}8ux&pBB?0~7M)Lda1x`UPA0@E1(pB|`KQ3IZsZz7saE&Hjqu1Kl7v** zX-}c$9FY-rCmtSC11W?cl{x%(FO)7MZ8Hvs6Fz?W8NdAfBMzqtIjwMYwa16=-&usm zFMmhMqd9x3JwFSv_g4s>P!8>N0^(P-x|W~s$eB541(*`QUT?5kt+Cndu^$>}8itIV zEiG)b*?5$vb*X24t(-Id^d~c1tqDxQ`*&{v5uDE_48!12q^pSfczAfg=g*%b9dVi_ zTwPru=N!>DIS+V#c)*xPGp4d&x7}dO2Ef+i4ml-^s}11fZWmqEZCNXBu6B+5 z@T;nO%0;aHQYnBieX|LEz&%DHpoiUrsKJNib66d;se?F@?wBfSE?5ngK2eSnKK}ey zym|K?DX(xY1*>s`o3|hE`22(dOW}pWi*PT9_>KTu8UX!ky#iX2fm9weY`7*Og6ips zA`-^wd78oyWrU8Z*KwPsR>!5P73xk2tJMm(H#Zo^0WU8t-96=OQF|g0bycd>)5<9a z2-a%ncsibtSci$vN;1$kT&t0!b5b)zPXY)UOAKTI%1(+Abo zcn4_n$(n;pLTXMvbl;CgF0?fwXtk)(1VPnga|Q7ZxM=CC0S=vL6W()PB15a9%4@Rh z6)5Qb<<*RiW*jUDwfgD<9K7$PUAieklTI z1FxDYa>_WL3x4_K?;fRpLK;WxuWs?-!@uBqe}%)-6V{tOswULZ9FHV9ps!^{zc$M# zU>b1ZGO*V<{4DUAXy@-KrD&M9-|x-AQY&(@MtnJ2W0>uB1y$fYov_{Q@o)eB?+_9E zn0|Ca!Rnr+llsW_JB=VyHR@`#j-08R3U_wPRh(fjc5fV;ap+}}Sy z(V_;gu6EdrBc5MgupR~o6yq@9&3Fe9OM&0*wh^rjD7M=*w%bkMgT8Aq%gsy^YgyM< zr86v>1+GWtpO4O|+4oG>fQWh^m4ZBEtX2c2Qt|ZkfG=Nu!MpGN1+`cX_5S(}yZuKz zKi*?Nf=IPyAewn%LRYqP3y2!=VEd&Rod8@`&d+X7fHET6o_}gabFG-p-uTK(snFrZ zNY7G=l_K#Bl_<5))lc1QHqkuscs$yevNeww#t{NU<_X8f=acFL|J2nQElp>$X&EyP zDCJmAh0ke*Qgf7v*jiguSa$NvB6>(pM`USnaysNC&keCylW9D^+~56PCs_5UZ$`^ zNVv0zpQ<{!BC#H9fx{pr65^uO$x|SUVOOoK9ErUdkrJE9f{8cOG0VjFm!f*qw;83Y$^r5OZ?9N|e?xR3e6RK&e1o z86XSYdl&I(wv!f~6g zjA3?(vvVnLkn zpYJ(as~qzNKP#%9If)ES8=D6`czs-rXxrpEhYk|EER(1Do=92&SUILRN|4a)Hn+bn zB$sl0`7__cYl-ofzyI33mo@`AjJEgYy5`cjEW<)xjHE6nsIQn;*D&I)b zZ`ZG1G@g=mHVPpnuCywwE{E0$wVt8%425Dk6|9B~K{g{d*=N*4;eqNM(Fj@?z2%+K z3W*Sn?uf|?AKS(kRFB}}Sc* zw$Zs)1i1h5gsS2lX`HK^+JFM3$JU_n#K)Tvr z1^F_LqovZt)i=dLV#K4Wq$zoN zF{432*KwAAXKYLsORcFM5ff|ZMxjMxW^9n~^8A3uhkIPV`CxNd3U>P&Y2a2N(`x4Vnv41B(lSj6cBCtSPo8bJ^*(iOSyp~<2pMbK4)aPmPQZd^6c z)zzX=MZ|@u1Vl1ohWi5u>kwx6((C&*z_26{FA^AfOZ`?>9tfBo~nqD&Ju+by(Oz0|kw-=a)TREv>m z3gG$WXr*4(YkdCnsio?xVsMhzn)Ds;?%jJlKfmDN;U42S;_mJahr>CXa@)-gDG8?O zjO?A{uWzm~E&(55@Y+iI=T`Y=Gm8K(S z)@E59hgg8JLX*p;T0PoO8(HaCp}1pjvmPOG#>3~2c=zrHWU=QN#x?Hl-r;z7alGWl z7dm-}X0+P+8D`48ybx(5d-u#D*6@zyQz%g-rvi@6;W|U zDMzSQoKDt^6{^s3GCKn`_Lqof7=TV!X=h8k*8+n^d=13Y+(Kr@sw#Izt5Mqq2PK~u zQGb*r8Rx0s{{AyQe|`Wk;LV30aeaM4*%u;DI1V!J(OtqyzKQ5i%hI$MXj%;B2(0!TVD-Q4FQ zlrF!+-kVcKoDct;c=m=C%6WC$v&jk7!DWK9eUnT+LK2b;P_fi$6?kOmfSLf65sGZI zW(GtuvNvhsTJel)RiGMaDwXTwB)ZprcBJaFonj5l2O^G7xT$W7fHoT8V z;MQKz`;76so8w034qCpsdkrFC%h`MqZwjIjU{@2Ab}PxpAh5xVs-~yy+4|4T4{+cg z(5cO5CjK{^ZTIykP0u+MzFE0vO@^{;TF6)cA_cW3oK8o)yqL~QgGA{xX3sHN)r=l^ z6s-VxFkMm=wVolV^+c(Xy%ZDI(d=bq83rV%m#L7NqP8*G6m|RHwSBN862C?$+Op2m z*nbPI|JuFdcY!qqOl^<+Bc1a#61CT#OP$ouL401RzdQSeYx57E?DF-EB>i^%>eYj$ znSgZ(Wn_VO?bS1CIiZvZFNbHmsN!b7$B;;J!fVX+B&GqPr1Z)VIMxWjG7=fx?sIW9zH)JRyLtGEF;}onz0DL48COGj*%lo ziq-d1$|K6D;Fq8OhV9Ob_EHMQJYc$Uu1zyCy=^{x9Lt?Gd5;dq9O%niL-Sl$*hyiSC9C(~6 z&PDL{{rA}IuCZEK!=R}eSyyU-jsV06(vzP#Hk+`t{|ocK%s}Y$m1^Zw=PI^q!*-Owga?|FUSwR*t z>8FTD3Fu_}Or|N<7|jtX@TMNtFeKjV>u9>aBd(Pz*ghX}P)(Zj>5Pr+nq#2;T+MY$ z!_CV&!6MdJ0!q0d+?@8AT9H=?dB~lH zAO7$LSNj{JJb1EQ!ujm)b|siVQqbxnuU0EuU*F=d|NDRA;mbX~e{&O9Fl3WD=JUXT z<@)lyT6Ok0rL85l|Dx_Od>wgCNpz%SBoWvQ*sMdwC))mQO|V*41n0gHUe%o@e80&` zi~8&XMXSQ`MFNsSJyl%2-R2f|A1{gYy6usYS#!#dn}vtUKZFoQr;LwRc-jX;T$@G<}$~KO6ql52qZjv z!QlZFqMotk`>8r^puE-BGSI%$#>d*(L-tY$RUnd^E)k0WC9w}*A7B8|78MC11(FBH zcsWXN#kq<=9{`d)8rO>eP?mi~?k?+qE_nsSEX_aL%kBOimu$JEt^Uex0p{OD^%V0t z*9Xgc%|73aVX0r1-`S6=|NH#e;|=&d*Ef>%+x4qgPtpMZJ)A{N$RsVO<%n7i(0YQ_ zGm=)^>_@yj9`N#bkL#P85NAmm(Llkh>NQ6JumU=bP&4+j2_R}oG4Gnyn>H5N> zsf&D{2){$TQ>cVcl%&{f1iPyNNEuZNPSb=MN*e$YL^IMbxM$iz`bo;lLg4iC))OmQ zHPSSJxu9AS7yZ2Vf;(`Cd%(6^^B(WkYp6$$TFuA`)s;0g$Qj%123K24qs)1Q-5-8L zN+fmaYoVgmI_!={HfovNC}<0pU>$fh6r#|YL8#nCI+{Tn1MX0IJ{cL;E2#Ng@LJ9f zU+W{H2=K(mqsp{2gwfmfp6?BrcO?Y?83sUsniBGMi^KChK7afx-o5_;<1k=74%n_Y zR=@Lnz-GwN1zoEd^NgmUky>gEFic~Jpz&(A!#b@|C!6c_YK84)gK-$JySlQ@x{=bD z1B4`aG&5Q{T#$UKo-X6ySBhn>_e#{kfH*K$MG%h2^BSK0d?Og+B`er zur=q{UK?vmQpo<*h9%vYq){10q!{T{eczE_jk;p5lHoe2 zMVG)z|N8H_Xk#^itqy$s*~$^92dJK*<&30?o81~uPfz&r$DvjRc*#lt179 z7KEITBxCZ1G}XHu*V+K_C3zTo6gBE5a^J-IVZQHv9r!jQYO~&8x7%SHte)C1WNg-J zl+g%FI$t)M4X*cloX%$q zv-k+30SXU()lM<_9%kSL7f`zSbAuCA=P9CS=cvgT-x;xgxLd^+QNIzg-VNEQhv<>_>8 z;J+J=s$#WT;cB;odPYJLK^{kJ)*EcM8*IC#K|{`fh-WT1`U#o&bs4}f)LNjqIR>Rk zB`27<_W{sp9oVOl0k-VwsfxZg+(-}7L^X6C37e>8%qX&$5&=6(`v+_vgHc_M^7<&q z3p$CzA1$$(ydW~pnI`lf$B*JObte$&PKWtSP$4WUsA%~hBldy9A5@0%KcMywx1Y<$UPux*)k-fBAT$m8ZU{- z6ARZCpVMMxt^8}0!bGWe1*!?v=TWOqx;SB;5({qF?~+i&up3067@$c|)Ot@C_H|NK z+<~W_eWoO>Dzqpx+ZxtZG}WFfJIUvBE8GKtbNiaW#4i93d4iaz^toXikrCh|w0R#5 z@g~vG&+#RiuA32aVXw74-3UUzhcp6~cu8Ouw<^mov}dzAwDuf*#uGCDtgM5!`}-%^ zWUt8?1SW3dX}Hdu4=$r>(^W1#(cl{Qi`8yQ&A;NM5Q_MYOoML;!G1JzS~Y8dV{++cUZ4RJl}tT ztjDP3dOllW{BanO07(U_>C?&=2oS08fflqyCYLhB{3u#gBfx63iYN*l z1zfXGumlp#NS&wM(wI%LN5AF-2t_ngp71l)#?5E2t>jU9z6p8-|C-2wkMojot^x9Z z6x@aV>mK`s(Z@a8z|=g7rQdg#2-NCnXN(Le)!MYoj4?kiRe)5{5ZJ4W=cGApmcXMg zJF%?IBi*@*@%8lz#bkkjZ$VEKeGOE_>oCVbtiMP3^+3b+O`bWu{@F_eQNPj59t!0N zq9gykzoi)Cr6U-S2M^6a+@`ePB=9gxp>~?oNE^?(KHFSrlm7Gxi*%GEz<>lDSB0u~zb;rf0jgz&vNFR@`eqpiR1xzLe* z-yq>~+^d}#-W!1Ch~}gIsFil3KytQhL=_Y@k`y^%vM&JuPpvoHn-xfIdlm(h_03_p z3J?qy<`1ZN9qt^_=i+wl(yr^}0asDoxb+O>usQ*W8tqMXiIM#-qj;tz7)+9lHqK5h zhR9Gf0u=B-Cq}dTZquf4ZO*B;{oE$Ul!njy&$PW`kJ;pQ1TpaY!Fr%B$K%;O@J8dV zevjTF*XAIW7JOyjD=}`q7Td5BqP_D;wdn+YVK{B7)l)wnkH|S=97mK|z-E_$r@S5} z^`EaG2Osy2X9yhc^MeeC*WAXu$u;7Pw8mb*9BcIQ{FNM*HkL~~LvQn3vdNYy=UkHY7s=NJrfsqUvwQY7Er2M~gbUyETdr>;>9^}2UKAd&sqIw* zAFwogkqIeTT1tXIOTzK+fIN(Nc|PFjX@l$Q8#od-rPUEJlpZ33zn&}tP|O%r07(=z z(V&IbL$w-*lOC*?cyiICo_J8%0lNV_6E-kqV-m z=%_bZS(A<3d0Erb6qq380mFKQ)thy6;T5s&&-?ui#ssXA)m~d~w}5($IBAhD(#@Hr zHT7gcli&TmDBYX_Evk?P0ME^Qt%0aj<_4_z{*06pT>{nyPhuZ*Ma6qy8%5s3fP|mT zw$4TdrC22zos6aqqN3YRO9O4We_tDI_G~tY&THAN^`%Ik`Tp%9bh^(04Sd8t^YREO zC65}g_fi&ESqbZQS_v-W;TmA@CF^Ygkm0=qAo>ywB*}RX@%zRz2IAyv?fYJx50{0M z1Fi&S_#ym?j zpfCvKQJo=*6>M%Jz$}tBNHWDMBCN*_>X;|7mRwrusir!NJR~B}+5P%GS4wjNYD5UN z{m1*x$Ww^x&t9Hurvp0-=DLyJ;iH&68!(sQ#2!_REK9jz%rcoHRFv5eF4$u%6qw!6 z7IV-JsCFeqI)|Sdx=TIBx$6nvSRd3^a|<+mNr#**y*ZV#f*)A0f8)e85ICpsK-I!gTwi<;tkFJkcLlxq<-qyO* zim4X7d-o1`81VS;gjy;F5PPySIk5pkZjpLU9 z(-wv@$$mvuWFH5yWJbe|oZkw2AJf*WWKC02EP3 z%1G)?2@w>ZXj|i+NFrWpglF#3%Gnzu@%a_4VJg92XK#VfEo6r`GY(y3ckRoXNXjN# zE7SCe#rw(ZuVj0W_M_KBH4@!ch)+cde!r^A{pNEElF;*#X8*{3c*T`)+}+PHr~FwY`i%%Yz(v}g{XN$= zlJwj4t5?5C1vzT&Bz42C7650UPGA$J1jTlhG3FJfQn4O04lnoE@Ap`*Z*YoK)h8L&;)uYXfahS03o`EZ(MnM(rfYx5qT2b}O_hsZe?3_UANP?9tPIs(MK%Qn@FT$meE zp+M0oaK%L-$#M42*8hF}tbMee0ggT*Wp?lG1-qpnWuk~KRSa$Klv;tV=2a;LCnrRw zX~Ow@@-)6ic2N;*HXE$h>-hf7W`iMT4C9Dl9Kn>E)i6M^0j;SNNFFhcYfL#Kp``>Q zvHpd%u!E`zZ-sX`?TtA%jJ$5Vp9=(`n3%ev24Yeu-jFP6y>24dAWggV_5~x!!Qbs4>CTMR_%(y!b-4$0dKk4A2wV7<;b9A2>9?lG?KP}pshGO%_euEM}m zROf1PFF9xyu}lFHZ}ys*VkZB@1GZ9tb*2o*zW1fB0b-@4#;FE))>vzE2AU2OH*{$p zSbgZ_ndpBe$@jI0u2*LYoi19)T)5d8_ZFV>21@7h0?klXOTS~5FAYL-p81-4m)=OE zpx#%`lOGeAk2~x$Kk!0f$a~beldNwJ#5v}#mU1m2qs13m(!Aa?&_x7xbIP+woia^R z{Lb|EB-Z>xL?U`~95QketOZz&E35hGk)D#Q?qu~QS$Q0>T5plZ5rY&fIneFf{`vZ7 zi2}zU9`V&@2V?+}%_&*DCU}yJlt};*W4KJn$!jb+IpSG0Mp#tuB+c{Sc*-WrjUmL` zqLbnMzU=E$_E$U`b%o=z>cmi#y=xh~v8OY0Aj77Q)_xuMvptz4BWI12Q2V-uJ=l;- z1jyO;MJW?Xxr}!-jC{=Io_lGjclvWi-D}&tx_&P>PbZAxk=`!Hn(?ldHN|HWe@?-C za$F(s2oXE-tW0GxQnJIS{rLEtGow};0s6|&?Jy`Y=B2BBhDLt{F}I2t^#AO|`oIvG z$(aNX#?T4YqaB9FRG>)6&c?rM*5z4t~wMozXeK2DY*S>UcK4U5dQ z=t5QXW^?AGBN4&|f1v&mSnjUR7ld_a#qZOWmGzO0@Q_wB9>j>Lb5^%=DPsC=f4#?M zx4~&T<9sf5{%eU;XX-HZFN_s%y=SY`vI)&emmB#9gp&*~EUT%Jf<|tdUbW|Qa#PKT zV&oe35}zqsEl~gkT>~6jB|rqlZ3#^hWvYfD!_6L#Rn>5U zM<9WpFFQ$o_9cNBxV?uYIbz{RXeDdG9o{iT7Oo@%(*&i41>5LG)po{pi^% z>eU3WM^Q+Ecom)r6GV)_(mFVxw@$@C!D<|kQbkURsZ<;eFF?M6BX(==IkWxygmz3wL#>5MNgFEMt0 zC+mTY!-$j39-zov78zoa=nI8j@ zOzXb@yp}}da<9JLvks^V>kM}wzgC}@8US3>BGauy^Xrs!>3&!mlKuGlXJ^TY_DAAqn;b+$f#l5m_1942R9aUP7wLIR`CWB zfa#ymMSiO&Szvo*^oDtl_YW=u5>$&3jtdaogY{-W>#O~|JWExpM`z*{c;f>UCbK2)Sbz*L-n!UpN#Vavx)h1&U4WRcm7D>## zl6AF)?k%ODc7&&@x>N0pVHj{epK&}MPMOcWTA2!xuC?HF zHXK!8du_A3GULBa7_?==)b82)y#Xks+L-}U4WVJwGhkZ8^aS8WyH6e+201rbKo?n% zUSaIfm~T!Nii;2$KF@vh>ZLupOifQ+)LmOyk8*(%nm|P0!JBW0|I9Tu+qBN)mO1yd zn*(uzJ$3VmW{h`xt;tE5?SuZ=mNiE?-z=lET(cRzaF`qN!ifZ}rR{x!gzhY;C`42D zn#7Nh2@)T9txqGGw2O=lS+H>O_df?Yx{xMIOc@6H;+o@5!xJeQ9{HaA9VDp;9R!LD z@yN$&ndfRmkwx+fSn{O$^JFyHrx3gx4%iIWW~;cKSNI;nfQWvKEC`>EAXv;f;g5)x zu`(x{V`Zd~h=}tRKgJTem0>zbi1Rup1#u*FM)aM}XGjv<+}z;&`~^?X&)D2tqhdm) ztx{dCIzF968vEJEDWR5vQb_}8U?YLacMi61Y-XbqC+Wm{=bFvJaTWn250GJvlms~^ zq#+~80LXxIIeRIPjN*MGipw9B95o>UBSHn#_arU>s{@|AZfc6mDX**_&svGw#qB`H zcijK#B@9#n@e&b+Lk$~Kn25`+UZ=%SC<}Zp8YXNqwYMK_-ym=kc)Ge{n5EAMH2KzQ zU%JBygjyU|!#4IZ2{yh&dbT!4agbb&np|cW6mF4;{rZO-(eAacVBh!|aL03}`)h6W zKf5`VkdGu7mn58hc{t|;-RI!z?=I>($30xT^ZAUImxDP}vl08@qe`7E<6}{24leGm zUWal4+iG^t7CMvilsXr_8veZscU&UI8P6`A{_@A1Wdp^!)fu)6Cm7~>yUk_yEV5if zAFT>RENG2uzT^hx>qDpLqMwWE?6v-LOER_To~BcSTX=i^%>SgsDGP0*c zyXZhtf#?~62^oWto2epsg*R2EN>z-br8rhinCcm;VT;7>a6kxf(-qQzLGd6ykCIC% z1cV8*+NB2&pf=a+0^2mz@`9C5XdIFZ;wFI)4KNxDXGuTs8ehctRBk|JrToO!7&76~L=6MoG)TNsd zJN~Rwnc}snOIH*KPUjO2hXdf=yOVc+SHLWH{`36z71_KTQ)hGcfObh7|K5w_RU2PI zmH|*Ng#kZL3 zzQx+aye#&-dUR(`d`{DZ)9HjVO_)w+Ga$60PK@4br6+RE*ladftyYm@Cn8v_EE1I8 zopTO(*>sBQ7;Vp}9{ptv!z$7+m@F+d3?F8TY_^`+a6ADJ=;Ym|FUSc_p}3K>B+GGjlIzT%jq$e|}Z+VrjM9-zY%{k-M^ozXu%yORXd>TQ{NT-yHI6Y4j z)^OS7gap&=72=MGW=Io9M08VF&E5X&#wucsQG30z#44Bc(AQ*B|M#{om-g#&A5*qd zXiKcuKXVC^MMbht0Mote1W19E19Qh*O-O0PN)jeyh)hUQP%@BKYm_pel!BZrID*3s z7|l$r$eYzhh50`Tt%0P71feS8^%kW&2X@n$tc!WlhF_=yQ~bU>2lLO_pluKDwp+Y? z`xgKA=b!N9;Rzq!+(HXl)dsOlJ<3fwb4(|w)l5|0T4Rd?EUBS z3CGhBDX$17y5Fj@G7UThsKt)$hntLH0IDU@=HDzK=g%^o$&&P3ekZeEm*csF6~0D}axKMc{pSQnGT|Edr>}1$ z>9^}wuiof!|D-FaGoWVxCs-G}Z)`nqaz!kuk6_sW$!OucbUhV1BrJu)QQGUI`oF^Y=#U+~}0bGq+ic4udwT#A%UQUqweC4+_m3J@R)HvCsxuqct>S~OQ&(J&y#U z4O&)1w;L3)ktZ8PB1PY~u(#(>H{5ER5q_TIf{a3O9%qdAM92)4i*YjDL=f$<;S_D0bfdKNx+ICB=cX3L%P4GRBGtYUR({uAx)xofw z{~>|cd2V^F=WCwp*>wh*{#!57fk^RnGujm>R4fe;C|)~mqM;&KvAU93u*d~iuOT0V z=?1P$5OkXH0N!i@5xphpzf>6mtUZg?qGqy*0`>9^3bcJVXSG&?sYPsjs-bjRokojD zlGcnyuY$6!c)D%a_8l)S7mGYdhOXH`75fGm_J-$$#-vy;mB?1$YjYh!U~=*)dWHk! zVBq5C^0|1fcIp{Tp30@53sa19L!IWG*-I(dYem~Oi1YlX+YJv752(9E8gJW%ecw>Z z5`QUMM_@%jJse-4zdSE3V4|E!sPuE0y1AopC(NvBvFOv3O2d5^+aQZI<#X z5=syEXi$i}tcmKZtR#A!_(&ed{Ca*rJC@HBtMuvNd(wJSNOidYDp8p8Y(w=YH;I@t^*m z@8Rv^X3>|9ZChc+hRuT*GDqFzCXgZpMHN;pl;f~+9@R^ASSFsQ$pcu{70YtL~oTPy(3~2yRyd;3@6}jChwno68HCrwdQkQwnh8Umm zAkg?+1#r1s@pOB_wr{vD)@5$Nb4&tgtpCXGg+av zwQnfxXxPm{jA`hz0am0$qob(F=24&fwxMpD6^r+@MF5uST@Cn@vfz5X0IGQP@+Drs zer@w_)#^Sj3rxs*L3PCd*hG5NE9blKy8$@|5m_jQP;lTn8wAg4U^Xme`kp`A>z|I#I5WP` zprg`_2s9obfr00QuC34P3>eScFgFKF>YzcIrM%erO?p^4?%mn5XRw^tB7crNB1dPF zX!H5a=YLkH&c<=35a;Lqwt0 zSgEv7*$|| za=l`!))YWqSmO>;OpbdpE5IjM`gk^yGDaRT8$C1q53~=B=nK9-KPRW&^C$1YXR-Mh zYkr>9P$f@i+I#-jY6Y~R)`r{D6E-)9vU@wn%`>sCD_*^Nh3oZdazQn+P%JBEvBn_j zU(AO_40I=7=L?Bn+bb|dk;*m#3yCYS3ZBnSJ1loo(pnpx8y{gBe^V;4JxZs`EA0nK zy3suIkk0qpAj`if4;YPpi0AXOXBgy+ug}JSGkSd&Z=C<0r}tmyYKV&~C_Z83uSXq{Zri^&o++KnqwBfkqdOX~c8T zjxFXn5*N9MOwF>6_|*2;M!=u%zS4~km!|i1I88CfpF*GQ(SkIFG!J&L$bFICm0P_w zZLQ|0wnko-eqXepl?7#4QT?nH^yomK>n^m2*n07Id#eIHv(9J8uLKt2eqp4WkmbNo zXLQCT{QV!oHwxhCcEh*7{cU{w$=C4a&F9w8C>qL$qf>-@WLX&X$X>e?=)P%5p)uT(Gzi^m4smSyrnJTD)ecdgN(SY`Q_!%DFjGwsd+0niOmH zySH!{mD22lXb(t%0L{m?sM1y%=TtSFA-^{={le|eO>oW*RY^}RGf1$A1m&-FTCGXUK{BEL^3 z4~jbEu}5OTOy!70XMQ`sMt*)M=LXXas3XQ6rtkM!)9Fk)79*x4U0ASmm#2Mv<}4M~ z8dVPv6RSJ^`1BY(3bL$?X9|Wopl3RE*748I|CzqyFgLVSN%DhxO03y`9(6Wj|1#3~ z#5)F^BtIvudB&8yZ~uO><8XARvPD8i@0k$ir2+ay-44D#{3(O<3EXmmF}}$4!ASby zdgm2~D|ySTIJI@NFY0Df?cTBsN(I)n(>my_K)D21Y+l!ebu&rAO%+R0?)u@T`5^&? zFj_ei6EbxNLn6^Bk>AP8B8oJFjIcAN)>vD{nrM`D!R@wT-!|a>jtdkXEc@3DTqa;T z6MUBG4d3tMtIgBjVL{ zh4{$lKPq6eGIS6k;vKhB2>|L}6Ij-mE`jBcn z(cui5N|6zCOlK&6b~e8D&zaDj&*Ch!^SqB|lVkIJ>6{9xg0`CxM?DX;_$N$}>Pp~z ze$SjIvmqhI>4=U-r^EZ{{?F~l%y;JB&x{zydyppi{rA^qjYnI}MaE|<0Bsu33URkS4Nveyz^ARdL%*|;l5U|r~j3c(`mSe@2kD)O%!U;@`8uC+# zrr^*p3Ba3WjORETGx_@C(-R&a9&o$eV!XRM*lxEQE~{m2JUl$u-njC5xm>NT^t$5i z?hbc%cTo>CM?OUdaS`05^=N9fNDGpD$H*5TMkk>Rrgh@EkN-O;kBo_R4QxZjfLMSL zLZw)=gr+sRZ8uwAZ!D;VrD{g3z*J#toN08@S{)jE4G}HAU)&?E(;1x%vQ=hTG+r5B zobm3NpHgEvdlhJ8GYFRfeVo3l|lE1@P&#`}$m z;w0B5d95&C5DoIZoK2^nec!|BYsPkUngBUw=fU1gYu<}daX!lCfgY-w$d6jq2qVP& zUAtp!?a8HKAV?;jxR))n8+DS&S9LTjyze#WD{vZ;9i>z_B8qbvQSc(rlAJ*mP$^I> zXzt*yMXk0oi=K~+!PZjf(6i~VY)VrMsr7K@FH41$kVS4H&$s}@yK*RDG~-mRGI9EV zgCJ--@bOnZ!GHG)zlgv1&;JSA-f+KM-3cY(%!AnYnj(z*Tdj_7+(IJ->*b2FELhen zuGbeR>jleY#j>o%!^&do=nnZ!6`OjdnYC_5E)4^@godXmUUL^#H&y}20+p@Pk1p;+ zkN_qMg{XQ%MmjNCV3vIKa~;IfYq~n0HNK1(Rdb$Cz#&>3Gk8sJNMuLaGx!_~=O5a! z_fhXNz))iEovwY1v0nUc@E!FU#XcSK10y-K=1DH(ebbo^e#Ox<8n0>M$;4sQQD(#2 zh+~Pjpd($M@52!TXPGs=KjO1dcd)%Te!}ngv%rYL9<0JD3P3S=p*bSi<-TY{IkIfi zwrzO(_ANvNcXxLqCc`-Qnb&4spXFlyJ>qNaR%fLr1#>D0Y_uBxXzX&s!|HYhh z*@1~!Rv7qaZM1A88I;uYoFRP@T?x2(y1T04cDwbzTf^qHLHB(#&+fisDJ9b3scVe{uGgy-h8Mx=d%^u1E$t})6bDq|QE~(q z%QB|YcELItJUXp&-A1J}f0ow(j7uRR8i2RDG_fcqwP*qWi${LL&k>_WAqE^MXf*BH znKCAV0KR!WvSK|8;=J$qexs7tulaQ~BB^)Tm($BkJGhhf%)v_zR^%B>vI~C|qYpDBdE}o-&`YlqG=W40>DhaeAaC>)6#=vE4S*RwKKBm$`uH*If6G*djZG;NCK~9?c{3EK+wNHu7ytZa&QUb$7H*6Ie5Zjd1O2?bY)Mf!S$5e6+} z2Kil{`?%NYPLXb8uw@dh$wqnt`JL03ZNKL_t)?T9xHz`Ajt?T8 zc3iC<=__6Dz^FI$;17XRF4-~IBL6hnwK10kSY*LcEFE1H_=R8iMf~8e{~B)}Z@7DX zhZ=mzoI|#2RwAo4tDU`G?oie%?q6CziRE&K)tjLjff>Kst71n3o1#N|(@z~}LA-W5 zTvu~k-&l)U%mAqkmOE>kRv@U_0%sLjpjwkr(gJgYSf4cKe~1WX`@1-Q4H|`v4iJ~! zRu-i?D>2@k%hFJ942Lbc5jOMMkk`@!Y%&3tQbMK?gP^rRuL<5nUI`2IXvNn~?D^D{ zl-X&2+H})nEXtynel^& zKo;(aohiC>vjM!z7~iYJphP74rMzn|W*zN0Jz~a~T|RcK-CD;{fF9_9_W_Lmmylbt z&Wqu*BxLj3cv%dl+mkCOhP8j+>w}T>!}ZR~goNdRmD12^L)$l$Rt>C+GYl8N*;!%(05zi>6~Uzx?DhG>H#5il`YZ%O(S~)HEoB+f$!ScxTrN?I?RL9` z(#eb8skP$i=?VMpU2{_u=+o0vM1j6|@dE3z;PLToq~p=(dUsv%^8Oz8FJ9o~ix*aJ zFFM7qU8ty{EDJ7PmqlD@WfUx*--*Iw$2_W0n|gX}XL_Xw78C=Qs-4FZz=MLW8XzhD zj{nX&T?F^78LbsH!;013Y@iZNFjHI!?}iT(cCA*A1W>Do*Bso5)fCiaF@q?MJQJ#b3&@0+RNz1pJyKn|LX(AWzJE@2 z$>XuH6P#!OV}YWz9m@6db|-H7JDmL)9ApqV8zW}ELW4v0PG?%k*O_7M4A|t~&wxu- z_Q(Awr_cQ&SETVt!_t7g0{d-;cKMA&FW3I8lPz_S~^5u`?%~CyGJV5k^y7fy)`hpMMO~d9gj~>mXfA| z*2bo0c@Ji#VK!dP-{Jdn^E`gGxD!lOqb@Y%Mn0pe=2Y9fao)b~=G;mt@ehxWSW3bD zix+r$d<6Xd>#|ssEr7f06)#@Az{g+yvNcU=ip3pim#Z24_ub}y|Ke)$L1+lIlzYIV z;M)#H-HMc`&1nB?7NI2_s2f@bQb(nL1awexorkkvPc%g&MLBXES(|%a^UN#fvnI{> zYEebocC-d8t6&#kDGM&^ok=?9X$u?0$jC={?|DpF_KL{hOqrFAGdz-cyBV`>t#V11 zt_+VxfH^YMf_IL5aHg+3KGmaAHmBYJJz{oFW6W|@wE{XCtn)MSch2P2ynifJb7mNr z=f`_i*J2f}Fh(tMKZk*nT;@VicXt#oi^-J+?`Yl?-r@}%jn8=$jyhgJzq$jyHy{~h zjC%AY`K6)=og|sNA%55CHQpy))x;SmoC7U@cV`c*<&KP>R-p}5!@x^S|H z%%hRMZA4yk}a`>YIlU+o}TcyEO;R=P%gzv6gj;e(g->dY8VywG%&6#-pecB_}cFHL`^sq_m z3Q+~5mhiBt zGAgGFS$KqH@%1u5Kt^odV^NE6JOI#QAfRgR(%9U)Y-{T9NvXJj=&IxQlt}v}kC=S5z zOjB+X7!ia*a|Tk{uy=|a9Y#9R_5^LaD_RuF2m}Aj+va_L4s47Y4U5+2`k)&a&b+%b zIGfX~XRtHS&h+egoVkP2th;Zfp`*MuS$g zX0pqoWGXuNKd<4N_l$-qes%`d{JpvJigHQSjGd2&Vl(L-}7Ku-BjYJje z^@11o_htZn`4XRe@(G@vp3rJFr{20)X%wUgLa{byd0yMLgHdxfUN^?W0d`ridQ&A4 zU(cwd#|n*xkfZh>9iZSEuqLIAzbmtb7q)f_hnLZyeTq8MAm?N3qfs=UyXR8u09U$T znH!NZsixE{mrJrLU>HlLVRKd-l`zuI%)|Q;%u!B9C3Tip=7Smy=k|J6QfHZ!KOai{ zfZ2|zdHuV-mHz$gP|S1f4kjQgK7*k@%r>)Ar#T+%#^Ah9`B{0*N)Ky(R+i6u-kSC_ zNmo|YZ==ZavSVm-@Kz5ppfRtPf&iGZ>xL6(Z!%I8XjU%A)=`6pc7B*0n+RMLPPj-n z?uL_CV(mYSH_|Xc3N67&^ZMBD#K(%%%Gr#8`6$2drE2;KSn{d@x?x!u#l$`9SU^2W zQHnq+jdk9PNK6M9@F$3`jra73G2cs7%Zi9|PNQ}*u=;tZs?jGQ)`xP&Ws0~=k=A(< zuQBk$ubIbq86`+@$GM%AU-~D%j88xP5sL1(zgY96b-iG@SRf0707MED1$%3r8D%Af zs&+k2hqI+nH&k{r5)B;-q`kT7MICGf#KDhCid#(U*l4&(#_!+D5 z{Mp)hDHrME_EFhvll%>GL^_|oEYfHwr?~2zd`? z-RMkL$nyX+MPz%5zjn+Z6E?E%(pe|HYkfNu?CNOBoE4;8zhUTj5*IXuVzZ;YBXlrqNoF`LZkr!*yM`LQZ3b8N{N)Q z*mG9|78=gfAwU4PzCR37C9P3_j_KB2K&z+pmtxj^b>M|&QPlf(gNQ<45ge;5SeG@) zJ&p9SOs8|CG|*F}XW-KsVHfG20;Jz}j&{oTnL!p6p$t^)d-S^Z2stW@GeF}rvO(^- z`gXArgA#kLRQB4iBVft@a%$#0o|w0TKpNW>{rmZzyuvfHZmSqdO zzVG{vB7&E%Ug5H?W;FG+5GY=FO=+IxbzN~~eQB}UbL+ZT6pyp?7kBp{g0-k{qZy_j zvleVu#sx?`iuK(Bn5zSB(js7)0dQRii9RS(gz5FB%0s(T%g%y*EMz*Bni8g>kl~EB z;y&cF%gDe?PuWvP*ST<)DVoF6r=U^;&sAL)a<{W(6vDA&v@GH;*h z>FoEJ_hr7$NTW=T2i`1QaX#LE97E>!wKZ?lmcJv1vDtfe{>|`N2Du_Aj!~$f38Ep5 zGuA`&@Gy^VSaBFRJlp7?JGF=P01z-Ijrq(NF!Cb+p8j4G-qD)|B6Z^&o7lKvk8~bu zq=Ai;KPTfx$L?GT>FLqLLopvZ$Xw}7a?EHLk)R2$ zn*2jVU;zjNc28MF@WR0Buq|)N83@0t;q8JZo{GOL_}VwVY1td#K3RSBy|pmrht4PB z#xaXZG@eNd1@)!07jSxIea_-Wqr9!EQJ3`~i`C1|=txU+7BRTR_T6R}O@nN~{oMI8 z70}`t2Otm6^derzlvu%MCE^)b_KYT`&)DhnJ)kW0)u2o+g{9HN8r8CTJhTSFzBjkYXe9Wgb@!xQm*K61A3<}-IpwS?IV~<454dJ_e4ISh^4QK7K;KJj5)@Z4O}rregVn_@WS6s(F@XR3#Bq@ z(D|bWAO{QrA|KXc`WJ<)-#0N<@xnaC89a}5z+tsdGo?l0wIy9J)@H`d+#raIfWZ9m z@i9Ol)8Z*Ow`~JU0zBPrr_n#Eio5F-m&*mWrzfimdUxkhNP_$OdwlfKM<~mJ2QM65 ziZx4GS))FWESAA*X=`PSl7PhP^?3?sc%DcQi3SKHgPapsZpylQI;?*b!50crUzb+V_KE_g zaGSzXmbD8TN0(CiTFpx1SsG^k$+h6`%Ke%YN`5{Io7q5?!Pfje{>;Xm`4O{_?gDq5 z&sntRs6?Kp)$_fq^yhn@0YU<`QkX^qL@tagf;nP5e}CpFGeF_*0HP7itUSY&Y({Yv zabq`-_DMYjX7u0vJ9Yw-#=4Av}v3p0%96`=WE`F<~5n^ z{-?u!=VdF{bhuk8yW*hsVc9>qzf1h1mspY|FCPT=wojq)~>R zHKRpSF10ydho_B$beA1wrrfHc^I%PUlypM{0fMD4%Yy?7G8bXRgz-0t`*+E%g;qAC8A}roEZ7y zIgg!xc3!8!M`uMb^X8dn&Sz&<Q-!?udX1CJe54TM+hSJv9)e+ zw{i3_@#owm&DP~O-g&I!>$8mPcq)1-NvC7-p|NBQ<(3)VEhB|E#(76HIO5u{<8m_u zxlH+|4OSObMyGC9Qf)rYH39H*y>{sP zU*ZPw2GQN-DdG|2dH>9@*&5xMKBTfhV|!f z;*^n=t$S9`ewICy-SF~X*&rAz=(uj9p~dBg@Eo{IgX=7{)^JcQOUB^cz-4RY#^dl= z^Ii=i3r=~;^mmpEVJLJg0+*#dfV5-%JdPL}wK^e|$=J7(w#nse^hz_NY(cY(Ixo2= z(YJ(r-1x;2Ur&719Rx^p!7UI;ji1T$`CZm#wFLp4sN}DMuHkz(V*nfDQC1m0ckJR$ zi2ZiM!^1;wlvs-MaR2@@dzja4kV9!agYHlS>#}-dzlPS>4D->A@``=ivDb=k{mi$p zE^9cd?O6IDg&gjk^)S+P(07&(!5YMAF0D`MP|tbC9{WeEq!f9Xq@FAqGAqlW9@5br zmCklThC?vWLSO@a_@}%+7)d`|@4nR7rWwmBpidArKqg8bk%M~)GLD022W5qn6@r2$ zV&UlMLTCV^aFCFJxg_y8MU???FxouAi@q2gID_*~P z6*b`QuGe8r3>+w4dg?su@tCp0L8=RtHmz4zbe*A~E2Mz?oqhcbVA5OZ%uoRuV2L0Z z`BEJ400=L!fnOLCg9NZr?Tr_h&fjaXj)FG|O$YP#6yjnA)d1nrjbQ9duYfCDwvRc2 zlfbb#&6FI0LS>>U7OzdUKRtOGlohs@#X1pdt(M}`F?7s<-JM&r+HN#(*uF2rID)ae z{0J{8bm(F%MV@VL(7{g^cBjf^k{lF7kOfS!>40veAFd(Mb_5%8Xq5iG<*=SlLRqwcdVRS=V)lQvaeC&y}&M9fC)Q zZtg>K2U}V@JIjm~FiB8k1uN~ zAD1mAD_ig^BqfUUC}RA(l!8_jfAcqgi~s)TzJ*1b)gsif%*wWHQA?Vc1(dJbZNs{* zc=_@rR28eA7dF_VvEy>N;G>T|ihEu?k>#M2b;DU#Y~XcEEs7GQKw86`4$kq;&H7q1K4`Mh zjb%x$9B4TBHXu?!ds0?*&dyUPpyV&AF&5PZugQSD?&iqDk!R#RYpvmSyJ20|1C|&J zSD7!0VKzpC=5sSgIOcU5zklL@NxUY@hqJ%qcu3+!H0r1s7;OK$<16oZKEtDNxSDb54E zJG;@9K)nvFs%MOZZs$P|J}>Vd@3hS`!7>DJTtM0g@z-T1=MDsa1td~sslzmwGtuU3 zud!ik@MIm&giWydcU{(s&yQzGJ@`d{B9XvA|9a}@-iD@G-=;wUaF*^NBM&dZf7{>F1zy1M!_`|=&Pk!<_ z-oAZ8-4zcH5BTh}&%*XVJ?x+V^WVj<|N3vBR^qhoOgz&+<}q0My7O*Hw8i~Or3Hf~ z*YgbzG0W03@rD_3Wfs~8Y$3XMwnKN%TfnoB}W^gq#6^Pff zT*63b0U;fgU@$~cv5o?^WBt@#JMid2`YRsTI_QIJ*Yt2(m-K(0xG1o5k zrl+$B)Bq&NP?lhLLZMD@nbU(B!A^;S{|CbZfwHis835@D1lNeg&H24kgOPSnWXw)e zYU!x7aL+;*0nW@3&z_lRzCS>L&-+?bSb=pj+-n8aUJG$?PcC7V!01ZcV6aD+KVtoR zG^v=f!-z=#e_2Yb`Pq1xl7CFg$;U*7*Q5Cp1&!0i5UonbL0Qs1WChfqZOE|+P{ews zG0k(&U?hVOQ*7&C#J1OIbk$HU`pEho+jm-z*zngIfl4ym`qcaQf_5YXe~*qmDV`33 z09P>tpyyh>4pLwHIh}tpR%cqB)+?`1-upa{{QclJUh|6UmuY7()|6tkBc)(Tk?IzW=@CJcA%Lu3s=~pu3q2O0MIM}WGD3lKE}gKSm4&hMcDYy=^G`qh6i<>fF{& ze6$qo)F>%Oy633Q>-CCPuU_MNx!_A*`Vwy222sWJa>3_yNC*Ms8);6@#zJAg4aW;=1|S7`W1MhE}T9AMc%P-0$aC7P1h_nMW%vK5AE z9~ZygWOSlXE;0?-6kZAKIHKb?HXv%ptMgDP{oDr)7BAl+V?EO^dKsCxaWinJjmMg@ zj^!p609DkCDMf&)fLuWb4x|_c)^5a{@eYj#yl)r@Vqct}_+Y5yYx;XIv_QR@t2_CT zB77C#6GUnBN?3&B5--s}oXxRuUq>WM9ZU z>QjMLxHe!+bkK<1yP?S9d!VkLDOiR?(fNEQ5jTF4o)i`Z>`vdlHWD;o_}Q{iEZZZ< z*X_!RsACEqStHVJJf!UF5%0Eiwjw< zgll=J7@w}SWAaXW8h?Y0q(MIG4T2S5`2+xitPD9bU``C5n{jiT^DsIhnr=NkK3E<0 za_@62Ly!;Ue8?N;6_HiLu_YXu*W|}P{tVy!?tj1!fB1LUciYIUAM)O{R{X&q{2@O2 z=*#%WKmU(VTXlM+?C2PaKj)0V!`%H{zE?5;03ZNKL_t)LghfKrXX3s7v$A4u#x}0Y z87q__dfUd8bsllKhm`5i9XB>6F-IYr#7)?qSYpI*UtGR?Fp_?_{(;Mg*XoyTo-${Q ziFIj&>86Q!+CeNRQx2&{z}c~x-8+p$02kO|O0_fL#m}zf0>2?V z;GiH0dIzt;DEu|38!&iim32`~8C<>L(rvFEjnGiH-Hc$an2JY3?%RgfAAJd5{p1t0 z*6`V9p8-wr$ydJ`jT-JQ7f4wmbrGswtInfzP{AVi+Hyf@TQUMu^*U03MxQ;f$y6QUbzw6a@fujO)w(*Diw01=TwVa>g60YpYm#zI z*>E7zBEpL)LOIIGhRb=3HA}OBF&n|Ng2?@&GRb}AeBfsY@!cF1Vjs12K?1j$=3@~T zGy>$c&c=*vn9FlGGfd@mQteTZH2NKkCj?Z(8IC*kXCdJX)qyqiV^2QebCph?9K&D) zKw1-zv?xx)tnnilK}KKSV?+a$r13MOfX`#eKhLgx-z|bpPR2g1e*i#+zd4_q_k{)> zRW*eb2(Xmf>q;YQCHeUib4Ey6P&Z)Tn?*&}h8v^J zJrae+iR<->uYc`pD9eI3pM8egw&5G!_y)8!)Yfo+y+Z-8uBK@2`{o7$O^zEXXp|pt zL!-+^@*ieiOlhsypPmMVWL++n zCilepZCqCw)*>r?cXxLaKhH+Vt}JAEaW?jOo#)qQo-}^G8#6hsGa1dju)nF~X2;>! z%&$MYuYZ>DXJhR$#iLPZBr8@UFvjk6>Ssf47*Cydv##y5c;Z0Q&(cV70}EI(tDgsh zF-i7#L}o-+dg(18A98+5S^m?=6)7+WrK%a6Tt6VYGJRz6bt_&mOQBx6rK}3Y)!Lc} zQIqkw8MO@OJPkE)3Af8-C%e>h?dS;0OFnWnN1iNhIWuz>J?F{r%u= z{@F$?E_hPu({RI;Fh4#;C?v9l^X}17!k4hrIhy4Wm#!3dP%YZ zu;;PfaiWs=C(>ZXpB6rg+{DI=Q}8{(;p*72V_weF#?g6MLv{Vu&sg(lVq*B#Nml&~ zU^?gd{1M}@VQmCP#qS-n#dmlIcluDTKoh8r4U}#99k)#m(GtzA9A}iQpY`RAOcl~} z!f8Nv&M@mR^D%XLCI6an@@!1xxkc=Upqm~9b*p%Kc)(H$F4rrf42+Ik&DO_hUivxi z<-R0pLI)OF3V#0Q{}F!j*=KnB_Pcod`6EOY=cOPZ0$`amfB)mZ$G`bE{|D~>)$if! zU;jE<-CfpcI4ejhogZ~>qVFY{#NTE) z6Ir`6v7alu)0m|siGDJ645o$mxjq<4KV0v;!~sI96{uE!Pa!B^6f zRy0pdX001~7>hG_riixIJfnnZFbDtz^kWF6;$Q+A&1;|3ilr>xA(()KKs$j_)ztkk zr9SzgtVj_q0NC<=Sr$MF9&bAywjJBU6ABtW{_@9Q`g&_SZnq5=kL*!Z+-@5_`SQnR z9Nl+|q;jF&_Uh@5CcH#FGoT>SHvOYeSXvbz*6G?km{ScBHbCA5iJ`G*!rA9(aG0sUN-Y z{hV$q?(Gg(k=7;C$#X`D*#J9(y0MPj`S;K6!E4?_iM1IE%Uhjby#GbO&Uq_qH!-$^ zG{Yf? zz_hLb%uTRBi=at?mI7H8)GBy<+E5p(C-u?mFIhQ`V$rrwPaE#;uDHLy$GTcQs*gYZ z*dk3C0mwaW4g0N^V+f_%4bx%x^z}9%sll_w0jib|qX3SMDG@-WdCgB-YmM58bP7>3 zMOVoE%jycOrP(^)q;o|^S|wi?&i4f3**J ziASb$S_;rw$Xy$ILu)svr-+h9AYMXZMF>xA>YlXYxBzBVG;@?-id^+8EAv^#&U_^A z^>chYKf~VZ%57^ptmAWhh>B07k5B9T93MOzOa5G!g?%50L0E6vrtgYbQlhdPom2WD z9W|QV%Qdy(!24eRGy6%yk_5M=n z`_cJuHc<5Eh1tO$rznupJX^!loEwIyP*r{>?X~l9_&yo^NP3O{XbC6M;36q9)UXko zK2iQK_!^-6HxVQXD_13oy{0vH9MaqYSoa(DeG7hL`dB}+hT$5JjP5kHa1V$jY)uos z3E9szSP*9i+6`9AXfRigPPDS4T`mGF4?_Aj-bRC2#v6bPwdQ#yir44PG7v5$ko36D zBP9%j_NTf7WUTj3tj={(bbM=(<=F_>!j7dbe=^pBm&gEMG|>9oE#)27&%+m1L8DbL zA22g5uWQ$7Nb~Ss6^JZG1deu{SK-mCC7q(<{f6^9(LO($zn5jubFV@A6IFoicEh$V zxU5Upt(`B#w|wkiWU%YpR$2pK6Y4z9RvYf`@9`_Y@+)|J-0|H%{T?1}H!O5Q^Gus! zhUI$2Uw;3u@rU2}4*uou{T{CC0@@T5jI?IfqG#hqNeVcg>o^BM+86klBEO~_>#|WW z1@|P`>|eLn!f{Z7ibGB~ZQI}3f!Li)h8srb#VoTl@AZ3JAB?0Qu6JJQ9tVh^log8< zJ6xy%9w3X6bpZe~B&w{S$P`1RU?fU-H$6{ojQZ%qw00V;>1V{ojvk?jCf`k|V zc|2-{Q*nc;pTro7nN!Ii8ur@_x7!o07q0~e09vta4Xj7xK!}2Y^Ir%MeCb>Wiwk}UfooGbD2CeCDl1kq zgUf3>E3B+>%01}H54}?--lRz&^*NqBryCn`-OJX@Nw48lRQeey_9j9p`vvZ0qmk&jLb^ zyui>v6R-V4AUsC!&e2?>k<=nTVzB$u>9%sIP z7z}}~MsrLN&2BYFIVYa!`QFd1^*rvp@AG%gz}*bmR1M4))*L4Ros|CO=sy5T+QW@%a-o&>B^t!VfHZ6uR4IVpbh(M zw8r5&_fv`jfTsUexePG|{7sVGS+y=a^w~iG5HV4TER2o7bqz2LbDMN6kp`Z%js@ zlXETcSz9|A_l%#mP}oCp<36064?cr(i`RVCpZiYcqw~4RWe)g$9?M}(0MNLAprB3z zj2075o8I@WuZLP=1}R;6htEmUvpIx;SCgg&nceY@?FT@G=8X3p6&acCH_FQVHyzTd z$M0nt$T-8EQBLol$CIB4jQpv~1BC32XO&R9?5v7?D4%u83clBxIWgx_0mfS!nj{`B z61ACosQ?*d{_Yl{X)5D=-EI+hmG7r#sdpG}yjgQaThhH%y&il?d(Jb6F`5bjNQ<=S zGnq8Yr+NS9vlO2diP9-~FS*A3ek0BGXtDRa)b~o08l98}!px5aUicHGHi%li zc;aOaY{o-*{*;S(ZoL`MNc;0SpnS>e7JNx3Y#pEJ>t<*A$Pb~aLqd0`0$-&|Eh1g`2)Kdg1f%a(JMc!pheaX^#`F#raHYn&m~`XJ3ORz*KH48gr&22^mWvl(HV~nHy+kC&Bw(AB?0Q zu6JH8=PXk4a_@{vDc^!2xc`tZ5R$s0Q#{3@d)34buzAW`q^$Py)0wkQOo|F;2MZoi17`(&el5@AOt>HSPX}R^mDhf66P=Nx0ZpG7 zjVfnjn&|VKB>|y~(gZ>uv@*gVQclU&4PX~HM5%a`rSnMuSfoTG z{0#VPuUu)Aka(dT_1{OuIMx-WR4O#0s@8SIx-6)z;^Fp$`^D=wFM_u19$~3~Ry@3Y zh^!0KSv*x;CWWLRQb~E`=th%awl<7*0Wc`-@cR$1O!CX_AQ8do6SbBe;uwJEDy@_7 zb4e~{S`9^?77o?^UDBlXj;Cj`<;*bA_u@#;`SWv4F3wh=&pJQy&sfi?_Hb*p(|F@K zu=(9?o8c2zTBH;dZ!};^xP-yj?tM%}2Y|8&3d+fO@5W0;K4v9ijyOG&MQ6N+KhNYU zH(MMmHf^W(%b%a0k?(uzaLe~~rl3?biRY@0>F|O`mFJqym|`%5q^p$T5usx}*gY9; zGUf?~6T&Qgm?OVu%{2@=v}#7xA_WcAC+572I8aTg&2@nl8f8NA*k@T+9IWdf-?O zd<5qXW?RL6o$;V~{qlO8VTAmC9@7CUpf@*U5;?JzXaO776a}=1QB>MnIyVB>WnKwS zudm4&6Jui59?M1nJ&GP~4C-}NO+NW^RjuDe80ZTwUU`h?rIdnoQK(uoLeUMO_5tD*D%8&rONbnKeBTGI<)n}K@3{f#jH#lvZmg@-lg-_l zx)>Y{+g%~E8)OQ~O@i_@*4eZ#)6o*mg>3Vzd6+2BD$F=qIZ#{g)&N{tCk!GU(MR6v z*(*hhmuhmH;_KbeAYKEN^haBO)lTNvi3hnSuKRi2VC7yA7-FRF`HW?J+u!rG$oy41 zu2Lu#Z*0brGLoMqz9wqtpjO4>;}goV;Cj7Bt%|+X;78$f9cZecEanWYbw?NZ9ftr$ z#~*$48o&9Qzl9(C?cd`2Klnk=eZJK9`|Qh}Ptjhvz4Y$Xq=rBy? zHP=4N29jZJAQNa<5)-xWFk)z&54h%JrfKdOfM(Fg_gljdB{M5JgW~Dw_cODb>&A`y zIf5td(YYd4Lh+#>o!2JTXHsnV`rLqG1}%B4vr+Hp`LcD5CQ1YdRJv5XbKVkOJSpl1 zxhcXEecgj*5`Di*VN_)*{1}-v3!Zu1&)x^ljbnN5xh@0=U04!8+g`~4xXwMXnMOM> z9BFnQqpC(Dw4DBZ;0Nf@c;k1+nq=H-HqpAIT90|H#TCZ`9g8_0ma>@PR0K3S{OCu2 zkC$Kj952880^4oJvY4XMeB)*>=9%)t=gq0^`SpCA0l*pbSp?{tB!<9>3oT z>p*{dd_pN^qQ4E&Ka09UAVsjC#IG`a&GeYZmG6J145_EhGeXB2hb}NhGl& zG~} zA8<5ulMccmgRYX!yjj&tYe67ayI){6)&ll>a}6!tvEgY3G}&oF@)rLVC^U1tB+> z5kQU>nLg^995mD;=+EW=^gs*0-=mKm2NYPw4mXkLF+~n%M{w*b978zqMi~G%+Ba2f z6?objF4uzfvS88foXlrE|9kuSTP$V4ix)4fNw6E5TO-Y{hJW@AU;gr!@H5~3Hvani z-#?{M_3{(N2s?#nFGKzyk%c zGnP>~G7nO5#W28+^p26|3Ojh?Bj7v%FY}?9LEYK+;!yh4i~ReODWuW87NsnxtzoY> zti_Z&Sr(MqK;JZy!4ZHPf%}1<=aYqYFglTlcEZ4H)P+nr1ya0cO{rpSQmn*5$DDFU zrjm^`89dltOYGsGV3S7DGXO+GCZQmC*M0o*k*xG<@O9n&J6pYbn3`>`I#Q+ zO1glRhp4;PkS!2UfFXbx*NC3kca3`<=S;ifce^*c8@KzO&GVY)n%|ovt>*Xh8g`IK zuqN?4FoK%Fu$u0be}+QPj_>vHPDU4}$5vbLmjf6$0|?=rw%_m_ro9ICx7;TYx zWao>mc^Mol&pki$q1kzG_^ePF{V9M4l{p8+oFC5{gz9uZo8Y6E`ZuH=_B|q~mgzi4 z8YP?Dbu1kBu(NL5|BOf5@BOos6DmNlu5Ij5V4o*VHI2^Xa8m(G23(c}ch?J+b-}i8 zXu3jlbwlw2Xhm5Tl*Nqmvr?VurD|_@HuD&cxzDj*d7YYczGa{9$|R$zeMjP1^OetS zrc161WUd1Wb1I~>CFyfigfgAX^qJ?Izv}3>0qAIOox4J z83UEU@O369^6Ol``7`n@jLogDeIJL7w|8x(VRXh{`QCYM{w60J$|cw0a=9EL zNoPJg8>INTF(TOZcwJWf<$wLJc#A83_1AwZcn`eH2dnxR?(UJKJS%WV330JTaxU&*@_Dr8d_mZ33!N{M zDaN^wgGd|rBl(6LvolU+@b2n2?rUI1vM&Fw*K2$y9C1r=r_50ggp4&w^VpB) zPQo$l5a4hQ^XJDolh<~d-M0-ZDwd@H*rB?4#ApqAf-2C&8gCY$NCTET$5+0e`7s4( z+IwUe{)6Mc61_GY)kRrO8?=2U>Y;jL%%ICc-bhHvGc@r?S{8+KgXLlZ}9fv z0o!fE=bwL$)+&DEH+}=Z_G`atcyWqk7FZPS<#LB#`}JSLr=Na`KmYSTPoHte1rSE_ z%jJT<_%HtjfAmM+!N2;K{{qWWQ1{w18`X3RIutYJ5x0S4Los=!IIiwClF@ONW&atk zjMr?SgHAEUjha(HK;YyD$s&Ctd2!;|E^R=cD`JS_K6v_l^tETmxQ^21Cl2icZNXh5Z zjThwfpbR29y_f(kV#bc`cEchP%>XW5Z?+YBC-a_;&&x_*Ry^`^$2F%=AB93b1NThl9_pX<|Dx9ESTxQlqrBb?lJBmaR>k(gVBgZEaEU1 zi}H4QS{LlM4Z2s9i#ab>DY%pi8XL?gY2wJoGp|2O`JUH|(G`>%r~H26lbvUc`{8?94Vi001BWNklB6&|nrUXn8?pXw%uqhJcnKd@ zzzff&jCA`&uI@bSbIyCBz>onUBH_rIdDe`D;$Bg12thY9zsdVLI33yi2S@%g^Rjcy z)b)uzE`GnonYMcnZ=}8Aywdks1AaK~f>FE(~-+Yd@Z{OnW=bz*8cEi3^Y}k&m4G#}*@zt+>6+i!ve-7+V(l6@pJHGz4uj6-r_jmE;%^Q6G``@=f5Y;H@ByhX| z!;jzlvp>T(zVUVZ#&7**H0OkP6Fb$;N3-loXFSSf_*tfo6a1`k4 z$t(4GtbsX%#&f47$LaZO#V{ux9QZ|OxqAQWgOT*Z_0CJ6)~reFAPdlo6O+L>5!*|X zf(q%LBd~ds3DznNi=KJe8&ynTiulL^Eh}B@7$1s@GsO_PB9Z1sP?_ttwU!Q?c93E3 zDR#43;?=9ykRrHk70Y!+RajbxRx2&wa#_R;b=p1o1ziv`$|ZPYtQ$Plk<80L1TtvC zsQ5LH@KFc8DgYMSBNlXCn5v+xjaDW`DATx7y&j?W1`fJ1AnAKED+R2vMNq&63#yVGFJhB}dG zTvnUcUbAmG7*}p~rxB-f)(loCq|kU|=Vb=|XLIB{XJv)Y=dYH21XPK4>^^1jy}#h? z!(05(cm6%T`OTljw|?f^c3woVh$Y^u0~D^snK9=8Ofa60A(}@7vUH>MnNl|@u8b_{ zpz~}!=8N~p3f}-gehS=SU$b#61*rAhKx4c>UCuc01q~VKo@Zx~(4&Gm04--^>}+jE zxS+-vpQ9`ls@2aQYfG!k21X=y{MfwSl!(=Y^G9oc8f&A4AC zmwPiIJ7^Y_QU{}S%moTX?Z$$|j263YfG!}@5WuW)5QvvsGJjYaAGpk3o&k)MaVl+! z>Nt})?`&=OdyG>go^wW9O8ka`>*Wrg{p54}(RcnmKKa@=@$tuBLe&aILDdFU#E@bJ zivkRL2T-p0zQQqL;va@TE#g$eP~el7P7itSX4!tWpNH4gaV-$*$W(3L+6gc{FO#0V z0v|g@bz^s&Po?3>?=7&@(m_rhozVl2n1$yw=b7j6bw*R!J{;fA*fXy;&!5qu#=a^8 zPtx~+jAteuDOTswUT3HEWE_rt;aa452i}ngKH)N`m#=});EXWdi@5q$IDV%AFVPke z#Zgv`62Ruzit!Dr72Dk4=Fe>{9K?Pg0|tcNmF}J8OkZy^$f%f;KbmgQsOsInArdlI z6~nsqPT@AWC^;aCrIgS^shimON*M`ylp%fp$#eTY1bpM-ia5PX>~oweXq-7C4r?%4 zoWFHr7Xr^06x60zi}A*y4QQ4nX>x?P$L|mFKLB+@D;2Udh+GYaz#@%=lOfGER8n(Yo?XsYz*lESRW=k;7iRM(+tz}m6fDJ>xOKCwU~fiy+g`CZYZmr& zd%|aL-r&ufH+Xt_!e^ho!B5`2aT(fh+cs1$tDxFY_u9+Mz+};~nA5E+i_u51a($u} zbVd4E*A)*BkNETd{Qu(XU;hSPzrM#__Y;2Guy0TJ=GVT8fA&v*8-MVJe~2Id`0s;# zMhOw86O@9tPmlO_fAk%E?OWf%&wl%7@wDC29%!_kh}yJ?CI_AoazN0@R6CuL2PD2Z zl8g!YsFq$q=N|=85x{ETR8}HWny5K9bI^xHfQ!CA&@VZE6^IA zYIT7>M{n84snFzWNP`Ti+ZFiCK>JW#GBC+tKEFnVHfToGjCtOi31Vp%vMjV62H?xe$ZQxe#gt>WR1Bms=XINfNxnFj z*$B~To@+811D-oiC6q@Q);WM?6#5?b`FVh!_=W4e5nUG>8XKFyk<)N9g(r;4B189Z z@|FN11kBGUIBKNSE3>2nevgwqQ+V_5*$^=(!m-DA@5{!a z;XKRp8|hNh7Z6H*!??FV2X-uWyzGX^5RuczC&Tj~uACG$Txb9$S{}yO z-xuj?E%~+SeA;>extl%Z(%E_#Mp2Jep@MA&c?gvnt92dgT1qH{T}YiNELlFbZscCq zxYyBm+-d)qGCs;MO}r!T(Q^jvyni!4KJb*dpRZ-YjQp4_!?7etV?#73n2uN6an`CE z&fFoARPDarZKO>a5ZK@eu?`(`(I~0h60+6=BC;{}Y;ETCQ8h)Dj+x8d9scSE-^cg< z>_6gne&=_rQK$lom;tDdH7lkgKh4h9A}6Vv0;rZ=<4^i~XZtwsSN?hSd7j&h7p%FQ zEt=U_6ds-!IO~0{n7i~d%YB<2>LTJ@!ACxGid)j0STZbUgFJ`P<})97Fv%7E%xgOv z|IJu7k8Re0$P*<6H1xCC8{_&p*An+GMIh+WVCwo)%*My9&JP7{Tr6IvUv=P1B8Z4v z8pr_Y5vM{km0I)5rkoQ8sFiMOMP7Ht6Zu}J14D~M%@!m((P^YWLbM0zI+FP`#?iE!l*6SV0vUYu#cvS>! z2`Me%p|ozHuS-8Of|0k)j=gyuEpti(H^OP#zE;p0ux|~I`wb5dZ}Ilw0iS*L89smW z29FOn?6u+X=@C!24Yz&AzHiv}9ox2fV3K&rgwZJ}V#egMELdbQzUqeiEImyJatu)` zw(2DW93R(O@h9K?6MXjBkMTSI(?7$ve&$A3u5X z6G&OP%Dz9IxpckaM}Pk*{`gP+1fP8MYq;KBv2UB}uM*Mx#eb)xl68+q8twP?9Za+> zzTQV2Jg?P&8Ahy$$k&v(d;0try*?O8KV0v;)YH5&_?Q*Te9g+w z4B!WF;mTyMuhc;?FFQEs;3>U+_I%*~XYb9QEIE!d!OtTy-&NJ!1VHKlNP(nmc!&hR zL!6aFnO1AFT4^MWZ2s3Zjg75VLt8=s2cYe&IFv{&DN+MM0EmlCbXQl^dzlfwKe&5@ zM`Tvx;QrVNYt%dPMMijdxPR{9?tx-R`R{LxgzDP!uX{kd*=(@cY>;xolx76lNq?P) zKsR=%Bg8v)JRO)@P(&IPs}j&DI6QQb8>lfu&vt>tzy@-fOJt{?qbh7_+ZL7Rotih@ z-_z3X=GpK2x<0rdv4d7cDd zmqQ{V#$mw8a^VOH_=U#}wAEBuQI*zTd&aDFWbII)V%P*KhE2b&JaAt7uF|mbil>2} zI|J0>l=J{ZK?)O6u5I?lUvFfrrTl1a&mvW=F&ed|r$t`~pA_v_orgkH{a91~A~fZU8P~@n5@*D5z>k0YBiz1y2VeijHxPyaY`m&Y zj$(+Sf)tuLeuI)L;rqt=hNe{PjSHQlFBMU6-Rdias)gc`9^ zPjIbsI1B@}+ilq}W3)!0Z73Lkw6T`;*7e_?R?px@R%XuSP(nZ6o8(24t>7XQ?Ot=J z_WHi3v%l9;b|s}u(2V&Yor2FLpTI+0(l)q(Z)ouEQtOx+2=RfN-9`z z>$8)YcAxP($5hHV;WusL2le)GT4vD7{;op0q{f;wuYjd`9io#vAM`Tg(z1J2IQ@a1Qo zahoQ=)eiNv^w=RR=FZoOt#gACVdnLx*YW-Q^=+)_ss3|6&-Nml9&rZnN75_iyi)oY zcJR;dvC9(Iw&U~PmDKJV^oOTK|GLMWH|Zb$o%LUSZ_b9Ld^Nyn{AWQKWxf|#V@~G7 zWQk!a{ZE99@U7lQ`YZ+kdYB^g^mx+W%065!j#RPTs)JcR(5xrbaWWs~9Fm!oVe8yv zvlFyjjP{Y;hN#&MZ2$=%r>)nk$;Lqj1-EXCKD5tT$FhIj2QxIbgtcYz22|E*D2|?1 z{whI=CFy03&^E-ENw%co+RbUt+4u?JN+_{6zrq;Wr;A^hy`WVdN9q^?ueF+yA7x=F) zy@Ywrh(j!yra`m*Y;*euKllO8&(HCDzxR6>h7rgKfqd|ZcCtyYH=OBkl-hMbDX0Q-9sRoO81L*{mvhkqU5Rw8Y3u^5+d~yu(6tP&GgSltU%_*eZ?tdVtII&>P71*-gCeX<5NvTb4lDgXp>y z@X@cE3fjfsGlQ%E1!j%F_9>sv=}FW8#nwm&WwW4{4Jc2kS0e{hk^9dUY3fBD0fO*D zF(Ryna*1%TT3Vce#NZ^(@-%1s-~a8uVRty-nP;BW2<};<3Aq6AwK))jq&gvc;C++) zTa$;&IRQ9uISejPON;(qdtJZ`7y+7AMeA$tgI+?@6(IAFafyS10k%Ub9PnW-4n*6S zur_*`xCY9+T=e5N+1Iya>Gr0h%~axH`Vfo8BYW>GVJ{PTn_w7304vzmxxO3 zcg{#eHGR*<05p*pHPWL3SPxxgy=ZD7p?qe2so*sio!m!Cc)qa6hCW5Ur?<&+xM%jb zVO^G>ZkS{#mEaF!S~@$HI-);p(CaCpy1BTfSD9sP`}aMc^cbh7Su4l%HIX~4LQ0Kr z(T`>XtNgLvvu;?GnO7MW$O3yBJ|?2J9%qNU`p?_3SKb4mqz$fNhn#D@G0z|V>gU(L z_cQ@l1F}81M4c&&dN>-ab~g&Wtb~&BfeD2Vf=4UQw7j=QH`6I)9H>sMHF;`d@T6}_ z82El?+2o#+L@W)%fUC<(y!6sbI6FJTZ-4G{h#Y~OO1TDe2AkXw`U&pwdaj>uuXl~A zH|h3X7xitf;SAqSKi|!79RC>J`mh&Qb}jPJkGIhU4SQ3gGfI0m@QiP_kK*_DdpWsw zkC&Id1G;%85jYzT4hzSC>4}H&sl7H?N+3-y7bgZ=`G!ECTsQ#{67`ogs?e}!B_6Bp zs~Ed#V3S^?3SWxP6rIY_wq@+t_(aCF>&WZsiqjMuYmm(vzsg#!c8aOaTAIc=2_>Xi zbf_!MQs<_4eM@S-;V6RHfUt6%qU$?;ud=M=w^|Rio%_l!=JXT?Hicky4Vv+;@mSBZ zc4f|(PBZ4?5jkfJAz<8$7zbH@QDv}f)avvZ4VCWJg`jmjnG+}gVaG`6gp{rkV#E-l zI2$#sT{a%o-ccRg_Sa-l>3B0HqQVBKwU^iNqu?-^pAZ6$$0L67)1TnM#T5wVe3aDp zVT@8*z#ZX06m!$uP;a%#&>nZ^jKa!-&mh#GN~L@YIt};_=6yz~hfS zhTCUn$`*o0x7&@_56A#5ZM$H6FUk)&&lomaeDMpP$E!bk760YI zcfb2x?Duvz2~EuE03I{kFJMbRRGi_(+eP=f<>=KY0`YUA`J23n=)9o#7G$md4iTpTSzPfbZ$i3Bn}wdZ@_-a4C&*eJ$a-#;sTP=Tm{ zW=lzhf}v^@c`(7!$qFoB5F5q${?bZnu-P_34Dn88Ji* zagfMzof`w4tiQ7|Dg?hCMULm((mZiToD7bcr*03Oa7^RWSe^4v0HU`*1E@y0q%Ih>zYD4_P@_fMu7Fl z#_GpW`@n^sg_pEWu^ED#t-OM^3&t1+S$8=j2Z&R(n{$hjuX4{E4eOB?Wy~vhshtz6 zpIpliEQ}*3r`XZFI&qx7bhPxm;d!Dsi3wE>=^tj&)0P2nJ*Avsb@J+gNMNR+xsuCdspoCjOfs6p^q9BU}2Sf33YT+)B?itmeP(@qN+TdVq%# zX64y+ql;V>6L9mu3IO)ZQymY-?Ulc_N4=}Z*#5hHm8P9 z7i|$%`>Ah=(^#TCgK;20EDlkYwn0EphY%Z5Ba&#*!tR|sDPo6^k;IW|sr=Br8}p=D zy?&CK{^aW|v(cdHX2V=UA8CE#u8iyB#8{4(d$R-m)vk z0pl>^$Qf5xS2#_x;*TAMH~^G1h%oAgURJCCP00=jMGxtQjFt)-DS!tcMMvLI{UAdPYWSnnkKyb^2@lmxWL!H@+?07_~S@TB$sK69)ARR2{2ow>;$854#>YNgrJgz1TTE0A~m~ z<>DE#F?1Az$zpMiNoSn)AVJn-J*lx5o@;>KU&Z)?f$Qatw>Plt*?GMF^RY(b7x+S|@>w{LT3JB;$X zI)1wh&oWTveb6Wu&_vFczytyL*5$RDr<(36C?A4xj6GB(r=>%?MvT%36~Ep z@bCWkkFniJ;q~e+(yv*XbyzJ;dFV93qJyl%*DLMZ2`p&m6bg-zo zLLfj5N}Ep3R`-xfWH2$1krCKpY3i6pP2I{#eiviFX1hU}P9RpWAL`mD8)!Kr!9}x> zt@oBs>PC^IDtoY6Wueg2q6qxD?d6flMWUsgu&a5mYi?=4uH5V9e371=W$ujdYwN<~ zl-EJN4Lfb#JM4O_(XO#&olf7k1{P~uQCMXS+<#5=}}7qs0#&2_e;!? zN91dRhH7v^Z{#fXQ;CXv9)|B!WZ@X zl|HY^n5E6(f7jBD%YQadtA%RmuU?+?vc<5GoZenbmJno{B>)DVZti0i{Z^gG-t8bv zS?o96ylF6<)?N3{F`ExWateJ}FSUL0_cAI)-J-^o$6ZFNN-rktr*B|6pxC0=hX8OmAvYX0wMu}E7z2B#&kR)=|NdV z|EVlCUN)@W>TjEK9dn?fah`tqX?&A``S}@dzx}q{AD|JXT%J7)11>Kw@tyB{2ls#Z zOZ?@Z|9fnAJ4~lZH%nw=g{)8RlFdht4bi=>n>s}*aOK6qmuTgd*&;<`y7l19rxt&h zoPo(rp@Yd%D>?E}u18MNN7q9yasmjb%q&8TiesWTfJ~8#B1MS|DD4Dp6c`o7W(F|I zb9!T`QDgNF001BWNklY|YgbmOdDlN>2l4lCNszWazT1Kq)Ids4EhMLf^Jz22@ zZJks?TLVOlmfF7kT?f}zFRzW(0i)~~_aM`FDy16zV{Nt(X0DG#sn!1YXokuIRSMTS zbPm{ZYdA{uMF!`DG|fQHpg0s-48s7~dyBf`>y2l9R4~JMSre`wo9FM$?f^7U!;jUd zZtKw1@$lj|o>2X|C|@nsJQ;*(B7vcD0H}w)cs?qT!uGiuU)dS%`jEQ0;rc3a#?s!o z&V?JVajB&cQ>Nk&wQz&tB!vPmKxBo@jn#Z5lo~!geM&t*$`UOA213*#^Z|1CK|p4y zTQsMHfBMmn@$}Q5#^gn$}DDC;S7`g!Ht89^D>+6;j)lmr9869HI*k|#t;V#aX`+Kl7ukNNt~wECR-HA z%Gxl#cTszOGfRLvsWRsRC>xMj=w!M{PIUG4C0k=s=d0ZB*5j)DZ|Ae&<6=a&myhB! zU`@_R5BF?8W=|ix&q}%!mqQ48GJM-V`;8gnec%1KY}3s)C$0TfM~NXALXF_CTeFt& z00DVU$kWtdtq?`-Ew@RRPAETiPajW*x~5Gpw7)M-5qSLKp2}$CLUEck84kQ!4#CsV z?(3u8ecviyXqg&_?#L-2MmvP6E45&{#WEDwT$GHcDaOpTHgzN_ddUCl`D+c^w9ep_ ztPAIelDW3B0M*c!{@cm&03cCI2>^uwi6zSlCYy;cj01AY_{Sgq5WoG|&*JG%e+H-P zD=qzGGM`H%X2l?NA_J;EC5lC^fT`4I?ALJnS6p=EKC9WwCicY9VQaI=eo)z8#3Pi) z*mNkWGw4HJHvfL^%6I+T+PXK}M4b+e-sL4e>gAvRtY3dbRLVnm-D=R2yLDXqs!`bX zrqHRCKSA@%Ey~k7A*d3#JTK=g4z^5cufWPomd8{&6%q(P`SoN61VMS&##r!JICii6IvJ4`lvzz_R?gT(b_P&IE2*YZ0p{lU4zmW zTrou9(^lqLL}XNlbDk$$T|K~V8!^NP(sXP2Z4?>>6KTd%<^ZJ1KM2Za3CszB2Gy^I z$*Vjl8w7fg*aBb{S!ipR%DOGMl8jd6cKu7xojZK?GoQvgZ@+^d{NoS73?v5ToQo}* zl0E~%UjSnqM?CY)Gx+RhKa1^li*X2|S3=N3j)Xq4)~sH;uFI4FOi0>4+4v5KA%JK= z$yAI6C!Jh{<6p-&LU*M%L!H@*d2`06pMDyL!=K@W7hl9b|MZ`Qw{-1fu5!}s*MItd ze}pf5?sNF+*S>~%N=Ph$AR&k!A+Y?pWs*>P=qu z`WaB0nW{e_P-titoXq&J*CQwCqwC>U5mYtGq&L7lI9W@HwtEX$%Dl2TG=`s-zjFczT)JiqrQ4M1Q zkOdSufRVr$5CJ>25e6c;3V)ar8l~-`gmPBE8dRrN`uG$|1FIg4#d7G4(W5mm{hV7n z)~?X9MrHUk{c6B?fmRJl5vDa_LBM2NztzvJDb(I6V&m+M^uX=GR35wg<#`*=)87_96(WDRIz5&$x(Ndv@PXKQ8G6-p6?1Leu(Bd8H}M z(Ec@LwnoQ(E{FtJmM)dD1j5Ir9D8~Tk4owk>-V`cZUubSHE3Y2IOMrCenpW|i7*A~ z`etTvMnZt99Tt$YMCLG*mg*&2Q?|`>;MT&N#Qkl~C=e(zj!8BsSQ?h)PK-DXI2})T z;XB^}Q^4uLLouG}xa^)D#F+%H z1`I&uMEa^9bt8-H`)-Y>B#$v54iVGkHPSqTC?M&fMhj!wmL^w2)W&J;T4bAdloo>v zm8QL(bu$DrnoRGQKropi?drOBbJ9E4sq0&DOz7P8vRV3F4<%^JOSDe#h7a89A_v@t z=~{}gHPg@uOQ)Zg4W18M{Ur2|wnT3D6t_xql(vd92@K+lG*4P*l96*lh!GSc(tJWj zjo|UtLod%gEm}EN^}JGU!3R}8^J0v>9IA6#dBeul_oH9Wy`J;9!)KN-8z0wff)K;% zd@utV@3!c#l$&rHit4$t18I6WlQl{#GdG(AJ*Mc_n~b~GkrkOs=A#m$Gs_sEeIX>| zOs-@?D7tVehJI8TB950h47hl3iEqE~BEE5&@Y$z-OAc}2qz)=ur>zlM4rI*LA=S*2 zI@t;(oQ(ByUr1H4VO=*i(sn%;-Yia>T2{dvfYN7H2+eYG`iHzMs;#dFU-(?a=XuXe%drIu#y)Upqam^{)XA=+LQn5_H@>9uqngxvy<-P#z6O}eIHksc!zwxlu=N4h z7EXXf#uf*oHXmZdxIN(d`h>gh-NT*Rdu%tc$QE(t)*6*IE|jQ4=v*^2aa%SODanSd z*|S_Xc>TKbSJfv}#&7evw5PnhY1bqZFsQ@(aOV!b_=PXxUtfI<@4a^qwgJ6aPrzD zi0~l4Z~Hf0kDR2BuJ^facHrFf`C<_`kkuI4a)aJy=*$Gjy0g_U3h#XK&M)b;2;l76 z=nbBJ(Ui!e%*C*+AX?rJ!-yCoQknsf*0B*~4n&x?lOYE+zjc>Sfq*yKpdda5sryp< z=!_^5$C0I@Fx$aOiF1@z+JoD5^v+Uh zc*^g7_x$ANpC~T)u8A7!9X<9uYWqZFV1DU{YWn4rbxH}y8KZ)P%ri`L3g0oJGql+Z zh|u=McDfi`4*jaSF*kGBC_*(Z652jCB?u)S_KJL%a%TI&1k9khPa%oig(|A7k~CAe}d0{ z{@-9eX&D?lOh>VV$x7j~Q1C=QAEaXz+2Fo+Y$S3?Y7c^oi$=e!czKO~tWKioeG7;% z=cSbaKzO+9zv-%d27ISmo)kmhWKTw3@X1a1cu6ZX_xMf9g6oRc*=l%qdI`B4NC%@P z6A&a=gOnGuITu-+I0YNPbPn_&o$8E%8&m1KZCHbgbJ6&b%74PcVqdg15ZB~`T|IU& zJyH_laDSU!bB?749l>``Qk${VG(Wz`kuGgLBIX$$QoAoWOt(_5bA zMAX#t6&joUVdSdc&uMNp=}mvcD1F$U-@D7$S41DTSpTcv`eFZPR_#N4VjOJ6If_Fk_>GjV) z{xLrJ$xq^|&pj(P`9P&UYsKqsn#nuD+c8QOCqr@v#I_6+n=&A4ev0}W(H(655a$Ra zh)zxOgx~n}U&C|HJ&Wg`e?iU(iGxIVcRrIiM7;IRJNQrk`9EXM319o_*DxzqQ#Y_~ zco0CLl#a6X<|Cww%n7V`wd(gZd!?DH_qlGwR=N*kGPrC6cp38%u18MNN7q9yF3RcQ zAlqNfBDvunXMo+5I%wm_Tp|D|*C-?ZykhXV=sI-$w!ui0Ks6|GuFe(1VrG1M=O7U^DR6Sw zR6S(D3*%N%85Ng(YUgFS3s}df2MHDM*f}a3XyM4+Zjg;%?yp9b?j}2a@J6gRYL`Y3 z7IRSVseSWN5Yse)5HMn=2dS_)x)gNh%%B+cw0lbj5+@w#b4&e0^a`PlXU%EU_s7ra z+PbiLPMn%KSz8}%jXK$wXdEt7pH+>B>Xb;D`WPaKG`y4)Y=Qd8qQ{fBa-vR_d#b8{E z9#u{)hVL4`lsQBNTQ@m+`jpuAISS2*%3%cd+diuAgIAZZBo3P5s8c>JeUS!H90RU>W-cl1!!RP{TxxgK1J_oJ z5Rjg>N{jZqPHE(uEj*%PxLc3<2uV*j?|?L3_59P;=3GW#`FZhl^t{v0oB!TtK&2 z=7P{9rBn_h@_b(%m}vUZd`<*QX)m(d=s{X1xY*gYi6YA>andCv4jsW|N%WkHx{+XY z#;jwL(l5H^wBBQeWddc)GjPn;xV*jwh)T*Xm}MVaOC)XfTO5x^{KG$dAHV(EpT*&D zj%hlo6IJ>Zf^(9xm)BK(H<;OBuSz$yJ{4nH{fFXWzzeZT~veht@ z0}}})5Bx)17Hwn|Gp(f_-#{Tp;szrKuz%l9y8!1iPLj!`p?3V(~9wSaL+ z-6rSv>ufM)t?`(l`_}~<&2tjR%Zl@;Yyf-t2QKxqOSZFKEmnM=s4V7!ef?#!N}jJ% zCFBr?6j|gKU^TdlY%4May7{QIQF@lCXGZY`>gRUQQtN=U`Ea~xG-e3`prEBG$ogqA zw$4Mr2(U4)=og(=B5Ol+u;(}TTaiO3{8>BP2A=>be~FqyMti)2j&F@mQ%X4M$@bgr z7BR+xv11IioWlUbIAaJ>W=v>io1Bg&rH-&g(bkO#0wD&Hd8LdH0EDR6zs=t0GyVK{ z7C5-kxyy~!M&}VU*FZ5yjQH}Ge+RGpk5}+7Kl@jVantem630yQjF(@28J~RWNqq9x zKY?jJ>NBl>7J=$E<&9qmP5*0+5TL_vP>6^Pl@XZr{Fz>#HN`OhaEe`@{94og-bhPH*;ecoVLB z*wtgWe!kc4C#-+>L9Rzm(nr@rFEiBpT2v2Hl)Yo6Y0on_dSzAgE4-1>|Gqc)ZE=VL zr4~20cvMT(GKFdY%15I5zD5#(S_|B(Q8UjNh5_5n78mc`RmaUBH4IImfpqsti}3s6 z9%o>2yNQ8T64dWJ(0)i^X3{590&$e;~{TOTid!u{J(O`7A$Y=#a~O`R&^ zP_vU*fQ_7vEIYc1vp7n#)TfI>M1mMC;_GGPWb0C#xTn)e>K3s$p@tA}etrjcZr{N# z|K$~&P7^R}rH){Rj6vs}!PxBf_{A^Z!~gaC3;6y2>EGfLpZGYC6)d9iM0riE^T}Rk z&P}=-s2Txlyl(T}JDNN{^|HNur^cnx+Vf0ZvmXrD_)BVh-n@qUey;Y-edfp4tSPFg zc>V8sI#?V2IVD2hT`~t;B1yUHv-mKaZqd&S3=`Tln>C7P+{j7hDQ67hMs!xr>X@zu zQT^R=K770Ox~}(H@6Qh4Dn_G|*=w}+&+X;Azu%l`ZRwIq*Ljxg3zLCsbMO1H=9G9C zkY4L!FY8QS*?RN(%hOTXtA@R&_f5RyFN;>~b>=V(#Wu`>ryE>+-SN-?Z zAd`E@(?Mx7BTK#boB^(zZ{Bb$?UKlLfb>u>_1dtxwRCgWKGq}GWc)yyGngW%oCeOw z^Nd^^g(&qXIRlBM{_{Mig2(1LVVdQDm!P$Y?>zQ6_F=@`%U5wqM}%QpHcn&_2ZSMl zK^V6?y#D4}_`4UsgKzxq@8YqK-N8H^OQc!JEMYE@Vjeqs-0bH@4iz%|6)F#EWEBA} z&0FzyIv%zneMTb~*Pf#zr8{7(tRaal5mRNlY^Bgk{Rj0`uA z7Lg91*kh#anX{iXJk8n=Lh-Y&>O7ova_n5%WCb{>6RlcDr&YF_C0Q0um{CI?lLv|31$4z1H<;u$ZMSJGa@T&p*=+EOyLa(lUwRq;@h|^9#vx*!XYI4Y@9x}* zI$vf_TOd{KugNW&PXEl>7lzLus%=<5)p=do(2b|eI6phX*T4RC+`oSxul(#)fP9&t z77J{*Tim^S7k~S=e~aJ${oltYKJf`)P5`nvnu#zFz>us3DL2~Ex@NGU5nP5%Y!lRU zQ$N@5cdg;XUS@mgf)C#G;(FvHeRMtaGJ&*a6x?L6tO>4qwcyr?0sZa6`{M;qqu|_k zb$IdA>p@=}ab|^tlQyORZFW zb|BKIIXh2MJbhzyTz}MVY&LB$vDp}tG;D0PvE6WDTa9ftwr!`e?TOLYy7PbEd+%E3 z!>su-Yi7=GpS_>`poIJ(wq>P)v>?#|$^x6*xcCa&3LB*79R1hx+eT~CO!2H5fERX# z082pWgwh8f{^g{FKW6!d&oI{?+-#C8&=Mo*mcEtexwCJ~M+IWz{i*_6P_japGK1BF z0o#CvqUWApCary>Y1e+5&ST$0X^c;&B^sA=)492w(oaOF?bD%E*Umq`dNTFbvN$L? zco6;nZZ*=0IftCO#Y;?T`s5~p+5FZ%WrX5E@Tf0 z$nOtfOkPHuQf|KP3y@Kxi3*2_%o?m~8NvfUE@M8zntk3KUkCLe>E1VKipG3;{mIF< zIXWity0WJ4O6Z|5YIp`^Z|yYQc3L>-z`I;0)6P4q=Rmz{q$>6{ZAbf@J1ARn@DdvL zcaUu=<@C4cS4WTZ+q$7{TL>1=@}~wjcjEy2{E$tmK>{DfrCmTpVT9MPeueC?wIJlq zX3bo1cIrX?PX{#&vj(8J($vvln$Np(Lr`Y<-+8{md1K7$&9$$5RXQ3}GNGu|!>XgV z+8to(KEs=5Cy^^_cdfz!n-x5GWd87=yz=Jwtj6tG<=wP(F{oj*A`?Y!ke%rjcytRy zqo6fJOfwl+j<%A9<#b#a59ND5^Cm^s(qG~}d+?ddz1IA7P=TLcn4DfX)dx@`&0W*1y8b-7WyRFxrW; z9~<@i&6A{65dP7zp&w%$6p;u}j@RASuoKq!b z^V8)r+62ExSLLfP1ajJt;tW+-z%YgX+~qIO9%pzjXPJM*eBE8zab?H?fpf7$JLOj-UOboafqp+#IrM3tuS33iGETO!|!UE}X;lGJ315 zP3u75+(>7{D$LIM zp3e^+e~u_wUsuKKsduK$WO6T;Uw{yYPi6|~(r)h;+^Xto5D4U7Utb?jZ|DfHfUD`h zyYp+m=!|%*h3tyCjShp_T9tBAxbmxPN8k!sV8cXcs6+h7F-FJEJ@mJg2z`pnZQG`r z=jP@u2B~(4=&8L9IC6S(-tBw?AcnwRs1Fw#c4tg2xtN~sF7>^bzL&6G&#H>M8Ql-) zP{Vx#W}e6gW%t>~d@~@Qw^KVc?nF_w3^pvI6|ZfCC9Tg^WH5tDr<iA9;?G;e22FVX zwwM~b0lyuNGQDW-oKZde^~Z%D^wV=5nW%)Vp`?p42( zXMY=;=hi!z;%U{S3iZu9zZl#|F0VfU8>FL#Z`T-$deEyn_up2m5RB|9s*&gPpfxkT z8rYzVfyXkbuI;l2us9@nuy55ykQNi%eoLX{9i**B!-{Y6>JqOYB&L8p@hu)6mfa$G zmV^`3Uk{|%1jmyx3PV(6s{S#I$MtNZ?f17iR%d%f%_n_56B?}(H zLG*+3nsoe%88^!mV#hXd!T}4-q3xt0CWBn;4x^#4mw5nr5pP}`Nl%?w6hzPAfJ@0; zauruE;fbhHFM^(fAFD{Plp4o!0iAX=x8xHIl+YorrgkR%MEw~iW!|SoHVvc4rM-9U zq9f`s=i?hhc7aOj`)Zu3Kr4)?Oj$-qFA&r0S2H@IRow#bxT(DBYi?j8KY5RlFM;87 z;mLd1%kpbzrFv>px_M};v*LQj{|AdbEKR4E#XgY%!aE@Lt^rL%_kzhW^RCgZ*|kaf z#w=5qd&`NKZO`fD%?HzL2=a}M6Ud8l#+RGMNRjqUe?*b(MGO834O3dINP*5)OrOP^ zCvjPl{9OgT+ zg^%g^Zqw{g&D>l-3~qwxsp~caTWqq0s~>woGetc!cNTBO{HlLRO=e7uP(LxmxF zCX?N4(M^$NoGHW6-#IIuNQ0aZDJ0({Kk|-XP$V0cZeE3TAc)rr;kN{`d@;dq|4jCx zM38qT>jVco_5p8et5R_*tJ{8BCYvqt(*V*9vKQ!k`c|)^o;xw8gpQtmph#*F@_3M8 zNl0m|JS%Bx&4$g@vsLxZ#rr>a$fV{0aq*TtO=`CBuw$TZ`i>r798-@|fdXuqJl73fTUxjH zm$oX@)Iq=^W;x4WNdj%YPNryV-qNy5rct~ynF)>OQbls*xmIcbf_)gDx)13|HtPv= zihT8DQyT4A;SViQ&>iuwSM+*C?zp-C*3#C-FjGL*e-|Xb4!+N#wf8y|F!?!bUB<0= zjyTVIICi2@nyi#LOFrta`ZGlS$Y8l)u+1u?ga;nHywJ^ZOUE$8JCp|EC%G!zdipdp zLE`(C^A5P!Xb%MuwR_AvXN{&&A+x-0pg#V`i9X(X{tT(!Q6k}((7EtUHS+Cz7@GBL zVsLl{0InVcv;s6a)$i#EM;y+53Uj3f<={K)hksj)nz_8@`>-81 zlkJ5AFk~)KCg}6m98JotYv-4f-!8V-wtPrp-u8+4-)q-^^0Z_!_YuQvog@ZTq0%Xz zVMjDj{YS}NWSZ;VEuVa8o1d33`+X!Ff31Gl|L>kS4=?YF78EYbQNM1H8iBoK6rXj+@xLWLB1%SR{kZMtB;!HHoPnAri&(NA zT&4bBy>}_#Du<#G?VyCo1L_J+5fADz3k`g^Vy%mt0j@@3!lyZ`<^@DbzfuUGjBp1( zYY=Dt(5zqUJ`xpB|F_Q`EtlMOl0m6$T73ir|u?o$yp-MYe;2MHzEe9rVrxFN1o0_&M}>W6d+QQ z)Og@;+9<5bA#LGFaLR^B@3E{-ii_oJ`*X zTDjstY*dV4eJ>*f>c`W2#du%xeHdQ8a7{Ij^7^#nzbrm+hY(0W#KX&*ED_IR5y?`f ze7Y3!R^`g{)EGCh{3O+8K)~iOciQN@3j0SUVX@Z~VRqH-&F+NUePR0E`*=yabmEsy z9r_$Si$lRG4jAbrNzGGztATSoRsfta+HMS5nZ#SQ?DKTJuZu3cZeh-uO^L$)peDda_C2MHwomyKxXgW;DUNYq#n4Yi= z+}g4O_MEWdcJ>R)e>qp_j5-vI7gV18#J73=EW!RD6CJuc9eS)s(|r&`L(dD~2u#J+ zEct;^pmpmSy!os@4b6t_RIDvSSK>|1Z;B%OVii4E)%^wxPr!rHOhaBcgxW?WNxG}} zU|T!Lb`1k8HhfuH)$0AHYHsKpt>)QhoXFK_+kl}p-azqFt(sk{m02KOFj(o;SSD4b z&-$(tb`)P^eUgyARaJtD!OD*LhGjojxL_F_3LY+A)Q29xX?!yuj3-T?B<*|l#P_GwRW5pAR%KF4i;P-%AxtUJ$_V{ z+&je}{6?qjNtSvuGW*}7{PH+eRWYf>(t7&3yH0#NPU-d!|2*AJCwL$_2l(i@QtL>$ z8%W*qcO1$jC_c5KU(35y7|?o2x$99b;ozp2CUY#}LWULZk@@B~3O(08fm_{q576^C zrhaAlxFI#HCyrB%=NlouXMEPa^VxW;+phlur)*=ChsaaS=%RD^Hp+qL*8Ucpx{tu{ ze`RyeNmbcwO9YKi@C?7s(0!l&8FsTsv~lbLc1F(g1jM&jaWtnLp2mABNM=pQXf+s! z9HrN&R8G`2DI$NPY zE5!4vhidM44yx00NGXWUQr%_jSgVU+OTnN8f<)){WZ{kgAgqckSvy>*jr?dKw#Uui zXe-M`y_$P$oJ}^RVcUy5=jvKDSN4w$kAu zqG`8P%)tnA*wPnnAC^QdTP|5t@}_b$Fc)7L?C*|io|cEeV6|3I1}tpu2M8_z)oOx- zQx$P&qA=uhj3?rQDm4a9BxLgC;6y_@H-?2H;(XTtpps(fgzd!(@7?e3EjA05M*S>cj4tDlPi0zvG*Tfb+*03MeiEW!$nB+7or`Ze; zZTX+eawH)d*zee>@3gu*`ojC78_cNhjsXUa5)IKc(y0^S33H8(=eGPkI*(d2XxtlF z4934iNPlsj4~!PP#yGh>mp{VvAebWj(EdP&ssNv(KrDAuq&Pp1-|y{(ABUHIPTs+`ZRl57DTj?D`l2>8p@DgBQpa9H2!wtn6; zH;M2~hbeMw2x!A&*}+sf$@Q>t9cmwmK3N8a8Lz0`RID_2XcC&1HLaEBeaV)!$8l~RNf96(vatMCz($?c2g$#ekvNmc2*V{gu z4SpAcmL`rp*dV)etKs95_nArq$#7{U*7I^yRB;(A?7k*iDE3*VgZSh}GTF3C|D43!stU1DZ!+=wYWJP3c2(gf0#;$e1qWc@-j#VA;bwar5yYX*^2sRY6h`ebj zi*k)*Bydgd(+(P#HJl^^$LE>lBj85+(CuJMf5>cIcuLszad7ciexE|F=;+- z;Ch{ET0s3PQpw%VYVY0Sb4#?)*a1H5CsxCG%6Qmx82>un{9j^hfq1~&l#TI7i{dVA zCvK}mIu7=)s@K0c^Fp9nA%-3iTf3zA8u-fDE)BL$pmgy zKw-KR`s*P|5-WZ;U=is%S1-ic;=M*FSv$-+Yv>{~-mD`~g-$AeTh zMVzo=%hs+y-H3kI^=SM6VpY2gZ+38!YsZa>P;pqn7zG?mpVHB^G3Q6xanof4(V4(=Gnd4cAde#kG+^!ebeLc^}LsRcfjb!!<_feEIxmaTAP@1*<>XZ2dmNrZB$cLJQ+>MzTcrtM`}R(v7EU06*T-+D5>Q1&!Fv9==` z*w40V&!LiT{|{99CZk>tWeY=h&a$o_fVVDN-1B_n(Yu7-DHf6F@v}d_@7;sl{@7o8 zuh51a%PN|v)uo--D6*xiOJWk)7|9Ps{3WYU)WmG>i@7nk$e&>;6pQkq9C1JeG$LU_ zq)OHi<}n1_5W(U1tO@c;8FG#TP7xKmc|%+ZBP6M`I|yhJN+!cV zoj4USM=gbt>vy4LK0?U;e&Rp7YDJjf1o;RrkYnjS1Jy3&DRg&G#Sq{$wKDq;0lrBz znQ9Nhx;%70k%jQj;@W8z%FxK)v^siO_Rjpf&z!$SIjJ)hN{Ng>=`;mu!`bx`C#l9& zboxiYhD}u@kA{##^*ChQNfVc*BP~a0$&H!H5P2?#+|vYM%`s!A)8))h*Mj8HLBqCL z#?2c$C(kJADe9l3Yc`Tq#a!2jA$n80jw`-wj}vMByLnYp+e(t-RSBivVon|Bhox-7 z%YL=Q??comLw===KNi2_Ly5q?ykDQD3X>jtp=)m;xOGG_x~?0rcI0Gh%n^3>&iJZ7 zA}6`}nVOvU#RjJFM{lBSOduNEF;r(EAPJK4Zn)qj~-riMUp^T!A7&NhN}v+mhb zFC{aL<}V|^s>=b!<(@^w;MIi~@3h~B9(6t{$r>{o0OG>aue9n2-(Nl%s|B({5$wBW zb9Z?K@$6btG6uCJzxdoMe9jli%6Q-A(0c8%l-%rjhnwxc)WGj5Q9BGWu;-;4P{RG9 zLzSTx2*w_wBkbdqWuW*}r68%Jmtzm|9su!?bFj)sg72sZPP`ahA-jKh|cap%sM@!N71}F}2Aa3aV|G(z<8VFJ%^t6Ih4lD8(Wz zC;BIXfJB#&#P`57khA-5@KqQHA0pDIA?B(19O9mR`FvUp{tt#r=)O9YDg`|FOh%F} z68%E;nt0<2MquabPlS+%CWM-*&z>ZNnwyd;cE#dG*d394Q^$yU%j<-f<$pbt)@#|z z6C$6RipF@$s@k4EOi|3XJu}>ttB4HZl(081nfKba6Mr6Psx2M;PROKbkgIZ9S3&HJ z`O?u*)r1i!(_LY1{o&dqMH!Pee|#}gwj3(FZ@|Lh7$IkWev1*s)y2erC=)($bH*L0 zgh|hyb$XkSWDK4j^FRy`(0wt zO|5s4=p(WiB#+ky@80B_TJ9$FoxY5MnuhFGoxh_|83+i@7phS zRTTw()a8arS)+{MYHH5CZ+!}FP8A&*an`LHs=!H#MCOgGnaum`Pi?kfoF*lJ}mPZrC%ZD4BMX>zQIw^B*#X=3!4@f=r;>$kK4!| zM=};xaAfl{roFV1slRQMSb#e(E@E0fE+k_~k^MNggU$~n65Tw0K zm<=Qoqlu(|hmGQNg@2C$Ga*mf76D&biOv6$%x%&h&=Jzu!amvY#?;Ze%(1&O10B1+Zc z?mI<`bN=>~fOi_0ibmY22iHFUy(Aao;9XfXIXCpuf*?E-!g8uzv1QZEGMSvPcfJ-G^{oK}p}Xjh1TXrj z@E&pFhtE-2xg%-KE^j_e$_eRn3Fx5}kRVp@0=^4JO*@|dOlz5!blK13bZB=KZt5Tp zQRWh}S$}`OPwTX{$v?8)W&F_jcXY%umvMfBoS0yJRtCl|OR0OVGbX~afT}Mla@EA` zBsnK$s|(74%~-A7Dv(UMF{ky-n9G|*w-RGBB3=l(SDGhTqRC%T#Gha znrB8K^@orgy=7-30UjnZ=;Gabz1z(XaTs}c;EyM}F}{Qn5>P&&O4M2K`>)#H`J(a< zP*{?x04NZzR4lJmAJP}|3|<~n=7vquzeRC{GI)|D5~!%{R%&Gm#-o3DB1AQUup#VH zR=3Y#asgZ?Xj4@106JL$j1DeuCJ#Y!#xJ|WWfh10lAPs*q3-Uej- zc>0o?$rZ1;Xf-(47B@Uiw}`Qok(Jlj_4OPw%q-L{jlSNmP~2#1wvDO^mu8&j@5!=C z)UM5Mf?V__Tdfg1TMvkvhcdvxMDxE0*$w0~dAgi7NW!E0WXPFFZx@o_Jq`}fw{iTYLLVUDE2cN|75&S=W}7XcFf z7O`{%VI&BBZ0O@jzbp702pR2Vs4QfDF&;})Nw_1FHQM%L)e`(k&dja*ZQCJY;+1E$ z;mM%!G`xrptpboc=(ARcz5YYO-1MJqmJKU|uN^lfMDGX&5@9S`OIU|0*OaV&ec8b1 zr;D2f1Gnvg^GtBIryorjH;cv0El>(Bl?HNzIvY%1Nt2vy3A~#MnCdI})t|J^xF%cz zW}hf^{)cL=e|$adtGnP`b4mkiM*h0)s3kfb)Q!^3oLk5i-~??B&l!(EO&RO)onqQ1 zPt|Xpn0kdboQ(pZRDI>Fh*9ZMJobD=_zQ*elAKBqfhIZ`;%s=XPJ~J+m<2mEnok}M zpmefKKHu-3?7UpT9F1e4mUBVrI_|$Zty?W9ULGd#E7&NF2SJ9*?Mu+Rdw@KCPbUngx$yqE!nw;(#_BVN0(a~EHeQlq>6?hMImbWubefSn2Bt#quCUb@Sj&9 zl9iz%jQ%p~>G1@AhZn1T((qb;?f@wlDjOaEYp9`;J@;Y3TScf#K_;7g{kyzM0zw7X z>TL~5vTEQV?{ELM6$&&$EQHARuNa4v7|l67p2O<)7ysaUppjtNVViBYhQKl2Xb>?0 z>BB#LsKQu5851jAz_mySAkkEUI$UHYi$t%eeQB^aS1!+n#<8KLj$qRwAFF2WXbPgl z-|&ffvkkq`MuhM#BK!TcnpFgJ%vd-K=6m`0!O-&6 zv#5yxkI98;)5rP|xh-l0w{U6mSB0owEsJzH3OTqQ*g#obiJT+@37@R7U)xR5v2D;A zFU2$7S%!O0e`2f~)ZTs~BF{hyz*>@B?tib)zt}!~nly>LE@O5a+iU_TPVLN2_ec9#Mytq`Pk8F0Q&uaAYiN`y~9l z&o57KI$tHWs`9=E0BHL3RqS-0lU2XVe9x!nP$)+J`SBz34-SoUhwMO9B1Kp~F26Na z2sYR!W_U_4Wa0^S{q0K89^{N1P021n#wvJ!HOv-G__~XCVZ=8{c0`jQ{%bW|X*gyA z)smq@tj39xwmjCvlu5%WEqDopV9FL-Khqs&cF1HO~}*Vrfj_9NOX)b zICgk6yPZ`7a9`<;ejZaj&5C#Ze0O2LM|k?E8G8mhYv;qx&m1YLUA$OLs+L4DaRvwl zmAp?bD&!lFz5vk82)DA|1^c?DH;59(yCR(B6OsiT6s+d_n@Z&YafBkktfEg>$p;?7 zUu$i4HCaWdQC3#%Q~Ms;r(3o?!05#O&6IMVTb^Q@rl${RI`@Zd8yJACmo6DU3?5fU zf50`g{n;iiQN=np1I37Yyq`WdOit>%pM4w$H*o2yrjbSM6tn3s^`x_lAvdry3+T@jwZq z67(lW;D1=>aN9Q*>W}$&qRlPgmXrYs2@RjGHG`a;gRP>hG1vkedMp*7#L+Usq(1dv zM?OFkGx}!<^o^_Vi7tIhdAB4=vHg=Q$av4O$^Jqiv4X#5Epg`R`QLT#dFG;h*7Pkh z1AP|@gC7jpte1nNX$ClIO)ZU^!dZNfeM#&i% zlgLdGGq3(BKO$G%I`7p^0e1E->&p#%tXXv!JW?l)tjn|T|L(2S+dP7s5Mmb-6@2f= z{?YVfPE(%-(^dMlIn#k5ERnO^kZ|!k0_O)B{T%QBbk1 z2yM?pDrR$1i9fUnw1JMgD;KEjjIq^1@!pE=v~@i_Z4pOm_CELb&bc=>{)|x8w-p;i zYWJjD0!~7bD7{KBqo17!-rP-O917y?N7=4Tr)I^de&e@c^NQiRl*bbmq6th0o_?Qpx0{}e8M%~Uvw-NjHAu#_R_Ghl zXHZ8MbDW|zU)?rMw|1$O40Jug0sD~7EH9(t-yMT~RwEv%E$$5TdkCK2E^zO8{IX*o za&yB0+5QtkPAcS{Nw`9X-DNc(Dqv1}f-`wjj-&lK2{k=paDP+L!z81hR)FGw{mV^xf29R5NJ3>&&Y0Nw$hy|S?J*glulQsAOPew z3dHu4WW9TU@dIrB9}N@YNWhr!nShy5JnM9xL_t!kx*jNnYAfDLl+7a6)Z9W<9wlBz ziPvy^ARRJbs`DoB1|1x@aLc7hvq@KJqr>AFc;|%QK{>HV$k9IWfFAg%%1t|96e9)jGRS8juS=9J zA+k(0K!}AJ#YYHblQIR+2BrFqNU44=BG`^3M}wlM_^gWthl2ew5q8o;YZ8vs0R0^f zolt3={3c9pL8L6knw^=zEYNBMAHL)cmC}W}!Q|jyRC{{Oq}iaG zdRW1iG(~W+&=bAGD3UUTz9>>Ejda@9KNlqOZ8vY-(WDdtl$*AD5#8<+M$m-@l?8ubj*7)W6znw+%vp=mSe-U34&z>xMg10;q7yNe}m zz64*0;Zi6&nf?`#7s$!Nku<{opu`hXnr|LckLyDeMw-{GuhqdaRd$-BJc`U7zFE>m zoF)5`%>jh_%wjpCOuF&Y{Xb6Yn+#s9`4O)D#;r$V))#}ugI9LgMdt4QQ86vl!9P%t z-Fo?ztcnOjP?%I6odd6>LbfwM1k7~*?fC$)yxnMbyXbs@2!H+O?yxP>S!3rN{@x(Z zaqiS?&>NH~dqJHbPj5WRk&j_S1c=+ZQlfh`l2rlj&49-n3&^m*ViT@1B%RFO@wPEQ z3DVK3U^vu+@-MS-j~<jH`)r`=^ouJ#vCku zVSS!lPji$wpd0~QIEop;9~0zX!s)ZzhuMwC$2&cotxhf?(C{iae%2_N!9sgf?kd!u z$YxT7bCvOei_#cNGUv&%>I-NmJ%q*6aqyv~WyMAmYQ%IyfJR}6M7B|FFF=EK-tDtj zH0>y}-=H2d4g&}|G)TndJNh1cxn$5#8Y~ou=xUxeXP{Es9P&$`!oe7k@w?eW!x_jB zn1>1s8H!~m5G@z@Wk6MKq(}WW8ENyWOvY=Fm?)XqL|}$YPLq?EgTRdoOh~Qn7jf0b z3>9$sR*FiGXfBpAn=gNwS&$jmn5;Svf3J_YP|Px%22Y{i?k>R_#`K*Z)xOyYVm=V}mWQ=VN!O^sm}# zPS_P;Z<@JNNJ+!5#e+cfXjau+EYe|IzqG%^=FRu4^SGXB7)1Mc6E@zaN7^EV0w)Fo zM;-o&%PjufqLI;ZY3P3XpI7=*;INC0iw)*q6Atz?i9bD}fB?WJ$$Y}M=(5rA%eQSw zH?e)I+*O&l!8ON=#*>imDt(32}E3Z z>kyyXmj%>x=>a}@@EtjJ{jSs7BFH||<1Y$|YfgK87G%k}^Ub zbwF|bYn$==$^~bfM#EH(&wpsz%RdF2f}hh-5+<=E>yKkY%eQ8V@;s~N#vj6loY=KD z60pRq9K@t-!iAC~Ui3Q&0vp*;NACpj{O5ywF?=J#{$uRmr@2FX z9zs9lj0pv9`bRo%)<32t=Gk8p0@xch#O{UQ6Rf#z?VJB=Bes9}_AKo9g{rH&Jsx3K zRbeb2ORV`cr|9&9!}zJ5GT7ti@+NIcficC%^%Il^%7IEIb0a?s3Le+^5&K2XLS`1r zZL;(qPC0km!oHej4MtI^>6tpL9&WOxR9Gzo$c)qTTAQlk-ClgMC zia8Lkt$q3~w|jV7y9@h{Z#xI~xR@A-UN2d$m-lvFsN?m31G&VS2SVWuC`b3+DCIJ{ z_8UYf29X_-OYtWG_^049OtCcL&KIzTgfU7@g3Og6Nmf%QGb}8=fdoxxaESRI9g+J9 zN-Rr%rqhyr4H6^=$`>(hzD=lV^a`tF0Hv-dK{Ln`CAVfUC7&yfGzZVFQ? zz06TEd?wH9jL@zt7*QQjXKOt`qi)^j>Wtt%6c);$eIr1nkAG_06xs?~tM?||p$h4v z-hf#4$*6@XPAo&ZtSSnadiJn%%a{5UKn%}Hc?>~CJt^;Zp?n&up ze>UG%S1J02WM19{uzob6v#_Z8sY}eN4}VPM|J>+Q>sm_8O!07O_DfwsrAWKJAirr+ ziu6C>+JNm98=*I*k1STq*?F2kud=hX7tB#c0rO{p9K9p{JKy&QxCtRl{`2^-eTKBz zFmq1Dh6Zh(=?qc~!6K$tmw2!hT*C(FmUmf9R^Rjk1faSC=NJPJvddrydf3!D$>M*d zqSTEVMM9Ej{t7vkJT8as4!Lg8hV7-N2Qo1XSw+@g6qiFYKzlwPqffQ}y`>lKIiG-lmtvzqY{<*H$?!T z2bDb~4bDmM&!Q)PN|T)1*WmK|fm?F<`CpPJDlZ-^5#!r@S@D^Z4cPn%S2k|692<6- z3qnIvtRIU>$85vJ3xBBii+BS(kIKClJlJz6juy{t7G_LBC|fT%6*;`qi{Ws4fu67< z{)H+DF-69IJfMtR8Z%S&cRS~(r_<@*l_|NwSzcbCi%7+VYN{GR!+}$7&wC9WXpvBx ztAowna@8CtH_-|Y>Jd$Hm|ziLfv>my8Kw1?w-6e9;MWgkw02crj)a9E&rRRr=;OiG zfg%FpHi3)7^vVezs(XOk_hskIh}R**&ZIOp48m84@CaM*d7tHKN6{DK`}avo+l%Ot zLk_6En^VH80~uHc7=%g%$p6oaE(NHfd*bJTboIcqCb!qeJhwVq?&XW7<#Siado8Q_ zhQ7{);t2?qC;}9R$vzP_Oy$j!?1~x($RSqar!r^o&Z=KE{DYbxkq8U7K=J+B0K~%L z?OI}rPt$Y}DIsl*jh_}qCCSl~!B+@&fMzaC#{EG!#ROAhz2eDVfZNvR$6dQQ-!doYFphqH7PsrCL$~`u z$MwxkBfhCr2%UWnd5MSTaW~@7&F77%c&>GnNvcHvDwBquB!S)VXMUmK7n%)gW2tb8 zLTV=`ED)5E!0`_^sPGt#s2gU=Z+aGWf`ZkR2wRiNgwl&weDhHZxgI#H9P!<%Z5i=O zwfyCPXC2%Gf_J3xKTG8BfhA0{Wn;O37__x--gHfh^y)f)3>R{bl=4znE&5dI?L~Ir zA<0IT*<;9LeLxc|v%P_?v>f(W#J@2)Njy@%=s6Btk>vez^+)_^3UtpUSEK?{aKhnu zQQ=uB?g({_-_n{6l9>o4k7)R)5t6BtEggGVkw^n2CdB*yjLAifljFXF8}@*Gi&BI1 zRaO-vTkov*3_OpGq@B{E$-VbY!Gnl@JzEA2O(6VW9VfKR3g&tIWPhJu-Mte;3 z{`Cdhlu)f<50;ZE)IRMS2HhzQ^q8dlJ(HA6_xL=4l3VAPh-Xa{#@yheR#9(bzw)`T z0(TtICl%ZresZ>ZZ)KD=1SVQetBQ;TQRKL9g8wXrXYqB2X1KBsPOIlw79S0CE|QxR zkozrVP%?4#`yEur)Uhq><+}*pKlp|jDUZv+R-^*CS~#y(s7K`_6ENZ$Jq!co6r||7 zNi&kLpMhtSs(lchF~{q0_mehJv8E_^kN0OD3xgFsI?8wCX_?hTjv^I%SN;G}p~P5| z`E_8OAyq&SYQ&fiR!HS=!m^%qhezng-Y_tX$gc@tI3qr0lH(RIA1Z zg2S8t?#?+CgCBW=So~qog6Q}>l-yv1_Kh&mx>2{U--KS@kht`hsp&+70&+^s6<6{+ zCmEtIDzZFew~V@U|NgE5O1>l__9(~JS^zyXHHLm=gMeq3`X4jC!TP?hY=WB$bnuHT{D!U`dyk-zJ$eb?i-+PLn@b0v`B=)^=~Yv|EaXU>YOJdVW-NV&6e zAfT-3q$ZH+H`GtnH6=KF`OECS!-HF$-W-A%lkTuU6kXfT_hIhX#xc{`mE~nv%78K^ zGUbw+SpP(ONAL2wlEu!DFfA~) z4ym7$)>`@SV7eS}S7s%Nmm8Bu3v&8Bm`CPWTa`goqs=4tvVj(;sgx794PVd;K~c9; zvEL;knxm}G`y;8HX6_#qWDo08>&hf9i!5@kMUbmm=uVUo&|ML63DMCHg9s;xJfTwY zaQlmJoi#=SOwHDbVt`o+Kdh-~Mu> zs7L@LS=>JL%QEU}44T|zFWiXl1y04xRoIA0kNk3iV}nIc31H8;BHZ#q^}XJD=Xt#S ztLpW7j5CO{JE69w3W99@<0g2_Ubhj2dR{I%WBQW_L|yTRAbaG?yR1~M)&rcpr?GY&h5fd zYn^D8Xb~UAdxoJag;=0);%}EKf`>0U+My~>F55!BAFjTk-R~J6K^g5hX7b=2E8I&? zsXY=?b}Jnd)ek2@aDR?h7{n0tt94U;aj1h2BHg=c1?l6DaYqat01X^$T+s~YN;1?u zCwcNk=P)_m&~Y?^=M!^YTV*Enwq6M+8q8mO>B%T*(z%b7WFE56cYwY2LpR21coVvZ zyF+-7i^YgUxwtda&_yqSgT|`E5{;Ebs-@r7vCoIYsy9D~oZ18+Y(Ot4Dcu~;`A~+d z`$^|dOJL)Hc>EMApP_g=H9nC*MEN)XAO1E~0SVLB0^7$g@WE>BnwV%1%=_m8sCC44yk@>Uzt?%8Qzvr%PO z!ZmJpgItH+!iNxNek;ks_|y5zdt2M+|J2`d5}H^~rFw^3l*)CV512DN`HxJ!l^K@a z#1#fHJUzuxC}JjdFgQkNXwFQ~)Q?sl=)2)PyH8}@dJi{`R- z27P^(4C|L2p;Z`e_$}%ujY^cTlV-Q|S-RrHaAaRHDB;b>65V^7yRPJ4AAFy;b`GAt z3O?Q9*puii)Bc|MBp!iJixZBvt|K(ev*m$$(fQH!K4iQ3c|-1IW5OIFP`TmEXG*~1 ziv^`{c{nc{k4O{o=k@4G^B>4Ya-vcwjbgB_&*8x-DN~w<{P>=%J#Jy-3y+s<0>wSc zT2_m!rQ5(rQjhSs`_Pg>((4U7-`_Tu9W&=%`ATXGx(~m_IQ{@0$yXY$vykD#bKia zYPBQdo(Vk6Yij@9II%nP+uzW2M%MFsXUE9thFZk!IA%{kl*EXhLc>ioD`I1oS!$%r z55*hq!*`6Xvy@uCQ%_Ik%lInsWCU}3L^NK?!=TFR{IxZ0KZvqQq4RkML5SwBKr<8S zzkid90-1^`$UgM&j+*w_5uOM0Y=m*c&@bhPpOka6AKayYXQT$@gCtaC2EvoD4kRL$ zV#+F1F>Ymcqcj><#=dx)B41tp3;-j7HeaeY1{FbzUvD?$ z^|%xIc#bL9gV=rNovGmZUZtmy+O@aE!F2-$%j~vVhT!e`rTy(I3{F-(u}3s<)KK}| z@Mz|ZBfm8aMfbPp&#ZL9uu842YR@bUvz+N5+O-b>YL#Q(L8YCg;5N2^iNoL}*^j`C zZ{p|ptyS;I~CGlA9p1K?} zGmxf-2L|1O<(s)&kKFVz8QCT6JqYCo!9Qr*niI^8#z-oKEm+Ue|$9@OM={Q z_JXn7$&G+UO!SN@DvALB1^pS-ZwaPHuR@>tTD+*StLudxd$lJHA*qSmi_R}C9pF_{S z6ONy(RV>AxH~FNV#HJn)C+g zHFtdlGK~k_J%gEZ{9-JobAb44q{4pZzjQIDinekFcFcM&Zcw?G4R>z#hanf@T9En~ z|0WiaTQ-kiSx|pO1LCBx=~%_R;jx_8=1g@hRd#Ux5VSlXN;6Dfmy4H3Z}$lH}B5W{u-5l~sKV zbhAPzoxZZ7pK~j+vcf8_JK@FAo^Qau<-I1aS?@85!Js?GWlQIWPoR&XS4{^{fAagQ zC@cmM6j&#b?5lG3=M{y9e1w4A>&E=35PJGQH=*neEawbd2*8U)Otl=mV%e7DB(Sqf zg!Z4TMABT>+q7!bzHalht&r5E)^9*(#wc-vT5cG5e59q-dHYQrJeT{&FqM_)o>%rv zkBY{CVilPy6)zo@L~0!6cdO>AfKAyfn{jX05*ZPyXX3TD@QdJEzoO89@LPYlRtn-c zBe48{q4YMeQ1&uh_@8&jzhm-$*J%IHV-3Agc%xFU=QEE$w+HMSn_GLbQH%tV^$k2+ z&GQ2LmzSu^5Y4c%d8^O9`R?Ix<+t9Povc!Su$_iS2b}sAh?O`9VD~82sa1~={s6ER z__BPuHp?*ZUcbEM891nR8SzH`=#wPm5$3puMDWNa#VqCJw=&LhmV1VlLc#Dx8jGLc zux0Q#N_|AWf$Mpe{GmZzzdaTT!RX)gZ@-fZy&M_tzx;*$jQ&y@;LD!>7lT%rlY$+Z+Wi_%DGmh;7Lgr{@hEDJQ^l?tVwxRz-&GD|=qF<<3~YWt=dv4MC7v~x-P z$uaCb^DZ;oYdKtn@^&P#f*Y@)O&4``Sbk??&Ui;~^?um?bg}&cmFstls8B-5VrJ+- zF;*#Zc|O<&`4ekCMSVPe^rm5LfzITI3y0@1rgMY`AMR`*t}i`(eK-<0LPV(qdti=J z&ZVRGJDh>{8$Q|>A<?A0SAFxv zRHye}IJ?5OC*ubX_r_VCeR+I49LR0{pBJEV(yg=e?Pg5+ z2-wvGN5KLM9u($ZjdKNtC4{ck*%CwI#2m1$#nc zvSONz!X+f&x?+U+3XraoC?EToB9wXrD)XOu?&Sx%+AX(#E|_H@euc!jrhpExKMg8x z_2HN>@uL7sKhQ&yEmo`SVYhvC_Z<3JBFN_cNpJjVVj`!#q)Zq1OrL?6pShn%&jQ%^_S0jj{a3QbISFwC^_)3$1P;fNLXMQ@4VkUYpbPtf6Hs`p|GQ10IK(l}lN%$A z4rkj=P_t@^0-YSWC#lP8QHh)G=b)lR4o~b08LU^i4LA8 z{30VwuG(dg0$(RhK2=K-foF!t#=Zt8!+xmw^_*iqFw#KVKvn1p=F2}kL%aI3@-K@$ z#`i8?XxYs;36BDnK<3N(O+-S9xCWMC5i842Q(O2)9b6q^maNx!(nOCCKX5zB*t|A? z%#CgCzUE0!<*TbU?!=FwnpNPEUjIZJZ!fr2uD2$HP-FR8&Mb9O%QBa5A4JUV&MXF{ zwdSd@HP0}&s05{{pkIsXyqPJts72Jxt@b@Nr^DC#Dv|Ey`F#l3!Tfdimw7i;gCyXY zC@qyu30{ZUt_;B3w`i`EG}gUTl@=y(Xkt*9WFg3M;mpICAWV8O(Yvam;!wljc>K z%A!2K{sPW-x45e5e?ZYq{W@)7Ff!<1T0ASAvm$ZPRkd~vx)Ia0K#7m|95-hFERRfL zM%U7|wlCHF;SIX06^ed(9Fy{9(cLVk%R4dSZ;AA3TS_Nx? zHA?mC(C)#6e4`MB65SZ@=oOYgKDJk77;XMwksHBBApiLgZTXBWDam1lM@;CNLpp9mG<~L;$NX_KE5jB!aJcxkG?&`UB}O*Eixiz_q%?-`oX$d zwDb2e1hQ5$>0aNRg$zU&56ez&JVpk%;-{l@zziCnzb7SW#r2XoIp2TAC-TfoA9o%z zh{@tN)Z{*VEee4IkraiVVdp*jh#&x&??k=#{2yv1~`mQelZhVlkJqveL6|2sN^R$}&}lC=1}%w0e7 zSz=?Xd5-%BqQ4I)wczGm58g&RE{CE*&7w=Cr3PKN2QM3VlPKo+lIIxF*$k?x=LgM6 zl~EzOP%{#q_K5T3THs|Nv9mSW#qrCLrSHlN%lFo6*4~rwwhmWapiq{F;i^eeUo8^r zD1B{apQ(a2h4QNgdE<}#G>`>nB;=U|-FRPpJ++fW(i6dKW2%Q8PEv-ZQEym*qSd5K z=uR!iXp|1{LE#UEn}pJ%dJ`;REQL)8(heM|$l(n|D)#L4%qUc0#!GjA4|58h+yyvv zJ>Wy?$WR1)E?6OTibW$a<=|7qr8sXzYzuZHl{4#wPWoG zgM1ZV>6&rAOOhnll#uh6kgLKOK7HVrWqWgy2*W66ksVzM840HzYO&B~GO>W?>=y=n zfIB0rha?@`mES9g&npBUZa$gWJV6Ha`VJkE(HxsiYw9<3#146iPr$b|M#P_OrOHzf z6%CcN`hG&+)Ud@W2V7t8!X%ju{U_5ycETO6m+c@&x3A^HV2+5{wyUSW^|A()zc6pgk|V^ zYqk7E*}U9C50p9GgOn^v{Wr&$^w*hD(WUcl2EKgMp5GE}oMzEQ@L z;X4-5SkyRFk3}AvLFk3Iu(94(A6l1cR+E@MqQiOkV8u~6I56NN;ptnwv<*mMH z^_;2?(bju%17f+0`X^waZ2p;!dRw@XkqW{pH;S?1gyG@jtLepz(%MvMgtd*8Z?L*E z;hrJM8Pi#tlgzg~TQ^wwOB5nbGcj6`{WlIn-G}?rz8P@yO|DxI4~v*2%!NdPVzL!z z-aQ6vo;lB(Ay!?O6wlrpSM1f^icnZQwC^#k7TcgZ`K%H|VF>^FKdds7@qvEW< z!uwt&DXrv0IqR0Hu!2;<5iWYo1F>y$q8}!COA5@N`cuR98igL=PeHlYnA~^A8!9e# z$?P%tEYpeIHW`q!@N>t%wX>)5yOQWB)8mxH!~6w%RvF=gC{S>$*ieB~EK3Y!3h(#G zmxX+Jwl6wQ(q>SZ;oXg~UKWT}E+jP8FTk{tE!BrwFFTTLA-5P3-Xo;8=%Gv5+z_Cp znGQ4BIXY>w{w0A1*{BOEeHf`*OwfLKb8O&+IocipM{X!} zB9i&w0}jl{BVz}djj|DS8ivlTf_1Xzw=K&ay%b~7eCTBPM55*IB4feVH1fO_ozmJ) zftYg2>H8g{&zK!br4q*YtD7DxAVmM_j?wG*=tMgqgN@gqX~8A%nUj91na?BSGRO@n zL{%E&kw+@NBY*_v-PrYFYUYvX6k%2`65^v$QsY z`eN1l{Uok@Jqz4d?%y!d(Y7vPZoR1F?RA_p;-J zGtNGu@Ye_7jc*pL0yStj=Xgb-EbA6M?$HtfTE?cBm$BvjI9=~k>rcb6en4sx&#HeH z9x{8pKOu?=EU}^mBjXV2dKxRVJ$wd4E?`-3OieUZ*v({w_MShJEz=IcsEi=1txdx$LG#caUw0 z^BxAUH4>P0B=ji>jd~D06hw%Hk3wMPS1L4dX?l{VW0M&vI6QIH*P%F!XpE zdUygpPx##ry23pV578lMY)TvLJ%>{rbl_BxXyLLfS!}EoOiWOwe2*0K6`yx4AC0t% zM*sp6cF)S|Hc(4{iHDsgA1KnV3$8)p2H* z2Yq6TRpms+Mz@c($U4%-#w0OO@71e{^Ai72_Srr3dr#|iu((?yS;;xhM5RBgYpxrq zNGUGXT;yHH0{U~~%>z2!ScakM$(Om}eE8A28hWe)Kp`7C3q$ulz5o73%FN}s5+h=E zN+V&C31;>Lx1jbA`ekQ97$rBdv<@oOsMwU=g0~*%m4n$hfHpzVHfNBQhyO1Ehum$2 zTtWfQALz^r()G^;n%>jACf&kD_3J>$d*hrHOa#u%#urnajJm{Rr>$lS&tFN=#;kbC zFm|tIhxc@f%@=5m`z_a`ZKV#mNicVeEFkm}?%!2EkQL3V+|}~Q-Acg4*^N+Ze<0Ki zjP@W;L~^R!vcfIOyA+VPYg75k8YQXx5XA_HM@XvQFFCPal1E$*!GWm**1r3N_XDd* z(Es54ga~CJG)ZuG9UMN>ppeFk%;8q@ON3W|eP@O~df(qywLV3O1{4TRq*WXzoB?cMFI3-$hjG#U0M) znQMiNRx}S@75idgT!& zsQS!6;)_nWg~HETu6N(TmA_vS?ej;$mS3dfE2gvqaq+}IO(0=Yn?O-yo8Sv6>q(Id z!c2gqGXOnXq2>lmPb$s}R|bU`L|6n}?f15Z>|+lQOGd}*y=Hb=q)bFlkx?dMd%wZ0 z<}{YM5Vz0NP1@LAzdfE~kw&560G$Y94vS)eKk3o2{C0cB|=2OiF zr-yegm4oe5&+aVKU?NMiQ%ykw0vSURW`PkfbXi5`2tF=c3Us~uuZ93)l%37T)qg|8 z7Vpm$Tc0{9CK*X#HGXo$Bg8u;#cix6iQ<}*CI)H-5KVf2`gF^)bLcwI!Kkvj?!Ktz zm~n(0K_w|aop_j}t!7nX3Xh{qF(Rn+HQZ#5ixC|y?6L3exAzy>lAdasZ0W68HELcpB9=lvHDimRgm4;^5*IZU zDM`5Pyn)L9-~{kWnv2rH#c$3!VZ}y1<3#hMnrIOCh61Va#ZQZPvq?A^;8=$$ zF8PEpYJn{Yu|&xWEVh|Aj1uW8V=b+ngC_#O%+Qa1kZYN<0wEOH{9p^d!;Xs2eo&*5 z{3$4O+Cz5CpAy1Hzf>W7(!+M)NF|VKlf=(JnqER^yb?7&x?zi9gvu!(f0=XaY(mYj zNw4h6$I7_Df*0-LZOzLYlRKj+*WB)dL&Cx}D5QAn)4Jd7XOT7Ao+I36B)#iKA#kHLhs_8xS+Rb7A z(l?X&3ynA?35BiRpn-73=ms){1I4OrtSmm2E;o&tVW#h&QsAleH^dZGawc>*nH&Y$ z`RD*Fvy}k5yZurvZFML*H(bp}>clYI8|>o0uONBFvyuqO9~pO|(OSKG*Tmj1Z?lQ%R+@Qlh&S zIWJvCp$|i}(Km1d75kc~XDc{+-O-&ZC4N-R|*&JhuMP-TnBV$xQ3Xm=QFC5g^_%}Qn7rK75n>&l)3ws zgmV7mqN`GiQdsTszZF^Ayk_KbVEQecAgq~ZPV`=*7_$s_K=}%glP0yXpC#s2wq{$MqZqNC%TihqM5&!wu>|7wxPq z)V8enV*=Z_*gbgcJ+L)-Hk$^gL?~#Jj3R!p0 z&$rusnW$W3xuADXFyw)9h^uy_jlG(CsacUWSLpu{o0`sbDI{+)v#c`q$7Cfi9u2?v@Q7cbrQ`A0O&t+S)pY#gRr+{hx+D)h|6a?sPl0v5bvxf6 zg%#S$(y0rS$}yb0n_3z25LREtFK_z%9SUx=@j(r;)zZCte{OtT0++-TBs-cSBb$^T zQJCEWrwmVa_`cY!KNNnze`wbFtuGz7l6Fq6S)8sRhl%CgcBse}R4=&SeoYb0`cYu9 z8^wzTsjMEM1Lhp9p`!9aP|Aa>p}Sw;ARE^yHG9vU93QsMq$$7m~Ph>i?S z9dfGaYBZT^>h{V9e1rQZc7Tdy)6#eSYgXZbzH&&l8;vcja9!9yamBH$qy~_-021i! zpG{vBp^kRyI=&Bzi`{(L<1mHkjal;Q>JjhiHFeMaa-^_;yY5#S=PZgza5LH zi-%Jd3f-=VZ3%bJSn$KPg<; z1Ajo9g+i~pONJMw^8Rn;v(~cIpAnq(OV8KCW7`o8>1U#%_eK|#O3(GOm!JleiFWu| zrq_7~q#sd#nuig%2NDmCLuBPmA9%cZ8Y z+@xC62`IgD%*w!Z&vf}PnO#!JeJi7&;l6oUx-`zW>Ked+nT7);hA+eqAIUzg0*n>^ zJ==!^^&KT6v zg}>X!UYJu#&NvM~qN?ontPm*9(09?puT>ai$~9oRIyU_p5X)_TyE>eu3ng?8xBM$v zdqE+TK;uLTW<_xaoz^vH5C9#eBNV;WfUN5{V$8}z6eX4fib@qWm^`|*y<7CPrAf}y z9!?Ko7!eToT>!?iA_qEjB2R)T=}&6~;^1naZD`%6V;RA0gbb#jGn`8w>*!A*0i4ab zmC*O8E#%Er5Zg{SvNHD{wG1_UX|;tB0%ue@Up)K*1pec(Oo5M@KpP}YdiVpTqZQ}| zXg=Q~Ux0-g=8Mfzz>ha%QIqpy=oo(mcq;zE#)8CZpSUrc??1bObP5WHQOlr87<4Vv z(~bHyy0&0HOSZy1<|vkiX;CO|&Z6xv!R+uXbs8V-f4;#_1RUHDpjQKJa;IvWHA8SP zP49;Lng^9jTk@AjxU0gh)G4L2h$N%)18#y}^dK{Zw-SDyN?>D5>v(k%5nru5m(rv* z^1^9r#aM>AY4RiuVr8|YBRRl)E~~3Y1)mO!7E%0L6%WnL?>P&mBBLBU#&NJGomR27 z%a48(1UjohEjE)S`0#R)s;VlEd*7%@4N9a1+Kgdn&y|1#d|MU5Ug^cVI0j!P^FkA8 z+NQmLv9AR|C8VU(3@Y!ok)E}*M91xV4xFU6J}bu^eviU00*Cnkm$eFm5N>y`V$m~vF7J# zR~fFftR#DobJ+I-!HK)z%TW{`U{h<`Bf^$#U-#2*X@yrH)Re`MAhocUC#-&A7VPWs z?*gc&y%)ltY+*^sH%n_M6Rg7=_wVZVO<{RjGm9$G$AVA*>joVXBI_-)v{9~c9Z#ig z&6CMBY_Ntwl1#ROYqrLV^3?gL(cFs!hkp$W$rVtUx4>Hb1_Q6lIaWtruVMVgH9OKW zg3yk0pVY`tL6zlz0&xqfv&`8H)`o+4R_6cNoIovcP`%~HrFpDX^H_e}mTPd>c;)Yj zoC##4Smq#U_mmOAiUB0GzML|cM!-;vmHMxOPpgesv zZ8^U#iHb8iP~PQZSXkq$UePmwC*6a|e~@Rvijt>TSFuInkOcvO36M=Gy|`5pg#i1w z$&rL}$z;Yl)1L~!3B)3*foxMDfAs&n0D0}-{_22@+t-2Rk!LKC%Tsy43Zd=uf^Xzk zDb^xl*GTEVWBVpyl%Udp;@@M4P!`Gd?`?Ny4(^%w&j@A5b$IJ)!sL*SO(q$r(2^}^ z!o2f47G@D7;6#PqTz{Dkxt%<^aMDZEAmpiQ>=ROp-p&kBSrPLzNa>lhP48+`KP`~S zD(#ngnXs46{d%q;-2cIW`h8lgvrN5|t$&G4Q9d^d4GPur`!}U%fqaY}=n-hnL2+LL zt?D&}yF+tDImMbJfY6o<$dK-!-_#WwMd5a8p~BNbs#p$ zxv_2I>+QKi?qXMp2HSQwcxOW@3(LmUqnR~iRvAgI_bQ4Zt!Xv^QBqA?JYfFL5hFBLSnb~`(ROy7mH>Q7HtVe*|5qPABo>`7(aFy~^o|N? z(re!&g%q}}U!b;cE(wZouYYSI`pG6usA1KSi_{Y(ZW^ICTdQTxD80DedsQ>q=s<Sde3O5J%-XFA!ujP`)zyWy&)jda(? z(y_P~TQGl%6qr9|-q^olX(c>asMUZB2GhwZaq%MQ*v)apdX%Onc=VYB0MXxs{Yy`U zQt@eWN?S@ZUdKo|w!`J=iQ;vLlBocX;MjNXn+LHFr2d4_C)iaVY(``j9P#xQ zHIvF|o3YbVPwt@mumlaR%2_1`s&irQsotO&R9b;oKIgBtGu0jQDD|5TIHDhn@<-v8r)1ak$yf7XW3uFhLhM*igr@J_=dE%^S6(`?nLl(DVkA>)%>dX zz8c{5U($+1apeFxhh|w(T(eYCMI$StUZd zvUXea9u6t({=A0WRqZd7q7hz=^YExHU8)4%E6*!JhZ<$BjrH+=LTq4Pkx3>a{G>8l zyF-Ty-&FklpxCWDk4i(E>DX@1`z%K405NM}&jeh`v&+V+7sB9iMtJ&|pzE}1ob3Ob zX4T~3NM)L!#U^M)Jg_un>0Ljf;w(0VG{K0sz!*CE#r=^#zuX<$8$dr^&Ip`wcR>6x z`yQN?tqmkIVhjE5rCJKDgh1C zbElFn$tso&+La045&hG_NGrE;QJ0e{DjgLTm{Du5ZLS=HH@dEoHaL&4ryS2s1YU=L zFa9IHK&;p}3*V|p^?=>mlz&3LBT=P8uj1?7|4zGqb`RW%&%Y~&T9Pgwt;If0Ye<8u zFTN)?CE3S(<~W;5iV+MfoTDMCM7&9#Ym5^mL9+l>!=9jV01K}Eu_+>AK_P?EoU-M5 za&|;11g0%H=}AcyRHXVt0lFh)P21A>xZY(VLqk1KfziR?(+o|fn+x@_>4lNv#7IP5?O4&3~^sWLbg6{qa}`%QurphQcZ4^k;del3FZ^S;1dDp_Gm(RtHA*o#g~$xd_cuWq|R`O z^I~SOqc9SmcNNKig=3cpq-;P0LU2Wm3R};JC&?%aO&ctj*>)-ISRiga8%re+m#cLR zRiDn(-jU!P+H?8QQLGwi;uYC7Ib;?c+vKY?O(RXeBVUX#Roa3s8-7?yk1Tq38~MX3 zuE?4g0pKvdJts-sQipHa+PFNGdDDNL^T+KRrO1ASjUXRTF-y17G4=3}(Y{vG^e6lA zCgipU)n-0Y8GoC zliH>SI5Cce9Zjkz$SmL@NLqw$D`|x zUVo5PS46Xk{DhAA;DdFFSuRVFdK^$ zz_8m&2;?JB9LB(j64GEY8lD1fZZy}(*xRTFSpz?`G8!$fDMVE4VKcxFl(u6;wh3jF zXwq&9`*6Qqjo!wEZE^|J+`Nj8R1iIrrDSjT)0aaT>}x0`MIIyvpBT;K9kgHV>y{$5 z23zexn3^3|Ch`YbN|)8}4w^Y8 zcsvn}2FKj8H;kLn;(goGc)R_dq}O#Hr|;EbtTvdN!_86+F8v(i-jFt^VT?XhWmn_< zC;dToQKmFSmkc0Vp^{m5NGvB^%4FMwN*jP{)*OHj`sjST*+=t_w3zPx-8X*_i3AG2 ztBL%Rz@6xrgH*f^vGn(P2CJB(;Hm8x0D7X>!;0g=!%ndkpNB=#-G0%0A%c$STZ#O1 z9oi@Ym*3tMBCJJAa25l`p(R)7aFOmlB92k`3=NSn4K;;wMB_5q#GLg~!so3Jf zRB2mcQQYc?T|A>?%->$9O_ z!-;o@-o(cxdp~Lg2=qpBxA+CV1Q;CS&#=s=Gq8y#-1aOOl@!#N96`y4Rvb;X+cxj> zX}}c4{Pe6Ft4RaSQPnorooEAjvORHtL?+n7Hxxd&611>2>dA~{aS7E@bI{4I<%?-w zqP*gp6bl?1g>Qu=k>b+u49i8}y4;RUHM8V+5hDX{egW~zcDRMic2=I^8O(8P^`R;x zBQunmT}zdDRU{T%UTYN~G|f@L;IiJOB(%Rjokg~xi&kpQto(&wI|7x^RNbZ%5@fZBUScYDC3xqweFb& zaq00)@!9kkPE=E2CYzPMc;NvUI&(rE~I_~ z*e=)Ac!KFI)w{?8xPT*dbku%@gq6QC&5?gHwRH0DLFgv^;b@ND9-A{9R$f6Btxa6( zFz)T&A-gPHVpJ7dhx$z*yL}v_Ruexi3?p6gfSh~lw|QFP9?KkQ0USG(<};rfdA@9@ za(bvR|J7_G`IHLsewMK;N*+mA{EoAPz0+Q~1cnSHF8ItQoK)j%KfbH*gOq$Tr^W z0BjAU{2N2@m4xKpT4KWIih=O(kjPY5c=z-A2ZS;DjxF-nO~s|Jdb++sd60%~7u3=J z>?1lx(4i)m&q&(XQg~DMqNlAWyARZt0*n2|K#OUXQz)ao;gF(ht>r+G>5FXa*;4sP%Tv1$S_$-`l^A=Y;4>w=A28g5W;2m&bG{3ZeqC~ zbO@MTbxMBlFPHt&AuT_~RQ0jc?&BCg zXKxq)zA4TfkCQ9RU1&y`q}YC9{khG7bQ#rVKPn$-X>0ySsPpQs>@CO+yq>nfjA!8b zKT{;jfQuAG{pbK4=6VdHnkDw*zq4dNf82UN)`(Bv7^h@0W(+O4+3%gwFl}wi)`S{O%a z@GffcKRJr0s4d z$j+xipG1j57Bi@VY|`Zu1??KHv+1-n?9H=EKO^>Ur67D5Yy}rshm8hidb+N1n}QyM z9cEf7;M9xDq`lKM)8cOmGZH?_nuk2HA6L-v;SP~(B9r_k7@T&{U~cst)xcsR+~nr8 z*&^(K1aKBFdE?K1W|YtGRS&)fYCjW>^rEI^<0jG8E6pF+er9UDul?b* zPzH!NE1d8a6NJ>I1^&$5R%e;+`YTJD^IK1cYvO-UG&~QU!GO8;eYK%rOp}2r|1*9uZS}ta4!EDC$-uAi|4HP z@k343M&{M_UzuT@#zg`RyHV}2{cj3+Cy5Y3^KwiYjC>FOV2}K_<>)Ee_BFk^Szg3XQ*cs;TOK7FUZZ{v}_a77?IAZ zfkn648(P;-+0!S>hDV*kXl%=<;?52PrB^^28JG=<-L)PZ z(K}i`te(;xMr(UCJpJ=6_Ux+OB--HB;=$SGBEn|Ga_NCS?5N;_j|~oFM&;|~Gm4S^ z>zli|<)u=fB}P3jgEsjXf_Q-v3$zA`Ofh!i8G2;#122wG)3kv$g3N8AT2bf%yIfE2 z;$kwDV^da^T4-UNxY|B`c`(W@hy02?{DD){{4>~$+lU@cjBV%lkZjtXIAPZ$sR3h; z1ZG+0QF{I}y&UKLbW*&w7$%Lm(wJ5X+`OwK9i$%FiEonDY^V-fE|E}}Q?OUy8&9^P zP*VWN7&PZ>YP7Pend=+44e|;Wew`PFbog|U1JYx%Jyj7B@dlO4y5P;JLxKlgWxs+O zpX67_g%*y05kqic$AQm&}f@CUGNXR)+<- z1ybKBxlk_6rv9pWCcNkZb$cg;y0~}A*j9BfGb-cA)kH@<@BmJ(^5PJ}(GJ3(=U*MD1%v&c)24zw$M->aYKNIOEfx zlT6}5zTPt+LVEbytrpeYhjH78nYYyj`}=ds5tN3+_<_Wy)~xu5<`jbf>!cVPeSwig zLOdNp)>3m>k?I9q{>;eV03Uf7oSAV0Y%2&gbp$4*4s@IrXlJgw*5owg90O_o6Dcdt zRiwEYVFU+BRMqj`)Yc1?)ux1&{LHr|jrk5e-@w?XDxNMUla$vAl~`O!J9ztpy*S+| zgGTNSY-UiC1b1|&jf9O+oX$FJOl+2S$aS|Uo#)eY)C}pjnytRJ@c&x^`rzO0Wii!{ zqKkC5XenYTHdf!3IK(xlQbRL}AMdNaR7Kq<9^;GpbxeFMownTKX*%ud_Q}z&QlO{! zS6yyi!0B|#QowKfCGDKUv2jF%(y!>p>$!N(Aq2hmTSFqN4BSH|ZGS!eKT)?UdF^df zTwD4ZSP4GoJKLkx1tBB&)_OFNvK85tAjL&as-e^*G^gR4d1vY%@nxJEJJfAMik zl??Ezig`6#BivSld8;me2mZ^KyYkoN_rLM`L&U5SVd%O7xH!?AQg<*oQk>L_0!!=A z+S>_oxI$SL#*WebIXZXV=2Eoz;+?+ss47JLfhiS03v6DOp(0)n3m^4zj~!a9WhY1r zD8d$aKCd4$REudt7VpvE`tnjRsz1EAza=F9y@bCcr zJ?H&*C;X08RqeoHFA2$k?jF7nayK{gDAtcawln(;ini?9!+#wZm8`xNBO+EcIw70+}+1~kp(;>{qgD&{pitQDW9|8F^<2c zQ)zdxMzRDF$Y=8O^c}Q%5VEhr=>`XwEf(ZzbCbHhH$dzZl4nnvzN7nhzG4>%RX%zP zF+CIVPhEz=DKQu7L%9JfkFTu$SvHF6*rsm&oxWGqC)1Dj?L+MpBo829WoP;QAJ_Za z|Np21MtUZFLm@vizR%}V+dPm*r2iElawfCp71=8F89a(_QlIAP{gvBj{OSbLPZPZ? zOyHq~Z8|Y2!Mi6S^(TOz48QD?>aVh%7S=c_!=s5F4)zHn*cJO4k>*0+1ev7vL2JGu zu2w)Y>!1o%Izb``k7ODP5T)Y9m+j=;(QlOjjXC(}!`JRK{7?3^tQ0SY*!SLXO`J-m zlXBl;ROThs|6y4RcW3(J&3~ZaGaAdJF;vqVKdk7i8p5c%28wucUYyPd#*S>^YJyk4 zvZ?EBi)B&^whukZJNx5NP>%=D>fbfjiUma}AChI4@?@onq(?g+KwjE(=V~I+Ug)?EJo6{F4 zUDYkTMw=2KIa6S z%xp@buIERDELuc~oD%hOsKm!aB8rS#H`qCDGH9tsOG&~+BR|Asy+Jvr-c#Mjajew- zN=e_`Ndv<5((#J_K$<^#ECED{dnF12yB1-p$RB{pWLu_+l$bx{QR-B1g=#^%dk=X#-nCZ9sx{ zBpUguJIUL-qJLof$@aeC$MZ+XWA`i5VUdW+kXAc`7T%zmU_UrTW+>aOvo|@?Iw@f? z6r2&&QUYX;sDQTTxrl%UYf3KX7OmK>yJ4^C*dEYEmVke>x!6aw$T@=`K-&7Rx zN2JV^%&A}0&s6NjDcm4bR=aETo4eb|GdSg{*mpnf`ro+R*<*QU3q(FX>uG)Lr4gYm z8Z2;yIGt2A(y#oby2A&*gPs3Bn$9w)%`RHo!QF~GMG6#mx1z-ziWY}LaCd33V8vaF zw75&r1}k3NgS!U{`sF?6e7`c2$xJ4*^Q^t(Ue`Tt_m(9^;)P{uE5NC!Z<;2OKiNK8=m1IVJf!cN)|Ks1SzbDBo;usTvLjK=H3D+Q;Nrr7fXYzTO18s-3WhRZJ% zcf=J2B?$&=fokjed~(!@isG}h{ydJ+^Np1hzj*yzM_Qqau#?A|K(MgVv z&LkA; zdgjY{VNKyVky$Pfra>Xba=*(L#&r}HE-Ps~|BfbaR0BMXF91F+?8fd^H~*<1aBR9N zPe%B5{&(mP1BWQ=U0_M5zylKvfnBOL=*L`E@r6i>$j)uqXI)!o?y$I`=H_Vy4qvAZ zB$GteY;`y;W70s3vs1L^_F0nJ_VnP;D$V6?u{0ok7+V<9buMvrzH5Vd@!wYVeKOcv znZdULYbdjfSG}8G)fK?`4jGYB50$wGbll0VZ|UpyF8u5KtzUzx^rsrdjr^w|jN$Ad z#n?vpTHbdUJcog<%@GIXx5_4A2gMC?myJlr{Gi|> z>$l`Lv;8Y2IvMwSh5!zCo8h6rGaUu1-u43nPS~hL6~c&q z&_A;ResTRQOwf0WEK&?m6FtrQ3iv3cWraW^KQPixqhRY_$!lVlk7GLH-*F@h(_7ZgbvyA^FF{6w-SG)s3+PFOhAEL%IKo1tlfAVy(IdJRl! z159U_YK&Q4pG1Mx4{n&KwG7H{kmzmD1jHc9ptDnadw2H@P>iN^xM1LJJUXh{9gxma zFww&H8HnoVL2Cy-%>I+eD-i$X#zfAeYoXVr^w`nM+!6HaAxzjY;#!9k0hB6>O3ypx zup+Ny7J??-MiMy2ERAQ4ySGOmV#>j#lV?YKP?CU`%=}2C=GcrhQgL&%lN4DN3tCS9 zBc$Qt8sHIecMf4r^h-rZ+7)8}UoozP&`wSY`|9qg7>E~$8O<1OV08%KsdLW#e=R^t zCFw%ev{-(DIkqO-MWD#`v(NdZyI-IDoHs#W;Na-4<#&na@KJd;{cppl75hJNK{%3k z9EnX$9P~D6A|FTkKF_W!iH0Pe(Kfq@=eo_vm<&DCd`AAqX8AyQ_pGlWohJ=`H+>0R4d}hq*fQjBxn| zzV{QPim@}Kf}u_f6h)D^4?bvE8Ta`Xr($@n|EL+2eOoQbDZbDE^Mg!0^Oba8x9^7q z3Y1&S(Lx`M)h7=qGHg)=29ROvULk1)jFW`=^0YgDRqzSH;RzI`K% z3@|e@ySTE%qFZT^5tK5iVedV$VHIO7di-KG*DvSFOjka-egK)-o^cN@jjEMsrMP>5 zWv{P|Yo!&%OP%mW^}bJTHk%{L2fTFgRGfb?xnvT~LELtVy?kHJ{h;{R}=y zNpnCPbHK`nd4!emzLm^V;N}k-$&rNhtckIF5hqIZa^uxCsn3pxr=)>*YXuj#YYdSn z$1#)XO{_g2-rf0NXWdUC8#n;AZpb)T)QG40jyELVZpl`3lH8%a3uTRoQ(!e6>M=!Go~Cga8v0r9Az6OBzB_ z(ydre$)qHk2`j--cnQT8yu7p`eXur@+Fq4-%`(>|_r_@ayR0_vz z)njahYi94hyy>fjLmN6DkEnz1eoOsug}%xe?QvQLAb{L82TIwDR;F4hb5}UledK!< zEf}A-$!R4!6{UP8h3*KrxVWa)F9Rjvv0%VG!h2&kP-X#(*S)3ax2sciUt%Hh6kQIr zV7*qRqt<~lzN!BZY?Z(mYdnH1=$Ld=;NklEt571IFZ3d`c0K4@ln|cp<28wS$g{wD zXHZ1>P=NR0|bdJs> zh7`8`=2gd=**m*1sdR~;gqC||L^S)0tnQ94X(^$9BvwW^AMCxSyEH?UT}IeGg`pt$ zoX+HyR3Wm9xe4rJ;Mph_+sPr-p=CFIs8&xF;o8R*w;K?;R!r`;O?q=e3T_BZcYNws zN;1F^NBgi3B_G=6={vL5)Y}i-Nt_dw{mz7z_r*9;o+>)Nh_XE?DCd3NkqbVC5;5-f zPZzc+5%UG>o2Qqjgvi_{Hv_UFr-0LPeu(5^S41{QEOb;{OuSYU4NXK4rrbBvLSv5pFu{nlEM9>Fl;3-%)M`De_xpW5C$s&1}#Kps0_i}TfU{( z0`+^Zz`z{EXb^4hE*9`&xGnmq#hcRfw8>@9wAt;TzB;b=^>Q4kJLmx;KYxAWaGdbJ zmmHVwzO`qGb#d{n%2t<)y_a<#+8@DJ{T#c}=elEu#Ymgpa`>j%hGu+RC5 z7Q?BIB3$?R5=p!j-Dt+#%|IycScIoiRSCPDX~UPvk>M(Z>}W1J-n^tQG*v|Hi3jY< zis(kI{$=E`ko%_t!@NAiPYI~wnPt5)dE;C>zQsZJ<7_|LWk`F-oL%_CE?+Bz)! zG&a!I4wjU4Ar;+PcDc#YBB{CY0W#mblwbeNZwa8ffbXy@@B?x)i4;h3)(Kpcqpy1`2%lGy9&Nnz1PB;%Cbuj3DJQE9qzr)IavN*iI66q}}4WLpE`3QoR%04oA zGXuOsozA^2A2#bYUp5iW*So+gLqfj(ZQvO&Qhv8TsCGR#erO0yTzqx=@)8Gk2#Iqa z>z7pw?|1(KgSals4U0kK@dp1v7j}mGimlFGb}9odT~(h$^pz+Q3d?D+y<8pm$7o!m&#cXv{2y)wP0%R zGlYm>&IH(!COObg`WsT8(X~|eOg~YDXKU8Ij2kCz(lhB*a{z5$AZ0$xIGzKkYrVbq zV#2qS9>69+n~SqA4y{3y3*}b&Ii(}bf^Xc7&&(pbihstc*;c(I-GtlDbj%okO5F9k z(Wh~S094o26ViL>IwpuPK+ew^k1>Ww^7i4b=T-4(Tk07D@;vI}UGdFGcM|4QS$$e3 zKMNw}7=AXStfNNUsaQTzN+DTc;xl&;VV4(pK=f1@pLZhmcErJJ6@qVb3+Kbt$7g45 z0ReUi|AbsFZchojUmhqs10G56?tFx45-z(x0J;hb%nSGT$;2qosLU~q^RKAYQGfn% z#^V>}1nYB}3eV_{_His?*t8V+jOr<-1PD2&aGS9`6MP=~;|~&-lX%#3z^;hLms#c}lUE{^R z!uY#9yJ&+baCf59Nc!-gRmw11>;&OQ^1liiWeA_EFRBA42bl$s*;vf7L z+=naT35#_2hmJTfaG-a_M=Picw&36fZ!EWLlJ}eMPvX07Lk5^$0__PVUM+XbMo~nd z77azCDAdjhS^YFy9tsxjir%N3@mC`0=bp1Bxokn@*|^k_GnwkBC4t|Req>gxAgU?S zCbbV#u17!xY+CQ{mn6wiWny;1Xj_KqHa1E5ugLWJMT^>R(twbg`UB;O$L}PpVN|6L z(EheJr;SJryd$pS0B0~5%&;y=UFD$ET>-3&JP91wWHuIPzEDy<$m@~9;~t2}Kln>mg-K{C&1(Z?PZk+&x72vIuM z9!kDx$WNAJbtOF~R74+!(1#ljU1RPLLywB-* zp`>cXX>D!2hX>00-&n5K?3&Nn-n;yjn9+z$I8bf4ydsNpr_ra_9GW&OUrE7XCZOH~+ z>@@I#VsAVr%={OG;ZSVaEC9~UVj<-g73rUFui|b3?ybT9Xc6>CbJi9m<2ThOW{CQHjcG|GhGv%8u;lRD}qZCcjS z^Aom8gnYQ9?63gUUMhFqXfaiyV9{FEk4OvD&xphGbjxnZk+RT~_Y!5_)PKpaB78?n zQV2H_eR+9(L~420y_<}wT}PcDOvCXjX65w#K?{|0+!y6gEWHXdb{~gO#*!FsxDV@w zX9t{4(r@AD+xC0l`57rcKmQ`7AP_zYX)M^P^l@?P5ZUw;-GqN?{L((ufMVHJ;jq-_ z8cLoK+&7eX4s=w|S!69D;h7ab))p?V0jSxF@@oN`HokQg6l2z%*&y++VhMki4%I(LxA%XXSit^Sj2#@7#r<*Upbe@p+0%S1UQfcg;xR0c33ns7P*Fk6kjUH(SM zY#m9&^gty&GS(p{NXHaf!7pG4p(|X~f3vNRfUk*XN-3kaXNBDXdjj&KS_agMHL8U8 zKDhB$C5R+_7fIQww$i0OVUx96Vclw=V~AU<81a+1rLxK)qW;A}?T?J4HCNGuHpNIL z38gDdYb-W9vGW3)NKb_?AnX*05^{f<6MzPzFxN6!zvim+-$Vk`R+pm5{7aCALqg@# zlW|x-UJ=G_za3nCBqvxiBRQ^i&oh3f(^79;W=fY-HnzbBw10$6BZzFcx8#0}G8`sM zbO!!h`N94UoxLKNP)qP>v*0CK>O~6xZ0pMm(%K}; zq4K|af%AXJZg=9h63atl869ZI}D?>c0W~EjZ{ObA} z*;Xw(YD5a`A!t@nyRdWWrF0sFn6u;D8}u9c`oxS0`Oszk7L{WN_ui_KmYO0fQ5<4| z-`157F8477_UzV$f*1AtTN)duppwqJhuPL0W$SM?8(*>_5KICCi<$m;JNr=Ktc@2O z?uvwrLU{6Y@(LwuQxBa7f$3TRzi{{IpT;m5BTyi4nsG3I?6p`iK35+?V#u_zLjfig zPeE;DaQ5z;b>z;?TZk`bA2Eu~_zUlzk2^k+x(Cu+qyvQyor>rd6Ra% z8m;BMU#7>@MQGq~6At*~7arUSE@lc|kpGAA^WQ}TKO4BVSV%}{aXAuf0p7H}jXh2F z?SlpO?LNh+*aa_QeMyj+j)T%aP=+DP>xW|%ZfC~4+Io~v5rePY8XV(5IMwo_9yNUB zU)Ja+kqT{}22c#xY|pPhu9JB!e>t1q-+wH@Y2>nV**_W0UiowPE5*;Hz!d!B2ab=L zZGVVml{FM-CFg)@XV1ObUCWpEbBLD%Z(ms)q3m~(aIVJ2$^gCT8|kj4J``Ach{syY zs}8L##AN8LPt-)ya(tf0m$ZU~LA&ljQ4<&L=9RcOlKUw55`kEVH&tE3U;XoO@4MB4 zGzr~Hy`b*piuHC{uOPSN;C8dFS%Wj-tbudZ*uwC|TUQF)0liWb=}fD?%mCu{wm*07 z@|5gBrAQVOiMN1X767T!$rg7Y{-y=np{CW>x0n9g$~UO?j=pziIKj`y<{NOj*6S8s z{@7|B4Z2my6M>9N_kcOaaXUO^%TpJ2#)0&NxP;T0H2}xN>-s2hrGo-I;zN*ehZquu zkZ^(EOW)q-XKHvdba{Ut4Oix`uCH$XS2;Z#v58Ac!eI^(k1JxUtGVp%*9R-_C5F;P zz7j8+yNa-JZvBg4dUbRpAz%2za&&m&wn3t70ytdbebLH%ivX)TRb_mTV8OlmpjSp8 zT!)aitj_uuoqo7&L{w4YD}gYpIwhXaYtuJ+vK&n&djZb8JG~N@^voO^3T{g3N=%yU z?>1Nm^mY69us4&XePRVp!n+lS25B6vIw-jGh`{*;rDO$)RG#P>VLXi=t#g9?TJ>HCzHjQBB^A!_n{SDC&4^84qcMsRDZQTso%AuY=|1D72U;^cOfC2x z+2a(pz4uOFs&Xo_k_-ASGopFg%zMZuEYinP(FJXw@Zh5}L`blpTGa$iW{U)Vf!Ipd zBQlCzj0Q*{`c=%LGZnsjPdEA|5Em$&__I(_sTjvpG~4sqthjWMbA*$0NR?bWEJN1R z$>Fz=u7seyOYb~5hWgj=s|!|G9hl1q%^G~V#t{qy6>Pr3dS1CawSTSOTm=DKKad4wJ=>Po0A{so;$gt~V`LkHKx|~%0 zQO7@~BjQsP9^%c5y{Knw-**QElWXKx2f+D5mr+ySWGOr6;8b6G?!ToN7CV9cUoWwc zPx-d9cs;doiguV4Wn+BU19{}UpE-69dy`Bq08kO;NslOiD{Ej;X~_rs7eccRuZ7Nooi7IlsMj9aG$K*lh0F;x;AR|np-_s4`iDOxz zTW+V0`QLjp!@pE37#GoZke)kRBT4Np!=#}B23}U)%n77t?d#AjU-7NYO@tw^?eB%N z^NWjn``_5`w8_^evAosga_^K9ZZh;=PI0@3I<$=u1qAtxrHtzlKf6cfbKT!R_3d*> zW3&8VBNH)mlDYR_Y3N-oO5h{J`XJz1%e9$7-v+RVNQM!9;v6AUe*#$gZJm>KZ?-RG zH6~C{yB)_NMKEC%U=!?t+?e;O3|%B=fqDzS*pFY^BC3{cy=WTNMV=$OtO()+hJJMw zVAk~7qP3jY zfT1QIGV|4id|zK=tIUjyCzIw~g`E}!RkVYJsm9Q|1h%hVUT|G#ARC*TeZAjY5_^7k z4Xiy^SJye`0R5aOe|SagttZs9q}AWqb-uddYH}xPLBS&Im>&zjMrHCjZmN3e zZqV#=?scZlU+IF$b4f}G{=_1uyE6RV3?~}HO3D#$O++;eJMpD)CX#vEJzX8Dh|EB! z|NFZ|r{kalDeFXb@n{>~E~1XIK~yOG zBLiJ>Ws+R-HzH#r94>KuCZ|GIgioA7Y1rL^M6v;hJN--a?%2LW!xY&%wXyjby<4_U z5s^U%Gp~C*Pl*IWJLN)y?O0bc^46RGD}Biwz#QbkjKF}oSAUuD6_@?;F87vpz2`34 zL3D~gUO*tbA5mx_QXYFdsihm3^eMLC zd+i?vp#Ba9km*vJ)s&%P$diF@n16BED0(~ONxGbdfwyxZZ=#+KE3;2yo*u6b%LW(w zkg`J|l`(#qe5^+hkHtj+mbW`#I&R16h_+7HrXvZhpMEYSHC2#!s0Uv*6PxzdS1gu0 zPHXq-tfsVh+VZ)#Yn+zj^8QPAc)!T_mh(!yXZ6<5X40(tu$NDu!;7l1p;wU7U`_^? zF)z1lJ4|VogXuw${V4Cd`c@$msp&@B3{Qnv;olq8pECXi*s_upLHRd9NsCx|w3K0^ zo}z4Ye=85(F1+V3oakgBX>#?`%VVm%g9WYs({zxcCG)Ee@jza~TXzcQMa0u!BreDgs9;!U|z9;R2$ZbGbfT+UpCN~m?JYDrBY!?OIhrNb$;hhw1 z^CcXAIp%i=ZZ~m#b?tvVhx|4>oEk+rz+4;SX#=8B39h_(bqz^;gr^U=W2_^I_4x)`(2WE%4BpgX?M}9jZ-8f1^E!PMc8J#g4y4 zMJa3WD>9;uyjwQvdfL=;ddiB!kw5qd#XTm`Lu^-L>+wsX99Cf5;(X^HPAF#;Zivy} zZzGD(eLruVC9JD;{Lf%5&e(>x%b$l697P?!qOt;5>7W%^8u>0MoO!KHgJ!VcnGBLahv zWpaL*?+*;i$0(vAQlhY#h(XjeQH}2AQ-*54k*{QY%?E!hoCJ{Pcy1m<{BO}4_*f|!IOJ4I-~ic&nd)HYeD+`%9n=r&uwU~&DCC=m3>saRO(f< z{(oro1{T-FU|C)P~m4&nK; zYshQp<8NcCgfbo6D66p&TbLBn1hn%uSAP!SIVHdO$M)w<5^t)XYt`-@>kUVFG8Az3j z8)#r8Jt;98AF0Lyu9`*-<0xcg&*GuqP<1b2dn$f?FJr9v_<|FZVAA$Uqx0)lAbN+Q z)rUkvLV#yN*~#vGLuaSKp=w@s!;VqYY#djH0+H13xcH91IPkv&dY#y}na}%MZo6>p zRbU`F4(){=@^*1!f7{qY#+7GtSAbwmRPcLjQWDrZwQwQTRU(S-52UvkxJfq_Xj9fkrPH%wrEXDWzjcTx49QbV8hjD%m|g0l2ZifcZ`gMOP4VCK8?YNa%76jQBx`%)`>g6Be5h3KVzEMQ= z)l(E+cG6rPU;%~7k#JY~W&(j>9IRXpVwnurail18w&1V+C2eoyb~x;;R*X`=yARpV z2L$Ikq*-kiunjQ3)EJ81NKlu>gg`&Vx2rJ=4poh)i9R)SrGm`J`8_|xX8n6>UTd&V zMLcl*lxrJyXW-tbka`tRx($E)Ve&fb-#H&!42<>;&wri+mv?;2I5!3F>AB>r#%vEW zC-=f1qV2FwkDY%dx$tTItg}%(_Ma1ZfKPDF6G$6ZWKG%HDXt?sUV@+N+JgW^Y)}7R z3y>3MNb;nguZTfdG)^cwmw#R@yTOWGz7eTs3_GLZ|8rY?0=iZ|*V+8oriNVIBCbNdP|UDZJx*nF)DFyx-*t zIaJpMAxluJfkGBXmW8!(ctmc%UNRD;>|2J zOks$oTVO4D=3X1Qhu;|>9m;n5Kw_E=Nyd2qN-qtQ{E-m-1)S(Hw?&|iX{E{yk$lZcc zJvs#1t1fg_K%ewD2&i8CJa)&?>lR}V#qrUSPHV`1-sdz}h?9Hk7H)s&3&dd5Ng0~g zR`t|m6s%B&6CHh2lpq+wgo9TIJ7 zdsB}e66&LULS6$OZiinfn*1cZotP#!jC3hGP9WLN^yn)@gh)&^Oj5&nchss_1Z{0& zKbL$nHq7JqRcR+wF+pGJccGEvxV4!F4#*lycEy#O?r;OV$Mehc*R>vS z&vWZ5<$tq>0FOW8ryT0#C5oUK38jwv;%q}@;!{#um5jSD5B=pb2Qj!`BdWE8v*7G< z=nuR=tMi;O_p@dZ&bb1sh@C+ zycjWDp81syKHmWV@)N}w-g)%lDF4_uESd48cF>M@{vhneKBM>jkO=4XYaj>EMC4zM z$juhHD5V}lH5N>sWH(vD7HKjc8iCU+YC8+viht*|YtcjaoWT1mlkkrPq!6JkoDoZt zGi1t7odq2LGqRTZ7S6{i{;Fwfu^*hgSzG$+n7RK3EurSVNm24|*AwoV!pri_(M-l4 zsC5TTO^|9XeQ@ubQAW+4-*dN=@0%hn!}VrrdhG`ZG1U`TxEIgWk6+6l7Ej~Tib$#o z!$!q})UsN=Xp&!^?w+0qUN5;`-}Jyh5JRI{W2{wSr>In{Z1>TlCXViB_rW3PDBY`S zPn_uQrB}e^n(VKQjvwgsc$U-o6K%!+G7Xl>8)P|ILRB=32z~r5kY49_w1%F6mre&m z$s}m%Lw*4d>>&|IX>CFMOt7V!pREyIlWndE6EyDo+8QJQ5uGu;6MsR_+hcOP>YXpA zlm*p6b~!%K(HjiV&j-3eWY)yW;9CkbCtI8ADMD-HFAs)$oS;m4N=#NCf_hnqd@RJ$ zStb69sX1FvQ!9AhKOjnCWZ@HJ+@|&8WV>$2UXT0)(Fs=5|( zvX=5^M7*CDwe#EMoNU^19n!WhqEj|0(PFQ?u=s)rt|{E)Gci4cS-=FuK?%27k~j19vh zq;IZ{=Rc-{uAESsb3yhvY9Hsmw@_Gua}D;Qoq1jvl{Ka^dmWIcZj3~5Lp=*?;(9xB zt%NK0{C2q*a&1;V1W-buy%7-SPuWDYAEdZc){a!oq{wu_Lus1f8OA&LKTRaDDql zrTG)$P!0oU244r|uM9x@-?cY5mGubo8*qEUls~xOqot^r@^CKvVyaZhAI(Zfv@UH@ z8o?YOLrGKxWoj8wmQiigc?wyQG#`82eG9MkuZw%^Jeog6i9HMY$t(gDSMdl859xOA;xHXm=6tOCJ|`y zrjGIx%{#|v6|2Ue6wBNJVsTX#RM%2FRKw?;6x%(MId}5AW0(vaFxgB~tju ziRAlb5dU_1%G*XEVJy@%JJsC8yZ@9MkJO)C>+1T>OpF^k!I~1I&iqj%zxD+7H##ah zvmk!v!KLgm39Ej#*&Y2rZnT}|D6PG`z~g6m;TB>#gvuuV1j;=hJT97Yx5uM42M9wb-Czo%y%M^^fx}t*W@e1fb(Fo>_^7k-H{9F%`$GSb@C?nv5etuZ zkZt$&|5WY!Z6*`-hTiSD9JL($`=Yo0!uB)B7rG~cOCFaq;jG$&;T_Ab?h}!{poX<% zO6%y9{zLnw<^7;InL**Q+*DrZ84ch6S8h@4CqZf%1rfOOqTG_4AJrZ=>BN1&OKnjEk{6YQ0)z-N#?ZS&mNyZ!2OzV821{ zwRh9-N@$+YkB6!C;8A#n6`&`UrLWMJt6sHwOWG8OZ3&XNVd7dnExC@ zwegkQ zA#!V9UR91b>ScF^p5a?H6MghBv+16214$RBCx-#yi1~-r+&ed9yY2lst}Wodi}01U z{#&jDiui*338-kx96Gl2HUSqg`D1>D7n~knz5KTV<2KN+@!2cvIORMs5>gaO|Ln4E9WXjjgHe4+e2F;~^hd|$xE=oQ7P_FF1FX&0!?~Kiqh_Jzv_+cIW zN)0y|Bf9agC*l{siJiJhdB(E02^4YCqC3(Q^L{RA6__n*WdX6`hgpC9eYutQ;#9J< zOS}olezZhseXKu5D5256abgH|MFh~<|9X2arWdO87fXMv03juwmpaTQm$W6WBX76O zbqFt>b;9A?jF2?}gZ4B%VQyYcqzHd2hi9iqM(1#Zh6D7(l+B<%r~AN6Y*RTC5zU~KIDK! zH;I$!rZ((_dAHj4u79k^s&jSy9~Y_gAjkfuFvm7^8#LwLrob6Wh_@k0@n`O`ey{7z-k+CJ#xDB?+5 zts5U;axaU0Cb|)UAb74ytriK0)j#`s^jnB+`3hT#QM1MeJSELw zDsnXtV)Q8s#RuVlv>vR*`Fh$$%_?}PG;v&l+(oR$J(HH0I>EV`^4o^n?53S6l zWGqQ4AHZT@ zNb&IJZM^vJnJ6f1pu39ZIVBW0H08UtiEOxvZ+JE!ajuI?Ze{em2n65G6l`5?A_$ce zstXAP3m5DP0jHudm9sJ$7?EAcN+kr!8we)`2m~xAddsqN2!(xMMw_8i_dn1!aETF8 zS565$Lq|#7$eR$r2!OmvT=(`1r|-u^i6ZkS#)hUb47v2Ww_EPz-vD@LAGipZBV?KA zLN;l;jjvg7z7U>zcGeS909#DvT`vvtif8pof{&=}fhJ8kyRt|22qnDZQykV9Z`>v_ zac%QpIfI6~4g=^BJi3UyII6?JYEGraMSSuCxKeJ2O965GCsoGML)OqdnYasP+mB}g zrpgj&9TG4->(Rqd>mUk0hSR4o1z7Giz*?Nei3b&)#6I75S>ks?);!pWWHF;zNnFG9 z)6krjErVpMAr2^BRbx*e3BbSJK+Eb@`XaoZmZbjv><-2|E2KC9-v>B;aTRj9Y3 z4c^n!cu%9j@jAx#AX}aH{Ofh^WrEj!_aK_Zc-+4eEEW+YIUX?Im!ujd?N^dOyv^@* zpNoi>P3W|E;rklBZGoig>LF?=MpZ}c>?)q;8ekRmF6icrI{2p2e3MxUhVftZEKIY# z)Iwd?hx^=_J1J~F5xTfp`8CvS$|21$wULU`n^jOL&GVCzWTERO7gCQ12Y!fy4kFYU z9h08m$Zq75F+W1mzbjD3tq0#r#w1^wA$h>u>c`A4y*Id{^QuL%t2~ow#1I?fK^XBr zOx_l&U{2TsP#~k=(_QCOdPjI3PyHBG$Kez|b)jvJnZunjjjcbGYLA;8m>(~w+je3p z7RBa0bKCHW(aIidQxiBTt_0kzu>SNj;En+NV=nvb7>-JM$*##{Q1t6bH}Dz^^&36+ zX!i)pm9M5zmR}EF{?H1DP4}QJVGx|wiaFmPsF(gxw;!FyGmQ~IT?c+hVA9;vXjbvQ z)s0)oeB`8@T1m7G8*v_X5gLNsz$j#E+eLvg74Vq6XlrbnAmB#gISHCl-J z+dt+R?{HV_&PQtG!LJoDGhd1PMJ z;n;+5JEI6tFZ9WZ+fT(rgtVfuUxE0weY+VX3)ucX>ii&NEcMGP3^Qd;t&@!$izZM~ zFwqSax_FO`ydL7r%S5+|XgIF*aVG$PcCHC;sl6m=|5 z^xrjny*X=YO6w0AMz9UHHMGQ&CFQ4M`-2+_G7DWdQg8k7JLLPEg3x$Hlc%4 zEB6=*^G1WKRj0^aczPp1&ir3JPc*8_MQ!v?vHdOh8MpEQ)jIozYabA_4?n_4=+>Rf zO1|09_m@a--En{ZY)l>UFjKJE^R)jO4&Dr1`3>JnS>L>UnZWH5rmCkFq{2fJ!&vkp z&IDnRUN>&Zi%|p;I6&KpR`MR`Od~(p&X-RiMbB%uEAm3NEj6Pw+C&{i_2TvNo+MQUAlWn4(d#M$4InS2Y+%k zoWRnGm&1C!c|@yPp@7S3j1GLA&z;42Wn!%7SJHC5EyE-o>DAf%>g0VQ6bYduPI8^8 zHXpBD@>`vR{@_o%EJMirG&yI{&D{|z ztUwF%dml$|pj`RXHVu3P zSEe(DJSX@2q;byqeOfU&F3>=zRZr^`AP)HbRQr%SIjNqtG&R|zFma4oA@-RV1U3Yi z%yQ3hy*!cLSH3(&!A6j=zWL{4_AD~@z$UVE&TBTdjqqI$+`9BF4 z*9cGZxSXA<#UXowj+H;E0)s96!t8r0r*~CR?F`?@{JU*MxMy4sGRoFyJKI>G9<^NR z(_9P32E=4)fyZ7Fg>tC)m^;?l%u-<{`~9w!Ou2$)k?(Obmg984+5{2A#e^%#p-y-y zyDeg~9jr$cJfGOz!zM!#ET=_6<()Q<{QF8nu2X`rU1Kw?cyTlB`QHOV%dd?Js-9`& zm6l_0zl+OCp@l_q52qP>uCUPgHu%O%^HJbO^AI%VO#YCO^UNY7waLv~`PeI-m8F}f z9P6qvb+B;Fj>W%cn&p7Czs8PUTBjLWV4p*nYU7`8==_aI$_?qKEP=sDbgoyKV*JZ0 zr!r;~-NF{~>Q3eTG(!?EfQ0D*@qvZ@2b!AL%))Q3e9g4v?Kb6 zo4b#3BW9CVVT7>;#!u!=to8ASDTU`*>c@x~E~ZxTt|)C&0%RwV)rSD3$dVslG41VS zvB_3+i8uWPT3G%iw^)%mT7SCv1<6u;k6?z?U3dCZaPu1*tXK=8`q&=N#^8w(UV~7b zwT}w6>MPi>O7RO-Dn;_1oaFz-4`~_4`}}YC+fxMRjT=VPQijs(ZtO)OtxnoY4IS}f3L>VB*vYrFC;0q#{v@%m`~g0_g*B8*4wl1X(f%iRIY z8RuAEldeP;Ok}rwNF!sOB1jX7M$)l1<_p^n8ZIoUU?!+FgzyW94cKV#cKvlTU*; zY_FyundjRxlKiF3O)@K!kTfaeYS|{Y#Aql^u{{k{hwDv{x9@EIii^zcRm5RUMu1w6${~Y}bm$_P4MEubM_@=V%pKR5$yWx@ zHnB;LzDy9+CwQ1(thx?-FYS0RZkOuSdor>{pY$Ia8{<<^!7jhkm zwAc5~$MVZ=>t^7+To=q87`njPDa;j-ofXggixZ>1)l-D-@i3qR9`+o$Rl5U6GmqeJ? zd$A@aG6~^gu)xzQo)Q&?4r{Jl;PeDRC_u(K@#0Bs`XWr}bB5tx8(}#UWRkrd&HJCZ z@he+I&={w^O#YHO9!$ave=Dcg#UEH$i-2o7>m(y+>kpx4z<*q68@%$Ck!NVJN@F4N0S+&jpO8*Mhwm zJ4VpZ(q$5|Nc|b>g9TrYd0dLJvyh%no%Ih)3fo=%ZbtKQg(1WZz=R`z2i8W;XaRzj zUN5SG65{}h$vu9f!a+Zm6&~O|WaxcSfJ)^i)B%tD7XN2kZ^911<`D zj45+D7Sun?Lsxm&WIT1SxZF0Lu_-{KEVnC0*}qlB6u)n^RY1c@}E>ylCrDz%~Rp5utw4|`LgO=+EAez z7juSXRGQ3(O#=H|uh;P2T-Gq2_AnGl7YkIuAdANL3hfu;MVhK=?DSfdv%-_`0EHRr z@j23PcK+BHT5e9#z1CBA2<)-2^~ut>cyPr;v!d2eg~wv(b~10}q^e^yzat{%r06<{y3fT#Yy_*di7Fe1c>Hm2Sh-E4{-w~qbC7I2<=X8Qy!!MAT-))+kE9w%$W3z0>yCwH|R1?SfwA}!8`7B zQh^!8-l(p{F&IwFh8o-GH!}bLAOJ~3K~&Mfa(lPh8NEv7I0|zc3zn6q)wZak(lrHR z(q?rcAD<1{iS>ai-DcZ0WRRd1A<9S{ANH2OAH2u0BS>f_IGc~{yecW48*=4nQ=I|3 z6WgO90T^Iu79BW8G13vl?;&(WGA+{#gi(~H*$?sxqj~2oNHbs!W34Hq z7kMzr{kd;LKSew$EA^cs)nDCGZoRUyGdG)2ocW^po`MT0ZfHtNXK1_$DD@dDF5}1T za4inRvpmQ=z(}>1lexvCoPnm}mfOJrBROAFr)0-n^;#=h%19Jl3(AaUi#?H|M=1OA zpg41OTKP2KKpq_Eh+*8sqaf-WNj)#Ig)DeNb8J*?t2})CMyaem=0-QuXA3U=s2&G8kLN^2YJl&q>O%k%yfp6p*eZ^-0jR7^-GGjKfzE$OntJ#~!cIeJZo?#5HZ zw*vd3g($SQh2zYbq<7I%n!FJ_zr$|1 z5S7o5^_jgoI!1$McArNXxY}0E@2{mCF&@;wAe8rYT-P$3^F*+1z742x)yo-trE_Y%uj!Ii-+7SdjHN#J`r;)0a=m(qN0ZQj0_21qLE4xw z8enALs4VUM{6F(^H8-lHyQ3A?fp1J6k&HBSeYiy(*2d;eFku7@`{jF*x=4J6n>i?; z-Gm=N)YPoS;DJ%OGDwFKfkoy~X-%=sekL}Fn~%_0bSCkT9436wKbIKM4iv8e@$Vr#LhLwx@AK8};kJ;a&knM0P4 z(R8S7zXW*xfw+*@uv4sq<@67!vU=%0fcSd(+ zY89)@^o|s{F1|?D0KG&BF|G>8wwXZ_xk9NMoAq6qfr)mB(AOre{E;+HnPxJTLDiyw zHs)3rs`G)bjF&18+q2wh!7YXmiEXshtxE%_=rKkxaz2Gj>5QUv3YPghM1;w-I9j5* zX8AMAAnHx(NdIwSaOJ3@8u@&r>YkPST+RE{?<JIdnu{cAFKWdN__a^BaF zcO4x~o23B~&)vvF4?`X~O)%1ZZo_bo)d*t2Gf7{Z)}_4Kc9Th|<5&Gz^>wXF*M{yq z4*A^|Kz?M@kBwEz6-JMTF)#UC)$c=_T~;W7CR^Z_K{tt*5M*i$xj0aA3V~=_6&Ck#Jd`=t2dliq)&(z?V(K%9J6 zP}$jJuax>b7_j4oT$KfLe|i7f+<)zvS-!8zur|#O_r9e6%!k))vVDDf8jg12jMwM( zU(;WsKFM7o0Njq>=c}D*w4zI$U-RN#^hM1X>TufCbB=QiH&K=AZ$|5mm<3^1C~N`z z;`dsln8T~|o;o%>KkMYx_WLRiW?9Jm$+2koBd#w_(l6Jmmu=}Ke}!4K1D@ld0LGTN zs^f1FB)Zj^@23-1BqKji4wA?TmJ^p#(095g4(Ck)xUgZbN*H>K5^3ePyowM|>l=+U zxZxOvdfU7`mIA0;0kYB=(bXe`90)V=j`l=2q9cXQBz&!oP+IKra4K-6`5y3^ zu`WRK)m1HqsVm>4w=3WvI0>t{JrQ(7vhAsXMG}@VYD%MjW=s!`8SI+MTaLK<~sOJFK{Z-QxC3i-2O(l8vi1eZNq!QWgZ(F;4)b z0T0xJk#c;sylcEi$4~%iVZ;@3YrL@UD73K;!U9WguNi(jBP$BH@=W>tsu2%A}#kZP0XT03%qf5i#cE_3f_F_YurT-9FA>enT&R6#+GWufXLsBYbck zio^Uxc|*5ld?r8FXZFVbnm@0M`DEDq;LGPY4*{I}6J=|mi->P4;ytIg(CEzQniwNN zYzyzuA<`29PwT;j1DD4%RAc@|QKz;HtscG2}?jCqc$0KPjWc~7G;aLX$ zd+oPthW*OWT^YnHBRk7=$42*s+sHR8fHr91$L#(%?^ZH**0sz5E<@WjQY2k-CIoJC z-U2dee|8=(>t4u+RlDbBQpY)Me~ey{qL*OKMLYkX4RcQfVVmsQr(9BRL*C(CUju-s z3tWF!eY_$H(4TRPY#EQH#d;P;EKS|PN>yAi_T532q}?^X*o~FXf0s@%9|!IcL<*02 z4rKs{B6lmjju+-RP#rk0;i6$&N`L15=Df>8eZ=)ozMHsTT~ES!q^3twE$^@B7k#gK zqxM^~7R`m9*2aUPNO5a=i+hySfML-2fIYS$>6CSc4r*C`z5`^+H5El;S8bAA*_B^% zk#R-8Iep8u`d8SW;|s5|L5AH%)vsehz;KOlC#@1M5|?TCPqMGXRSKplq+I@-Yo$|H za%86eoSvXwhFgAwKJn{|ll05=`X#=7jaz`aI}K$YUYr4MWIRTq$6>dKG?B?UGx9X*BjO9u;RmT)e%gjv5H09fs5c z>OfxyK3A!Q!OA1*2DfU@$gtkgwhdhD z&Xw&k_fq8z12-k=M_Y`!xR;zjD8USQ!ScPb>^#_mTW%#!j8-ZwSI~4C74S4W=4M4T z@{puLCryi@o|c zjUAL+UeIy1l84vW_BhQsM7kgWR#5i}C|d!cfyU+Uo`+rsWYqxzFvnmz+-p5GPwH-* z#~VvP`9rTr|4=+DtNxnd3m3J`j81nnkhhzp!NV~O8`ZlyY-)E|t&Ey+eF3ouirzU7 zGlz1qfeK#&9UfH##U@Np$;$cMIDT~wRGQB#=P_@L5TReSci;9Nk`bn#E@K;q=DIP{ z4E%}+q?-X3yf_fh+8y*~8vrPp@jZoOylelM&zLfW+uXUBXSy|ae#AjTD;0$f~9 zY47L-cz0=go^@HEZ37*d9D?q;oAaD{F|dT>*pMErHRz?}z-Gh+Hc0c`1{6xt(lMwW zY2=QDuAbgS-I=RJf7B6-{l+e1lyV{IL?=&Opv!h!>zo@r4N77L1ya9ziiN>g4LQx> zCNs4`Mk2^v=oMJaXh3I6@cdxBH-`|0gMw+L$TQ-EGH+JK@i=D`t8JI_yQ_PwqyApY z`P6%39&y>xHJ+BS9Lk5@#nTHhHG-*?Sw2*`Kc+>3%OL=AaVJoY*;z{(i%E17KQ(D_ zs2nglM_1#p!UrpZc8;K1^~FmMUGRf0fy)mUU!jXrlr+jK)ZbH=IhR9t5aWd1?QeHJ z2c&uQ8jo~V_CviJ%@*&RkCoz*eGYnhI~4_=_IO6b^Ib!Sljm3Z|22MQzSCSnDwoe` z)5$B`Qm|CZ-woeRLlHFf@@Og)2VR9NW1A^&rsk1G1GXX-Q~(=l3NouoefLR&)cpHNb3?iux+u9xkzxLj- z1@5_c?$S!9k?y^xovNzXw(SZ=AMtBK@Z1HHx>vnkQ?Sz2gPc+>ad>T;e16ZUP|CX& zS3hS-u9{QuI!(Ap3HM`u5XXkM>}OMcNl|(%%#3uVR7nl zOBd9P54D?ogG3+^Vtym?UseL-O^db`7%95vbP55?tGb*&6R5&kCh#= zvXxeLX6WGF(Jy@^QaeSYzEq{$O$m*v~P*B^RG{6cgV3-(gkSUl%!8`AVCop!p%(-@Kc5F)u2#c4W>e0 zDfgt0msw~?KqWMkV2Xr_Mx;h~+Rg3_*j%_b0&fM{w#AsmsjYw;YgUISg3fG1MwS|I z&=Q@cK~JX}qd1}H9%(xA!)$!y*d(n+T2??n19n_}pUNZnndC85PeS8dL9f^-w$7H} zm${&*udX7~aMmc1dDaYQ^wQ^15nodZMvt=11&9dRS&;_7Cq0_@Dj*HBy>UYW45eMX zKP#IY!?8X9k>id=-8BPq1s*C0Krw0%;8%fexj*fos4{o_dF{q`QlgPb>o6u-?IX+A z9AoDlW65;d&HS6-zVt=;;~L=1hT;m8?PyW{Uc2V^uY<`Iuv?GG>YX*H%V$2-&h?A= zu82S{>`#xAc9(i3`sFe!=H3W0$FYWk$XO2fhc2-E$o01(zXX|+l)#-Wko+E!uohHT zS~UI_*WAz599ijBEgjS@G_8cxT zd97OKjTwOg37Ku%^?kk}nZcs^CG;!XSaawq^={}J)??#9S=S^ZMN#Hs>Pg>@>La4T zW8^1z9kPq02y9U%L@un3PPb}o+o51atkBz(yFOmpHPRMv3Z$VeHkdT1(W8F0mCx;r zK>*k0LpAIH#pTkM&(txfdUMXpxjH~Zs}QO5FJ;*&ZUn9k0FN?(58Zz=WNRX=*W zJ>^LQ#GF!9W~fheMu{``UR<@$T9MNzuTAdS-i1i%7yvO8z=Wvol^N_% z7wxqy@GuBz)RojR0Ak@~Yc-gG`pfRaaaFaw>-ec6(wo&WHa%wbkHHcwv&b$%#O$c+mGq~ zsK@GWvwb)B+ZIpypcD4}P5z(fjH;T;R8q%qvnVlwNI+$9QfbWZ+AqgWuKO!a_?+vS z4q0L0nO^nz*?wSpfgf{yagu(yUcGp_V<>D+umV12r^-qY%pi3zcHsOQd~6fb)q^=d zxWy6%)CJ;TRN{U@Y*y@0MYH{>KMhEwafm2^Mn}QJ-Y1Hg0_+?NMZ1JsD^SWctq=}M zVr_vZ6?R}65hWB@zO@5fsbtQovA5hB2nWW^|2j+wFEAPl5^u0F@6SDqs(iuR1r_`Vg?T`ZX(?6>sr=j8UxvsVVhzS`yQf z7FEd4b&k?^be7il!vGtR+|bUky+bqI_$kJbj=7t{un9U!Mz>B%)(k!aS*wWA*)Uz5 zpgtQuE9EvTu+32yRI;FfNSjU)90wase){15$2%hfMmxWwUyy9Z!iz$U*O;ze`z4jv95A^Cb;u z*I}OmW|gipy;qAU^&0OL0}bMw@BMH&0ZCe!9x;i??cj7K+9$Pz%CCJm z(`%%i_rjm`cU{l3j;gclyQd)Wypc9`iA9Xwj>*(HgU^(F>;gBmRiGYyZH8La3)V4-(vGO_A9zE{gx8Prvlbj=7d03N9+PJ{0JRg5~8i_~4UE;?|8bA&TE z<_mm$UN_FG)5x5625v0MJr_1%k}?&o}*?Wn*_WoLoWW&;o4$|7?t=W(7Fhk#;JI&C6-LD3bVQ_Sp(TQDwc5qzO#R6C+QIvj` zxB)5iqSEbChc~Y5p_-O}`uS5>{Mz-!N&4k_^`armt(w4Ic~k+$cjhweFF*xG01g+L zvNhip!2=L{3kQ{42muL!5DGNv5JVL~I6M@Hr7k)^?In$=8ZbmDPlR^0_mzskCO-85 z06Qt%BPZ0AAO%tM6DeSX8o|L_uJUOS9(3>|&EUe!=#g6z)K?!PfBs>Y<2%w|RmKW9y>_p@GxPKc(AW28SzW;gpK($LPppiY{}~s{ZBf2E zRoubAlpJ)y>`5qbzshGTdtsPk?@%a3nRN4ZFrvgny}J06c*f3YaCur!zNiHvY56&{ z;Pt7Ke?L)@mj{F%Yjhl@9#oGG=}jW{cRB|EY31-IxPJEcM+Xml_eI{Nq3P9+a*F?4 z$Gfd+?e^!#ZSZ_c()g-#M#5$4>P`J#rGu4~PLjkN0Cl`Z`$k>F`hXh6$3-WOU4ZhU zH_YfRI@Tj>tGrLw*evU9TU?}(8Faz|<=MEeIP2Oq8@?-N z-8|>=xs(r3k47#z))*tS z@_F?XQUY$zPQhoq5Qn)EI(moI_+Ja7db-Ro1;7N@fP z>K)V4hCNQMeTo4}S;$;)lkGC&wki+n#qq6Ukl)qow|eTFYLU(?^;uDS1vkz3k$lbm zG*4?}3ob?%vk7z1O1nB2FA-y#>7B|hJ7N`~L%BF;7c{wMM~wWjzgG8GWzIAvf3C1u z`4)3v#TzS|s+Pa{tk5{HvChM}9hBSG%89Xz9YM|bo$?OwokIfKq1u8?NBX*K2<$}2 zrG>{aj2GeEm>W3zH#o#yU%j@2VAaQYt}Gp?9Md16Q-Ci{(l6I1E<35)J@L%|Kfy5I z5Tq{{vs`<@VG~zXEzCX~up=N~N;4K0<@&_J8`22^Gp$MlYqp`%AeuP=v*ayn%*v4A zd;ES)kj~{_Gn_u>8q1*4Xby^ue$5Yv3S(knIL&RS_j~U#2M6#vE1L4|s!u!T;=)+C z_HNL&7+*jdUFO%yxmgwWwQcxOX51%Pj9+FjG#h6Hbvi30ug$QAOv@ zHDLHZ>k{>C%gq3r#K|@R&k%Ajjx%fa{5J}lP>x<~)&}X17>Ojo6wS(Nc znZLgOTva1#zsmDy8vrhlh1c&hM9Eda=M{X8v1{d|F_h)eQQ&;k1eOO|ftCl>Q873h zA}HeX3aS>>1{f@#7ZB8RqiqwH*lHJLM?HB6gh@r_BZkdL-@7VuG2bGirkJ;zSO5yq zRt|VEqb+oGJh*qt1TDNze7a8Qq+!RlZMKEp4>Fu(xH6)2A-`*(CO`cdzhCEJ)G31A zBqHj~LEmy~eM>nfurckf$5S0sk6++JZR5}-a9qf4&ZE-zrEG}rO54YEnj1KzB-v^8 zKIOJ{k9uX@zI-h#TVu=lEaR4RF72-0=ijg4hWdHdvvUMf6A2wq+=(<-jRX<7c?FB4 z>OvZpIRUNw9<<(%!TPc``N5Y`+E(N!(cloFBYXN)-ds5kVm#>RU}`Mt$D$Xn(Vg_A ze(L2=)E{~!7INXMimFe-q4Wygq_I$Q>sI>YvnH!Lqq8{nu1`!ycuPbgk3GPss;ajr z7M!;J_vwr*reG?kS&h2mJxP^&PFTJ z+82UgdCIvJy0)*l9{mI`Hv-@0)X6#y?_0;=wF3;4#1TZE2jLQ)^ z$U-^|JUL>?+BW-~GX`*bqViGU5%R<=`{&OyA3$?ahj;^%469?vzw=4;D?P~f>hIC# zGG=Sy#j5}SAOJ~3K~y7u>=z)f=^^WJDEOW19Lg^J#WW|Pjjl(#dp3zB2Kk^|@UgM& zUN>Md0iB4D&+pQd7+xVSUDOeoK@H46xQ>7HQw2Tp`S0nux>mAoN6+AatHr!}eQ}b0 zxn8}7Qzl(;5g5b1=Fba3HVgV|${X&Kgn#z5il)mjF~5|G#Z_PNcdDxS*$~l$bb00M~00kE$2|Uu~5(g4pQ`w~)aJt6e zJ7`I$5jF>KgE};n+tD)NN1!h{}62 zztnewuG3tYLB$+Z`r2Ih*IrEiJ{a^a!$VG089c}VdsYe3{cqkkxypGM@43-CM9If^ zIp|lEEvWE?C(eUXj?hs8vL8E!Tm>pZZ$$%5XWnkkD$Eh4>Zgli=u6UKC6lJ_;@f6p zoRjxe5jvv5K(qz=rDGsYQy%h9!a;Wr-8UP7M%NgyYz*jJ!npOGEvLL>uHk;M;~ePN zCDC0r!HrXbZsVYWGhAU_lcza${Sc%*~AS#CQ6Sg31GBOxu4V1To4<8`X=pm zEF#kS&UIA{aRv1zv5MVoW2_V~r%wcwgj?wZ>^AA!dH)qYsK3`STF2^&2db@%-$NI$ zZ&D`L1_bAllQb?$bpd6;6XZ`Q^UEr{7 z#Z5a*QNPzy*JCv~b21j)+XDu@{p9_{f&Rr3boA5`>K)=ia9q&P=>|BT4djXT5TH!B zaf>v7l{XZg=eY)1`My;z6jDQ~@Dy=`YAm>5`@!=PWF7y|x1pP|bnLtf;MCvi_SD_) zudoYObjJNk8nVN#hh6W(59YbFpUXQZkU6jlErU-5Jx4ECzrc3(k;bb2DRw>bgu0y% zd`sI!ioRL7Kj!s}^w@;-lau_d*g{hh2Y(XFn} zJK$CRw2{-)|CGs9hg1yBdVA0gNWD?%vC{fl#Pwh2+4`>SGY#|hXFGPzYn0!;E$QRO zYgfLxwy8g#KceW2#ABuj|oA}`qP zB#EGo*IVgAy*T8hoYePs`~Awt`g_VdNct`>3xz2dSp;0M5{}A?vI{^h$^zo2zKWj~ zZo*_UcSR@zydabUfxTB&X8AmK=5XB2nX$+@22ffBfQsiI^VMYbLO#d-7Jyr3AfamS zDXUn!vaJ2CTf`RS48Y?uiq&O2iHavB<-~kOO)QC>~BzSMbpi4dB!bN~P;A zuvo7T84I0B>uPA~SoD*TJFf=KblvK(14;pgd@CzN!r_RZLv4$!+sAvkGYtH`D?M=5 z6PQ=fWBDG-YQaK(e)q~inVQAQ2~Ubu3H~F*jBOpofHQDh!FU7!*%syMa`IMjhGiWm zyUu_~>qL8U&g#~ewJ-(H_JYo8;lE z5ox2;MQ~J1Jrl>)iNPtl;DQ~^tL^Id2Hp)jd39c^-MQpMzri+N6?^01INuMZR38)S zPnF4TuLk=KKfv^94oKI-$v{i^-V5ubL_?mKZT0UR;!jlw2`_L#QP<@8+^eT8PnL%Wrh zl!+QB{SuQF)e*YHKkqPYz5eR7^y&jHve@j&u5Vp#I!>$4bsH7@LVHl?zP#@RX%h9& zPc|Nz(1JybM?zoIzi@w+q>T1^m0X3bpzQ&GnK2RK9g*~JO1o2U+TxP^A(Q*(x?i-z z#D8yj2T9-MWm#r)r7G25U`9=V-Z z^}R+|t@XX~z@}8%c3O7Fp@YJ^d+TrA=+*0ejQe*0k-k9-|Hn_tY)6PK4s2rwM7w@} z70B9MyK866bZ_Xu``7Ch=&%DWO%e$FBO$()Rf%Fesk1p}OPxk2Q9qDO5Gfn7U09wq z{N!GrUlj*!kPfQsH>RABDTv&7E;GdA7U%#lVB1$?8DCNi?Jqju;j$E`uL9>CT^T&D z&ZKoKgKOQHj{|s0P~$5=AR-w|!JZ#p$;ZD%iJ)RB3^sL;A5Np@cvL;H@KS$|UlnDb z)4>?~$dFUh*UEq))w}Chf2m(jy#)_k)gVu|chMbpY=Eoni+4qU!}T_D;o|PXLy$Oyr0FumYH8o{Z~9>e!ka36CY55BoIwSuoePcKf?T73$j+-3|5} zaB7oi;Hrh`r*D(TVRfCSr39Ey2!7b_j2enSbU@}eVEhHZ5&6LDWJ;`Nvp-%31*Q}| zl~^Gryd)ic+B8b4KoE!Q09f*`xswg;yxqU2OlUZwiojY(H-^S>n97#pva^rcA#bqd0gDPy-8||+TKUcQuX?$F^ z`&vL(F~-EypMXBi&N1jLu=hXy3eoR?9*J{rbVa3O51!rmfnAT04|#oe&d07ktHUv_ zGH}|kThK(Y^1cL4?RlM(=ZI5SRpvRZE9Se;5`C+DQh0FfyIklNG-B}oI4*u%f1mLN ziu@qc&`D9I?U~CsYQb(UmphytK9JL@Pd@a;Ij?-mJ~nsyvSQ0vV6#?xwF%i{|6ODE z7N<97!FEw6)xD~(8qGS`pP;ML8MI;4n?M4WRys{1mZ1BEO`VQ+I_e)?-a*oLd0D!W z+X*pn1x5L=f8{nmsi%-4>bMws`(b$pzuyC!wY~u3zBid3uvB zi67JiP3M~J%r>njfODHz8kug`vJQftWk%lrndcMpeEKS<1IOcl$O97-=jUf6cOGNl zI3DY2M~L^?0hOjZ1Gs{tl4D+Roxte;4|H6oxyouYu(ra+XA~6>oE{>u@4yM2Jb=J~ z3;;~Qz&Ai1n6l2?)1j&3-FfQjsNB!g*4g!5SH0&|fMIJC3!nB}WtArguz7#9XCk&6 zb8Px5fPPwEKWV(SXIFaPDm`{a`4yeJ;XaNd-|uphP5}X$9csWaJq`~=slpEavVi9F z*~XL^T@F{EBkoJfOkSs8a61rzCE9pt9jm^Q)*A^~Qal)#B6tvper13O?yn#w_yW4* z)#HqEjAaQd1P?i&<@N21vpeEDo~UCMyeNp1iYuKu$oLiB`bU-C4!~D_!Df;ZxEHhr zT=+EQcXfaPxKn0!XZRr-41U%&Tyt{C;uKF`Win)M_m)#yWyEQo-KOp2Y$t6Gnd55C;Pdk*&hu%qJ`Nlo-ym`TvTi9Ak;u-H z!2~IGz;yd?=hK3lw))i4lGp^AxLuhr=M@0(oDe+$JOh{yfgk$hx)QchZsOD4Du09e zs==6{g0Ef=yX>4e^6q-tYhu;|jlI|Z90&#k&N_^Jd%E^^%Dwew8yNP^eJX}4d2xXXv!dAiGAU)2?K zn|pn^=;4JHtIh0qVb>-_j{Ds>u~dED?LH)f(p}%wI(KcT6DAI+h+YGKMcrt+DU6`Y zsz2Z5WPLG0mv(y+?R0F-$-itw-h0JhzLP*U@BFe*?*g%8DR^&$EK9(L64*x`d^&tA zCn(p%IhBV=vK3Dyx;FZaWB4-w1EeBWcb!niaQs+y(*RVx zoM!W3Q0MN@!=5)(Pv2ZLeRb#w=o3)ejUYT2ZJs=)&UnFfxTPN-z&S9E4@`W-VSN|d zu)zbBW_48}f4jeb#WDPCr|)+-Z6~AEUibTJS>LgfyN!QiD9USboZtj#Y@8{=E*!vdToddr!=W_S9PGt}Zv{~Ss&rA( zY-jC5Z*S&BTIsMTPT|2mh=8Z%1GBabQB3^=)WPF99J47NzB-Ouhy@SJ&*0ImWF7y0*q>!v}Xp@(xgRg-!6jJLNk*NiX$dMx+KC{SM~Q>j20N0zt)MfMLFi zj_WF(`hRtR5q}#fq?38)+}-i#osr%Zf~>`$xl!dKigkiOHCK*`)&LaUF>|2wTn!iT zT%5iryq82I%|{*@;tmW?p}n-deA014$ROy=Yynw~&+QEQ?)swVyzUEVDnOwFsNGmy zbT5HD>n?4tU=3IU`8#Lm)%QD|_!-LuQN8DvyY}A6p@>9k6@Tiso?X4FMdn~T4aQLDJfZW%I1Zf8X)C8? zVBiV(js(mn^f@7q1FFOHKSpdj9OJ-o98h2BGvc5Jwshh=XXI*@IdOtp=TEQCWfvOh za%g|5uE12cg$QCC!>2s;#E=P{TpezMu}BPa4})T@7pJDuZn=h5l+M%@hphUH^4b0_ zzt^$btvr9VHTKGX_l`xRGr8z9fQNWgUDH=a?dtD+Ro(NsxXk%q@wwAIcQSFO+bf>h z(FB56owuXoPS^Fi@A|y^-rLdJ!gp4k-+6Ag0%>PoI$luK*jW|R6;dZIuKGOc0AOZC zERTN~pI5w4zhAI9Nl-ZTGf4!eG3O_SFm=)s^Zdgo zsZSgOV4xEE6LTI$<53n!K=6T!)oy_d)(zg6vHsu{8eV4Dw5;u6^$i4Ut*eecR=Y3x(vfVvV zPYM2s$b!#8x%zgGbd!9wq}}8>7XhwT@yZZ^l$&y=AOX$@3wF+J+$V?x;-(aQdz-+v z{GKPq%Y=z`dEnAR$z5GvX`nmPF(x62OAw&)GlyExU#+49G$XaZ5JS|&S~X~4lW4T zD{${){>wn(e__eCx*opa!Cvk_=dNxgsCNEfsDO`EfcPu4xpO`$U}Jg{Uwnr==~ge} zTIIajKyjsEL9GlG+ScU#p(i^4y==v&b3V*^1{QG#DhFG;peog z_IM};QzD3`ofV(#q%MW)4^?w^pyB**XqbwBOqpi5Zad+6Qmb-S<()H!mF-wAPu+()6YNvapX*g0& z|9X9Qe}CW3M)$sSUg>&ku@8bv{k^_jTVBz>$tc^AnI0atvS&97oxWfr+7cprb%Tf1dLRom`cAn(a`}8!K*eJ>{4T zb)Q9T7n|=SG&yjZMj$n@f%yWb=TFqckKM1 zj#Ymv(1es7`xMXzRlTm#-`Sx4`$ca_`adC;ysp=YyF0op`WsjN?TfIs_86<3$_bRK zEvmHc{oj=?)4S*ICebP;xT~}88m#?a^hnv=yW`!+(>sbETl<7N{LKz9yf}KvC~=?dN3h*3p}Y<%T^;PLoyr8ZruxPx{I&dK1Hk!S)CJ)!dn)n^z#=A5w$ z4miR<9u5>7hD)xbJjM}q+o3EHTbB%gKLL3H`ULP{N;;54gmI!Muxsj z$s-)4rA4wZRYwMhXptqkN5X!8LK+hq$6^^-af;mi>IFV?1FZV^?!e`*eE&z6o$aXaeC25L?<}3C#~3Dpus|A=j%v~^?r-w3%gtCP zYxZ``IUq$4lweyZ_GKoGq0eq(k>A=EvsEX&ec6*=`=X~Pv zP{?@V7=l9;I^FKf3FwJ)PKH;bHc#mJbbUYv8Q=kL z);M^u)*Yb%&$-G~RFr**xe}pG9*7*KkP{-GPdM#>>RlG9$Lxn zpQjBt1FjH0GcMy9r+sg90PF8NY5L^gD`&a?-fd#%VHt9%x9gxzm#X*r_VzpHaEJM} z_Fd8mzDwm+mmMwRQ_{?EBF3IjKQyP+MY;38;reTbV=B*1%*DwCu-Lmk4meQuA^DBu5pnzClhkuU9s|sK_z<-tuRPs{&NI;6$MJ!2sHcBP8L`8M zOqZ(TH$X8@ThMUM6SgAsw18&dyPU{ke&3-0gZ?Pv%ivJtFC{lemWB!72@zsOzfPGG zUsTg3u_`UQj@SmDHT|CMv-EUcyD_i7y$TrZ>_n}D?W5>O@o((^imMY-*U8@6*Jz7s ztOmW)k6own@6oRJ@BFN3OLn@RW8KGQ_s*(^Dc7|BcX+Ma+nxOEWO-*FJ1y^4@z;L# zlqFq`m)&Hc#|p-5?M)ga9(4hO1JKn@3H-q1XoA1rcqq={aJjKh#O|m{H*v>KOFg^( zR~mI%?@Ax@-zo1P>AQScb^sW-H?TV=a#zRh`wj%|lxqJR4z2@CnwGmLuBC5i6Q0GLd;$(`(YHL3{O;qFyTF~EL>K~99%@0V z4KRV76eCMzD~*n|ee1ZbO8?b1l;9WGtfz9^foKb)jIpwRTJjdc0s`v6fnjxM0nfJL zsu&Navyc{k+A3$?!m)0Sb2rumK0BbaqgB>H0JG1t7k~icKpemC26$C^imIO&YOAz3 zdrY3Cp*v_paWzQY!Hxdfl%(-Jd4LXyR^D-^Pi?iHV3cvC0~BVJZ?%;!K2FvKUsVKO z^+$jThsbK+epbH2-VpEf)QtEfI4<^~8CeIG;~^99$jhtGDHZ3=5FTn3ypK=X24eQ;2dEkOMd~ zN1f8ygLp1cjk8p0%)vr0JZMlj^Op1s2bqVu@%@rENeJ9*hyW~1$ik%Avl9hk^nD0Kj{CB(*f3x0=&aHowXX?b;?!Nl_ zZUy_U>|~;sMULXV0-3ZU3|2WkH-`exmzo%@KE>)NOssZ}g>ulZDrtEFuoo&DRIIGU-DV;(lko10q-RuxffKZ3)HU@n3Aa+ zcD_W_$yLF#9&ta|{CR3Yq+M{lW+_gjxM(S8JRH@h-Ax||Vo|_u{C9fpWhr*y&y;tN z^j%&S3hFBbT!s0P1o_73*5CVYRT!#3^d;nUd_wqv1%#O$r6Gl{G;^Tj&K?L5xC%|g zmYJ(&j#40Va9{<@uV}`06MIZv@A5X+`}_AD z@BCTN@b{Lk+iRQd>_gw8-W`RVPEHWt7`k-~AtO(&Kw&N?l{Sm^|H+G1{`FvUs2A>#Wz|{^@@O;zaX-`Bj z9;O4&IdM+K&mVtS3V<EPcl5^z$}z3oae0>A?i9L=U~|`QOwJ0~89M%d`cH zMzQSz41rDb!3i-iA<%h3}vE=)z!?nXKzoHLza&cE*t@F;w zqcdgjXT+p5$5lK~vD;dB)gNCw$~&9b+tp?1l^%U%o3Hn&2OuqYFFJhtr~x|bs#4S` zNq|mYH3!Hs!bZH(Pb)UAIt_u>-~oOHNEPsO6h5`!c-X|0Z3!u`QDW)}zn?md_O7qI zzY7?!H2B9iaJP*H&08eGM`WAJaOPB zru@Xf;aJRl1z65#Th?hS&gPt$=TCf2vrlq7?A{^x_V|E;D@soQxhsxi=78O<)2AbL z)7-9YtZV+qP{kbLc%GA(BQUFQjA4^t^Hk{g1jYl3W8MDkbgO*7!@I9BJKUC+dmC=7 za`ctXt?!slgRXZwj~LzdI|BL&#a*8=rH?H5yua%<6%BCdQ^kB8-vN8Q+}n5OGwts0 zr9V^gd+%GvjJ2Kpxx4Q>Thi;S=S=K$Yafpt4_0606>WBYiiI#G&w>z%nT^B!H{w44 zIK4^3&w3GHNqJ-bnvmc)#C)z3uDfTx`z}4vj)wmh&+DieM`XNoHZrB zp9xz5Bvf$3WBPKd7xQNt0_nfc-1AW$9sghNE&$U0o%-+^AX>rUC$&q@ahyWhP4 z4}f&DRiPq^^Z5rpKY!rcw~5C%aU2#9`uzL>(G%Z39#9ON^UPClhhUxqpPx@Vp_obE z#_;@n)7Rt-2W)<-Fz9;uLS1mDJDQqB6uPBZM|&1+ZBuioyJHF;JtGQ`)3Dt)$#D& zW7O?+;yVzSOIgZHcx%I*e&2y#bv@(Q(I=$}|23Xi(#LH1Aaj(3lUnq{+9p3a-W^Lj z0^TNT&hv?%fBX-891|bM36TS1D4ypho}Zui_U#+K9RtrZSLz&UlQqw$;>VAt1xjJw z=r{zAK?$;sicB1sk-J%hhqy7sV%IhHLJsIWATlB1=~^5-Pm$P}YSs#N5MZnrI-nSU zd;|0YDi7E5;=0%58L$*7b9xZQED|}(6LI1WI>QVkRysQhp_;K9d*`n--+AER2| ziU~O801ao=ox$6d-(U@~Y#bqe@3NC^otJi9`S{+!dW8jd`e@fag*YZ~yW;(`?dAKx zLzfHN(wEZ?7n^X?cC*n}jK>u+oraYjcaC`2%o5~|cE~7ps7`Y2+W}bMdkn)|^&Qk^ zMkhpHIFWBRCZ^+evwg+pA+HPSJvou%X4UBj%V^=UNcNCYw|iyR*XisNns?0jwa8-7=a<$(=iOFl>aBUgHLdaU*D zvBVCW)UxB>2#nU}+cka~KbO9#;b+>K=kq6?pMT)v_{3xU1n?aq6Q7@-kfHeau)NnY zCoJeG_;^^*<>$|z`20NGJ_3S)ahM&LdRpo)XqN{P~I(WNp(|pF4VZv$nMP)$$IKzRNF_owC{~yE_N{ z&Y;%-=@v+D6dsVk=UQK`C{vkG9R^nDoPjgs8BF!)O9<1KLRY?bgU~@nS6(ZCP6s%F z>BQkH20nlOfp3SvfW@bQwDXCnC*<4Vc|a!g7!GjE8T|OLZHUiPZB^niFqpds3dl1~ zaTGQ1cMKRBo&(hHs(=o69C+%ZJ2v)d3s4PIC{zca-vJqzV!>FOogPrJ*gLmlrYw=w~Z!Zlim&#a~l;M3UlU{cR1}P!J7vTLH9c%djdK~ zhQ*kYKz+wQfgd72(r#5E?F_JP(SX0vK)wTS@^%2P+Svp@K_82RTFycXc_#Rq1Iksh zSRFz5wn5BkKx+e7wgBCJj1HN60D*W_7x~`llz6U;hs8z&GJTb+J0?8`mw`yP@N9?B zpkuk#`?2fWj_(L&?#gb3&0U?{nc3;n8ffcnhj87>;Q8uJ3Fym6#;ng zg>`x$Z6LO{3iFrV*sVKI-^b#*71uWsxg*920akaBi$at9E|=@I&-^~QDu-JLi_BVk zfIoix|B&y%A=C0ypTqN&T5js&0RRJ^PYWm>hv0bR)Q?FbPhawv ziGsPbIeAehj)Eq>YE9v3VZ?)|JWNk*lcoht2NVZ}9Dp2VcSHdBX7Awva>VeFi;?E5 z1T$h>dH})xuLpFz%7wj7j8K5|M)zPC4N+Od2d@UJ6+mKb?~};)oZ=& zJ$NdTlj^%XzTy}HOGvWH5C6|xXBSLm7yU^K2;9;1GAR{YSZJ%XC0p{{>d%h*>R2y2 z-E;D;D{8LKtm834XCNsO4ki0;H{MIf<~SAp1#Ro^uyQ!3@N z6)V+rOVYN!@B6ctwfg-lneTR$r3VdmSlZN}79EqijWCJ*_7(^bIJ4ecsGS0TR>c+O((jL!}j z)TF}~1?pj=*b3}k({MDXY6dqHLD|5M@IyLfjHNgv;_QsED$D*LoKD-{@W& zlVU%bZZWY+y&Qb&*Y^B<Y_ikHR=eb?(ftL`t>)nYj64MwoTw{0PJCsl4)sIzhHd>U zx~wr~jP@*iNcr03i0SjQ}SSA;djMf;@6 z)voUB_65_najf;#v8dN~dZ7mI*tT3PSPvzFVRd-@91`C%XaU0_3mHMt@ZDobG6EQy>7AuFnVbVaMCBb?OW(>4~{D0c?Eo1!nAmR zS3iK*iMcCX*WK~Z?l)DnbV`slXYp^8caZd5UY0J@x%FZN@+>R!az>Vcr|b84t_3{n z`@51Q079m01B0I?6ljOm5m*c0 z+x&O}ya721^2f&q1b@MN{sEC`D?x`D)HzQ)pP%@Ae&YH3^n7f#g#I`N<`j(M10Ns5 zx0VThJfF~0@bT>f%n|Ck%!{qM1y|R|z>vcXH^hO+;akB4>NM18TU4wJs4t_p;9-JY zg@H^3bJ}H4&|+Z%sbd&?#{g-W#azKV6(P-d7AS|5XoQcsscLhFg5#@0YgC zF~{C}=$|&u>OlbKKoRFc3u4k0mtiyEbb=&!>1r|-VB+mp2ZAx{?m%5F`VjpSf#=|~ zF|eh<>P}I0#{ix(?YK1m5rNE{R0v?fwv@J^@jX99hObzeK%8DG`8*G|kml6I^JVN? zpd%zx!?t5Yj!0igW604s*7o2!z$RcNZS!3VpaJ{ur?rw!3)m5eSpV$32_P!a?qvs} zJLu_vrmogX8t?h%4%q)nxzL_E^S5itl3U-e0J2`&fui1?JK)a3dX~OR@>-~>uxlx! zMM;KzxErfJzH`EI5%RDh=f4O`XYU2An4bbifbzk!1@j$FbUm2yme2Xtm(< zFmE4o3V0$7={%jznageO%#04uG9@*u)l^0Vp7*0GF~J0^MTgs7$an8l`nqplnOjl@hY+{ zogQ}%f2ZL#0I;!%D><&uy!xH=h~SvpDrfeJ1|eo^ApE0VmI7#Dt`X_ z1D~ItIM35{fI-va0LJ*hF&-F?BevQ9{CVPe3O+t;a!jX`g$Rdlf-47^jfcs>5ZglU zy9}I}?Nby}2B44d+oo_Q7+j7hceGj7@$^6TByevCqA@saxMhX~M6-50Faqs&5Ya>#xFMn$aRX%3d>BRH& zGy(jy-_mXdwn{r}%M9qZq~Ua9Yp-*|g9NG87k7P2U5kMd@x<_U-L@IJ0v9pEuXdc# z_;}#s_zRw&4?I7gI8V#ZbDk5=pFc65pO7JV90%05)Qdb^Ioiq>c|3f!@xYHy#W@uZ z9X^}$$RJ_lwmJ}7k>r4=Z%^?+;grFUpQ#+5X`Z0c^VK~8@D(=gJi_l0sBhme2T_%~ zz-buzDwL`$(SGB#y^#rn;I&vX_m$Uzuf>!%rpCb>GBS{^$XujS-m~(J_%?pcEpc4M z1g{goI7a3V6K{{l)H3k4cam#S-!>O~%3x`gRT!Y0Q0toqf2}>!gW#(J4Zyas*5^5+ zxH0g|F;h?clnqd1Uwk=78ZA0`K*^Dth7|lPed6Sxc9_Z3Lnm8-Kw@ciq* zBb`TcP|u>bziPt{NcQV@zE0mKgC;ObD*hX+(1@U;V$!b0tKuGsGyc&*p_>La%As>^JQz}3UJ z(!eH@Zzi$D>=*SZgh5cBFgR=*xp77f7^2Yo+J26mt(b8OA_5-TC?4!uXqkf%Z9^S9 zVhUoQ3NXt!RvJ(5haCo_flCh>5?FMAz~hmi{uWk@$9d<$GWg2L`olHF)QY z?4^dCBpF-;qc2xG@pXW|+PuGayM6LV1`7;ws|C>}=|iQfak$bHjY*V*m7L)8j(X~% zN)y_O;2%w=+~BkKP2jocXAt&f@Iv-Fr0V^?GAwCv4X)nF=XEDT39Qj3`GD(4tOU5< zf(K-L2j)+Fs_iiNse*HU;`y}m5kze3_v1K#Avk2nOs{?l#^-}OdZ7zs;6C}tc(bfD)V;x_~wKRC$*b)2=PO?k-omw!gBkulS(KX0Ll|n-*P}?d_=oc4OV!A9BydKrm78t)E~s#c>zU zc&UbKYyVOFE6Is95%KxK)%H=}Hj3WTwtugs>bUr>y6gn~-SQ5SzRSxZa##SQ1h43j z5I~qw%>#d04KCEYmrBYUm0q@>N)SP%Py%JPgFq#bns1dOn4usKqGqau;R4J6iU8xt z6#}fA0Fn+@#7xq7roll|dK#c(#L77jHo8G(pa<|-L=P8@W8j;7hu{-aPduLr#l-O# zI3C|H#=zqkk=xP^*`fgzFsB;^@a_9wpw9sv|H%VdAB&R-~s+?$ub zDU8T7^3>76h;bZ87=tkq@WAORbdJPN*(47Jcq5PRXE1l5S%g7%2Q=z!g$3qp|AKX# zi>@(k6|Yq?{1kVF5;abLR!`P#6A>j?EIiG*7;=%!OG??TdC!ms=7{8A2pMoV-5ZDy zY&1%>+;v*UoagGhBS&q>c?MU7JfZ$Msbh-KR|XDQcaC50Ob0Z) zua5Pr?TTN4#U8l3b5?iGYya);J^CA4SYpK7iQz$YwQoE6{HoKu1J=8Hlw-Cj8vh`5 zTeRMF20@;$st0UxfPOT6X=v{ool&+`ZRHDV*7`oS*Xo$_^uMivb=N|UYiayAFx2b? z4~-Fst@<1v5PU%K#Ch5Z9}&U#@84lgn&5E=IPr3b_~8=bI|#h4k8e2VU!li0*dZ6b zMP9^p-Wm)Qw*?yZPGFH89$q+YYd@V;I;s#$)gq~{p_P9}?g&xZA0vou=gMb%L|i^n z9?b4)@W92f9D828bDDB8<+{C=-(NY4Rql3<70Z2|VLp$7x%R=?tmleZMd2c=35*EgA>y&k&)n}X}kfDGc7_+hgpPh(&z^p48k=Tpa((Dy+ zn%RH5mHE0g_=Q+N0rZ^4c7w7zTYB@|%PGF<_7<5-owi2f6KlTb9{zJi}MRUi<1fEm&kH2LbN#i^Fwesr~v;A(V7*VFny*l<0f%t)UlX4fI zY^kT3Leeq%#^8Xk^W=dVOi08+{jNTaLk95Hqy-(U!3g6%t`MMIOl)EdJ5_rIL|}5J4|wTQE8Q9e1}C|@$gQ^?w(Jb zabIt>CHXsLcFzmlRv0}r0?#|FxZ}H>&Z>X!Y*6L7Yf7Li|K9mHyLWW@)$jc@^c}vY z-(eT`wC??=b>5{!+qJ3Ft^U?`e05pm=k9%X?d!5#>C$(w#j~LPG0aI@q10g@jvyv2 zW9M;|u*GT;y`05S+Fr*a^6y?!e-^v9x0^i=A&+1Xiv}&{EV(MPNe+GoP8>MofxrCaFSY?O zmJZm~`&CJ<4iO!MIj6E$8QazV>w4|)e?ZN zO0Ke9c_f&I{|6=P+vLj40!GA_Rw^c04u&rLc+b%#+7{4R?sW0BowidvJ2I{U(6A$E2sE9c(qP9JL+BS>`?5-USE6Koa$j{=`Y2?_Y z%ygcx*E?@Jh!)b0{NP5`R_=H(S^acITjmD=a6+I%Bjm$X*5oO3dJ%2t;DtOF-~Ap2 z<++lBGS!{YJHCj%c5#qvfR-a&Wwry|NJ1~ycYIY?Yk)jINGx^a9`yW~^6EMA%dQYW zk0B*UnmR+7IZ3GNT*ezPC5ZFh*(|&yhpO{t%u3y@tw?fEO7=k zd|iyEIT;uVjK>E=295!Id^|!Q38TCMSit{)R0m&u0`gQqzT@%uFL>e`REA}U^Odve z!82Pv&0s;*Ym$M-NdF=ckC;dsCcXkJCPrC@Z^7qk#Hb4llSH!s03ZNKL_t*6jG!?9 zjFI`-+|E^g=;>TYe+Ff{LsHAsRemEsWWzCa+;&dRT>$BVhc+_T<#}}ylP~*wcK1h} zNWG(2pJgyH9L}3MSZdqSQCqQH-0RGiK}N(FgwtNy&Swm#4agz!ybzg)jpI})0RmU? zVu!0O4wg9YG5E)Bs#uB~PCfup|KjMQ@TtO9F(R=KwP7Fcg@yuHF73n$7RsN79jQA3 z!xq!&B1MFq0<*TM;kG#wuw}5S*Z~5%P2oFGWz(-jA2$!*2VGX4`kfLw49E$m(sZs? zKP6z?+D9KBSAA^GWz6h$*Ojx%tjjnY15V#rBcy>*Cw&y;jyKtV^1G^{ul(D6lAiV2 zS1U*Bs;m0$3@9ZY5@aBqyfkD$^Z`-9x9{I@Kpgm`S>m4)ybn{s1n) z#@*KYUS5s;ozBl|#)l&NpxvddgBUjZ((mo>te?9>n|49HuY!#Iv(~lK4Ld&V-+TLa z@2PS$G#3%|a+eOP%UbUra1DIcXYORS-rH%o%WbASov)kr2&QfO`4bSg3!uq(=&%$-Vnx=pIH)?b%yIAT>u2z&|=!Ki^H@ib65FRt-G z0Z{&r1tlCTR0o0eXqjcXF@iOSG-HW6kgGHmIwcg0!kltU#Fii1cKE=M4-7m3c^ciF z*3(a}FC>6Qbl0~KyEZyi+_iTA3^7z4#Be7-_zazUiAmcz%gN7lhJ75FwnSk0FjWecjUoC@@yIK{EQBJYq+I`*O4nbGPj^_ z=UiOV+28=( zro1BLQuRXGK8|6^x)#2TJcC?u8qdpx*7Y}j?wq>R4cCBYy%zk{WWUSQ-6`NZhpg6F zf9sCJT^p(n=nmVua?IN%c?jhgJ~mTr;q-;Yq zR3o4mv?0c$Npt6Kc$%3R0dq~;1>bJ(d}yLS1IJO&$cfWaBvHSY*QGAkLQfPM`$eIi zUu=HSyJC?x$6$6JcUQ5kinL{>yJ(w6yu+>wA)V2fSe1BeW06;jwAyTQh$Sw(3Z^6< zdmI0xDX8_p?WLRdY+pjx=q!0~&$=e8zJG;&W&V!x8c zU~Q+n|{`7_4+P_!Cl$OWbZfYs<>gXiKRbxydKvF{hPD}Cbv@jA=h(t z%!k=YxSgZU@F|j1oyv*0()Re*bfr><4!3783~4IUFl8OMJKR?L894G!ly{KyU0#;1 zRMwe@Jk7Q`%UzIw3ZUIl5n$(F?+nyVi4w3%Y{SpMBao2BWJ*JD1H3v=B!&wcDkh)- zbX@W|bIfhhiWP9MgfapZBd;R`o%9jw2xm%SOQO)Hn}8meazNySt?n! z-Q_*1x?ll1#V70Fsa_+XTpdwQ7ZJ1vMD6s$TL=*{es#=;FSlOXmqE?o2a;%^S2_b6 zvksgpUr-064B)cr{X&BckX;-Um$?CC3N&}*W0Zuz!=`xC0Z6&Ig0aj4Y_({ivCBFT z`iFJxz|}g7{WZ|*ccvY1R8;`}uapk5cYyz^-?Y-JwUK(;b|T2q?r1;Cu7&mKg>U%& z-RblU^Q!~L5qdn|xAM@+H+6Rgf49#-q<&39J=mB(JUz&1X)%O4&GJ?YShqdI&BW97 z@l;@*_S~sIFy(=vp1)JX4p>sA*s*J>oS<>%js`Jk>8s?#C)!AF$Hcj+o%~WdOue21 zwep&ec-U4SCmZ7{2H9QP^3cYCt@f=uAv*_e=K%HkcK7a_&7Cg1vr)Txc1~}1?3Qhl zZri6`SEqExaO>d0wXgqedW923BX<5&x>o($>mzS4)l%9pfJ<7$b=%~DeFdY^fn$y~ zP7<(9;5RYZ4Ljp~=rmq}-3BIu7kTGy3}gICziKdP!7?tlY{LSrAdwE8bcZIOMxIG04e>arWE#lM6|J9TJJjErB)MeYBeb!aK?+(K`CK?X+oTd4o!#etjv z9IBCKsE)1FXL;{J^B_pjA@nx*zC5t?F6cyB)X9VDgDtee(xJGg%XSa0)w*`_Y2S@9 zwsXxFk+_}?1f}W+wjQv9l|HSPN*)s51Ahh`L=ykvX{|rWfBFMczC*`{jmn_-NGvJ= z5H`xxh9c5w2&rHDv(hzf@YPn|>6aw{7N(y1N-ob=+OM`e1Lt?|+u4))+pbMr_tw(y z>3Vf%^Xjv^@0~Wg-+>-8SjVBZqvqki((Jx%m7jZmtMBnkHVu3F)pzy&E__jbtGuzh z_gDMYd0sDu~E75$3vmE$!zf#k@ptDBv~{0FexMciLbtwOdICfyhyQ zuyq;39dpBqhl4aX`*J{W8bEU;ReZxxAod;)t_U#aCv==PyK`7CbEnG$h99oMx;)P* zXM@BY3dG900v3vsFp6Q|w&OUACx9YnpNjIIGj_-f@vY48RZ$DrNj@}?q_DTb4>u?V zj>?~7spil{FhU8`3N70#V$f3sf&ohczvi>cFCPrUQJqab%|~jX()x!1?J< zlsf>{OE^nN&A{t-&i+!rgX74-s+^ec?f0AD#3kokX=k*R;6jJzQFBNlzQWwEsZQ{K zsi~2X3$YCa3Yj@+VRX$&4m-d`%L-cqBjRABrda^?P6UDMS3qxHv^=Y*+r=tfb^wUq z>pkIkZJI*5Qcgl%;D@-CHi_#5${JHxFZKk;ZSlvEZL*iK@jwIO9l+Xew#o)T9PF~w zCw%4#%x|dcyB=)1z&G8CIPci$@~`945qQo|PG-{PXW(B8{Q`5i-q*?elm~!y`+Ifh zdZ3}(pE@?X@4LV2wVlJ;^;UPb^BPb!SK_c$c6NFw?dQ0>XPE?QZ6^kZi5%DaI~^DI z3v&-vY$1_pNi^FKtD+po-RbjtdQ0$LjwkzSaT*?al+Rfjl{qZ9&-`kATVP<_2n_if zb3b9UnYK8e<@27C-Y1#sO0jiito6lYk>krc%^@|_sWuwLkkyIRsK;^Dax}dN6f*)) zm>T+y*pqmfIuo+mfxwTnT@jelHNXvIj%Gz1jH%cM=Mz`{xuWq>+DrG%+01q``B1}Sv;*XG)}`ZR;sT#?H0RCubTK|MtMxDSBT>$^bI%J<33cXqm;JigNlQCqdE zVGnI}H`H;4r&QvMzV+w;XZtf}wtBoI^@ibC;%@ebd|+5=>KXirX_F?#v$W9}&G3$v?C!(F+s3o{y=Yt8)3VLi}k1acEiZe>07jf4xSQs z0zl+ORj+$ZI{>Fs=?B97GpE#0t1AuH9-;=?Lf@w{SWmc2#Y1$;LxU{1BC%RM=qu7j zF2T#;fdFxUVn9=(t=8e}9Kq&>1B5!}c%o6p^9Y|ErAF-_3CP_-OWlbghmM%_f{Y z)9=>^cuS;o|{In{A9%@J5F&>W{%q2Zh7VXRFh+b5wdij00?B zl%nFiaYW$A-abqXMb0zOxpTPyMH0X~pP>tx#~FHf4}9yJcR`A*Bv84IeI481FZJ1V z>tCfu{jA@+9g1gH*7ZKA>m^Q#NdyJxteb+eUuFgMx;pXz;$S?!H)J8UhUbI}OJ7NG z0dll~VKeuWEcF@tto&YB(e0ADvJs~P<$mCB&}qNh>(ZIG7tjv)Y4;f6_%gSf(fkpi z5l9|tGsaQIPH}KGf~1~6*gFQT#oI`^NeLAf(pmW0bTZ%0iNvl&CHfGe!d0@Ue6$8A zGsu)<9ko~I3s>H)&n&vH=~{kvM~mZDw9LXQ{F`LF=+&KUv^MR&*EaO6o=XrfCJ2G! zI2I>xx81KhoKkX)aT{OUOAWZ_mizYCPs5lt$&=flod@7JY{Gu$jFZ4}k~)A3c?Thl zPd?H z3_b1C8;%Kl!en}?1I~MdsG5Eg06M4dYN38TEZvS1uF`^b#Z6b(L}-4mSQNx!f3mn* z3wxXaZTp<%JI8HW1U=i?ZFp2J@r)qHGx^y2?s}4Xc?bi1NlRkvT>xpf`tDUe$X#&Y z&hFIr)q40_m)%USW@9y-KAeOLJg>xmoItgK5Ga`5EAmo1@zqa*)rLKW3{3JXfA^oI z;k+L7>bkfFiul{zq<^RBo!;*6?)UF-lSDtRft@@2)7x|B6W{6d{#(cHl*c<8wtKE# zBaa=&aS1%v-|M70?Zhj(hOe?2-+KR@J?njpT>^g3og8(Y{E8-fSt<0zmA?JC{_LH- zzI(Q|wSVu|?(q8U`*<9oPwp7j;5e97rEar{N0a67!#p5rsp?4g(mxF?Q1tc5b@qre zT)6uw(U9w4R|txg?ibl}+xZ)*!D@L2N#EtmLY}6hvH!g%Iv)Pa_4#CCKEGE)9VBe; zf%vO5PqAeSN>X&kG3%$*UIHfdU;iSyTME%$boSTs2r#PH7Y$i_W=??KuALqx@_?e>gpY< zFe&6Sz8NxQ>|j5{QqgwEpHR*3)*3x(Cuqi>qso0|Loy>Krfci-;fg0IuS) zI*;S<@zMw`*Y;PM?Ec4Bd z9w;@7EDzT|10xO<6MTb=4@`VOK)zsKk`lK7OMX8{+Vw_`f?Va}7s@rbaOImA-_j3N z%^6nL-VCIsU8(Qrj@!bs zjsf#jhh~dJ4EG2jRSL?Q19Ei)?K2ODiT0L%!v^s?fZUUwdVZ8gvd{b>^24y#@tr$q zC~I^k<1R^DQro@$Eosl?Km?S;Lq9rMgYSX{H}Rj zc&!xXsO^&tAU#~JBp5{?!4GCX7?6$;h%{2=9^wEUk>B%fRb%}dD0B;Dx(@s=VV)w_ ztn;h)N(9%fA8{}#Iei=$q7Xfx^Wi&DX3`2dnJY#9(*BCs1D#N{)u`6KBW#IDkwC^( zhw=L^uvLAW-rt>Vt*aiZ-s(Z-et-SD(_0Hq^ylyNWDmIZ=lU4k{oe2GK{PHx`BmPz z2B562eyG^p0fl!#(!K(=(vgQWf7QoMr|OUORqI`*Y8|_A?xiotxQkKjc=F$(^nBgB zNw{BWgSy{u_StvZ3{!MN#LTjozYZMf>tSNzgq)wyIZYqd`u;Yd}3H^QUP04wAmh7lkw7HKz>)u%VCs zqysYp1t)3%fY01H40qT1?=t{c37pmYB6!5+Y7ssrAeTI7f}fEzmz}i8) zwd(+(vC)b^klPZ8EM4K`GSIlF&^UQjJ>WUi6eYu<732-E9Cq{vElA`}yd-t+#@_0n z($f+^s`TcssrW@KXuy1V1a0wNk*G#Q!a!fa%DgqE1p3N&mIFj)b6I#p^O*@i&ukZ+ zW&q}-1VBu=yBc`PTY>>Pxxrhy(zfzupM6XyjOF?Q<|tntnGrF^V0sQ;281bt!w;I^ za|`wUZL!4i8Y$m<0I&XTyouPZ7ps-)y_IjN4*cstD8bA_7GT8c7$J4(QU{ovCj@^$ z3BVS&9>+Xc#hZS`3aoVT?6Csz!IvW{hWuyfaKIuw4_$JwaIcep z7x=}A!^NiD4S1iK?|^z~2ZU#@UB-q4X0BQ4bkaJF(X}l(R$dhqm1@E*DH9{*uh__xNdOp@2YM(Nc%@EJ4~0B%*d{2YLy`yO7&SBkz+4>)YVwE< z42YhKJvaHb0D(>|q$s*eYMTLwMo@p>Zv}kI77nMi9Ob=UPt|dSMAU~>=XU+D)W924lpGHKScyAnpAh~+0nwChVFmtbUU2(NI ztbTu&ub#6FBC#TjeeHFweP^4hO$iIOtkOi-u*45l{Dj2L0*ytoHs+t0^RxrmFfpH&-sN~4IF82>?67CPK{)Z|D_y4? zHsap*v~`F)s};{3pndzjvg5s=tE7fsT;=kfx;QxOO2s-jgLhp)tn^0pKWf8@t|Omg z4J=jtr>K(!``}LBl~--bE-<*|CEe$qzx!@Ma0b|nVB|lWyE?!Sx5>QgB=T!uN-ks| zSfzrn@1*+}_N?JVTNq%6xwI9L?nlL{Mb%{-*$@7`n=Fbk-~7KT;m6zrMf*GQ`}Mxs z&bx`VT0ct<`1&2q_FV&bI~uSK`YQBWR=Y)>$#L9y|9jiI@{?gvU1TvPMq6E@_4{|q z?%lh4`uDr{Eizd6?A1b(t^5}IP{*Sm8r9qL3j3`#z2c+aqaSr2aWydAH#a*Okq=IC zIxdnafc|0jL{0z`V|qQ9aSn{kpP6b;fy0~?3^_24N9uCCvI|8xVE%mM^I=tfA0Y>;XHX@! z*fBo^w{-h`0XEzS(-$8CU~u+BixNo4&Mh*)1GS5Y?J)^*@;Uz;1^NeQDt8so6NboM z>dt{Hxd)(<~1o6Deu$+sYAFq0P1efZ4Li;_(hqHwlY@m}%4&wNM zPC{`wwD6ynci76n1RfULHmJ>&G)y3`ei($o#LU;m)ff<4Js<*KNm~r<5Ikf6hn*PA zZT6g4h&Dvf0t+2TPaDS>rx63`kP+mFB&bgC>QyN@j{txxdNNp`4rs-%^Dr|%JU!S1 zQuw(D=Wr)Ti^2WvlFEWaDU4OFFZW)H`0v%mI@QX9MvcMujCx;wVW5r`+uz35(N^)g zeONVUBtd7c=(3!T0-XnBj*tx-i;1B=i6Mf=<3O(XID!{Lz6DS{jrQXK^<1zbpE&%0 z1eF6A8rxy-h^ESI>FWx!uS)3eYEy0;k-H%27VK%#ew6PBeuiynD9TvH4?sh1&Fy-H z?_FM0`6~KS9f*-^2|6CN{Vs<~7)Jq~AYUeaQn#?pRW3KdxzNvCitT~uk~7cvaoFZq zbqCbnIcM%ns9Qyy5?&vmIxwd*@POI9VY#!J_Yoq#MQgQf>zL&=uE0j&5fL-mX0A&; zejjO6X~DxJ*#@1{cO(=$R)$i-cBz{$fqH5hq1|+lPf{#_p)%M#Fu3A_$~S`EkXjGz z$>LlM*a~6COOg73iLNAZ-PsD|EIjCFD7B4|@jocH_UfV;4lc8|y? z>4qF@1@ilE@y#XHB z85qL9MQX_e24Vjs=)rcCKv$*trgR6n)|J6e$?kZYn0i5K-vVF3Y>={n3h0F50|QSR zM?DeS8(GC6`1URBkjMemb>*DpXlJ_zM4ry!pHO^2#{+pvxzo*ufp)jD-g(YTpx{@F zs_nAD=jYX~_&e?W4DRVV4rT09rlX@ahT`A7mjHJqNML*s1lC=Go*VlTa>fM>#YeDL z`B-y2y_tinx1EmDb%d4F_oPdHuUNJQ)MWEn^g#3vp^v#b&;FYj(^e9XNS7o~E+{GQ zgxfF`=EJ6s<~y{#Q*@<4*DbvFj%^#=aXPkbt7BUo+w2$}+qP{x>Dac_;mP}c=UjgO z-9N^>tWo26szzz8Ip@j|$q7yG+v^DjLxlp1-zxbsm$%}a>U*Xrdhn5%i+!IOwG8qW z7^&vCtaJiDYrj?v9AiQ9pBWT&Or)jsAhU}#3Pm;42NBs$W-sm!Z zUP8gwtE7ged6yX}LF>9n>fLYL&t)UPeyWk^4shA7D~|S~U9idd6!^wA%|44m`rS-g zlgPnm#`d4a1RG(0=@M(VIaE(uz?4JfTPF5NpsnNI!bymF+?I{k1TMp@J-lWg%G@G{ znQC9T|3{O0kp1yb@4EVP`V$U^Fsz{VrqE&Bwo5t=@T`in%-otqYzEJg$bi5C+)@37 zQS8Vm>I$)stRdusak;&_7tNqNyYhN2$Q-ZYpqhGHz{FQ821g>twwyb=F<~3lrkm7&=;7%#Vqc6Is#{E)yE6!2oyc+EL#bLb1TOx{P+eo+#WmJ#dADPCk6u&&i)J zz7Q+Ejc@baZ*U(E-S4iEH}+gpeP=hIL=?)cCjp89noA|ujX8JZ0-gh^PSGLKFu#Y` zgpJprrqO4b%opqM*i&hB%2e4OOfM>16z-f4s%$qVv58wcGYbzvwF}|?*?u3_f!*Ld zHX4{|$wi!YP@usb=dUCcdl-+*Cf2a0S+iBx&{xz7y62Y3hxHv)kU&Pwjmdb+)~i)6JCi0EjD60qi6NESE`+ws-1F9uefg7O-oW zmN*&(EV}6@Y)t#|khWXL&1>kfyV0eF9hK_vhxj@&Yr%WT;yqcaH{FA71Am}n$eVp= zMJF-bL6AR`e3|~BU;8^M(kkV(S@W^;mB60VaFY9DF zbzkoU8G$c{&Vkr$Y>v#M{@8-l-IUobPI*edo^=CPfIi^M7S)xq>tBJT#L_q^>6c%~ z+nw)w_uiEr-RHghXQc1D-RFi|@w?if6HNTjseLoPbdG7EFnHc+i_Czr-KqTaB);IM z9vIhCn?omIS6Fj6ER{xDHEpKu@_X=VMUARJ0v}3IEFnyBwImG64OD7Ko2Zl z8OU3?%h5&{;>jqJJF0i#3x8bmXKgX^Qj0as`T}+hu-u1x!zYH-FBihEVG}SPc;7W} zJAxz_b8%f&xPm>`Iy80aN#CJyTDrWuS<~Qwyf2}9lQG3J%M`c=f4nMO00SCNF&?&+ zBWwa|b&JtUN{-cU9MMxd@YhwGPNnkHyMIb6zFeaZVwZ}o%0-jXQnjvIgrOhQBjL4z zx2t?7(krV(%E&o$>jUPO4a=u()mOD!d9;WQr4+aXvUh3O1lr~6c5)a;>feo)SOiRF{iw1rp5&Ic*QeId;ns}t z{{fNHSJ90l2m1dNw@^Ao%{u;$oXJ~aC~?g?5GB+q4>sz1+EWMGKI6e*Z&-c;dOMtt zv0j_4UPfc=f?2+3r}qEpuRCz=1eLTeSsmtLs9yKqAqGlsIi&0R60mX?+Q@*)Y3-f&2GQu%$VSsHmV@6BC5rMd42@GS9MPo}xNP%wOKuo{D z-1@w9y}3c^LNaagPUGkKorXF3tHe$JeMx13q6r|6R3o zc=?wt0jLk#{8W@Y(CLX0f0p}Q3U~n1pK{4sMkPrX!gB|@E``1P%1i=Qspo%y40>@fint%Bh8OD;jW zz(jP>R$l&>maF39bls%v<5Tuo8WPWN&2+zck8h`vBJ>Fhr}z)@YkoQ4HPlkaiE@A^ z2f|oIx2n_1z7NF7kf?mLLsiN@Y}M#~Qp;eR0AVc{aDRA$rRh{RJZAr}Tx#U-R@PID z^z5oXucZh89`5!%58T0HXIc4{~7qu ze&FX_^#^W*N(sFJM!nu2K-e@2-mnG_m87Z{0W;u>t+w2qIBX#Qk4Jvx-`_1VhQ^-Vt1|xbZEa zqhWY&t-g0g2>iX&+W$6h5!H)Ql0i`(g z77MAraACDXta*a#KRp5hS;G9)UVSE_o^x5;_F5(Joy_aA=e3vN%dwkNB5Wfy2xcd> z8eL0pniSJ=cOdQMD-!rOxL}bd8vzh+53NJ!m2!|uFcXl7DL5u+3MKmWD|zTcF7^GF zQ;6Vw`QkCx+dE*^rbAFyo%0fNeO*NckgWh2t>4Y zi>)1h@)X|Avp?8j;i}H0kyY2@z`mns5%D#v;!>#}17Z0?;z76`CCjVGqI8k{DmfD{ z#-i(Cu4dS-n7C9&Rx zPPEN|YOz9_y~8yH>sxd$y zjl3vCR@8^&D8k$d)UicRVE7K=Q!YJ;VPc(glQzEy!jFp?D!nEjU%0!J842cE{F+S9 zr)O@g9_gXYa2k9U zHjWn^Gz+GILyM=eBx8Fer=KR!&^x%{`8*jR{k9$I>-1f+Td?r=cDC;goc4NW52-pa z2-Y;&efO>mV2sG@r$|zgr;iE^9=W?`!xXB~OG^?;3+!2V7fM*MO5poLAeRd&{VMOSmj2G2Tj)*pKBXJuGJt0^l&I#@LF#$l{9F z7aMHx>cUl+{0Z9}8o2+>iRnW_lZ}aEzp8O5NzW|dMH376!1#mIk4fNb2TGLr;Hs5U z89fN)*4q2XyNTWui`nXL>PRK`{-$=rnDTP7Lp+b?0-s6fP>B=^lOc-VzzA8PG-|#d zp2lZ}WQqLXUIngNuWkr$GQ$o?%tbB8^hHXZAW%EG2s6Eo$z(c~CVrT}Ef3PgIYp@s ztJT=S>OadRYX2qcZ5bWIYOrBluYqTa=O5CRq*SwVE-(?TOz8}ZVw6R}0LwNHsSWGW zUJ0RteEmF2#^dn@UXrX)^;O{4=SKcHwEI)*>*$N&|G*~lKJrF4t#`Eq_V^j`F!-;$ zWR3?-^S!cmy>GTtnEt(>GK;_0wv~ke3W+Rlq+Z`1997|?&$Fb)Dh2}($-yd0MCF3= z9D54@+aU~L3M-w#z*9f;l7b+m%M=hv-@)HPDtab6JS<3gh>E|^#pL)K>C~`_pppzg zAuOpRNLE@|>6a`~B?+~@rLkgHf2==R9}6y&I0Idxw3XgMY9bhh+f`~Z+aIKxZST`R z3Guu%7$=e?r{s*(&jTwCrZ3o6jgSF;IEq5`c!W_Y)>30KHF=i=OA1Xk3aW!^jJW3S zp14l9QAn>^8D0wPF0C8bHpDHVEpfxg=oXYRw~X}K=Z;Dx36xTVqnP_YFo^J!=R_ca zu}d&T`w?&R`N2V|0ZfhV2|-e1V8~)Z?1pSVA}MF)4l6_z96SixOBcMi#GhG&DbIRV zH&M2;HvG`aU9o@KMA@T$pS->{gP2{D#da`acv*+e00rRSUw7>a;Yf1*fl;PPDGDe> zM`v@WS0gK_s(Nf$RR?s|n%&8W)GS!q=~INM;?+Ry*y~%ft&tf$X>aiH)Sx0hMg3k%WR|RF1kuOv2`-JsS<}^I3%4$BGG2Q>+ z-6CLp+}+76gX}`#27$rC;L<>c~N3>Xzp_AI5CbH;PEd6!T3+OiN{7$Yw zSEYrY6ThEQ5P2?PUNy-%G=W1|v5#13cqZ6zL5*S)EivB=z6-)wiqqj1-h_HKOHOTM z>ztZEM$M<wh^} zw>&eaC@wqU%A-l8D&QYul1|+1-wllvpOw>eczuAzzm87*Re%TvDV!fHNcdrO^Ba5~ zjPi=mpW2o6-UuwX!wX*5rmS)HQfoHu4lf^wUQjULyk#KsO$VqpcmgOR zx1`A7Id}vOK-Y79r2PXzNzhA9o+i=kwJtbe!4jY-VHi_k7!87m7>AVgE>ckfLtz|4 zpW^ec3*epMSyWxN67CU_4`}VAClu7xo`SqV58J~ok0d`S;a~rd5^p$D{(KXw*ma;~ z=(ngq?cRt~1rI^nL@x)7bV=%X2dNgED6wu(N|kt}kwe%HQEytv4tIYtJbiY2-qG%9Bs@D(re~sdDS3aNYPKk<9n!~B$$68tl+$i#O6mj}UXrYs zSr9Zp3h-m`63WZetk4)v1VO}K)s^HR+v0Z-r=WoeQt@Ok#8)stj?|z5 zXO8Gy$)E@{Dt6GW;%p>j5KZ2_lZ9Kd5Wr(UT8q*(5?>8A4CQI`#1qn|30TJrWHclf2~5;ZFN%rq3QQut*}_c&n`RY&0=`c zU)zH{3r&!vAdt~_OAs??1SSzsJ&*z}86RKqC7CEv&a^;|uOeu=Py!GmV%hJ0d+kNg zbYOxk&_6*?Vt(%LX*x>F1(XHWu0IJ*6mN194oEf7k&WvU2w97at#Y@g5ljjsMb}Ue zlZMO@t2uB7BbdveNg#;{92;+{r2_tfH)${D0cSf#CoaPuT!V8HY|g_H!xpeD5**#n zMEy09N|Z?2dYq&n8iYoB@X_K0z|b*3qO7y9P$(te`@N-2M%-sl9XG<&l08+8wb4+V zf%7EN8%Evy`o0_~KAiYBG)zd$+vGxU=l7xs>-G9khk z#DNw80KI~XC$MIV%D5QF=z_|)=zD4d6&O(_N|i}$>7V4bEm7T)AU$9Wkq*xK%Hp#5 z8};`Yc1b{q%k4~-Ow}u^abrThlF)Qmjj;h+gy<)Iiz zlT_h>fNOzN8AgmHt+kLCQX@0yMqfy^AG~vrhH=UwU2s8$qG-R*rgxoqIcp~jqru|>EYf=ZD8d?LeP3U(VN3>< zEbmF$h_liV$In(=tAb-9W8!0i8ZK0F=rtd;yGRB_%S9d5JkU$3b<(9z*&_4|jsM8w zKR}q=O6Asuke?U!P?Jaw95Cjbp0OJ1{i++z7s8U?G4vS97ja~l*Lo%CChOB}gPxxW z&YOfOxonY?*|YkdNxEuGEwmWQ<3pe}+oXa(7F>Dc@}rOQ*b3&{AFrFYB0${`!&6Ql z17gm?BIsMsz6OLG%OX8!X|0RHheuSS6SiEWc*PcbOvgZJwJHi*FG(yq`m4?LiW>uC zgF^p&8A5r<;p3YW>~Z{~*G@nwNb?(+2%g%nOwcfIbuaY;ba_x<4dO*zn}XQxceUK2 z<}hg1`-t(|fi0Q}!@Gw1D{n$ImF%tS5o0#3ykY9!+3MQVIB&^lx8UBGraL+O~_ zL1)+ujnM9Hdi_Thg9*yQmTv<|Wf1%1{KDn9<(EtYIoZuxd#><%zW;YK(SR0!sNwit zGV_9(^LwN-$z6))&op>%qN010MC8bD86M@;I{d?huI1J5W3V{_0AzR$^3H5OR7of= zU^}_{?Hl52Cy;_dk+h5ioW9J?DEvDB5qi&L)#rgSW~z1nFkorMAJT$Md@rx2d*T>6 z5FSQp-6r{|<=nPZe_INC!G#TgU`$yN(^q!#&BDdH(TszNU`cGC%qDcnsK3v@A}&(m z7ITADk`xU&JrQ1jgYr%Si-fh1JTnv@czoWL#|X6=fj-HM4=JGsrPOGX+NDZy6t+a- z#`KFUuTi-DromloKV2joSuvLJt00Xin4{dPGByA>QK@KJ^B@L5RpT@$5#|PzlX2wv zbVT!t$L$qmf?`IX?uY~7TZHN2DM-Q2;{;2ZN0SD4hqgF7dQMQH+@Z41X% zy0MZfRMr%4M#6ntfKg!Tz1{U@bG{e=?Ed&$eT`QdX0uV?S5ttGST}mBR~&1*yBy`F zwZ)-8{^_ z{)*mqBI_iz5d4lIMTopIAg5ahPWELZJq@s@*UO-7^x#Yt;CrlLG@u}@wG?mo^~a%7 zws%6lh;q*VZw-IIF{A>SC`n_h8S$`$%VTXAqoM;;UMFSwB55f|BShx06{Vv!p~Rk} zTEG$A%4=yd9^BhLNSc$Kj{7%TU1H{bGAywR@xZ-JE3R_!K7P&CYa?=?b@wYP57!L{ z-wF~_R7dUGVk0-EwU^Fk|5;X`Yt07QemmvJ91}7g4AWiEg-VaMy;)Z6hIP$`?R5hG zKeV@FasIyi2ps0=k~V=-P}{RtQ{{?G)1y&W1T`$!xYAcB!7SyFyM=#4nCy`In-9HR zHFA!|glPcwXz5_LL#QTp7&$St1_XYc&;+MU%7l-)Wm8j6N+}W^ zFE^qsk0&Y>jBKAYk&{=}&a+F3gr@oBkakLhRi-`ld$L z39Z%JQkuSHTL6OW;;XnnC(EbQq)64#@+h;`T0CN*m%@6vpQz>Q@5R`-O1WJ1A+8() z3;-$>xB60$EN+i}Y+@Cu3PvA^)((|oUzIhGs!$zsgFCurj7ktPfn=w_pId%~mjSiF zc=`F=%|)XyXaK$y?-_(p9yC7*wRU7WViWVIhn8dx-kiEn-ZaOkc2X^=W3E5EisBMj zjX+Vp6KZni1>oSw(q9-hgoD(EJZ~{XXgNPw1!1C&Tu5K%o$u@*&JUw z|1xt&fDnhwuWv+k#-negFV8X&-Ye9#ayB9i~9X$pSrz z?EV*Wx=6~yd<99=!n705MXHH0T&J{JJD<$4^_b4Qi7$NdR)%;FJedMg*p; zANzOJ_a!qAVFGI{h(eSh5jyI+8i;R#wH%DuLpd=R;j8t$zAA=X6#7g|6feo>)QM{{ zAe#ied_st%6(10^$F4`L`1?%BZH0wR-L<}-SZMpLi+pjIyGbiLR76O*D*> zU{j12y$PW}UBSU=>ZR(1TY7_{E8ggjMmUX=Q%gl$RZR_E!YvOSti9`CA+@)g#0#^u@dhG+P z-V8m0MSpYLVk(tkLY1lWecVWIjSrxKkeNbdI6AYv`{cJt+w0K-DzU?lKS+%o;nKa7#Yw=*v;39FARZ>J+7uTq?Hr1_9y>hq6>h zV3Z)g6O{`k>Dkglq_^rfuWScCbqDjm%pxiN(96@+^Dh-R1?Kr_aOe*=KFNW^3cOm| zJi;r5&lvNbwKqK!-9$`fwYGLIz2f6Rtpw|mGtpqAJrXL!2Q4e*BzS!RiyeGNVXMrk zFs?u7uaDyl{(KoX8u)Swo<)usdIbMo%ORv%h2RL1CHmK(W$bBV#oME@jj+TDKe-{X z+oXNS4XQ z4JUaSH7K~DF!yKrlrEGy(myI^uncU*xirQZcQh1Z2XIb!>VD4}6Id*?AdH(PvVI+}6%3}K8(7Pn0;KLfCqFOUxjkaXXxs*y?&hPLn?PIKx?3$O? zx2(OhW;+GSWY2V}>73dtztnFCAY^{;dKkB__=Pbf!>nCE!f$V8axaJou>U_UfZOdh zke-d1z6jw_UHy6K#gQ37L=g#Um{WPm9S`dYk0?|E%RV5zTlGLDK5P7frhu@Nj1rka z6`-Y|OUb@dp51gju<86w8xFaZKm2bq=dz=5Ysd&FLOVslZHQ-!y|*l>S-7-?6d?6A z^GID$#qwK&JN7+h+1?@3K6mNhwUZjoJ&9|zc$BRFY#`B*6?ykTt3LAdsJS(x9s0Qd zrUiyP8A`h_C$QYiequ?0SYq~}pbWwfclGub3UyqZxTOR>9hjM-VQP>Mr)VN9iWpiU zGyIIeg62v3FX4YWhdZajVI4mE^oz?bM6&29pjfvKw(Ikk9|-u!eVnN+?5oJ{u$KJ7 z36LEK{f+*r%2l=rDeeVw=daIN^!UD}l=ST60bYVr;VEW1c3dM@&C;SoR9u5cca%-t zHFzwhdRC8QFaOTVSer})cZ@ycHHUbJj)rG3lRAR%2WVb8@+1}9K35+IPcrY?D*cmu zYjNa&1Ec=@jQ$zhQ6og8`nxzX5GM7#JXqS==k`~d1Z#Y)R4rw2uo&nyN9BcHafjT_K1gJinRz&{i{{Q_5mZ#p*`#7`*U<&w;;f zpQrHyb5K`WWKX+7P)J{6CM(9Zu>Cvk6MBZm#5rcmZhs7K(}`0cFi&$yytlaceHsX@ zfOf9LM}}V6n4ZRWauhgzF9w+_8d&LP6D@qolZ~0nOv#1IIM-CjdlcOKBd>BJB$Dw& znFWFot(dR;EIll((2(M{d|}Hb$;3P++7`q#Rtl{B(Jt^(8{L`>4O5BdtFl*gqy<=9 zz!*e{-!U)%%$(~v1EIK`o6I@J0z}9IxI9N+a|n+GD|WhS?Z^}onoL5A7&OmElgrc9 z#gHh%g3%-lk?qTysJyo&YMaGXe6$HiX1hb&`usq;zOeHR`^pBGO=s;49%ToX7QRyr zo*$cVI(ZZp+J$wClAEYpX~X>762}hlgL~~5eJTP=u;;yG^{wV*H@1bWtjGYK*3~4e z(#Mb%kkTFQAc#}b*)8pi)nv=k*KptdJ(rA|z)9x-R(fk2M&?x^c(Mv(0Yte=J(YE>lHgMA7_R zs7`etdEw_59%}}uTky7Cq6HTt|7H_Uta)A;jt*-{wC-AUB%1&`Iw4lojO32bjZn!{EYc13b4)hELhPu7% zGs2=HU2XJ+fX70pp1&oUP5TCFVtl?5`TYKT^nGXdy5A9huK&E%6Sy;Mk2Qy)G_zF| zeSmhs9lpm*VwUuvZ>~lbAlJu?RRas6RN())9M7T-NK<6X!%))ki}Py~;>ha;*DUwE zq$sf!NXVXtvRo#!Qn*ORL^PuppskU0PIzKs zQMRay2tM!;c>!xK<*}C^$j;lqP`n+-1~b+O*mrszAm@%$}3VRg*6Y< zJIYs*p75sx8?%M=%MzXT90{Yw7##R7GAk6V5~PG@GZ_tw*wm`PAyhQ9Ii3k~_D**( z7lkF~#@w~J(HOqX$;cSXW+cxgKYO7Kp%Iz7S2o2RL$!k|y5C{#RaDs2{&}bbnUDm2 z1)EW2_jly8+KoA{Twt4Ld;_}}snUdmQq0@07-s)S;!N10Nk~^0X8Oy`-b^@d#`vQE zFqUS;G}qNbvy;f7u%K>K<3^$L*J#^V`-+#%zLn_}B>)=IvwfMW7X4g+T)RD?&QJH#N)~I(V2RbzWGrCNjnGM5vTAru_&MHu8a<-{yA(LO?rV(f8riAj9kk!VT zWJ>+?v&3hC=SZ9zL;|Kr?C;W?$a{(NSt2bztM45(NyNgaN#rktTr{SXl z$*p~w8>n?LzVk=5Ea#FLPp$N!wOIF>L`;U*KV9-_YokwS)nh%8F6RJPaQuq^3_vch zHh>onBw9|~x!)Y*sx7RGmi}&kX{jf@T|F`_9jNx?ci4;*9=r8pqCuCB(M2?($%8Pb z_i9l>J|~T#U6K`WT>t%C~OiP1K<@h#e#I|js=AA_Mww#cQ5vbS z^%5`$#zUy(IBpkh%)&dqEm@r2&9$swz9VzyMD+&5K(`pA_KwCIZ5yLi z4f%ORQ@v)dq80fwd?vf-H;Y!ky)~is&_N;`%JCGUB>c!jkgJy&17u5Aoz* zcy^Op{aI&{O0V$5)PQt4Ngn?c#j*352*z1VDF_U-!|-3ft_Z(w=g{#GYm zzc}!TNuT!<^mY%%znDlJec5l>{6HIud51Q}wLi-*^YfxBN$qQuDpTYqt?ONR;D6~< zkcfE&{`4-VSmemoQv4H#9r;$G-9CdTVZ`YNfWYcwu@OK_O#O|=0#XnOb1Tpj2gMm2 z@!+(hj}|PG{<A@TvIsr(0= z*R_EMBYWqqL!(8M-*}N2*GAaB*(1#aJ^WM+bXu!h6ZRsC>*WwkKl5H&0{i=m92o!V zG9Wh!XfP`1T}A|Ny(H$n9YKl9M&&ffx=@I^@;dT-eikPJ16=ZYMfMd=;<4<-DD)Hx zoEi$}@9QovGr4FdJN^s7P_PflV3L-YrH zYs7uDWpOg)AP3M%jR zLy%7%3`w0^L&o%!R=_e0t1d8Zwq%H#D?Rhb)h zsV0ypn8M6&`^O6Xn}F3A;ym}I6oyzOg!a9;TK4$b56;TKg*l%?!<2cdD}B8I`Fme7 z1OI8fhSqidj(XqJ(T9;B_pghktVYoc4XWAPOWS@2#q*E6l)LlLacAQ{?0u&Ntq_`R zm6O+rQaj|Z@yv_QZQZL}){|EUYuhyn1SSM>qZdDPZ@Z5DF8}3b?=nlJZsK$LW95Bx z(nq*xrjz?#RYz>?`H2)|xxvw*dY{V4pAPevUAY16c`qLFqOmWkBA&kYW>P6fn|Q(1 zz;NP}Zl_)9FY&{Rs&+$R57nhh=yW?@MVcGqINzu3pNmyDl2x!aH*W(uFFyWemQP0? z#ixPwATb|@RB3f*5^~*iB)B!&sgJlV$>MXNHHnS02nsA;G_`n|4F$d;T~Bde0mgyp z2u7tC%vvKa|Ce@i;Hlfy!J>ofZlFBNE`HV0Wy`MnU!vjbZ%q-rTKlKILik9h?0iUA};lLD3^E+hb0h|FRb8h-KsCp6@;VzwPp z%SjBdpr+*6JK>hUA?o@B^Mj56EtRol2Ot9j-<)>(&#`rPo$%F9z+(}49fXQm>Z(p2#Ks^3j@v?Fmzvcq7dMoat|c?UlK<{V z;EwLnr(sIqVBe8H@D2Ss`y6DZ1C^ja&5525?86HM-@5Yq4N9t{3mBr%WoDVT8798o zyra6x{(KmG3Ut+0_&Xo#Fl+XG^zfP7zPR8wCc^ zTLn5oY}<)@7Z1^m>{M1b>?1aRWqKDk{AaHGekkk5(ilLku@=MBxA92d>cRxkuvk7&=Ha>ZdPIWkEN8m#1HGwb5S1`h(z(vs24)N)Kghp^7OtwgN~ckMOLcXJ!sbVfyZD*_$R!uF;(Psd;Aw1SjHbQXQoe7gX3;lqa@$m0&O zith@rw0exq>-WAlY$f;S;b~>)PaUGdKk9GhAqG}Xu?e$Df-ndhEgny0wiKOZA7Z#D zG^p^Et1Xa~-k->EXgI@C4$s^PscW93M+s*V15K(COg17upSG{o)_Pk|XIt`(S_AN# zU3Balp7YODM{_e<1PnyVQx9hqIFtP^BoyQW2$DFXvlU>?Zz6I03<>=K>nV*~;LDXL zFjGl?#{h1gK025QC$hoEBm+&!>(tlvh`7LIg$FP-A{U z_1frkJ`2m5-X$vmnd##8HF@lVRH%&hSt8z9xKXNO!=rA#^5X6B!m6xEa?DxR{NgZU zG)eN}%ZHOEF6F7S)Mt`%5C5p5lcE;8Hvh;)1=)fB&zrmv7+jBUFj<$a2!Pf8=+%7e z4Arw*m^Ip_`A3gJsDaKY4iohZ(3J2ec$|}yL}<07<(bWU#T$HWllX=>`hF1i^5`mQ zUQTM~G{%HLC0x>hU%yYp0dWaju2gM_Ghm*@KM6J$rUH|7ipAa5V9i$2NuXf4wk=wu zGVV*mF#FMkk-cYym*vF=9A-0H?fX6J^5oghKa_owDdq=-AfimRMtiGJ27iWW>DY)4 zhh9qncY51C8rwu436Ga4C~!47{jbz!BdhN71(o{Sex9XPGw*E6WxMj@K~&orToP*) zj4X0m!O5SF{3u{_pu7hvE#$L^x)X;{1JNSehlTgUsu%$;&DzrF)(5jWS+M+x#>0)g zIECSqD5A5SO=xJoh|fJ=juGAKlE?AnYI^-*sc7pvN1*Iyp!cKaS0EAOXMi8)>N zr|3xu$DTpNSh~RgneC(W615Vh0yWz4Ij6cS!*Dfm%WNfBREVqggrx>}4<;0Yw0PWG3@m?5L}8SKw0 z`aIAfj7b`8xAwP%Wd~%W8zPaQ;TWPF56=J4*n_`Fbe2$prQ&KFt#hjkuu6XcobIB! z&EE@O%wAjF^C-Z*V7Aiv;5w`8h9Z_XFyncF|sm74KcrnvN@|Hh+am6Cw%h0 zVvTOA?lrW!)0p0ze<`~mA`2bL2Kl|_XO%YgpU&e^1i3JXS_vcXuEz;J$o@d3XWEvz-=OXwH2N$+#bIp}pb6E7g@5a|G3W z)IYDPSBuTr?BucI*W8E6PflK!nBK}44iYQg@=R>n!6dZj#xELn!kLyHsnWCZ@Cr_Z z46*b`0y3#|&Ln~&TFB&=xTm`;J+~UXbQ}*=eopT=FVLszhb&C z+p?$GfBh+shdtKX1*RZmav!B-i*+g7S4xM^?Gvnon(zHy`R%p)le?;_I`?`5X$KvH z|F}%qB`)ieE&0D;s48TX?^*WO^CglC@)#ASOMT$(*8F9#$dVBt2XsjdoXh>|g3Xca{i;!)#F@$7wRMNTw6vXt2KIjB1WT{S2@mmX6uQj}qq8 zA8l4N2k$5+^;5&fevK%z`+kGB_hM4;AdK-X_22Gx;oDXzIhWd{*FhJgDSgP~y&{80 zG5YnH#DFq~cs)9PtMYjpb}pYEaKJM7zc9T4Mj z)2l_Y`2MLNqqp{r6GC^9%Otkzy_Bw*a9K$7AT|*m@cqAnTK9b*nWHrPL?-bt!u>F2>vLtMTg9>B}ugc1|TD z&gwtvPKOF38FdkUVi&~y&RHdVUgpC(x*tM#I^Di*Q!QC7*b)b*FTsqmk&`?|^{KTR z7Ywq@DR9g3A(%b*r%D%2o(AaCMA~DJ+L!vRJ}W3JBYe{meEjxj71~`m-|)ZVe*UxY z#mPkwA`Fh62iQQ^7FSmL9KL?l2g7_k6m(Y`@xlImJy@SI;@{qs9oP zJ#wC?Zj2-t9i7FDY^;dRjD5+e%v5%{nlv_812!fR6kEGErGQy#R4y^=VXZg^sT=0> zJ@fs|Xg+PxFp8Z0&_h@by74La{( z%>D2ROfmBoxl12wc^Lb-_0)#pJpaJn{pq~#I|hd%Txkf?PprrHkEd>b(7ok zF=G}_Tj*qmAQzSPkH87YR>vbmLVh23)1j~Q(80KLht~~A#?;7A4`@IOH(_u}1v%-C z3S?_;&XAmQY;_J6pq$54#t^_nR_BkZjLT5{MrJEuS-cjJCo1X$l3$-Z$UQf890J1I z0^Ak^$=flT#ZzT__Yvnecy2eQ0VQzqi_gq)+Fo_&&HH72jRU~dY2jri5t*} z@NNo9qx$^>var()qgTVvc##pd7ml17%-D0nF{l=OyXmb=R{8BJiIrAd=&W&`qUqqt z9Bs~M!Ua;H>|+I1qmuc;94;n1N3~J_mCZ`^)1+)vmN>BVt4`Klkxwy0i)}x4!DUNU z7xkcoO+A&S94CKWYCrLk2<{hv3kJWJ{RO%w+JPu81m|2=v3R;(v#h&*B+mv8koCR}uuO3_N<=zL-~biDA`W_hk}>Ougame&Ml zan8fqN&ojVZ`C`g4q6a2AnY;pi~i(X8Mx|vmiAKrZWXu3_V`r&Dy99nU;1cE7W+Fp zuXB#ZdJCrXh=rvue~4{ls@D8=$zy!MZk`io(rbY)9gEJ);<#Px_v361@cUj5jjHqO z_=6N}tzdP~DZE+B;ZA~>z)C?3tI^VG+vS;sC5@B#8cgpuM5v2P64Ct><0S;f`INX& zHt(bMt$yy9tnJ+?ot`_jh!nJJ)lMP`20LO+Ml?J@%^xJ7#0(^Y+{LJ7rRDOY+a~ET z(U@hncYpnuIUs)Yg25CQ3Ao}k-47K9ih2YZoKJ%7uWe#O5y3L z^vU-DsWAwP{n(>1h`(9ZTwqd1Ab8_Yk7O-(?A$6&&hGCD!B)1djC1&@!2bQ|&& zh>+m<$@9;Z()6ka^90WZ!3f5Pb!qcBJx>=+#d+VrZlvmuoo6Rbm&@dhT0gl^r%RIf z&=%PK=n&bha<%wW78}$8PxPE>o;&#k=XsER3hggg?}=;<^ZgO%yuWu|a{C$Izwr$(KIp^H(C#)J{)mv3_&S#qRllL9MiSu?`e6Z#9=OCif5t+(Z zw-K=4v9*X!&S7?3;CsFI5$^2~dLjKiv!cDlaa+Y+!J7h5f{-;C#z6!_Yh+50l3scW zcjYLvKbLjn&i|hm0AupN22%<7s@DtQc(cb}T-1+uw3||C_=IJHk8n40`{N{G2gCLpKBvJ7i`E8NlQe8VabA$w@c8ohKe23k z-R;iIerDRkHkv;DDV$-q%0hK5>YVgsh>c+nXspJ!%G!;Q%zhor4W%#yqQ_nsA&AOm z*C1tTF?QJ(ph`;6KH6ntax;W4i2%q)4fPGTp1faT<@KPWscwJmeez%Bs36K^kkjeR>RZ%BYD*Uw`zM_CBRNxAR9|}nM?Gmf z*-=5k7pO1jPHccWDE0vfklH&eqN|sIgTL^EdaY0X61kY;pg{)+1=w|ep+B4`zkf&5 z(1P@#8W_`rfwczlv9i{wQX;(kH$N(z=n&1kIUwp{BC0B@?q5`hc0Sw0oHjZ#Oc zhCR`KJ5p;e6tY8>OBZ>I>vFNS(LtM2f%H{08&-SMy(o7;$u;>e9bex$vkEo}%u^?t z0j;QZw(nD<`$~2&PZxn)@~UEO^c^-85jrRZMIY8YiB!uPf(!Fb7XHpj7lI0AEuM^- zVqp#%mFm1n??V%y^;>)inA_K9FkVyYN?>Q!3o|-A3 zN(CmgP;k@VQZ9O5>=6WFKysS^#p(}%hGS5UnFOLSp9x5Ftydr&*SbG8S7FgdlcH@t z=8nBLbr5$Wmt2iAn{~fZD((A&dE)WY3tPk+L8uI*j0_Zf(+Sn!ceH<=?PAx#uclc7NkO^g1*N~ z*mQe}OclaDw6EgUG7?01+Y5R)g(Ppp#$xeYr8*1zp%FKCL>r`r7US~EOMzvSZ>x?> z7ocf3bo+x%%Qwy+Wh(tO%Ep9E$q$T5*T}9Y``dMsZM}Ht-BONT*UnFRXEY54INgg41f!iqD3UQ z-LHY{!>;u9)uXTE_~Gi$G}4^VIEX03zaD|4l7a2cTno|?o+4^ zI?O4F8UGQHOynd?m>q5$?xRJx?^>z8>i?(eLe>ZBnfD-6CHSBsGA)*C;7VCuv@afj zF~48Oo6tL*$u5yKf1-2>lE|G|zIz8wU0VU5K zpRStS{DdI4s8qD+()sFEAKIDm-Lo6w@4UdTe81%9Gu1~iBLxaCdNljrqZ1uv<> zAyo;Y(>g>U?L0-rbKAo?q(DP~#CsczO~!CLxRnlF@sp$}E=h*SV#eEIm172NUlNSh zDe$fVN*~|;v^IE!Ter}p#=bO7(}*mbw*%`m5y|?A1Tha36`j%Ar~O4H<-5Peaj(L}gXa$|=N!78>=xDtB-<`Lk3 znRopocAY^9colvp-ooe-RUgHS+ zu#9h$$E9^$+C&3z!&>2IZ8z{=zjoq3WZhgY?I@N=9PTKM%+wO1+58MB;fTe#8yz5w z=*WHtYGOD}T{iMEah6>MxKd0mzod$I2Up8lfzgiNV;(OW5P#0NOg!kU^%n>S;2~5Y z@`Q!yPo6g02^rJQ^1gGm_P!&C*2l*o`77zAwmAEtFfV@;a+F`vkGj6Mef!UOT5v@{X%|gkG`meKZMEesOG10%?u4l%A+ck ztIir@FNsABXTqc-lJR@R#u+oKj^&tVB{^FtXjnM1kUK)FD|DcXZ67?GGi-!~S$17o zX@KdWi4~+XWWLv|RwUuRBECuB*LIGr$>WzR=g3U|}e#Qv6=x^Xjri;>8 zJEsk60G9IbtJ?kpFXK0V=N&W_f%)A<@VhcHwR$Mkd)^#w7kh}jdIv-}`oigK=%DTl zW9VmKIno=!gdi?A^~?$534_C;U9h^`WE<`(zaf6*C*OnL+}6-{1@)_oa}1xh_-S=c zrELPW&Jcir+EN1oKy@!smt|LkKHdP~mZ)TZGzsCttZ=xp*!DV!65e~0HYjU`j|fM= z>k;|&`n&t@*%|NWjv2pjnyJo3jY6|F6)kISY5wbFw1kbz|0evJ`miLa3G*z(p(+`v zWS~M=RYT7*#+9lzDrE(AZ*L@`nDT3v|cM2x{fX%GK;RTkk^kU{QtpnY_IdfRYV z%>S*V^PU&}3>3xcAI}>eI~G$Wcd*A*OdfdaAuVyLa}OTbTo8}{SCaSJl3Kbb%NR)@ zO~D8s^?WG)9zemf-VpnL_S4iN zXM_e<=Zf2*JilwOl_dl+y{R=}yBPbM7 z%z34j)nL`D!I3+7uwrbLwm=eB77Y}O;KrNNy?D*nF0TZ#g=)BP$mL`te{c`a{}QAM zu7adAB6T*L@7|ipu8mkQ@8Q5z2rL3?6DD7quO(?v8m4Qzyu_{%n)UZ-UrbT#=AaO|e*T z%oy~Fnyc6YEOJcK?%%hDurjE`Hc=ng7xF`XCv*8N-$YAHpy)zo(GqU%KNGxsx0zGM z-&v;j0v;b}~f7ywf#ZQwTB40W1U< z&&MVAtEnNnGO=KCelrI9pW1F6s96`5?T`bz`1WnBGGLX~(t z&83~<2p)Q|dm)*NozH6?X~|A@7Los<5bYPXppB{_apzLsR?rMbL6|Y{Q0hI_*G51tWiWHMRgN0 zixswWY9jG9#gA{yXRtZ$_IypO*Xic};S-~8XUS>?wqywfJ%}mZ!>OK;^KsZnRvDUS zJ$Oq*2^<`84@Xz&arM@ZWtSu=*NW~`^#;bv%_Kt}Bu?$D zpPK8p_-fcn(?vScQ9GN5K=;+p#Q3%^Lr4_QEJnNzLJ%RTJuBWc1J@|0<% zx22!jDqjJ3#i{{eL*bLfTpuS-5EMT}XyPLz9K`c=%DBi2G8oNov+VU0e-zYo%)Mp- z{o}jghfDR%gyxc7_DUb_u@0K_@x7{GGbuJu$_4nh6Skt&#-IeZV;xav$Gs>E909(8 zA`30BbY|6mj!9H=JN)u>tA$G3xze~zl=A_<;UqD&sM6X(hihn;XR25|)c$Fcm#4L( zmuKq5`gC~@nh55|d>NZ0;N#N|i(c=)F)q^<;iPa;aA^!bZ?ozpc{Ohz-2Y|YH4VAj zMQf;gFp8NfaGx+nF$yuHFu>*cE=xqURAOzK5N3l{{y=J0D+R!Et{9iIQDyCGgpu;l zK|KG*6ZQFawWr?wilGPeGVlOLJ7vKU(BV;%PtOycS8*dv*SZ(AYAE*C-`5_qf$3>U z$pFDG=^lDQ2#o@@Ll7d5uQ|hpN{OQ)C~Jdk`0axyZkJcy=#r!yB1_U!aC8r@x37r1 zYPq;0kXVf&fTXi`^?77|7}>KpI9A}m3XcNX@Nfb!Ets^vqp}h-H80a1hLr=rczH<#i2t!Zefrlj(3>Zq%Gfa4n8R!S)||Q97L^c zQ}VyS0Ka;TYVmTN?dpZG=G%up)9sy$Qe7ZAyHe_V7K5J>rmA`)yhP$ZAM+n44}PNC zfLr{y1=rBir*!VgC6WwuyTP;mJ~VDNV&^s$VS>vI!+NfFbv#{X#Q+24eIKZ^c|DUw zI?4|u4hAHZY}US#;xT``Y%cfxnCiAfAVo!-=cWYwz6=Wdlc1 zIm?uLWUXr+!gGpo8C7v6oNsqZy0Npe_fa&CPp`TD?xw39J4+423tAhP=_Qn+tjwNR zSWdycSnJaB9eMeb3Ki8{#Xy^lE(CdBRsGh-QC&pj9e zN)zLQ*pP9Bu~j1_#y5{NK82(fPDt?v&J_O|p)Ad8#O_mPT^wr1=@IORdBxuc=(gpTh|DGAJgE@XP0uTDuiFtyx5r)1;_ob5>8=1Qr%oWN5{YIK zj5om^V|nA!&zVOc{p+pCaCI!>&bi<*+8a|%gcGUAjsSa$xPDdb*pfeLO@(kL|7olU z;g1k-Kb~ir>-1lKU#LEt>vR6YH+8>-Vy&7=Qkk6?d2Vn=eIt}fT=6UFSPB#i~67m2hacQ3OWJk z5Hh9eM^m)n=vouPSKvr(#O0ZS~ebkC~5m9 z)RVcP{1t*Fn=~$#YE{ArU6yn;vTEi0^DBm%jiM@wC12zZnV(&NKtV?ZlU>ji)YIP1 zlc@_Bb_Rxa7e=j^s_BL}&&EgQwY}L^ND4{VrGidh1M?}*C9Fadn|)b=I4ViSWiI); z8Yr*N?fdDaY$fbk5kB-H0wjE3>Rn|`l;RnE!5KI#G(zTs!HkVLxW_%9Ko2YxsVL`& zDzLleRb!{l1%v9Jx0(99tqz<5UZ~JVDCHn+qXP~>-pmf)WCbG@5?{~uor8|j&SWN# zS$kaoe@MlzPCLW@d|?6O(Bfa`+Ro{z--oRjf3}XPhP^ZT01L*sD~3tAT3)`uk(Lu^ zPnf=KVJwxV{K5lQ8@-*BLvj!P3(mdHGMX&pgZ7~xi2$pYH`y+xe?~hPQ4`sGWMUsk#4$_y zMm$mdD#IW5%v(>gPOvp#FilB(g?eN9A68Vw(@$8RiB48a1b@t$RvK;UqT8<{I$mc+Jz$Ab}6b`b|09ehjxcteJMla)F0+VGVLPq=yN@@TO$!ExvyKh zG>$1K;|6XK1J)3W;HPPF^~yj@kK6|z9-L!omekdkAJDSBZ@%|aH~+1VSJ&r(z^Uov zkczXR)T5tEcZc5O<}7R=43}L!@d*_5k<4=70V7LTL#JokU*0cY^|enI3gh^>uC>pw zer~(!tD4D)CjC<^zV*Ae!)y#3{0m2HjG(P;f@@=8WkisQB#X^eX{as-dqXidL%#1r ztzE42O466{^;sQynnp=^NOw5xor?dA<~lEDW!{^ac()S58i`;LZY$3XPvsNbe^`wc zO=DLege7h@Z7kP2uku!94GjG~tGt{9)T!8QTi2(>S{w_!Lde0SyZLl%jj(~0>&PhJMBpVQ{skaY1^r~6Qsc*qWx$uv0DoVxtR6_rv1vBP2Bf%^}7P$w*92TkY-C zKoTSxgu;jvN^4i7C>FzD2FB%i`oM31*Zs`j=Sf#!Abs~cC`k{CytykKy2yET`}HaB zK!>yxC+-ijuHWo<1LF6L`Pd~!9%AYCTo{s?WPE)IG z>##Ap?TIA>dwRt$1{P;?2GUbVgA|0eW7vi3KN!Br1Mv3(FADO;WLEhg!kiRyR5*=g z4Pfs$c?SJvDno~wx2sxDZGl3iL;rNaWZga{jE4NO~g*4?w`?PSOEaY2j&SJw5`XNG=Dg+?+Ys+?37d0%dmku|Emmgt}Z zJ7B#OBxL-}^rKM-RS?nig-wD5AvgAWSLmczHrpWgFPfNgX4R`v)@X14E;(_ue%TCC zfnsfgCJ zT8alj=wiyw5zIqlhD}(L!!*5yKry$vF&$J4az%OAjrCv8d`yRBKz&k7F&_te_*^+n z%0Kmhs8)aPM+RTD0{A8(CYfg2$D$Y|x*(1KZmc(vNjW>YAp%Z~EVI@1{xY#e_OUHT z-m%EKJ#Dx$PB9;DAR^fjY?p8B*!etZd%e7HxGn*7zkOJSnv5G%_YlKB>swd|nuSd=v`85!%e0#k-`A4o&!_JHW;+SLP6!z% z&^+vp8?BNUjG|Pj3Ly2cxyZ*X9lV(f$6sHYbhOsCi`Qg*r5s&iwZ?z;K2@ z)8>UUDLgN*^`<#Pg3)C|*Fwy=-&=WkB{hE*<w)zw{N(gm3?` zjY80M2U2ZI(AKMV{q^@+|B39x+x;vY6dFpA>OAyUt|-we;No)jN<6Nqpa<;5%HhvK zJXjg}ydLefZ_7RNKWv)&!!Y;`-bfE6V$)O^`w1)YvSR#iXxmw&mRVwb(9F-G)SD_( z0Io%09t^95GCRw=88zy5L1iaI=P;mXC%8Yox@Y~w379?qJ6g}z$i2G2MnW;zzfiV`_C6M7-0-!S zk?nnbw9{u)0`A7)BphP5r#O-{%YWDF=+E`1^F|PG`7cedx1zv*q*};8q1fIy45m>? zkE(R?e-lcM!}dGsc3mt8z5BrN6!go{svn^`pYEv%)_DZVApW|Cv_2g(uy~E@TNRax z8RCHcSYR=0;xH2ngb~Dh z9TB=L!Sk5+9A^X85)iIMslq?0eRh=frSpGY0Ce#cYoL0J>jcai+NFJ42I?}3gt(6J zja!A}WpxGjKFLvI%`Rht@F!B1kbL(wK~bjK0Q6?v56}qp)2la%?82H^YQc8$bsR2H zveVcYdS-)IKVZA&*mEnV09dIw%Vi0>vS02zJr2Nq!rD4PuWsylqYX+LvBqc#E7Itq zAf|ndc9(IImSC4d?}QgWN+%8zq**C}n!kn3Kh%9rnJ|Lmg=h~)hwwi1A@!uOS4MXh z^N07(7g3PS4{kFa9EvHwj;Y^-J(Z4S!qN_QTKFzOZ;FD6j?QG=R0Gb+l4rw5l2#M) zej3_ZSE(4w6U>iq_yn8FFu_W&wvQOxS&9{gn$gd5PE;$aC!P@;RD z*7#-|%URK1HBX7#RsX;hl`X}Ttr4teN1CV0v&yNUJ#@$=h~(aqIv|RSPgDORf%vEu zhQ8t`$8NG}7$|}m?E`=)4x{spSqZzGMjKQA*pK7*XD>85P~0kmFa+BouhOrKR%)P! z(@qp{5%dW^io|n-!6@<(BxoIuv3Z!Ya99%ewE3W`zFEFD&1>X{H6yMmk2^AnV31Q` zn}Uv7%C)L%4t5_2WkF3WY!G8@6H+B!3w;z?h-R%57zUWUkiH{6^gEkU8avGr zjTAqQ=9FsXdTV#pHKb(iU$p;6gF3?H@1AbId}Z&wywkgYxQc6P!Kco`PykvTvv4H+ zd&1}fe*$L7qTKDO%hiF4uC>EEte8@w?Dzt)oN`XIQF-f6(jWQw&6JjEXaFb8{(RmX z%(SVVYs9}@F6waF(jpK7qmp6#@^!%`&{RADnQBQ&^R2u-LoVt}a04%~RH2MQ&JjkC z+9N9LzD75A;Rs)HCWCCG%EH0@wW+H8y7T?=`1)32BbA1v8&Y5^I=`Gw z%z$`QKQsjuio-Znu0QxM7z#E>xl{_6b6vcIsGDn=_K&%iz&i->pqy6E*_F zj%7pfhw#&ITJlhY0TQs~vT~>iEOu^liK-+%qY|lA2Nm_}yr5vs^}lsS;MCm>D=bPs zX3%D&sVoZ3DqZO&Qfoo*$Vy#>sezITyP+mKGl*K?B2ngYtLS$jun>~5+CuI_+{-a| z4XLX3Nb+CX;^&?%W-2i@DGJv2emEKA@NAR15DHF5R*SnWZJegYYOGV+ZQ}&?>n?@P zCm{&v%`e1Qv7_>(=j^jUp{R2djXIf386ZxnF3;J$BxMu7|{zm>zY7 z5E3_ZIm?p}Th?q-st6StEu*&Z8QkUNc!g7Uw_w#S*Puiam#hMa=`&2wFVamc89vzF zGch&9sSLsV?5D^DRS0U%G&I%WZ0ALKCIa9rHE~BARnG+X-6#hbS;iGmt>pOCHEe4m z!)FfZokuHxWznyV2@}nlxWz4;$R7hIL)VK<2MYx?;weVe3^_|Iox}RL9^cf+cIbuP+UeET$!x3+^x`k*23utwUI~FOJ*F4S zi64uZ+5=g$N=rnu$G~pK&witpKl6)3OY^cIfl#q{$FM3JYwv@*A3GUj18az=bj^wg zl&(M68x^N1{S(9gA`xtlOt5D2ap<$Fqth-=z`f3bun1s!-5l6CXk`nBZy!XMnc5i! z=)0h{WmGFQ2v{p;!btRy+_hbtf#L_ijCg!6xP(EZ;eaCmA>op!G!*;L8%G%vG@@or zXYM(ybyHDFGzm60|LL@48Sl`7(7&qWz%3vd=B+}!^bf)Xcd5+fNXfC~yucME<&%AD z9Ri0Y5tpE`P!>;6;99aQZdr5f*w`SZE+?-s$ti|+!rt8)UHwbg{oDb1X^dNbY3sNs zY|Q~18+u?Ot`%j%H^g)4EXlEB&E^!npm7;u8%gychzHj!Qlx&BSg;P6bnvxmAKO_( zTI5#_zRfCXP-V!Mo_>j;$a$jQ33vjd669h7LW$}_4@Z%UkWHiZvPmjK0gv!U04Z0D#-(g?-pv2L)6(mXqbb7Dy`zh%VL#!BQL4s&QsO=LMe?T#M^~JX@pRm9Uzo$ z|KM=HfP+;vId3z1O4{T_KlK8F*m)+!`J7I{fLiO882|tkTy{|zbb_#zNk^si*&oLEu*h{R zVD`3WK?XrLWjin6%#hEWfXFqzV*ljTV|#Q#BgoL;FFbM8mrM>I5G3)j`4n&;li)Um0^uML1e|22~x9?ERPyiI*EJHohNyK3a zSM)bmW0nASo7>`4od8c-Zwq->Tj;vBfZ+r;%Km53WglNByV~=dQw(~H$%3?-9t$;< zA(vv?A;W%vyF#=*5!;10ZIg{EU0VE@Y0ehOuH+~DHvAOYY1(=dg>qZmAIXrTCz}UY z;VEO@whdY>-o1D^#Z~xUc2YR)y*1RISqKQi4c4o~6giR8xzUd97=`QY1f2`_u*5!3 zJ`Iyio|P@KAJN%A!25|nFIIR#ut#w{j7hRcuwT90P+y5qfFvkv2dJEN=?$pme~wSgne(%a_UgIY&R^w*c#8Ct@iXFg z9}C61*yPt!%|NsLwj;6q<_@K-CYAzM^qT;8#sr&=D0l;GQ|)K5o4BwvBIr$+=opRH z;Lcg}_vpoZ7ujB1#)-yk9Sda@P@5Dr*>xHTr+wmPBeS>BRcqa zyqsWE7IZLv3N$i!qOA+*r9=*;-kjZTB!=W9kffO6r`tp6Af3m?@es(h*r@86LW9Wu zw-a2<@i617KcY7 zXEDY7ma#PAV98u7d-0p6X!VC7DC}oJ&9V3|>-8vac;M~)-fkf=FjQ9Z7Qq^+L@*P} zgu_AO802So`dTFdbE*bSJZ_w?>c7eWT~~l7qFQs*K!%1|B!p`P#yJ&x=ccE9+54cK zN-3uC5w(X2Kg9kY7XUIaO(KP+>iysGRSsdT>gaeuss8*DKS!I0BkDV2;3sv~B#ETT zVV|qv{!pKl?C6FuuQ(SgYjA?nJTACc>peY9qmdS`g;VA7D1W1%j};$Ll(ua4sr4tz zz2ZhJ5xVMUk#Ik3+{VOo7KT~kP`v;#;?=_t@wv9l(D8aiD|9PrIC`4nYBFoRr;zuX zY_H_52Dk4cdd4+#Kf&X1LOb*rf$1KGmH428$7(3x{^PDRlr;%JfS8wEYh;P-)-opJ z(0P_g& zyfdA-H_|XcmAv0j7dv;cFsu>bTF66ZhP|_M505+tft}IDAalzjeJkS7kFG`+VxZtr zhP>Bic;)RCc;8{64j2nG$M>#)t&O72WSsIF&?>&0+^D>CkiHKBGrMGvL=>t1LNZ7J zSEgeZ^r5>9Y;>SvVk1wAM((e60*-LebJ3hy-W_p`hC-a>O_4q_X9W`0TyDE7@*hY&a;78}tMz%9U{)>l|3=y>Bv+ zq=v8n&grzY1Zejo(+=ln)&;af^V9=<)M1g& z&;7i9I>%7EGr-fm2RF`UD@?Y*e?wGS+O@Ql>-h3i+&NC;p>LQep7Hm+? zD--JAQvG*d{nYBFV;NmdyN~X-WhB2^#k7WFvccPxN~41dx{AS|VJ0;)+8`2s&-g>< zhkHEqN+I6DL`;3#(olqXX0&K|pFrTy-`neK=v$Mbaao6WZWSn9BSiR^@%IhO%Qnh% z{JxR^vG(87TG}{h3o-Z1nrh-Lg;=;?%!4sFr!9_jzt!s%$D=@>j0588@r_DS(n6lz zyuDnTy8nGAy!!seTwm`9%QS_Ql$1xQKTJh_WEg?0a&!#Et|9S8!+_`>qqy;1HCz36 zJ_!SvCJoEbEb&83@0RU#zKjBctWI$;!yS8K5@iWW7Q-kQ68{Q#f;sh`fPYhH1Hav= zQvfHg&ljxckE5Ku(jg~W8|!*|U6Z!raunRBNQq7&t1>Xv1-56AA(R;s7?${cTo{RF z$umFoihbD_-?&kKJKYCGfrk}GR%4{Sa+%Yd)C`QR0#q_hw;e~Th)^IvG5@bVh*xWzw zc=qf$L^^@r{(uaq@61K7aOc;i@^@x6SW6Nf29rPi1tO8%7_?tHwbs=w8$OI{zzx_B;d9&#iw|D2^<%jj1*a@m%OrkEO)zIxWGB=Lu*KZT}> z*LmCWQ~lL>lnJf#=TB{jc~03}ade0SY>oNRkRvGYusWK$#S z4(4-t-Go9=?(pr4aiS#2RBR7_vV&GzY#cun|1KnXti6*ZZ_4OI3v6>uT&Ek?)*H|t zbGW;VtkkG{R2I^FR@f4|#N@voN(S+TIgc2ZqZLtDkwB>h>;HV-XaOT~8tNJ-8a8_F zNF&N8pQRX?lEED%!wN;#8PaOkE-K}U3^y<8wtnx-6#V_qP&(WonCpb{=(};NZ$?gu z1^g5;?Tz={Hg-P2?}E|#xqO9$Tozl5Tvp+nj)3V=x|PCS8EW_s#Z%YXhm(4SC%0Td;Fs3!cU)#z;`=P9Dt$@Dm8)`kUc+ zUrU(rCvAQG)NDkc*%h6i&)lIxHf6a^OaF|Q#V=1NN&H`yj?8+CI4htw`fu_B)_(o( z5AygqZJ-CF$sPIZ>#XDA)YREDJ0($_1F`LzDr2o&R{h$AP)jPX9$a>gW#?PfV`pCy zOictgtwB^zrJNjzwn(@4d_&Fo`gC0HZ0PgxWj+V}((LB}v+=Ffk1aX_!p7eV{oYLB zH%38ktAAO1@}p{$G3Qe#*Xe+sld1!(l0>sCtx00hwhP!toZdK2g$mL;Lym$ct}4Qf ztYEs8&cl{LjQxqIhWk%VO?&%b1ATWt&y@MBgAOE2Q`6lPyI!k*9dW-O^R2xo9uSif zp4;UB&;Dc-K`qa_JE`w$RfD|cK?d@cK%Zl}(6hOJy@=0Cm(wc8+b=mlNld8wohMK)I}k+oUanbfBq>Em1M9ZC2iw^Lm?D+D;}slf<`)iJVF zLX%ZFM#l!hf0WT^w1_>q!e;BRk4`zws}VF9t(2c~loit|a4J}hi`NV4zjsbom}xH! zMy<9E|Nl!P6%P*1g7Rw`+XMu%9~3;&hH5 zyXh>^-~nsR*P6xZj?e%ouR5eI#!s~=oDjsXL7%)5$*Ml>BG+bB9=ib#ahBIs&si#T zbKD`7mM_{#S;F3>1Vzk2IP5V*5D)RG)ETB-esbYiE~;qMF2ta!p^>hUbkL%|b(Ir} zj#tV3`vHp7B!UuwkBN@$vVc;vE<*h1(`=g}6`9R)tq3!ROcKPHP#og#sPUlhtNa%Z zq0cj4H4>Cn4Sa3Q%_z&^=Pv?p?PO9dZb4OrF%0ZI`P|w)<#r~++e6U6yYIifq*Rzk z&~e|=5gpt@W+l-XcApk=wZ*IKjDmk~OFUUc0>@8SMqWo(ch7U{jiA_Kuq4MP-1i%{ zyrk^sM1AepAwaa6Yb(C^IP(F)BlB7K~}Xw`gDj9 zd5#_fSGOH%zN9^ys2sbRI*5$zuqS+A_{C$l=9{NSe4u(78Zr z1-AYBw&{FdS%j%ckMk1qD*VIuZbHqbfd5V!x9vV3zj{k@K4HIZzMi|UySm-5W`5j6 zi9HX7*`cQEzQMXHOZCHik9jGSKC)Dz-NG!HIEIilN}0l31#_$h$JS3`7xY%>LbdtX zx*Yj9e%oPqfquhd?EtOZCkQyqL@qF|Xbq;)BIiswO0Vl)Pq){5>O+gadpAKRSD%O_ zdvJL2L#lYf5V<9DqhhM;$rd$X(X#Z^?t$+*&6*#BS{tK!ez#7?iB&rLu18OqYwC56 z^z(mxzqX=OcQsG$PVou2q%Ev;TBDiHQ87I+*hV>GuShUstEc}d(-N3g$4)!CA3a+6 z&>!dzVwKE|oX&TQWrr*A3Ra-`@~qnWE6_dioA|;p{ff%-9@E~a*lk+ zgXeXyh+O&*)0(gIQg^B&5)VmnV)eaq)5xj3@Vs$NX?Mi8&ai_BhZQV?5Z%cGViPtR zwyb@}2MGJV+?n}Lxl4B4u zwJ;)1VUpz%@jOk4;lU z4QEgHMIZ_V8ig3v%+5; zw{Vs!$5T5gf?CoUXyYS2DenOU&PH|$c}n`LPkDHm*99n|p~(=wY5*3B)Fd>nP~IL5 z5H)5`20bRKUmw5^>X}WrCnA*0YQNIZ`rFYEVJaCSd`)ilATdwr@(zDo(z%Z(Y%I!| zPQsT|=wI0ZYe?kl)7%N@bp(BDf46K92qDMRqZ@EpJAFEbJYpraoBJiO#rP-P~ykoWW1ZyDS~%RmQicH;FBWmO22l+PQbqj--(`p)1O@2DN5HuZUjRJv?eK z_k9|4%cv(!YU2s+F22{jP|x3Fcn8-pY#r0eABu;$MG2KCP-P5hy99Vut`hVDD}pmb z=G5nc1Xtjb!GX6fxCCE|;Uf@ZziQgSa*vfZwwpOE91D@^Rg{%Ty&_N!GSBgq==P=0 zD5ly=PMTyRU@-8T(&1AJ4O`gdkEeW}+RV6`-)yv2P$p@Ax9sZ;%TSgTRt)KgS;Jb# zoQo#~tJI&NQ?81MJuW50qTsf|gVK+I#@F~&468dGSKLc~W;%;_<@6|D<}965#ZL4r zpV#qsqE2glnc9o3K=%|#>&^bu>~5_EdBw)MQvLEKJ1cmXqCxH9@;O7^{_H2@)nhSE@H1g%p@6I8ZkJ`8d_>dNxHBd70KwZ!sTl*+NieSUfO~>Np~8x zYzV`pZg+8e9@K!K__=R&+15yG(tZ)Z2h3GJMnS543wG3(PS&F_dr-Emx8}LrfX4^E ztHCXxvQ>Xus$o#%DD8yGqTdOL!dl8)BmEJ*`bf{#7!U4Y#!;t?)>^O!&(aQQAJo2~ zaU*Wh`U5KP<6zoqmAr|0&lZr*rLh#BclHghyGd*|)L3%TjGz^26 z30P55vi~duFeCgxzu&ayDTlBN`EJY7KY_DN;a#2GExn2Nq0jc$83<+pQTk>-pSyc? zc>ciyR8P0AiAS0kBQYPO>Hij}x6NRDf_GY#&g0shSm|gcoBkOx+8aS;A9N2dyB)GL zu% zi9vmEc_|uVkNLrD!cA^C&j3+{dQ^A6j-6D&c(N%0y;9UEUb0G|kYp?TDsT55$wa6j zGj+Co;Ux-dx(KL$xWzdr@z!FQeUBX8OaDyc}6k48(wo1a&Mh034MV5LlCfR=YL zA5dGY&hoPsOssCs9NPsk{DV-0UVw$@jt)`}+zilbvr?65M+wylBb^QDdC66-H1+=n z2toJ0YHwsRIz$$q=NcVn#<_TW)y#n=39bBNnL7y`~7yJaj=v_ch=gOHm8+ z!a4p;NQxx?2rf#o(+#cnwE1T1tbm&)z}@i#U_#T5dAG;maKP2+0Fi>b;~o0afZ`ci zdq*ubWGORw6D)OagxUghT+8q;-Sr?h$I5GT3etwo&=mn(dq<~yO+bSLS;!9xkLaRv zuOa?Xg_(M{z#tJ1{vqp!0EnBL0u*KWNlz&CNs#o>7C@XOl2Y-w=&9Pm`g)&g?hhvY z^Gn!}GeE2sr&f&MP$hvek_MVS=BC#GU7=fg_wloabTmj8&(7<*M9jOHXmv{fSS(S> z_9WvIaT4Bgnn)7rl>lsNrwV8XP=EVlCB`p-!w}Y&W$2cSUwcz!vS##GskX+82#S-S z?5|P^ijxe}G-0Y0wNzBsE7ykup1$)A9zDE4EyFvE<90fkUYO?@rBr>RuUk$6IOh4iUU?%*@E8zZ2PM{v$~f%?`vyFj zu(o%o7u>G$4GrmHN1nT{bs*NQh&yq#0u(`&2~sPT=3$gbkhksK=-mE@2fuVH~L+-t1;OuZf^b&IMbd zH9MdLq2)R#6GdM)e(IGKw?9>e?4gd?5~{2xe+G_8`h&VAS>)q=S!d;Eq_%9|v#R^% z?;Y-y9&OejjazH13}WN0^sw_YCgkQ$)+f2$y(^a9K~I6!JC4TfPcRSE{eFj!Kl~66A3VT3SM;`Eig_lEHxx*l(`Pz*^SP@+ zS_|33q#r4$z&tKlX8r#1m<(?$HFK=BDC? zEqgtHg6s`Y-2>4{Dp4HWnIXg^lQ+S3S%a)|0he55Alfl^d$*Prptu)7mlIGFsym<^ z28jhh)e6B5bG^beov@$xxYHw!iyd8C)Qp+}16Dg24jC^uN9A7 z1q?6*8Yv?SEqjAUtZB&j*TYh9OxJlvPu2#30V3Bi{CgfSUQ1A<2H1-q<6Z%H9`nw( zZ+<6mq5%`{aIl*JM34e$+nu|bMF3GFzL~(nu&|K;>T`r%nj8!J7d}<#JyAg$A0)sB zf-)L?Jlbx@Cuw+u#|_*N?euKTAc#zWwXM^@#(EqhMxCY2_Bu!yEjBH(IXH|xd!np} zh6t{(1!4)zhgXsSoo;qc8j29+jpL%xRw=9XyEXneUPZ*>kc!3sF~ZdQLKUc!eJ<92 zwM>}n1l5k+yu;&%@8I!+cTvl{irFV9nCcFTJi$p96r3Q^QS^w?7l>Gf@zMn%)i-Dg z)DzfLeTmWqsx!JAT(K46_|TFGpxms8%#wM;%oK+5`(`l>HT^-8JUvC0gq^ zE+?oH`nCkQIVF)W%`no~OrkuIB)lnR2u!k0(MWJO79x2bthcFMXvm zGzo7EKu7(x9xyu+hXIJ89rwX zLq3p0SjeKLezKfG-Yzx0YI1fUIFh7L*TpM4Bjjv) ze06Q*GwCfVlZkCQawNM*6y3wj4B&jFmUv>tX3Nk0h!45)Gg=-xfi z8??_*6x$f<1yux{NAi~i%fdvrM&|2&kL7TMu8Nm;cVVY@z``4e(Y~F^g0ePn3zBT@ zUyD_!XNG-k{jojOaJIpPK?dcrJy8|U6&-e_YRGohX0?uFv*D3tyefJb2@~lE(%Ddd zK5br2zcZm5pU3)sh(Xb25Hqe-hFf{j=x+aFMBN9hZ21g^^+Zt5Mr>dj6! zy~X98B)usv$Jl`y?=2;x=MymfL= zb_c8Z_zrh$X|xdB>V+Ld!SL#ddojFAhNmAJ*!_4Lz?fe&TVpO^#3dWA8i38tgO|9| z9zTr0s%9+HFdXEA#&~9BmJ7W|hEd@CE)rf?3PB1ni-5N75!9_|J|ELNl3^;+Q@s$1 zUpNxMUPZdEeW2~JeFr%Fw(SV_Om{GxC z1rvbg zo&n)IS{C%up?yZ{v)$)!Y<37As5_ucunmU_DHXK}T5mupzMRDMl!Q(SFZ{e-kpU5V z^G1*_vK%+P_8PPR4l^KO&We|T-9Uq2o4K0Y*f(#=n0AiiaUtBgcg%A-BeMm zVIzrb=2baBWbem`c>>9a62}|b#IaCCsg6U6d6(J-vu8Qy`tC4Y1Mx^y<~#zDWF$$w z{Ubr>*JBl6U z9Wn^i@LXkGH@c;(dOm`Yh$r{Ymh8$KT-#&rXS41##OkPSA{IqJBq6E)%!X&2YvL?j zzuRRrH%x7#l4QHfND*iq`d9NjU|m!HsUpbRz#qy@GOxdIMh)AbFf5iQzKo4I+Un6k zsUsB7!upg@BjW30BqWs8xO@{E&rY)q{mu=9&@uk66!DxDir!DKlZOiE0vumLjs;~o zV5)mxd$7~60%+4{KgVPnQed?f(wrEf3o2Syv~~h?!6ZOMM`mX$!Or;m1CcbE2Y9G;v-0;@*y#>9jEbK2B!3oB{;IWi7QBZ4?$@6<0;hE zBl~1Fo|1u>+E*lCIa>_IpEcs{{3tsOCX%GXcuoB-5=RfyFa{wR*^u+_r~YI;nS_8x zEA#WWKes!hiV>TaiJ0=3TfEkaB0!zg>sL@Fi~UpU1l5L{n``{(_dmhYr|)6jAJ8;= ziTTC{y{C%Wy2LPO#IN7Rf0ZJZY(Yjli>%w!)iP!-+R<==Dg&+#5OH7rfJFo%I~45U zvF*{j=@auxa6{kYA)4&yP-zA@zs;+-N<6T?r67cVCt#3J17;nNwpv%Jz|Dgz{NM+F zfnWaO=lJh`^95QzVX76q6gxVt3TZt&Nd3hZ$R&I3R<{h#K%1Z3M9VU6dz=x_v-O;d z$-fc5Oypcv2hj$~q2Wn-v8Zlz18mHk%7x2M>Yi=Px2S6Z6HzBY5Ss*bLl@^d=elWx zBVa>B6s-*pDFb@y*=kvH*F#F;1Q8M;_i14)Sm|iTytv@bu|>c;}sWQOh1>a@pf5LYy7o&s^>`$eUI;W5h#CBzsdBhu1dV%)SA% z7nldKhTJlFDSjF#=^~O{S>^)c9onH-(8WTDL7bQ?idtL_(gslr`mU;Y`t%8Y_*Xx` zFaG6!;vfIvOH5OBtm0m1T~V|n62GRkMY#nLk01PXSj9Zw`R<`*`+5yytxvMdxI`3& zoV;+ay1j2Qf2{+8B=mp82qX=oI!w&T{!SyFYa_Y-sXkrZF(bw~$v4^RVLAJKi`R15 z_Dhzl)+fn6E&~&kt>F*Df339$(V|$#wr;XObe$kCYzG+*1JM`WUy=yTRl*|??-!Gk zWhfummbKYNmZ+9aFsZ)_z__W!=Xh7@8`>5_Pi=7yD=Pifak95R&xz=vi>GO_dalNJ zII84-JaWIEXP^iUhXWoydW4(nE7W-o4noV&X+DKl`t8y>%X4VV59J{8pHOC(pP6B{OR^ou38!set zTrDy=j5t9G5YUL3GX!njcc|#OCIoyGLK-o*R2v>WdVrgoE4+O93_ts6HN&G#17NB` zTSsqD?o46hEWTM2)4OWasCMyd)G>klgI*bs$+2!&+j z_(@L^1nAGZzM%lw##BbV>1}M6TuwGIKxj5ls2tV%8X{@Vac($Phd^{4_cW8F1nEZD zmX+a>|B+W8qyf@8@fDSUbb^-LMK0bSXNHE@%HO)2K>KO;POKp8e0UkXuA@z!R+gM!)IH^;RWcna(sgGR-6#@wfV*6E@ zZ?k?_B`R5Y0P;OU#^=u~ov4ElWq1|-1AN0JJv)+4Dz|6{@sQs|okG&~l76mrc-0f= z=3}dr{oFX?rW56`z1!y|`%l-N|EB+H$mNiO-n|SzppYa>2Y|DBu8G-FOX!Sz5@rkf zvp(n6H~UL2>9?d)sf#4$%Q|#R9_x~H4s9p)o9UGq3cp~oL46RD4Yct`#{>y&tJoW8U7ZIjAvf98#@j1OK#5N8ax#zO9yu2{+K zTI-k#x_);2ywKmv(qQ52)@=|GRHucsR`)*B7~usbfWCoJ_cYRUjiy=}M=IM235a zV7EWua5!L|=Rq*LV%FY$Jl5m8T`ReM=WEE?yDS~GC|VsPY406B{mD=9;^h(7AN(0M zx4w1do+Q05Z(T9LTJ0YIsKxYppjHAPB~>$UI)w>-MYyVpcw%eH;d5I_CZ=L$=5o+(sSM+Zpv_yM5jYpi>PXna8k{ zf*rkdvQh1YvG9ST|d} ze<@*zTZH~j+pJ@_o7TH+hGpHG#?X=}C9i0L_cX?qNMnYGV4in49QJtk-FNZv#~-7s z;$}agP8Pm};Rr0D=ega)^+@ujdcuw`zkG%}J>kO-KEi&tgLWfar7KW;GbUv_-}cX$ z{dHg7n4-`)p<-)bYzD-JtIxYZcGH#^pToXLYxPV{xj`<|0g!{sp91I((Bcjrt`}m9 zf$LJSn2v}BeDcXBI3AC9@$w~p{hMFo|ycm}uw zl->+TB&nO$knVBf3JS(E0Dpui6a^g?Bd8bigy~9;%n|QH#5_(-ur&;C4fAa4u8$!S zu}49{op`fzg2~%0Nt**J;kn*H^dt`(C1x@;N8#D@tXu}cTZ1DTNN0-2jfVo9fjtpF zqV0XqBU}M@lMOMhJwndgvGou=BX8B?zohF{|7<%IRj7n$EUx1y4Wnv+Sf#<_gawaO z5HtgRq^4Vd2BdpeS?LqWYvh6-%cK*q0;L*BS}Wh12wToQUoI| zE9cgjfZ0=b+t1s%d1)-RB#5e_=%`U9Uc?EF20ISgFfyp}AG6e-PN!9d)zuDmDX4Wu zDS}!iOw){q4+lwV4VeDR>l0zh+Ixn$Vkm^s* zkKQ|;KYxxFFJ9nRzx)+|1%LeSuJNk%cVGTMMFbXVr9xGp@R-nk_KF_yLpHkyPWLr) zjt9TyUFy&G%|79gNAaY5?gvrLi&T9c<|G)kR@AAuD)UV^=Wt6cXp6WJzd039%sYFO zykTKp&tnY_S(vlkbM4tr>W6brw_Gj}V);9MPaIf`)mk|MTvu_+Fq&(&LQOB_TLpPXpVmgpq_|_ApH4Dc=S-RD2 zArsx3MIdOcVL34_p*?us*>S);4$)R1!irq{JI4v-tUtFQaJIz7C6e^qc6mLSy45MH zuOzU@>ss%)TTWOu;NKEv)F4TZ$0J&|qovXZ87U%|rwNDs4oho6caj$du~T|kJdWolFhlVzIui)Z=d1z?iSND12CerHK3?@*}5;(#W^gS@wzW> zP9gaT=xPqGih$0YHjf#{AGGaAq6#40LNU>}#8`JW_Y^YCP}$Lng|-Qr;%kd8VCp;7 zj#_OqW1c6Jvco(N@A9rm?g?DBF-(-KWY3zQVInxI#W_~7Hj^lh{?Z(Wb1i#UUG_Ct zW-jiO~nv;j58{VtyYwlW${>y#CjkjrY;>xB0|_yC8)0eU)O?sur1muX$)wyPRmHC(^mtk@E(tY;5m7nr7D z^OaKY;fEjM_U;Zp{mD;o`|>4PUtR@!-kNexlHQlMuqd42u#eK+_;jj5(=H(>JH)b2 z`;l3yNE5!MB6t8`RScEcvkSdk2#~uSwd8RXxaXNj>=ef{#0bjRsmnW;2`FWOmc2uG zWG@T(trv^6bzGN;m{8Dyw2LhP?1v{0f^;jPXw-Rtb0CwIOz+*Gw}aa_E~a@LvT@^H zSjCP14$mq*>V0`9?80uDJ$SWqh-7qZl?BqyK8;aUbPEPaIP;nTcCjK(Xb@7N5Aq=^ z>I{lUf0PY5$LfsCz_0S)!eD1E08Q3&%=a-zipRs^HKSk8-;<4w{QadJawB~CKtwWu z_<~&-596QoY>u6^HRjRYt8i$b(w^;b)C|oS}jxtV4q_x(cmw(IZ%oNU7*njj5yt-%9UtGUJNeBbEBeVWsywfewxVjbwIQgRB zx7l5xKi4)ysWp<}ZIfPP8-kkxWz!e=1P$fnrT)tOoqrN&S~b_C!tlJnS zt`pN$s(oc!W+LR31l)c3gBH#;mP_&mF&}AkBpXW9YzxOU@jOWx#Q842uS++)0-Iw@ zuw%N0$>p+_clKf|ZbOav4RLG`y29pfDQQz6u*!L?>il=MS21iu-Cl!X3vT7x3aj88 zt5B9wPg6a7Q>>D4N**uqu?Vcf9rVzl=S1=L8QV3wB_LPt^6zt~l=FF$o`oT60}p9x zP*CPRj}lJG@6C0(WT&n$&dM&nAXDSo@jLa3h@i^|JEef-7l?$#HeaWy4&9T-p=6N1{)_a^t z{48Jc034-!8?tjE4~a26*7lT9IV-I^x=03ZNKL_t*E4^t^P>*lwt z+>@mDNtv-IK^RD-912X_v^vl50b1d4eXJ{{@c6 z6KXAZ@!|!ZKYyO)(=-P7zPu4-=o6POP(Yhy5_ZqBAU8w4J26gx_wC-8jB<89eDWgF@E%;AK^E@`3?TZKmHgmUcQ9FNkCsWy`^}Rg4Gc*1La1r z^1JP^YLkyn;z*XEioy(qu!Kb<%|^c}#xnDM3Kcs5aY(cc;5YFZ^pbbi&?)Lb#ZD*C zLj|7U79g3&x*$es5Wiaxq<$^I=_;mO5lk|p`kK!kKLO&}$jof=fp!Q&Kk#oR=f-=X zK^Ls#b37ZFj4)6ILGrGlt{bFBWTQ@VxRioAS$GK-s;j;rm?fyp;7k=j5zqMUIxyW| zM9|`7#<{oXRv(9ElC|d&3C8U+)_TRWZ38P{DL!6J-RsVKwfBz6kGPv&830j*S`rac zZmXvsK753yPoLu5ci%-R#k@;PF>i0-Cc53w3;oHx+z+7IzWAkL|IE7}_}L6~dlGPJL6X zLQ`B*a>fi12`Phix?oEisq450vvC*QdJOk2Chy(z{& z^)vLWZ*#Nhja=(=cKqLDW`&f~0BfOBhF7Ex#WBWQkP;bLr|)*Vz{u2pqB&vkI$S|( zJz}G?Zz}r^Cc_ud`y}j?Wx)l9H#^V%*FQ>t|SHU<$t1))$+Q#gjS?64PXa&r_j2>#g*AL`J*qcW(#h zf#awzzx)z)o`K$i+|7OWHkEsl^uD}(MHEsRN_E2*0uf8xH1w4KSxJ+`!4S~){rEc# z{2@L0JB3SklF7dB+U=NzAD`0>-x(u$<afKix=yPCB&%#W?4qGXNZzQDg{!q~&95sBAKoZbR0T;r>IAJ%`K+p~v9_GOW zY=|{JOIYUu^Z`<1_$ZvA(UnYqTw;mvu9s)BHT%fGS8@`q84!jt)P~Q-W4}D z2mHyOe1dnLypMT*gR(P{wAY=13l((jm@(q!DJ)?7q=4!UDitCVfGdknsSAK31jhs@ z6yx};VmaO7#mnE~t7l)}bUdN;j<23Q!`<-?r{k^dif_Dv@5>*)h$y6XlPfOvs#KS^ z0_o~;Nr!>00GhAGLG*p|LSmj9dE;|&aBMNK&3jCTOehG$`Qd{H_~BpvB|iJ?Q+)dK z&v3juqN1SJ2}@~a^mg;gFwtxvf;gr7!j;}bXHa)B;hw4vFGOGG1OQyan&pcmHZF9E zL}pg|lY-2hg0fcvyay4O#)n=^L(ZI&3jjh-3akw(qrOHQaKq<3sX~A>?aq(LL#$Cm56p>~__?FzJC~ z37kXONbc)p@11HLC0GN7*lp1|Z`-wV@n|(f+ zecatfN%N=hI!CP3-7AuGWnkF7c3rboR3{4|;dN(r`dX_c+-M7IV|oD~nCgsD6hK2Q zz&sVqC@A|K-g*2O@4fpDuC5MPj(30*Ol5Mt-NOzto$SCJ3PFuzFOgwd3Z6cBj8Z22 z=6Aoui!WZ_+3&u@=fC_dPN$Cdo+=(+-JsxTr1LZd@sN!w>f^2&qjO*0oFb42g#rv4 zhrd&9_+C4@RxDa9i?=isG>9~F9F+-{m45N;GM*`2irZBc(r2`m>{tj?7k5n9#GIs@ z?T%Xfgxu5jKft?B-$nV`1Ag+e&#<%?khVaip-V$Y!30G|i_Kx9@ijgNwh*xp7TgRH z!io|xzA66H?NtrC)ydo-e8qKv2FB3PC$!>-3+<;R0_tI>eH*M2^_A{XrZIG*{dI*^ zwvGmV`8duG#nL;L<6@Y?n^kI!nhS=;x)_dke(VOEg z08{bPjjCwNI8{b{l#>^a_IYAJPS*5K;8=z^lVvzC2*mV@e})dLfgYZ4ClhV75dce) zH?WE&NSc%09|;?o=&`AwLB|PA;w|{Z3;TP>QSG$DY{pF-V5**O#A|QOo?FE1cy}hE zPMM|&%d%iuwpc|_%ZyqC)2?E_o3NWJ<|??kI^fCUhj{$x5vl-HfN83z%Y@P!^L0X0 zP|Mi3tlInp?Xb3dm)-g`aG=kFc#flZ5meW&#AtJ=II7^~^XIm<+7fg3Z6rv6dy@3N zyp=^gRwLOpMUlycdk3?0bGI<=3XmqDsHtG{F1(bL*l|T;LfL6j7tSt(J(isvZ!v^T zuhjwE3=dQh?Dq#edhiIR(+MwMzQpszjPzQ7(h8U;qyy;1Vw^h1<|!epzFj(`4shlS zBej0Ke}LZ(hj^o23apOss~GBX!VEGpSpwAQ1h@7($=0sw%Coo{MtVmQu*$m7z@uly zP+kPqeB%I|KDO!D8IO%)T<)C*Q))K&-Y?ycG#H2qFRKol5FS!NisicI^SFc8TWVAF zjJN(p@m*AwWm#}q62Sn=2uu$a+Zh}&R!eDvEDpm%Fx9La#TBnj2qQF8|3RZo^b}J! zNW;t&K}&IzEFNo3B&m1=7)T+=<&+9qn9*xYH=Wd9%f|d8=w=pDxWCvr~T3Xd2 zuoDSF?~@*)jYcj={1qp><{8)fYb@6%wARs13wk-CR-pLW?;%6&Sxavr$sv^bt@E&$dBwoy&WLN;L)ONe}Z*5H*YVdZKrORfjrl;4!}(qryXIl8B=Q(jZSs zNK!fczwEtvk0sZ2C-^(}M#S4Pv$7TzcZm`u+2&wuS^i_JfdK<;V?J(U+@GO619Z0m zwYp*2mb*o2Aw^2usw$WFBJMr&$64-)c$pNb!HkQAykyqfV!2zK<##rjSL+|8q~X>@ za>7&)Y(pzpVccutNPsy!Et=c0>pCfj zqui3Xvdya7W%(pov>bFNyL zhux@9k@Wf10y%-66A}s%Dms7$;UlSHngHr5XsXCnasnG~Da@G6fWyMaB!{U2RNQ1j z7j%Q1?=pMIFf>E3~+-olP+N*$q z3M%R-6O{jj^e2p>bV$=e*>!3~E%IBLCUqj_nL*0t#SCkr&xjuEnxV??rsqX(`cf*M zjh7)}0ty&Qx+rr%sFl^(WbV-#iB6ZP)laZBHRDkwaF-EzQc*hHm^@(_Wi?IB_;;hO zf(bFQk}0{)0hq30Yl}vgZS|P_N7s?K&9OxJ6;#dRS}SXmYQk>25nigPwX9fcnPe<; zT_vOI2&+D0wd$~0tpTn$*>3Rg{2aqDfXgUga_*!MEfKQm<^eo5Sum;mAozuX+uHwT z9G)+fndFm&$yUQcSoYX7VYA*~Dg_^XAcptVY909Wi`DKx(!2KJHKBA4Y&PLjEw**3 ztO~(MEX>>-A`B?CilmfUrNnkGyMDW-d0&{0z=7OJq5g&VeM7yQ-P zk1K*~N@?(nVY4=(3G&e^27!P_pskb&pojnjQMg}w{!wR<6T0bCcrb=9wNe)bSkneftsm+orUfa-cVO zgR=1ew2-^DY+9I)yvSA6T%<;SosOgNiDj5=qu1Q{glq*Mw_{@1_cTqaaH6sN#ICqT z#W`tCQomm+Kf`&{$t;c{|Q^L7y9BKF49) zV;U#ie{dhU%SfH16tL&emUAhqMnnHydw!Z3l#XTg`B80cC;e^&(F9-u*AYwwOd}-4 zm_54*NLeC%I6(|ismZW|6AUU$98_CH{RA%^H@1&G8;P7H?E*HW0L_8Do)l9mc8 zPt}A(P1a^Wj7W=dFXx~=(NNj3N?u@YyuzPpn<*89nbcW=EbLz&Ks(*iD{)eNgxfu% z7k}Wlt)B^EbThBVMvJ1XE#cqn-!(ei0CBsAMQo)+D5gBYc!AK66ljz4mRiM|+)goP z4h86c1pSk+in85dgxCa2{ic%(2RmiIr)qt*(Sn#b_i0w5S${e_s zNW#f4fEGCG(?0XTy=tDr7k z4!PI-L)omi6{CRyfQJ|hxZHAq=G0;6dkozgtF%R`d*s?97ZK=v|DlRUsTIV5RW)V* zYhKbaW)J0&O$e$RR6K-*|3dd}$_c=PQukP|FL8EyA49)U@VMnETCG+X)|;jjEClnr z_HWZJESHpnUUw<9f*Lz%D zUE%WL64%!k@_ZAcl7`lk2^v}z+45k0*}$652AoGqA0w?7WwofXWCkaH zwh1!-RnD!fM#YpgPhAn7g6c*>t`(fJhDO7Aih-a`>u&(uyzk_2f%K~i&orf#Oe+t3 zr4`+2d%|T316Jd*89ff*-^`ng!t`p$U{aKAnNwTFiKd+D{O8=E>zaWM1hl+%$7@$h zaRqi>3AxDuHOL4)R!9z8@#eH}`j(e4rIw0EfSn2CAgKWjjHKR1rB+L^sLHp5W>)pI z5`$@zQ*xIZuVe;lhnzauBa}esL>5uhId>VGjy?CCElUj^bqto^8BPJbtx~BuC!C$0 z;N|m&U}l_cH|U53Bmh9AfUEEncsc>&!?tlmo^Zb|4m?(6#j~?hyiyqBc);PXN6{1j zAjUKuQ1i+GB9|=}N`5mU+_mSaMV;ZcVyohc{cdtuKwhMenow_wVDKcisUrNqQVu{R4neJXH=%M>GSy zhZO?mkdcF~0*ln5vLTM^hg#g5Q zTpN4PVME$38@KTDxl@BXgA}x)M}Rx?0PMi0<=o6UAthj@T5`qVaDWx_5@6SydqfkM zrh;O*ngb7Pp8-!4z(zee%nyNi!pxyVw>4>GXZ1B|0$G$x>_IR(ZFCj7w}>+`4bIDR zBILf)Un_C~x-}tn0dz)NSEJD>vFj>k4DYgd@SdKW;I)??Bc+7hb_+fn(B%xuYS6AF zJgaI9&no`}{j6$qM=NF)=M%rTMX=cRLf?0IaQ{B`hY8boko>tXaJvIZ@7jyk80vaI zncs+8xU9{I2AKvEgxF=HKrH0*@gcPM_~nXYdvDet`R>u9$9VMUCFI=UXFvNH-h1!o z7$*g06o-lhHki42wvjM(BaAcV+-|7gVPoKK%?wOK$q2UE8bkqXZ4sTHQniA+- zOpInackUfj?HD86L1{L{ku*><^v!ZaMsJH~?Q3!!1tw}BDjbv);i0Hyu_{9m?-dg) zd@Kx6P*VV8boX*m@s7*OGKWR%Fe5malPLI42)BO zg>lNfs8VYJMOYsS0E*ngyn>n_m9r^xk~+c!iw5vRXSaG$3b|CgmaadUAf%-Rh-O7M zxE55B@k^dl0VCv^(x2UCi@xt#9wTNPN@-p{h+e(|R`mUV^?HrnZjF=O4x7yi>3YI? z=p_u2;pefg50Fqw)x1~=-0Fs@fal`V&Fs=G14!KKObRgdj%i_Ll)1en`t$X)yYuQ3xQZsEN0-Mso~qzi6n!JH3#8Be&WEdji* z+erIX&%(^fRQ?VX9(KV$G{+#wLP0fw=e15l@LsWzp}b zm^m$k@)SUgCETh28yK(@-VH}`enahhM1CBu=T9I8P2^yQ zgCii+lG^e!q;FOBMoNUPEDfp^=%DFa05eW1)QLV1*zLA1&QN7!A{=VPWcf%TMs$1B zNfq^>AFx{Wc;)e9eCO5IL6kHV41v|F$7BqIVw+;5j}@s&QWw~K`aV#;!i-0c9^k=C zFX8?7-ou9<{sz-D;@Pt&xV(5K=`^;z8%Pa6UjqMko}|xzyNSj(IwQir>_7EzX22t* z0F8LbkYrEF9Z%-Ea0T5;&9l%qWxb#v5T)t{~E=SK$%E5g`H z=(O=AqxDL2EKE6qcC*(gmxEzd*R9V)jphl>YT;vEu#ekFn3a0OZ~<5D80Xdoqg9ges4TQw?)o9*6TGSbqcATAjfvSct?7PCDlit zUR;6zk9bH)BH_$Sb1Eeit+KvJziTZTHP`89F^s=zTMbr%?QnlOzLuI~5HxfREc4(rt# z+ua(kzWfUQ_y^z9qEn)a9mWItoRwFYL6V*3=S&irq3bm1+{AT1a^Sk5$vCU05?Jn= zzVGq+8*iZ2ieG;Gi9|%c!0iqsy=yOCBUQlE%xFwvW~mI;kuM_{|KB%bmimb$tT`p1 z>on|)ixTY&PE)J+sOOL}X|uAH@I9b_a890F+5sMI9#&sjE2CG`3bzC%b^2tJH%R*( z?CHb?R^nwQQJSfCkDuF{%#WD4lHibfb_}08SE;RaL!C0BTaf z!t&RdwO9I30l;zqTQYN901B0pMR}c27yxAyE+EaBWi1n-S1%!|B3x%sE1Y89n-si& zbRRJjY7xO5kl(vb@-0bm1ND+EdVQ|Ql!1}~bf7F@ZAhJX&MNH?!PNkc3dVp$E6v0& z>o&o>uL+b_$eGc11zbk}<^k3tr42Hz(SX^z_S`gT^wfS6)vpb0Zpo~5xtW_b-waQ+vl1j!xJVz?NXIS^C%z^M#t0i8+n!PtE zAgx~0)FY=3wN4nvD~#iWQbq;1<=VwUdHde?g8|biEelxPwQp8yG%A6?Jb`Kfs3Jka z%o8dS6)b0?Uj`_SIv9I zx_b#h59c}XYvW>0K<;!-Rp0WI2(rHb25LdET(YX}08&?gn88V-+E~F)Hr=?%Hv)KS zBwCiRc;S2Uo29o)U9VuM7|$!S)&&t$g+#xo{67^?DVo-=$~aI#)Rau&OTxi3DmvX0 zi7N(T&8mcf4MzDIgk$b~WQ56zJZ#o0y!F;wc>44bAAa~D zraB=(6LqNo!66q96p(>3c@sKFr3z!@a_70XK}E}zX5JklP?(Y)yd_WN-#Vn zzADT}B6KCZ1Zb?@Y+}s=)el{Rw?P4(ONvY^D&z()xxf3w9G3-8}t5oGJT}r z2d86I+xyl!RL%pmYgUs-7@nJT^=SLx4~MQmqm`XOWdGnn4|>D$xi3*DQ82|GK}_Xz zx|qUZT+4f)HVN8cI9NhS85N`cVGs;2WMFLqI(|@K5=ZZ_3|lo)IT`@|h7_??!!P;h zj3O#{40?8u@>&WKmEJ<{oPajq#B>2u5;v=i2daZ%_y?w>{sv>qsLC%{!#lyfeE}I% z^jAyXzr!nnGIFix9tof=Ii-st_ZK~h7Nc^R^^*Q-1XknxdyRdu(CP2w^I~DnA%K~? znDh!3c(nu<`&*&p-ArDyJo9m5rs|ED!<2(eYH~73O999CD%Ad$?2EUWD@Qjspnp{(KMLLohT9>l&7?4;CFF{XKUAhPf8kN$(c z!m&g!2(>D8oB#f|&wJ4p&ku~-BdX|Jl(AL{G+7y!ps< zr>pI^bmbhETBP zk)A-w38QS;^wF`u%&MoXl61;q*#kKso5vBzl&0?CbAPM`B=v7A;%7m>hdMUiOLB@W`o%7-aPzaQ0{sK)dAZh-Qjl zWV)xJ9Ac_(!uI$dY)z}hd_n(2jU?axC7q%{f z*eEa<9RBnd{kP_0^%yOL<_!l+e&7_YxGN)u2XIvuu41B`#omgXj-+CY;|_o=VsR%< zPVy_2Q|}mp^E91N{eQY5dr}476Wl0**8O_85#!iF!9@uFHX( z-i$wKig)@4!=KlCU)-NhT66cVK7qa9@q(w^V`(bUUQ2?ZmU$GQC6nvFw3tRf7?%KO zL}k>nQ$aRMfTjIHB7w86`1NW#x_pol!OTAWpgxhBotF8jGcp!q;uYd$gBd!xf3lH= zo*V3sNDNyzjz79nxbz7beu)Y}De~7XXhdRt1c3WB_MCa{MXsmJokX&u^O|Zg$&uF7 zpkO?@O>?D^hN;4G#h4gA_v5mZX zMjzatW4{%{LG$9vt_1f}GD_5Zo-Ggei|v*~DqZTxhh7%%MQ0GEYXk<g|80 zrOFm7fLW+IpT=JKo?mC@Ic~^LbyK*TGgkQmmY;f%jFE{QF^ksZw_|=+p564}oaCU| zLUx;Ik-~3BSq^*68U}yu*MdES!HAg!@l6?Eph;=0eTrA{HMt5gk!{0_x_hTvakSw| ztl}r4OF>Y-F+2aAv1H(NcWZC-U79{Q?hEXgkDDd(CtW(Hu`Zwh)s!?#D(_#qSBjA-L(|A>YvXp2O$S_U?YX z-?yRLmB0`eX!%5DZ82D?L3)~V-d4_>?G=Xz{5z`|8c#a*TRE$-^$53}?BgHUJKSN7 z%#n|c{JtZ>RjwFLHqWkDfuP_-j>PdA=dQVA8iF(RqLE@V6CI5EQb>~&hKvW`FV=xB zh1bTrjC~jklFZpz51+QIJF<572TxZ5)j%tJCtqLkmn=-Cn&trIflq6Qw3lYufI%Y& zGe{}+VySbJI4{|qa7BHhr?Q&H>6hXuA*Gke;Vi`k8zJXrZQ|-w8NcCekaSdrX>=hM zW6FT<0lyV1N898B9;AJ+PCH*=_0CJ86h+bHz))|!=c;b=@_IOHdw}q3jL>Mx`@joQ zHIhQM|4b7B5?F>y%D@OkKrcMC=xYsUibjj&A})h0|Llq`b5dU6VQK4(o8 zLSROsO1x2L|Eg90{s?2Cf6~qBajuO~2$|=Psbp#`R~Pt2%c1FRO4UgA%0E=jnPof{ zn!@rbeimDdj~pm!xLt546jz~aYWgRr6l(1I^Lw{{E(_6uG&MEa1sl~Zm zDpsh*Fc>P*pU~3}>3Q4ZF%(a!GRjA>o_rZ#1?vI9K zw`_2og7SG1etmP6G!obwlDqTlQ3G}j3gxWrMBZiuzl(2PE@_h&#tCL^v@me@vdq6Q zpueLOwMSiK_!iI}OL^ZJSmI=NzJk?Zzuo#W`&sUq)E*R9L%e&!1hUp?f1A{XUYt_Y z;iKL+2Z1=%xqgV0^}TXCNtA>ObEK{b5wQ{g9fbhMi!5FJ$=!WF$G2FgZxM+nK=)9- z&RFB3qY=6#<+v)=M#SOpRQ_Cvvd7^9It$%+{I+mnuX6PBQ@~hC`IbbZe_J9(5PL!- z9QH`|a7>O}x&BvPra<_>dC|$%#G(ox46BsdK~DOJR85&t`Vo4-17f0LqKZ5h%OjJ> z0(c{5C^^}$r8&`7U0}VJbehmLX|i(v{MoI`y?(wi;q{jOZfk%_r9sMKbtFMpu(m*Z z5@*Ia(ZpI)O(E9wX+s}%cz5ZxmYJpswhA$U{D0s`)@zOC+S-tl@Vs+&S!p!C!bts@ zwGVtmtVq!#GEt>VCTZAX2T=1NMAdHu(<*}sjv-D>Zrt1d z`O$}v`ppsd<^!5=BB)Imi%E{TC|mRwMOMtJ)E3XN5|3C?krDxxH&SqkpaYxNgNB^ou>b!a=Ed+gDuuDY*;t&EpzFtJ54Og$m(d(mwKYZp*XfU&@lB=>>B*%eikt#W-CQi`0VZ+a{t+c;K< zDZVVU4$tkmQQ*zx{nEX6VEfC!KmOZ|e9;=wlp2i9>aPp~glhE`UW#_3@nK3Ah=h_O zJvCQ$2SQDfObLdH<ko7W5*xYKRf6TVdr6-SqKiPyR z3O8jGa?n9zTPX{w#rXFS5z8J>K@l`wA5{#df1Uo z2rlT$pv4CR&am?d20UOy1lGEH+mWJU3_GT_nq4+Cmg zez*=*GmVq6+(|8wb1qNU{SIo!M!tOJRRz{XVQ4T5je_JpK|Ep3-uoxOy4>SoQRC+M zFbx!w%kTJv_5+82AFUj3flCO{KtS=;+5`|1Pw@*?xu|hk4 z6RaBk!V0Pl_O8W3(ll$JPZZ*Qubw+lkx5FD6}1dpoaR)_dpRd7rEyPi9oHzFU!e`vMc;e09sdM zCPWMwHJ=9fX@9>qr!%DJ-Jb79=o#)S;TRl2d+tTA5(lbg8BL>a3QeU~ySo<6oWA!* z`K<#bBbuqgb6pD+roCd78T-4;QeTCyrUd}1c{d@|JBqEpRhm+V$E~)e zJ!&$SGzs=D?KJpc9V&rL2v!_`481TI!YywInO&~>%bMt{1Qi*mF!S^cA%tJ`e%N*0 z&&fDnd_d+|8Ic`=kR_FBYnFbCX}s9!1P?_~Ijot1gaN*!Ni{WdF*NUusX-b90>dAT ztRQ{Z20nob{2v%1mrTDxnDuC{w26reF_Z(?WVC~P=#Vy=9VAtNEut|Yd;04;NO>_) za{E6Yt3bh+Q1cUDCy(eW{7Nplj6<4ksK5BHiJ~RJWuZ*Rf?+^ZnGkR(DS6(%?M5Rg zb3d@Y{t0|o=;AZ{jZT5dhNIXjOz;@c!lOfmTmrL+9E!-M%C|gahQ@OdSMOkvBQ}GX zISB#8VGwhtDuw77hT7QFcqFzTc36!5b0baL z3#X=B&}NET{$3`~#)O|Ca&*$C<2v{syLNp%uAjVte%vDfKu>rerC6=$m1R@!GpdZA zNm#Y}7Ld_UG9XT%=rpQ4>jxg>6D{a}%dhiHU?8HFHIvAhhxpu0Y1C^YdnB&^l=NEG z?;0-HsnecV$=+p8!xlOd2$#l|W;!}af@zlesxHga-u6>t*3fU)V(yhj$IV@! zCEeP_i4Wie{I@Oxjd=99zeZ)?^ggH=oVNffB6&lKy5dMnP9-;ak|uhqH7QDUYb+Mv zm3#8R7^RTNHx|g1oZ!wQjGsCG%seVL$jC$Q?|^g!s3c+M<@jP}lu_%e8;(DZPG;h~ z8AsLoB9}=NGhM-?c7TXp;Ni*Nlu*nXJjD8rdYH2_^4Gmczv0_SvexZEgolI6uHkWHqvc#RBY)3t9BWkc+7 z`sjXRywyldSt09<1H48&?J@?j*j!r1E|AwvKJuW#( zk$mn%w(e}Z4N$=Z@l8%PU09z337Ih2OSix)juJ#Vx^jL`%L&f#@n?V*%);^`38c?F zDqD!|OT@WGyQB18zl+-y!iVC`$*j!E6});Sdk(K})XlB(tDIb7cJaO8V?`Yl6l)}> zQZ<%#jAIU#t#XdB4^hMVvyTt8LPqTTk)PAF#xC`*cW($*^4dq{O`EWSA2mi-^Vvvn ze`bKK_c9oNxOs@?PFJ7x$}t9VlJL$7cImHA$CdA;YbzR}ZXZ!Hua1dm4tT-6NDbtK zoZ`qPM#`V++SzATK-6URlae+!QZCxIi-_{;;2+@TOkylF*RbA5A6{dOt^gJXMuOFt zgEJ;4&=>^FOW@Y!M2PMRhWI6@dby5Q=L8&l`?JAsIANdw^6X1DOUG za^Rpw*Rjm&H@V=6m4UHByvayoX-(ih21!p%UIdc~vyFf23D=||cY?VEK_v)4 zo^`9kkYQwr4nbQh>=sQ!3(FrV43Dong*mo3mRty?{qAa2bO~$Nfn9MzxoO(8XqZhpNk+y-PE64w&1GIKUIQZ=ne-i)NI2svNS$B8Sjh3zZXfPbE znAaqKwH$Q@aT&81GqwH^j)x**8cBGHkoKomOI1W?|5SWAi4E5{l@gK$c)2h#0Sp*_`Ey5q6zNzkD(YkMfu{S7r9`o}Y$l&DZ8S8|1b1Bdr{b9to zL`dcs2_~#!eW*>6O$I5|StC&mInPzjRFqR(u11{#rmV&rl~PMkEYl^ln(gbbuS-+^ zPG0LK+raCQP8(3LKQ+y&Afv+2<&E*$g<-qLgfQD7mk48G7<3G%R@eJzaat)ya;6z< zQY>K7kYOZ2y`2ndOYdFd&l0{AY5Yt#OwV-W0*55J(?lH(aNCM0hw7(C`0H@`y1A!B z0_IGae`pLVFG(HlV|&N!t``oCOptdL!dIf*-k$rj;uFV( zoF7kJD}n%`A@$$6D@bK2H)F@Sy8@pd+xrikTSEq)iv~ucd{kx&!Rjg$Wpm8snC_y} zcrD@pDtt#g!@?32dxr)aa@atr$XRkd2xBRYK6R?_#N?yL&IzekA9jx5ENa1V^t^Zy zkw8kM115rKT)B>az6egvJLkxt6Ms0E=r)`)uIO#r_Vy*>nHE)ab$JJ67`ww#&^`|h zz96xC+b|MflY-sl71XHI)117Uebkz<@R16S8d>mWx=G2k*OESk&_B%?4FO$DRHCsZ8UuY61rS8lBfGAIaZhu#NVp zEF&Wtn$uReS)i^ylZ54Z>jwl&PO5c4r31i3yP-XSlFT(*&zjuv2wSK(02Kd(1a-#s zXGe{TBiqqSO#58A7O(H+Hnb#(wR4)%2&|d17@O7fm8#NNgeXtf$L7`kp#)F%pG)4} zP8={AWvtM2`dR`kU?sC?PU&DI@XfYs9Gs->G7-zj2MWgj+g;&%e4>1QsPzlY{k$)2 z`x-ub-g^3k0g%hiLlo#Qx8RaJ$JP3f{(#;bj4B%YN?n6=d=Vk!M%r#?D*e&VcLI_q z5!n?H6P+GtFcd-kvf&I+w;$fhMpHjy*Z2Q$)y>Y?RroxB=k;|CtdDsfao_$%;i?5M zv$r$Se&q8Z!@?p&>Ylt2%(F@56XjyElCkv|?@r0(umQBgdKZ9rcF`=A0BO1pS*OmL zS8D{Dy&lMfV=PG1MMy(9iCx@`}cyvFe_xf;sDZ72F}NH2$BrYvxh z2jQyozrW49pwG|j<%u|!JF*d}9sqf(Jwf1s2~8xR>5W$xnavHQB&;hy3ysCAlS?blI*^{Owz2g>$!ZzE%fvo$)C3n9 z3U485LRx#jQ>?CHN4VDSanx;4a4H}0=2dz5WU0|{Un{^@i%Ydeea|&n|1f7TZ@n3_pjAM-9yaEy7My&D6E-o|Qt_B~v zdI18Z$0~a0lXVhjy90luj;l6s@t;S}^K;t@<{^2}JRnPuQ{-~6h%2OtXoD~q;FUge z=;n*sqIN=)L`5LFa`p5LvA`1O>In%d{i6!k?O`}aZMuReK=7Pn{|-(txRtjG#3gzU z%eZ#%;9m77+f9cpC~7)wbieSlhN@^5P(#vvX)vXY<(xrvwph-be=KI=)*$%|z_JYT zv`R)Y_5}KA5^ESXt{QiCtFI*wxJd9n!dy=BQ@Vj}@G@)H?6i-ZJI55|WofMH&9xpL zKW{omr8Z%38n_(MH|iJc*~}B<&i{uM*Q(X7}26R=GuY zHh*i8K(kzAGNTQ~HE(w%wZNf31gKKrmBNbr-t(_CB5$vG`z(tWUnVEiea1iF&?y;j zrhh>kMt&Si>RrcJNFjUDtH%6~uXF5scxXNVB?A{qdWtqDsB+If%vyo5+)68%;2O0A z#{HC)04~kCU~Q3tyu;GO7Y&1_-hXOxN`f?>1Z12ng?F&y=b_!Ry2KM5vREUOJ*Hp})SPYTuo5c58{4 zJY8lDM*`w%Fa86Sd$f)d7xPpcw(cJG>J}Fut6HYbZPbSE!xTGSW1i~k^7iq}mQ7#3A-xpXzW|aTmozK)6$~X@U9ybgd$_1^S zwDt^NW?#V*ob>E+Ta#|;j=ohSOTs)og0OSnw+Qeae8?-)$=NIFY>=Iy1}D8jJD3<# z*QttXL0bnVng&yE8}f{V@DC|b;t^IfVB22BJl?e)*Mtu)R#%_2OPYN^kqA6M3=X!B z4fzFKTs9iGt1m-Li9av6RC3V1Q;(4zL^+#AGrgOA@`v^~Glb(x$24Lt4TU9y3V{@c zFg<)>n=JkBH{N&AkwfZuv-OHK(y=opm%cc3D#r}o!N9}S0TH<8jl)nZk?zrHqVx?BIeP%4Sk5)@ib*PbLr~q8>?M$&;};hq=CH4fP+XTT6)G3 zLAIQA(Z~_gR)3V0W!I42SMG%*h}tH5BB|UKDbn`%-!&?zjRkn*|FQr%gNPJ#r3Vw| z)H(|R!w7lGGW$l$TIX*%S5M@};N_F~PGZ{(@At~UjnQV6rO~fk{PjXHOPfaFC z=BC8e-_B<8igU94alYV3?JW=K);ggQJx`<1iLwGHny-uRxB48P6(l$A9VV~E^g z`9!RFB3$^N#LsSXaV8?;aY=KB_o&@>hhB2}d3PDugLxb@ehgnOTJ;&t`J7#>mX|@SrS%yqCtKiBsz@y$-`DI!VwM3TPW0bwgl{_1d$-#Ac$Tj zH<%reVTfLTaE`W5*2n?^+OR!cARMX{Sf*U?q~O$F`epR~_8uOVNZ97`mRZiLYGlKhI;pZO}o8P{b$&1Kd2zVxX zr_t0$Y5M@=daPs5m-F=-Ck3__qNzSTo?gtoCSOdB*Z-k7_L>D_9tvsb7FUws>#8zk zNf$;kv1p-hHsYuqF*I7*sBH`inK=g>0HOA1rs;ptjhgj$J01M7Cvn4_1|Chrk~6qkF7&olD2i#n&X&^|ZmQa=I4Y^Xd(Z_~d{PdG6GmrXKA zB~hofCWUlbpY2eVu=46)<-=SWi?bTMvAFu$Av8_45isOv7BmS>1hDin9|j*I1CsYV zS9w|1`B_Tv2mR=70H{VdP}$kphB#2)hD5r$x`w?1Y(@pi)8Cyq;l~N%_3i$$BCUxe zsk*12lEVVlG$WYpIIP}wq3qnvV%>mw_wdY9S&HHrge5U&V^HgeE@&MQIVT<|;Lcv0 z-!@YXha*58^CvxjIa`G3pY%G6x68F&yJQKWP??Cjjg;_beF7YrRYCQTP={$L>%4Im z%JLn>qUG02+rO)6k8<#gYzpTkbaK|3-uto3H)}S=C@Z$h9uLhLH;rF6z~>il0q8`S zYpfP_@TNXFfNDbT#Lt%XYOju10+MA9v%82h?zTDFE=ZRvpd@8l7o>D+j6Eaf@?p{H z)38Pzm%KlxFVktxE#6!2$y`#+=^HsBIVtI^i+{g?Ib@l=&a+@IDLp&6o#zM6X)nY< z$mR8U2cQUB&~A7%#Y{2PWyxb)){31!DM-J1zYYd*9l2!ag^eMA@a!tPmW}ZX$M4e6 zI0HQ4>;bRxx9H9{K!E^m!W;Abg$V=jndHz*tVA=AsG4`)-|_uFmi=RslU)u(apnjH zXW)LX@-|`>CK`txcpj$h8=5!&q2tSOWLqlhlW3o+Re_^HEwTE(%;)0a5y_zF`ucp^ znfhi?jZeH~=OePcK|NzAtbV_BKKig17knbMg@%MO!i=zVbVD<(vra6Nmz|^?pL}>U z5(q=hta+Q$fqqr&>U`fMcHQ-M1rO%$e5(-#y+V=spFzIf8{KdIS>zHOLcsraShiVa z|1|DJ91N&AQU%X*Hw zWFt(AF(at>!%``0^GlakjI=lE-hK=@RUT9LE>?n5doA0mh|#IWhu^cN6i4A7H)}&8 zSa)#9vdxKi^`a*nM#9A_!TJT#*#n&Kay}u{_x|WxXOSO+j^w>dd-OZYWjOxpcEscT zwh{#W^;e(QVj&?^itVP6MjZU|&=d{dV2 z{Foz`0yuq~OkHyvJ*DzL8XOB@xpsCGWoP;d5No`2Cs{DMB7SFZ^D^4dP+y6n+Ry|# zqN3UjEhsD0a!WJYr&PFL%t^@hET$?n7(Qi^bGIi)FAn2Yz=*kTsPj@i@!G<_d@<$Cy5@3HrF9?5ED3B>Hw$n^ zDQi#%>%5_#2@V&ef!S$M-0Z}IbQ41S)+*v8WgO({ubAjxBUs%K-ze~F&lAwiRzBpR zM1mSNlEwOWfqd2!tQ)0{>^uy2jN#%yXU&}r6OIbCrYoPkI_-J?_p=WZopo57*-5Ax zott)hNDRVb3BL#-Wv(1L_3+6C%m(hSWPzY@P=*|r5btnwjatEhK6C>Et~<)VyEQt| ztSo2)6(vJr1&I7+;}8`fJ`T_d2$X}Xp8s^5T;7700Xq`3I-r$WVVb!LvUWW0|Z8L@CRUg3|D^^gHs<|!gACu{?pZT(U($p&#(~e*7s7vdZ zFbH_`0tRQv2jpf<*uO-H$XrMSluu#FFi#85M-kwNr|N--yjIRDRfb`4#O^J<%t!^Gx_cax6(^Yaz3Ab{L^g5{m2SsQu9DA5=?8$TP! z!sNW-6OYzK)n`^XTRJK_T#xnk_PmgMv*@Uq_B<~X0}<`OyOV*Jl;G^u}4ARz}=%1eVE*=lF#*t~g%eX8W zsO;DRk7i64%H3%Qv2Hy;8>izyReST1ZF}LowRYy*i()8frSk9Cp=zGnj#OkS9ArEJ z|A4)B)Ps32u=g25;G^~{VB6=K_8^6AGOuDl{xbgvYg;*6sSlGFM3Nyw6wIbCowc*( zp%}y7=w2vN&)Q33uTKun(e#lz8@*=AvMWd(2)WQ@*NqScg50kcX4IdtZmfI z@6_+uy1MszDtxI?eUb!=IX;PNSo5D-&*e4`=*(^-u=e`Qz(3$(75%#w2fga&h+I$N z3i6iFNCvK|>yn0*u^HL5Z`tR~FlwQ9!Uqi4C%T$tqE{(j{HH#x0N2(Hz>6#WTDdYD zYaYHZO1+ayA3+TI5LSwS8>)s|xUxYQi&xXCY?=TctAOPmBT?%aWWBrY7s)=qH0svh zU*CQ~+VXuW{nl5!Q?r<1G$=}Bsj(fvP=nTBIlhEigv0k#0CIpK=S|v_Dqjp2TdHT`@4&-x`D6 z^0;Q%kD{)U*+FMv^WGDzQ5XJ%O)ynU}%91ngz4p=`R4I%I zuKgU-_vo3Zadm!PfZcb8>Xg3qIyx%``VkKp88F5|9^H+7t@KI@6ab)DdO=nafPzV9D6)@u zZ9jROtvl@Q4yHMN?(q9P{kytO_J5B5z9Zb0kcJiOUR3&#+axRr77^9DX^lhFj4=eK zXp*v!$&h_jv;bzzO#RE za{0xoF|($i%rZgH{L+F5a6o~QUvi}ec(wEfSBcqH6Js+?C?msSAdP3B--)hQ(UP+wX4BNn6d>HLzTRNJ$hV_mU({+;>Vr6?qcm!eT=DG*lIeqdJ(NT*~069b=)v zwKC)@UvlXnvet+7Hd4Qbru)*_+6uDJcDK6eq| zk>}z1_sLp^N(2-$83<9WRqxmChlG!}8mQIhA+}sL*IO18yefrrW&$uW$zVc|cPWXP zlW5RQ1!FJ;ZtN70g@IrXfzk$~mXFkpb8Y_Fd*1@2!(wAAD3#ctXarE+Q}6!v=E=^@ z$tP6rAgojk#78F4U17DXMR1RoPO00fn#n~vxrLke8#+u@P|Ep}uh09p0%%Nsp}vy> zf(1&J_}2>aC61fT z5HOIVtmq3<;Bs+aDs@xq>^=$$&Ob|t+ZaF8MDgEDRdb!oCS8HOAk}LhF|~A0uxtRX$nOX7zdfz$ND8ulYxP^AQ&b3C;sKFcu==oR_)(H{5o!;EE?@JiUakPfYNF0ibzUIaoy$2U1kU&;^y0 zX={RpkDxl|>0T=zG#*DhM3C^(3hW3(mx4eRLfG(~Ua4C4czro8d!xPA04nx8V}u*Q zD-M*LC59s^=O!qJM-@4t{dYYZ16D&~;n7x)XJpjyBlA1|IoC(sG4pXum6F(Gj1?YpoC=QjyoN0Q zcb<8Uk@vd=JLLdi>MkcCDTWwtR!(03)|vHj=z)nJ-SsEq0whds<0q=(d7G{Co3jFh zqZ}?ODzOUCvho1bjXL$;m2JoHnzyGN9xGM%+8MuW+P|r6l8?!qbqx z+l6P`OtR1pKc)kWk{R14yQkJ&X!qHcG(8hl@Egi$HJC@+mpe8Ys7hOQgW~qR2cB-y zsNep7sY*mw!PG<#t_Z!aZ;PzcqFoJ~6P>YkLoIK3!XtoB_K~}T5rno!R%!31-Zz3m z3vTmD4`=1sUq}($s4OU3nxP4`ZOLMP&A!nP_}so3{CWU_f_<)k+jf4v2z+4{$E*<6 zfJT@tR#{VPT{3?+9k*`qAS()m!2QTK(swjwFYLQR%$tUKdj3JC~;?@`sfNKNC$_j<;;ZGUr6?y z^huOoT}qt^l@6AUimxI1kY4okA@W9>Rtly660i1~SjjCbu(BWqdO;K?ET(ZD{rzwJ zCzyc8TYQ4cu)xqooF`dwEEZ!J$U-HThZjTLopqFII?Mf5?M>Lt!<8jf3AJeWZ7f{OZNdt+$ z?wVzRT<<|^K~}o&Ty=qHmIsr!5d`%Ypqs-e-4(Oi#ZF4!%Fpyeu30jmOf~EcN*s4t z(G-lCYK%`AMEgPWA%F#iDNZD=GGftXf1{I3c*Yo;#a~Z==$N2bcI6VPs#T|oLq~Bu z-CAh#DiQu$XBu_odq#h*{*xfv_FLMX!dK!9LeA_r>V*bplgCR-Wm5?xGmJU>fY{k> zhZv%i*DQ!hLnJecnA9-4(n@5{9U&SbBQgEsAgq(dBA2A%+B=fG{eg7#bp}*aj^7;P z%g)&voI#dU6_k3M_;YjdVgsd(0|Nn5H@(|#xJfIANmNWY{L8-mJ5FSSD45|eb-iZy z17&yo?mQ@q6jBx%B%y5nc(IRq?8)Qn9pPK#^M0}YN%$O1_~9`6bC*)!rS>~T;45yh zZDcp^_GgCEK(-=HKoA3^EvF3%d5qfg7+35xCEenJ?rZ|ZKTf>f_J0bau=&NLRzAhn zNS^a*w)!!piX@VCy_phY_aFeu@!!=6C-_wy0dt5Hfzy5&epVk#a*OwDi{!n!8q6Z` zr|spq&Dzg=&3t%W>HS9_Gc{Ik`DYy*E#qa$SYxD*LC*Z)ttYfj$nb=x_uX_swSNx9 z6|UQpBtyo)DLzva%Q z-$(n-tbObh6VVL>|9L;Pl_~!2?HKm=7LR%w2z2uE+jfmiX&6t0P!v9dmBR}G=1+y< zT6wy~_#r)D*j{yP>;dh>VwdaCaT2n*$%Z@ORIjtYY;tV0da<)gH~wQPLTwOCu*Nqs z7T1uIML)RE9jEX})k)iaPi&2x7CFy4_ENQN_oe&$qn8ZArL-}zG$NHh{zee8jY*AQ zs?yM`UE<;chzN^|^?%F0(R$w(-^$+LU|l(AD`Rs6Q~FP1SDprZC~9&B;nU%zmh2}O zVJBUz*cIn_C4~ctb>Jqhto||y4>*q?2c@0rBIdLfR~^5iLpsR8JRAOXNhOT{n~)nI z$Jr?gl5qT}|6F~AHEH3Q#QjvRj~$z+-ah(mwai4^U(v$~K_-{2OH|oRLRutxec^$y zM=y@3l=qhugX8o2OY9;{v*G)pfEJ1c*F=^;TU)hDBbC9dCcbR(ZKPyw*t)v2HAbzj z$G8~j8DH?b`L1H5GM><+lRz+>mI((E;i$kS6QAzUVin;>&bDG)t>|dvUz(hQmFP-~ zZ+AOn#c)jd>FJwccZyPI7AKmNbPx}+nPKaEu5oY-|Kz$cIHEWHZ}OlhN`iIm+lr$K zS5j!0Qu9%r2}ZK5n;J~q0FTY7Q27+>O&67$!@8-ZNGEo@&(s^#vXa-uc03cz1S%?1 z11eE!qCiw?dK+}GZs6Y-?rSU5y>Ix3N1*@v$XD3enN9wFMT7@2ZF+bj3{daV)Ib5f zgU-l;S(+HjE5c>(9_yfK>c~#3eldzvFuumcM{1B2w*;E&IiPk}rAUCYxAkltS@uB8 zr>6p+N$0AlGc@a_YD(sgOz57sD^Nf}@y=mnbIQ>7D21i`<6h~p582nC)96l=z5hUO6+)MEW-*pxPg9>y;=;{#MP zGTSiF+TKST5&4x0i7z&}%=Ko_IaxuqZnd26gOMLLIL(WmqKj>2Xm}m2RU4Qsco2&)mlC;0cl)Z z_h&S@Mc?)dvg4=0{!B1PVyd6E@GiN}*So}Lt zCy-;f=c-=2I@=BsnkRa8Sutm zhJ42a=<4h5%@#^<0RV}7IKS*7yJpzg@Cb4lt*`9t*QHfK|BV%J+cIc99T~?z55s3o zgi75$x!I>o#JFx(DEAQkKWajk)o_e16Tvwwjw;*P5Ja%9q)y-&f)wHQ9|wil>ysL0 z;c7<74msE&6hlk>5c5xPJr0JO4$u;oK&^3zALwY}3m_us`qrTumogZ3%DZc8I4=1o z6#ejhv+hL$fW`_>nLNC7Pfy_oPh~?ImOB`3zr|EEbJ=-&W^aFZrbMc#3}qC3suJ6D zEz7h*9)5oggLHUom;ABm!@|407Ye2<5WZdwlNb*7)bz~|lCe(e#{Q};hpHtr0S7>8 z8$*EFBh(KR;)3uMkOi3jBw-@-d>Pz|A7GfHDUdN@LQs8DaD4%gVbXv=Me-rB%FrKF z){tdB*^h!@5`U6mx{i<%c&ZIEiebV)^qV7_N@6U(s-e^iVcB#zv(lbDUkLaO5Z|qI z{wii;8(cq&x4>MN{W{5UM(sji(YC&jTtyto?2k3nUpgRunspK8 zM2Lb+ z+~kya`D1?&S5N|0Pdbn6A5j~YqLHJ~FR8AWPr}EoDyfEjZuIxKw{BG2_9Z9`7)1!l z#DX%806y#adrfzRtjPt1*S~y>%2|kn;^x*)WEo|DK{(Qc63f7>YsV)e&isyc>HOZs zP4fk%ri9(NsuD8lH~wy30gm6MIZ8lHrok%uSL#lL!%#S8Msbz9=c?)rF@&ciWaQZ1 zhVd?#I(_2bT0RKw`6GMCMe14zlr-v+hKB!&dxNT{O2(VuV#p^&5G+M)>Uf(A_;r$= zChIk9!%%R6js`4oD1HP@&yN7%hdCUn?`WL|f00(Ky6vZ0_#%KJz- zWHN}ztcB&n)GB7VgB)lSDX=8mn;y)af2HYh_-{KJ?p?&4-T|zh1Gy?NHoZ?yF;*T<}5p<4#8RCRi`%Eu(7Kio6k1~1m2o&4~`#V4F$pKuvP zO;h!1$Ni^LnuZOE%sib(&84XGF=$O7MQxRvh4QN?Yj#LNygJKE6w>JxOK3|a ze*G^CunNondXNxuYY{#nAU7YHG;*1_q5(q0F!3jUU~8$X~)cxB`)167GeQbJuuXFzbY z-@@;kzsXEAgVT$93MPC9-ST^5=y~3Q=k>gW=zab6L%iB5Mad~+7nX#@fx3Oo1z6Cf z$OiwKw~7douU36M%)3%C{y z3*~d(oDj1IVJsCp-I5{*NqK9Hi)E$$J~(VSD|MiW8H=Nzy=UHD|2aIv3U2_pvf?th>`lK+D>CI@8Z&D(Bnjgjq2W!-u(PDdlHlvEo`Y zlMJ-izXJLv18Yzsxr{yp<6-CaA>;bK{!#-^W>jpI1500k?0AS!|KGPO{{VrHd4a!o$3UmAPjFrj zN5Ze?_^%MFOeO@9#thby$VBKwRsi_|uVK9=(Q(X!*QVH2UPZ71X4As-^yY^c$+Uhe z8++PK#j;Qm9zC>4z<~#WuWDs!&)A*aZPt(LVf*faWQgSBN8H(Xvfn;#Cm8<+Jwd|0 z2Q+GIcuAeGpFFLRq4k~7(&os(mXZe{eceVpmhF#(MMl zFbp_YE-?-Zlw7bF28=@jr-JG70;fky+{7t(94s_)Kde1BCt!*!8cV;&JccMy9bkG?<8 zFdK#hdDt@k=#Tyg@4x>(?%%(U2M-?L-o0Pp-Y)Mew9U>q07AdHIzmg9g$W~92t>R`b8AN>JR$~Zh+;bb*ppn|H3gwV=!*|>4@ zCYA>WD5c=@&p($2%4*jf9UbB1&4Y<6xKq-vl z(=!Jnam~G!G5S4jKchjti$I<4D`q7jax0f%4h5<0n|6MGKfWG=36hmdLiBWjim&ti z0E}Z4+Wa$HASESmtso@H`lkvmNg^viTE5G{s(F;dSMB*N_m=8+p}a*6qXt}uf;Y8c=6|a^zV~jTmK<- zRw>ZRnuZOSPV0~1I)Y}Aj4lsFuGzg*m;K2bJs_x&tCoA0{AkZVfvAWi)_J3$9jP^m zOJS}0<8GDt2&7v4jMzOh0Ic>>1zP04%fsaQlpxgsTZ1M0o`P)$UaEhq=wg<<^hTVh z-H}pqnQd6o<|ZS9asqSFv`I@DCDD6T&N=1*LzW29oRaH-tYEtE2B$}7_?>s}f+k?d zj4^2~VO#%xq2#XEo{{jr82qz-T{chD$o5_P#)#UOj+;`# z(a{lZ-MooM4?oAx{`-&d^n8uQ!67CkZ5RbpWvM@Z#lGB+-`;2h=&NPC)#q)`KXjjd zwR7?8@2@gg&&Oue`9l!wdl9@|nas}D>9HhHoKn*_<9pxx9=`wm@8jc-KgKV9@k^{X z6Mpso{XAfX3?j)~u!z%?Gsc|M84s-2YXIoVgh^_>TDCd6b1f30qz`z~(lfPI4BG5T z()a};QIT7&;`LzRoxKyfuQ6K>5|l6x`b(4qi^ z=0aty!3vZzq1FM%$7cWrtX3!Z_6Hw;dBV?s_6z*|-~ST?AW-vWD%eg$pkctl!GWef z6jyrF)Vf0g%~KYy)&J)H9sp=`Oap0_qGupsv)M=uIbiEN4a^2WY6b-aM9DhI`?YGS zpw&Gk(pq}j$RIMS(TFj{zH<$9&8T@t0Vq)rN!tc6cO8TD%ijH0HI#W!Q)&u~0uj(1 zOZPdESQ{2O>PnBL+a~-t1Z1197GX-H-RE_lWUlr4xhh#g(hXCmOroP??P_66o7M@H z0pvW2#}Qh`CuNMwB`9bA2e24hIb)eJR*M145DwNzxvu!Kt$Ah0EubM&cd z(a4zpY#)L)XEOs;XoYA%MMI{CGW+p$8lHg*i3&7z^i{{J4BT$7IO!6B7`r@?8ge8} z0p($8#y0^}B_gBgHZ_Vhq7Y1AlBgSLc*e+i#GN~DVH}q@Jv{?3;qwPy;4lC3ukiBa zIfgunUV#wB)&Up*7K;S{Nj0nLz?{|-N-b{iM}j!cM^79xVg!uoO?k``th9iE6M1$? z<#cm;T$OI=P7rSdXV=wqTvf-Ofm0_X?F1%;e!N-3OK5TbJVvrg_P_NNAg@vB5v8wl z9tp#AXHNw>QtGv@SLCrKkxuQ&rQq1XKcm@8<5+qw;u~;Av*=4ig7P|)PoNmJ#1I`>8b3#(q0vaUH z0wf%(XdNay7DWu8SsYTvgS_uTlNSV$oYdj0cHSm;p|TxzeKVWU$Wg~j8dxJT(F9qL zO@=337aCUCcEHMVQ!DpDJqZegwC-^2-S;i4jVyAN0#@m>I;&+fXhW!mRgy$dT6r_A zha&q(?XE;x<6rFP3hBu~x{zfOlG}6)m@o`O3tkxkT+ zel2XxEaiXK5ZRO6rZT(2uH9?o>e^oCu_sCQ|BWDZWi0Y>E)0wUo{i8-eVuxiX>L%^QVA2X=EHPic|QOFATj z9YnTcXrzh)C-%d}&*(fVxbLqGp2`4j%|k446M!oO{nE^E0g@5`23%Wb$aanLo&Y+{ z_UQ?=?z$Vn+pblJ{H&=LwlBG|f+;(XMC(91*jfsT&244dR|dApua%jEq$H^)har$H z`uu>JBCgh{Q%SyRBxz->F{NNOCk*3&VH6cJq>OPGBrS3rFf0b7AxmoQI3N!RiG1mX=64`Retg4bJY8$TG#w(bh_W1ZMapq$)me|mh3w{E|UM-Lz4r$7HC zp1eHA>gX7?umf=NX*43%=B0l=ckTBWIc$q<`weE7A{?J;BL~=0u=e9?IgBBLkxpp) z@HNIRLhE%tk1g3^q)1Z2%c(oj6GRFuC>~6pKp^@Ou|^gO5S%Jw7)IPUyNO#j?%;R7 z^Sely@yW*@{a! z4a6r)9W>pL5Sv)o@Mxw8qB!VEpIhGATcX2~{;W#$>v>^dl*00`X=1-+)5{fvOaq8= ztMLZ-d;Cp)mLqe|NG?jf>Ky{GM+g=LyXPPd)M1C*uh_JX%5&rf^pV`ELuem*s#O(}L z)@JS;w!PBZIPj*SwTf*vO$DVETwa{x{{8!)JYscxrVSl~KHQHtW^~=QXQOwNnQZ`X zR;HBx>z>GMJC`@Fp z;o%XML&5s8;PPTp`Iucsf+esbr;Iu<7K??Hld9~_tE(_cyCdpIq&Zd*8526l>UXSR zP{bj61f&2&G0rQj z?v^SEATTg`yek!b_)PeR@bgQDSr}{zfcZ} zQR^DhB*%E~-FNX{{>vZZ{)5l(^Pl|>FebT%Dre0q3^N$4xU(<|C>e&1D2?@2Y`*5k zi7Q;a$H^z8g>d9k|)b#5jCk+h1WNIME6@ir` z0884Qt%auvO0%nee+b!GHN}v0Z&_NkDMlL!vhQF9hkR3 zMdwD3MLNeiQ!_BvJh+J_BwD*6AnB4-OCpeXW{H*TO$uQ9wPu#aO3>btIcMY{X{mrL zwF$M^%Pk@@PLb{VuKA{tS>Ruf?6(d{^BWq_S1jD`HN?G=NsR|^577gN+@ieQ^E*B z;;JNOGfw(iR4L5!Y`9@VPP{ZQ5xw`@U)_)Wn2#>nL;r5u(m+n15@o-0Ez(3SWs!eI z2r;CStLi1mP$=STAyPoQ0l=sVA3y!+$9Vbjd5iw9RdfoZ z!H%97r6{jC40>(b&bRm+&C~QFc&Op^ibhfi(Mv8bt2(eMHK|y*z?_hx2PCzUOefg< z29Q0^p78So(zdDSCfj3lm_)6&<;utk0Q>tkSsmvi&cmF%^*Ytz+_L6I0$T|ph`v;U zmlHWDERj8`d&u-cyAJ)T>m~W!;WIAM1_?<_EsKy0WP@ZQR-}}@9;>C!+CCFJZ4pSi zH;csdq(sQc`uS?TJzdc}WQ+@`9e1=k!OhbXEOQonh-Gani371(+M=`JMm8icRa7ck zOIDt(YEz)mOMuk&_S8}*4B(Nj+4hqzv}-}a zZ{c)Puvi}8-Y9e_#7^nf(FRvn&h&vKJ%&1q*k-GWNsijwVbzw<^YgDv=CLZS=Dc&s|fcxh7S z7)iaOfSt*s^h=4?Y4*+pOaM{FA~CXJ=cJi0(;wf|QU=sKl-q^_?NBQ75vULU`zu{B5tyx>q)KkIs6UGowR>_x zNI@M#yVFyWfI>?FR8TZzK!_sw?z`Xk27c$8@8a+N?r(AL)1P6psYujPPXsd)PzjYt zKy)JQdY*u(85xljorCr{&?P`?R;v0428u;MRx3SV${E_UK*0-j%CC7+qtVB*V6G^l z0pcVmARb}!+=lA}!ZzTUa$zAr1)#U4R6UTjTZ`9e#}&dYLFxzk87*~0zmpIN0Y9}U zNZk|FK!4bAZWgFvQMh`2pKjObbWvOjeFj?1JyJz0#>x=LjA%%ulrdxpf67_@PMILJ zQb(jL#+uaJ92&tv33*INBY~ETyaF&SYEsfv^5t;XnL)-2d#?_~MIS;o|(ML<%V&$<%-hApu!|BM9Tz^o2Ebn%9n- zM`v#t{D7w;+VfxSn0CLeFW{ioqvS(6nb)xcS{**tnq@o4$u25{LRzFA&lW)BEqQYw zzi@39nN-gjDC}(ynzhSr2A{s zVRwn%EU>IGa7C%D&S#4c_o}z~RvmR)dn|m9fYpIAx7yF7WbsEaiU2 zyab`(>EqAw@aaoDe|d?QFJGXP;=MnHVUQ@(1RNc&LU($fG?1ndN#>jAj|8Cq%nvY2i?5~1-lEt+cD!@MM#ew3exHY**kMWw#`pFrp=!p zH+&{~i?_b(ATlU>^!uP4l)HQE6^(IpGY=g?F?CA^(i%^qd;$pa!rSUSbl}y1z1{7+ zF|H9Fwr9BZM5)bt)xDGv_qcpw-r-X2p>90~V%&Xko=qTKeO}i};Gk9Xu zsbZZgHXDiB8HeoaT`7glYeg}V-?2Fme2)_O4calRtGvypr1}<2)5eW7A#gP!%A%g^ z-gMHO^qB3N`5u}N=Vh3~2DQ&=bVwvkzLF5xk2h&>SlgKx`HIJR^_Qa2+Q~vR`6JIF z+TZQl@<}cA!ofLbvdEl@mNG~X-Rd3MgItqHzyhwSQ#KQ(sb~Z}+^`m`CXP4qYtyLw zS#4_@S2-QX$TvN%>5uL+m{AHdoiu-a4nQ3k>#>`<4ODcH2i^PB9CAIduAtC3%4`!` z7p}bk=xq<%SMxh-e>TzDB8Z)o>l!;nS5vbwT10+7her5`!%Qbrg`-VYg>Be$SroUC#NqA4H|-npF1Mh~qF~)RH%O z$f#6Z7w^Z{dC(QVf62G5kfX0XDujGdR>Ynk5k;y)v<#H|PAwoJ$S{`|_QUICHk?5O zo?Kof#ShwS zN_!fZjm&x)>o-A0<&n*?ekPQ-F`eq`6hCWMKEo;qzsK}(@z3$j{VsY1@bUr>M;Td) zJhioFC~jk^sXL|-i5Tl?!lqOl3$N%!OW4Q>QeRl&QTTon zlop{Puidt;l#3?pw-vHh(twcP6mW$7B-JQKl%j4J;7DTSJt!6 z_V-o##PkAwm9pTok z+o-jml#QgS`?&y1ul7h*G@UYcG|cDLgFTe2154yRTc%Wyb%HBft>{#fI3VmkQjiln z^ve9XPAMT%aQN-e^=|*q%FVQ6rq1~k77XUj@p1_}_EEbo@>;H&&8Ay=D`U3{-$~iC zqB?r}9*D%IsGU}V6NH9?{MvLr?4x!#(*0rU5OqqlAKEeP9D+OKCCR_DzzNyQ+3Ulm zERp|1&d7N{PJ_$~GH&0vjXQU4V08%O@c@(=psXd)q=t57_Qp!_+H9@Q&Te2hIKure zp5XHG5;OHtaIT&N2&3AsZ9X_VZn%uUT#0tNDvvc8{Eed=Bjy>zwlT z{y$G7z42pDlJ3W~8${B3ZpLMZt+qhN&s*o`A z2q952EuBH^l|ZVonB*1J4R3ac(i>kCTt9EU^%id3x{Y7_;%E5$^Dj_J(QdEWd7QE; z)|Psa($%F0I)h{W9<)QG3FO)L;){{;i^dGlr$zc_6zqHD9yO9wV{d(aPUy}-a|1Lo z4^;sbE5S_RJ2XoR?SHx&>y)KM4@n(0?W7*=*No423^Dek$hy7GtlnI`&)wuYeBaNB zm-aj~uYa7YxsuAS?tbn#j_p>vLfC>HIQ3JR3p0#3>r8CWS3hcn#()YDQpHhTPl12hNQ$B1FO{v zKm6ej@#M)9{I~!1=Xn17IV4g;z>26?Q+(oB5l2uv-kdC*6P$4!93TO$&UJX6tmfM; z`DL%ob&4N1QP()oK&F)+iO+kChP2~Gr_#1;1zK~7>Ww5UqNUdD@AN>&=7z$$>%CLz zK)rlVmYqvGm(6o20&tl*ZSO53d4dwAC~#n5_uTy@{s zJ0^dDVURK}!;lr|0@L~eL>YH(o#BJ`ZiCB9P?<0$0@n$piasJF&6+8#9=gr5k<^fM zV!u~wKoUuz)astcdZBi$G6$08Z{)g85j-W?6;(gt-kFo_F)}WJuv{MC^z017ID#G| z{N&@0L64u{@uMd=SRLVPb+c=_b?wpZ*JvcIeIG}BKFpS3B`g{V8HtgvHnxe&*BH8o zrLkplJJ?AsY|G_-59^-SYmTD=Xm(=3)I3W zRt5tE<_V;I1jvuwoMdynGM7EgaWNwjZIWm9p8wOR@c166VWC}EW8PUj+UI?(P{lml z8qnIcb+uaBipX^y(W_lT7K zGDn`xL#GF9E_QFdhE-;E!F)|g*UbAPk_9Jdih62653sT{&}D`+Z4%uwXjWUn=JFgz zs{?%ZJMV+iIqGJ@Kowjj)Tv+`1}#$rSn}I^tx`(3apMf9d5Oyjc>3fqDl>+0#Npu~ zHk%Em%>)Z#iuYu*U|9=R7H=oPNlj+hvvp;uz+KP3Z+Rn=Ak=#0C!U)Is$gKmzt8Q` z-P|(3MIr6cKLqnWmQt`<9pPKw`ao0fH+cB)A=c|Pc*s(`noURw5N<>r{5pGuxSb9W zrRlCYG-VQj#=IfURiN2`ti5L-))dp6P>4iid_7sDA6pGLZpMNdcy9RB8q!9o1KMWj zG$U~a3S}`x(Gayxm)Hi3ksPkIVw%Edh`fVE|j!Qqrf!VZfL(4i84094*0>v04nsWrLK~KrKkjSPfY~dzp~a zq8YtJfII!0H{y4?kxW-L<$ z_!8g&1p^qi&$2#S{T#(-)#j;vK-b8Cgj`j(zCD=O1K2liY#IIAGDSZoMshGJze;TI z7E!muh@GE5UPn7s(`kgHDf7LY0&A&`aGg>9$d3xH1>WhLD{7tmIM$#}uGiAtq#?!K zyYJ%Q;0P%Z9zTAB^Ye261&Iq%22f4rO|UNUyY4g2`@93O6Ip)$?6szwOz-E`$)ziF zN^HL7_h#RpMXSuotF842$C0L2#mRyG`-Dc*dpn4=r?X;Q9m-A_N zV(Q*t$VvycAG}nSV=EZ)zS!0)s-zFLfM3%+UNYk%Eaz;J1(@uHa>jihUGleYNT{C*FGtEJ> zP0$*l#IjAPA`fKZ*6q^8Vu9sirCAb9&J$^5XVzoZ3Zhs?d0Tf!BD1p}xjmz7&*)5^ zy6!L=b9V1GVua^a>x^2x*&qN+)3i0?RxdQpZF9^pQrfQL-R`Ao@QY1Nbm&P3c_MR0 zwa({ePY5Yapvu~tB3!%QGeFcRr8cL!?=(ojVrFXvO4)dMx0I4*TJ^{E>(n)^J8Uoe zjMcS{>tOfl4YIOe5lF6@&IilBqbk@zZJo*!PEJm7`^HU_sp9PL0I6({X$_=;LFX$c z()4!$9UCrN>kx5a$^%xb6>i_T;uPV@*4n@Q-6xT{$7~Qa3eKKHOcuUz}QiyGW-w8Re%S@(!MM z#BG4tAHxiR?RrIK6E%YlU|1*KX6*IHiudm|Z-RnkRsvT+m~iur6mf$>=d0}w>2hDS zc5Eq;9Ap~w88sQ@$I$;vR8FtEdNQJ47ZUG= z>n}?m-?bidS#P81gh*JLv&!xj&~6tyb!+E%1CTUD-Q|znVIUywr;(tfk-PCTQkT4{ zPEmV9%Crd((`}M-)%12zIHqqooC|s$wr!~L&Iv@2*E5g$(wv%YBqXXDxlfR&Pm4xQ zK9|-w1zeHyfcM^e2j95+4p3P;Tffu>Ga8ASgz%Kwol1nKNy}q|wI|yvO2oJxX?x4; zNM=ZOf_>NSIm~~vXV4;q?Xx8J3udK40DpGF`niqh`%^C4Tag zzr*K`9^(D){UA*7Z(yYE$G^@nBE$)iCfEC(0^Bw6vGG+%&iL7{M4I@Q)Fz}RPwlu- ze)|5Nopb(svsq29$m`h~qq6UBOG_?=0Tw6xW>fIu#S2_sT=+39D%a$soKvGc<5ca! zFQ#9@+(=0naW19qvn?>i@Z}tvL}y#nEA~8#NFq?qOu zT(@;z!)gt$7>MWybtqo(_xtsf&nDMzrdLYghE-IjXusBQn1q}|{{t3BS|akuSCf@? zu6E9z(6(}9f>q2`i7DcG9{{AOtOavex;=|tRlLJ>!drK4;@^Jwp*W-pz`PMXG-PD3 zzAjp!YN;{OGHG*XYg;eE+i$;xTeoha){6W0@8j{KN0@3wnI;?^ufW1b_p5K>p+>tV zlKz(I$zfe1De;<-;|!fCM$4pWB)ZIH(`nav>`Bu7xOPL*p}8qI(q;)TL8*}#iG;a8 zg{70TM>zxl8k8kls-mCFaex8r42H8C{y<2j(0VJv zu)RlTh+=?f^ z5t-rM0yu8Qgn`oF4JGo`7oTMWx4l9$qlekjV9~9)?CmzWYA5+;>TJ&J+;U8kzP>4G zwN7fJg3W~jW?!3d90RNXTTutU5HUKkKZ}$IoFoe1z*x*<9 zAD|9PERJp>j{^!5m=Y?aaJ;z6<0RZp%e18H2VwYfaRfC>r&-CoL%{gb$8B^Gk+~f)izf{Ub zbP6SXJ`=!%aTr0AK~(V8TW=u|;fse4@$}i#X6!3;Y4?<1-PgBCQ;CR)_n4SkvqmVe z(B>Uno1-vDr@rI5&V#M(ymlQEyWX^ev~)y!j*ZydMFd1p%BnY8^pl*YkEFb6Zx|4c zQCt2V1u`Y>$8at2IF^+nq+OUFT@F*>qA%Lo*!}a4b0|BA#G0b74l4(^`W~tC%=ICW zI}ck#k>0Bt--EYK&gUw5}jgt()6qW^V*_*O+*-Im-`nT1p=s6c?L|+ z+SJ-SE2#vNFD7!Tbda7VAxQ7sxr6idB`!7+p~O^Llbo6TxgWpH!TP-Ev)|dg^3&u5 zvHj2NQmEYdiex9YWz1_|E1>0>+!ZCq3HEwQ*4T%8`QRiCLCRb-a?MI5Nzt&1qBSlp zb3tTQLLy+XIKWgUq$19cX&AAdHY&%0#w87$AbB>N1O=q0KuxHLJ=(iydOn9h3yWN| zfQBfy+HEz*NQX!Cb5Ret11-##IXO%&lQpZoa&1gU#(6avZF}RZU=^KtE$#2u<@Z4@ zXm}IeoUhX*_7)kD79XJ}Hl zt{k3+>pb=(>3&?lpnVN*;czbK zxEEGN3KFXU9~Ch>@KDN6K5xdizAnI#9afm1(xVYTBDUGcFj65%pqwx)N1O};N|~@+ zX8h;>{Kt6u^a=j!|Mg#Set9X)5~|Jtv8KA@rl5lHMzjG?5DLPywO}zMNWD^0OuV9X z)NS5hSB{F*WNw?WXlgv!t1M9&!YNl&jmWFa^1A^(U5b?8k)aWcn$a1(qBgoZU|qCT zp9E8`m(b72?VMMl(gV^5@R+eF@T3eSOB}vBJ=nkZ`aZ*2j*Q zQ+TfSd(gS>>|TnhajErpZ0+Ux>c=F__lmsz}TqRl?ZtTYt zdFvn)>xSyJ8t7#u60}L9BQS4N*l-a$5k(%EN2Xxfu8VQG#f&ig|O;V)f;FFY`R9Sq0WvgpGgGi zvzK(H8Hn3zu2XDcI|@X>DMS^*iaNOqO*&81*5CJlY#1iej@i1u2y!1$ z=G&&SIRjh|`F3KNV7CvARIxS2EPXi;JiBvTis(+B(+f~H7AwZ@MhN= zZsc}=Sxr$9(YO4Wm*JXOe2tP8ryCcT9TjN@*>+>(eDy~Nu0^Kmf zmnrO@c|PTFt6cF4v_R( z+zx1(@!|KU@3SE&)(97m?oee#tR>Pcaw>vs?O2VLieW$PebLwC zz~0{sd)M9*dQ>X#)XI%yG_sW0>v@_1OAx~{gE1%|MonN&7)D^J;f(SV+l)Frz zG$I!UPX(Ko&rn_-VJI&!mW6{-F2~ql326w>I&SBj#Vb6kquUW6+%8ngK$*eOldNWN z?#G)osuKGa^$|gbm+f%kPzf}XQ-p3$*oXjOD=HPU{S!u%L0e7q6u4NphD9^@>rvK1 zeP2!-HThauBy=H0P1)sJsnxr=+A*ujc5&oXOj?sm(zOZ93*VUu1+ib=-d&Y+mQp}b`q4&)MLXo?%Ogm-zJTg!Y;d+%4Nu5d~tf&zVE<0yrR;?_x z?tJcbzIAy-RI7ew0WJ<=m^+7DTaK@9LHY)bN=lFdto3ah5hc4RnmI(){Ios4QKv+mu}gRCj!sAS zT6}$*L=_;zRga%q#NXCu6=$?_$c;&`gjRmkY@k{zC=LCGY=0tfDIje^n<*hBNdd21+>WiPgS?EABRL}#3#0|2;6~Px zO@=#2$tQcx$vcVHW|M|_i&!N_8j8FnFB4VFP7GMm)}^m;3P=`YTdP=eymO|`O1Swx zs3NzMU5frR2NQe;+S+aF%V2H$NGZdlZY^-g8#qk;T)*E;=fd<|+*3xJ0^9qO)WMsw z>-Va!C6W>mAOh8lTt}oVY4OBBss)J%rB0w}jWG>4NEOEigRHsRQ9`Dg{*}NZmDf}~ z>&~-|>{@H6d7T)ECUBNUuqjpKRFSEoQUTXXpsb|}g05#RtN|zFd&ioACd-tleVMLg z4aEe=$(k~0po?N;wrbk5)ng%lL00=Z=pKU4CsFNe$?G`wBLvP?ZE3ngF-qcIvDs(rd{Lki(Y9*w^pkdei7+rCPryTWa6x@SSjG^; z@G%#JM#$KA08vT|5%NK)=A7})-FJ{u!sEw}l{6L5P#~fBOhpx@UW(2`<9Mi>BfE66 zYp+RPt6Dn@9(f|=4d78hDG8yQoL#fyb5jHyZU*pOCm9BJODTHBd(jd+b3H! zS0QOcRwGlUxa|koe@g7yYnmP;N|qWpW=jpUjUZcZxm;iz2M_@#iv?EWh;hiM>kTN| z^_hzGg?CHJqRcG9rc#W+nvET=+e_vk5CbatdvdwjAyNy~9~>+(Z8FL_Yo67SW6bigAp4Q8tKmc zXJceX{28NuVx;KSwM0^826O>vT5}R&7wi$=074zd2G(3ScKb4dp;j-BB7+9#eE8v2 z6m#4A!q8z;q*L+1!3sCd&M=h=TwJ_V+0mjeVtq9^cU6K~B3nt7Ol1NkmgWN7&YPh6 zjZ~*tR-=PInI91~A`g-?lYt;51le5OacQDmNIi4)Awk#|H*LjuHOsrJ#bZY zm)HxcPhj(JV7z6yuoBb6)B}2uUz^!EJz-)|jdniy*Yu$t#nzb{i1SD>K~S=uLC(4E zwePv!W(UFoEG=3nMiQID56C&;_;4k}Or3CR1db0zEXP3sFSmPCd&FyK>(DByzCQ6; zuD%Z$x>jb~3EOU6dZPK4~o8!%=hsjjFH>Q-vIMx8O2CA%DLyGT;| z?A0Wx9Z#-j{<-e+J7k$TrNl8HlEI!(Bl2>R+V(jy60+Ay7O}-@{Hi@jV&9srd47KG z7(kw%CXeO5#95Juyj+vrmx!50Qj^nz3@hzODi;LrsgpwcDv*`);)v7Oln#QT61%+` zU~ID30z#_lZFyE{>z~|DyY5!^dbeG1HC9pF5o(g|(m&9-C-nPn*Evmg>c`-vt|>Yq zRpp{#71t%qj!)cVp4mdZ9c2e2WG5$$BxI$%lj}e`UdkB+!72yK1xlH4c93!NaDmmq z617Z?fOH*c`#p&+(c}5e8X*aCLO0G0(B!gZy0F$T1xeH0S}QIuFWvc`Qu1;u1Z>wP zW;tKgY(J6x)asMQwSqeH_1dGn5L?IWBzAjN%HcITiINeu?b*GqV^5Oq$F&^I(+;V3 z6<&7(z=%R4)BJUyAwEM!+d#FQOTQ0zeW+c-NG2D0K>=9mSq%{o^RDaydc<>SC#hVu zNr>s-=AmpJB2t{%YS@T=mV+cIXevsXlb?UJTH!zbr~ioi_wVD+{_M~2;K2h?FkBj_ z)rJL-nUttQ(q6M_^g(e`H4vgof=wZ-InsFxr{DkpAOJ~3K~!RP!rVpyJTv?{gU;3# zW=b~0h{KT_tT7tcLE9I$k{#Fx3)~w4{ho0U%4l_B(4xtrhhE5u&7ovxo0;DY;UKqFTP}$ zk;yivK`u1!bw$b<$HynQytu%{`8l3Ed4g#wT7N6-OJA?PD7*ce8>`~HAXuGLv1myj z`fXrAp|Q$-yg9=_({8X5pBE=E{3Aa7^aX}7V_?EMO(MUv zZl~yGO?706G!=|VDkIo#AY320&X5Lq-+r9qG+hoHok^{D`28iumi5f`>G#N?FNj%@HMC6h0Quj}ytn7BlvIj}( zsEY5kIShA^_Y53-S8V0<5`wk8c zmKZbP+i%~%>G2A~I08Ty$uHYQuhZ)P5yAS888J(Mq{7?v&YrdCuwtL#7WK6Sf=$=h z2J!m~^Ur$t4%%_VX|d zn5GFA7Z=FGfa8;6tgyz*mzTIWuUM})B8zfD&RH@VN)a+OC)~Vw6PwKjwN|XxYYap{ z*=SADC|~v3Rd|bDNj~3javHFxZ2zL_AD7uw)sAdIHryCibP=Olb4u+qGpBg79n>ip z)^Gc#nUy`^Fg$^rc$^uNAO}AcV4O(fIwia!HrIZW0fQv*42@2O^+c>u27;;Bi+$-&8l8ju0x%WBOfPvTAFJJGmCrS6?dJZ#)0k1zM zFK>IJwurB2hyXZ2$G!%`clUV!#cZzF5PkwmWQIcK9SA}LS$6g)sJh>Ag%M)p(#+6~ zQ^BaJ_`?8bo0ms0j1B1H43|ApT8;T+Q_hASL#c0h>Kj&awO9*7EK!IQlu$ zbPl%qdN$WO|IFPz0F9LIy{WtJG2SZ?VH`&g6%;Cd4|YtSzZodD?{|9wPy)C219l{; z@BOd_UKfd4)H0x{>jTD2I5|1O(Q<(sr^h%tT7du@9xkz3E-;k|rBsPvE#{q6kEJd; z+5PBTO4NWx(KK(z&UxB7m^~FygUf`hjU^Ts$SLFW^c0ulh{rFUOIPkh$Vnmt#SuX+ zS9a}u`p zdfB{_bmSgj>x(n}(PYupUUK%9Kuc34lQG`&k2QA2IA zdHZ|*SwJ0N$@Pnn4wB+J3>o7fk)j6&OWZg-#GRX`SglsbiG)a5E!@88u50$YU5_;M zYE7$(0@<8%x6j>?-I;*o05#fkG2+MP{R%tI4i?vDH_$Y_&icD-Hvq-)r-fD-8` z;pq4Xr4+n;aenOq?bmG(G%ePeIT`_v_V~zPuLn=)pS$_*SDx!C4D&BEzKnF$za-e) zY_IU0X_~|#t~!udn&^1>3y8DLoYOfc3^V``M^4UC%YCs}=racl6Tm22dXiNaS}K;j zpTe^$GR$gtD_C&629xbo(Nb#q(BB8#Avu@vbN!vXiKpl^Tjyk@)wD#4$(lCozIq+) z_qc0M1YIp8?KUp)kGkC7jlUvEI+s7gFtoL#+5&mN-F?iD9q&P*hubajoMtB_q7Wb? zHAZ2_C(^QQQo_aT@Z~TfC&G=hQyeZv+&VkOt+Nvl7-y#^I66AgIcZU(Hs(PrUeZPP zMxnU|R}KPEPPAfAS|_W?Woc;IDrCmw0ghK0f>G zGd#IG7yG~pjjJ&?)d7_Yh_oxacN;f>O0Y&ioe~N_6Jd_#iV@geH&aIfwg6DldM;Jc z4j@1|K@S}wNh7$ibc6Zm02C$d!6}ivku(q;N3hxhiO3a{8D0jMui7I~85#MR^WX;H z#l;1fg?QK$ErSq@judMxg!ekaLyMLtBJB{(rq5^lRjU0F0Z^kA8AuT0hbu5(#3E&^ z#sMGw{_o@6ySFf{FTr&KLcy2_R5ut17>5i-1xoSMC27c!o!pQ*b`mk0f?;JOV+7r= z8f;sMfr5%j+pF1j^Jj^HdNRFaT9b&&dtO2Egp zGOzQz&LokLL=wIYHBxu)F+kIyzx2-b0FFT^x^|5)vf%&Um^`Db>$4rqn| zLmKc@X`&P#l{r|O8_M%@R*l$+=QcxonkGL^ysjqG8C(g81`NZ1QW&K$n2TJSI@pLA zV-k7Bb>sEX05QTj6SxlAeb{7}Vb$spqnJH8X5cHPjefIkSOj8}lO|)BTMA?v1US@M zz$pV(pH)xN2o9PNlcZ_e)wA;AyxZTM++~0x_@)qf8GvxyGxOJXk-siS_1>4u1#&*X z`T2#*u=O;daOpA(Y@XtAb@!dr8c0$zQ257!S|&`TfGFc|afY*_ zW4v|y2L9mpe-Ag$j*!4eBxO(rCe*3!T+^*uz4{tz!Fs*MdcDR}qyg7B4mdhK5nULb zQJXVA4iUH%lrXRHx&BS;$g9aMdnV1+v2~2=0EqrfTl=Y$f`jD}AAR%@)|<6N-|b1# zH*QGnUhTY%X2*JiAGg=Veon7G+#5eELNI3d*(gOi+P{4H66^IEhpU8~33&jfNh3tZ zL7LleQoCAY>}In;&KWmv-W1!oRPf`cczJ$-%gf6xBB&N=;zk(2D1bW7tCja6Rx+rx zbpLspvqnN%bh_!y*f0y+W0hV;Fft7o$Ba@Sb)ktc)e5e~3DO~tN*K#?ZgRS%sf(_S zI@{-ah95gQWjMv1aZOG~p?Z~mvESqCR{B7KYJ|Kt8)99=UWoEC%IIBoO{ceJy2$aH z-6LrONFq>9(j0QLk+s(K;S0uF@7}@L$qN754?n`&cW!{ogiK;v40+IA10r9e)7s`X z=iJRhvMkYvQNr~D(7L2Ttgm^4!tFi}4-fId`|o3#CX`a}`0-;r`0O*cyWW2L?X7u| zd9ecQ+lI|NU;}{TP@DHi!0wvkIUerpi3*Qiz0PA#lJ3Vf9IP}0n+wWA{7pE_y)wHz zVgHh2Zotm37ZN|`25?1n?;?x<^tve9z-n&P`|Bn+-9gkVc}qo!o#5Gmejs zky659vB2$Hw@}LlrA$~ZM?8D>3@^`L!lFdY|7W#B9%z7`vHtZraI|3}sEu0XOpK7L{FuAuZvOc;r`upwNMWg^I;4a#XB@7U7>A6kYno}qmWn>_0Z^K-j)HRlWUap zFf1_SjToVuHJ&|xhJ#0sPzg9#9V)?Kk=Efk;`Z#>@uQ(CB#sn9XF$?@cU-@Dg0HvP z@xR8fRBI`xvhBIQiX4fNWmoBHwSdB><^im#RbxRRyQ<`r_}sGr%HfrHNnF z=VYxl;No|3&YHbpdr1l{%ys(QhO{w%eNHaCdf4&PY>nr@lv@|*u%8WJA08fJ*bJD; zrfcl6AHTgp;U}{>O(l|^ttUZfTqEnMwo?=DZ~WM)pP)L&u|ms)nx+Zo=jT{oUW(0L z*hwjo`Py`5$1~Lh31}4II1U&mp*c32jg%Ler0HNSMQevQo#wVb(CUxdIo#wnJHL93 zd)6k6bDU?tM_K94bRtwOp(gj3Fbq(2T*pvMYv|C&xB zA`C(A*lY8-micO#4z{kl2<-V>>ZNYgz?Xk9VhgWJE>?~BH&!63bXjTMV>T^Ds~Zcz--Y9 z7Uh;SqP4Q8Vn?GprG)SO-gofrZ+{b(eDddi{^$6IzyAje!+?wR1uicNh?<8AnA8vy zgTxFXRPsp42)-T2$RB#2uTCTJ?=k}^X)}?6#kj!P*%>y|2A_ZNNM<`r8V@-8wXh$9 z)ksPjn6#UW6A);7tSP&c5;&6=N9*=?#!P2Sg0wGH zyMHr6=j(L6O^*MCh5-_ms5vo^dq+pyBfIKQ1K9f9>yAiBnJ(!`Bfy_UfA$(6aUEiL z>ULX^a6-_T1`xvaTAV{lNlUbx<5$1BhtKZc!}Dj)G31Oq5H2p(c=6&XzWwd*;KL6; z#DfR-@spqY1b_nPi#31&L;H)+e>QxvD&dehu;YWR}R_ zArX#GPO)4r@bJ-Nl=GKTdL$))`#N6wO&A`PpX35)7XfMDm5IHEs>sQtO^8%k2jFGt z>IRxDbv%v;m?{yd6zT4+bKnFzS?%c_SiLIZ*{^-BSM(XMeG>P^2yK>^2V^3A>l^Rj zqaXYp#!OhKuAo8IJLiN&o-m!iFat?cvo#dEf^eMcRNMDfk2U9v%T2-g`2`+6d?Y1S zNXptQ77M)f)?59)2=@^6w%3c}-A&oz@AK#R)z7v$TDR{>epkCLfY~`QBN5yM51%|k zt(#YzYd`*HjYbd3UlQ5Pu+kI)0h*iupzuIRGW2}~fPRmEIRSsgbDUIcGe1@&xzp-NU0tk5Q(AHB~H^Bi_0D7H-`-L(Z*?7qes=S-Ftz z5|!vXJ3YhE@u_DwJbd^N&tJR%B|=FFo6QCm1ku!(>J!BRWKHXAe#0F%>k*C>cFp0O zuuLfheNZu#HCBs5+`e@ir54=#^{;`#K$a-`%JBXHc1F_qlK>!#rtf6{(43>N^Krl` zMwoI#%}hPn%zpjJORxAXZ;^HtK*gp?lg9R%oIK~O`*^prxXqEw?ykMKOYgL`Ct#2! zeo`5G!qGD0){PVVr~l)B$LYy2rZVARxdahmu_W;NC9>%#PEw9#1}^4y{Vp5dfQjf( z2`sVaqkYfzP5Tcd&BiV+F0fjyaCCHp+mO5FXzl>DpN*`a zw(iR^b>#CcgTcP%`-*f!Q9oDLZR|oC|(t9ueo{QcG8N zu}O+e3DRJohZ*1k0|E2@U-b(#z+6$3MD|{5W}b7x-RwS?nY%}v$f{~dmu#le3t4B2 z#lsg{KHJp7$pa7s$YtwB7<)_MpSscd)pJmhGd-=s5qa>IvZzfC$wj)fz&U>ZS!w z(S;^p35wOcE|Etk0H6xI8Iiocx`vWq90m*nW51sunn9dg=!w3^{kf9}E#A1#XC3_u zFB?Ux>ZoeoNCH^60&vD4+WF$ohRTRJCG7S)(5W$~3T82*t7YX%Vza7}_mev>B)C8k zleHFp8Y3i|vk+W5#k&FsA}wd1_KHxc3S68TUamE~Rm22jB2aiRp=Y4xg4q}A>igT? zyYlZ_#=_iJLMXUZ3RWx7^yKOiFP=WZeqxM6!d*T>^AV>xgGh0>yE98DU||`Z*b%7+ z`gLh99f00RpRqT!PV7=?{9q&0!bu^l)N50$1)qOa6cx<#jMM3aW1jKjt5-fYqFy6Z-`{g%hVhm_m}7~)d+ zQdma=0ySt^C`ip~rz+?GU_PII{RX~NTC3+kmnl~cQbL2;w@x?@BVlOgu`|yzZg1YB zI4E3lMxJNndB!vic=qfm-oJb6N{3xba;agEQ7FooUaLCag3*`bA)=mQg&IxA5=`hp zrHDQ_15epJS(Sik8nN5$ES%5jC41l0bEcB{lb{v;iQm=$xi$n99i0nux1f`iY4!}% zzYjpIQ#^fsaw&i+hG8%sDN;d>I3~^!5u!kAz4$!~j!Tnkdpr2s$l-1LR=+di* znSqGvu#v&#G~tV9&#;>krerFvvZ2JP7Gj!Raf~rZ$v|n9rH6C8t^wZYck*$Vb3xV_ zAj0u@#PN6pk$F4Ey|7vb(bfw7e-xPdc)Q<&%6KLt3TXm9r49-O&;h_gj?4PmkL}OV zdYQk1?|@N^;1v$GAdZm+o?0HpW|XSez32T;X)cAbROwYI_qE6UtqdNN(5%9BvXo|0b7n$0Hw{7 z&b&jlk!A{qg3dsw9;MWQMJjqmFV+SUarr%Hae);vy1cru^ev%NgfS?L@?rxY0GqhZ zrXbgIo2OtH%6d@G1>%JmdLys^{_i$1wf*Fo!^a2?GBD&vc!78T;T;$v-CQC>wF64E&0;^G3L zYU#c}C{oUxYI^?L>!D}5hreH@021UZC`IagFQ3yQe_|ebpcHD;QPi1|U+9$7U4#*;aSqHJbGNu6sQoX6FKuFqEc}z9$8xc9+V8=1B2`rTd_ntUf@7af* zs*2^#Boi1wfXoCby)q|YGK(&ALR72=0VP|Wrj*!~(1c+i49G~#7!zTbMo?lD0LM9_ zC?R8qk}gro33qn~ND*A|4o6K;W+X~boXmTe#Dr`BmQ=r285%IZ&h2UA+`>RUNeA$C zA}Syu3{fD#&yW1HCc7nQB9z47X+p^}WG>i^BQVdPc?QW5Dh#4z&muO5W`$`F1uks?qo3jtq@^X~Uo=sa5SGKq#FbG-P%z^z+|(iiJ-ch5 zKR*Ow5#+9D0>L~uYYGX`ntPWkO`1VTkVvrKCtU9*+`Yd;IUT@d#wCC>jMxhYC{PkW!-yFJO0h8&Rb(Nk6bysi|E^fXLWh-BZ}dLp0lP9(`{&Hl(u!^GPjXLS zh|TBma00+6SYo71sSV4>kn8hl(EZ4aKJrj*+-a-A>{!-I`KSoT88jcW8e zR*2CtcJOnl5G8G)l0;nPAe+MqX*ZtCcK@&s7A+2Ht4CqL)5)~89C=)AoqM6Z${*Du zQ3%Y*6hT;qg8ejN92nz%2W3K0U@ioOh1;6`t%$U^!!T4@Dk?y3d!(k<2>^bTC%XSV z=ZvC?LcmOdk{Fq7+)e<}IG`l1%KzrNSOYYFLi*mMGAnYH5qr_Sfd`A!m;q!0QiO3o zwx4mc)EePs*{8dx*|)TkxBqgzWetpO@t@vjApAO`ZOJ&B9(Mpx;(G&Z#yx{@htu&j zN`3?A!9Y1NK~0KzCo&TfCr~mlO!U-6$+;X1Gtwl=U^kKz5k?%ras#MULZ@*8(M6Sy z1p^crMNbeYM2qPr1QZdBgM~rQd3ISD7=i|RST(05e^=S|Kn%m35TmH#q`>VdL!_X9 zEa$Zv&A02?(1{9)N~P1Jih+Q{CfF+4SS#S^#0c4QfLmXUFUMdJ87)>=j#pyxB0^d{ z26Y$!W+YA+s9j%*pr|5I!bqv!xf$+a4KRoka-K1yge;a~CyROQ4r4@lY0bxLAY>FA za-B_sTlw0FoSABKbZ|y74kJ=x$iNWV;V1)6IzbqK3K)a}!YOAYPM*@n)(Ue760t9| zK8x|>QrB)3IGo{$5;%>RMUg!hD-#3ay48@Z_bc8Re`cI3H9zUaeh*LsQTzS5)z*7< zotL}Gl`SP+GZ3sjWEJ6f73UgnCEN#AKeYA;l0LQv*c?cM*8Eli26?!ey7e!BC@VOC zKii%U!8QQS`@9B7&#i@U>zQ_m#p`uDg`BAitsrNB+B`_OMzMI|s1*(Ft)E2%&;sZY zkc^jKJjd~`{|W^y?bW@ha54>(TWFfLPW6yl10YL zYm8>)LDcfcSs09gsVWX-x|bfPc}K+@&!-b!zj|fUOALhP%0kdI%O2HEL|CS+q3~c* z*Z-}Oa(H(FAoqYQVVMmEE(mOr$i_G-brKPF(+<072j+y`w8JotrbG?{#&N_rO&|pl z4@jQ0eMnXS#jLmN0!{*8N@($7S)3T0EVoUb8UOzKKj7`Vw*ZXUGBf__uYQd$zx*Wt zwtExfcs#fj)jW5`al(FLNVx?$Xgo6G^76t#c0v(_Fyr$28R&3_fBWM%xV^o_^|Q}# zdHuw5KNYK9O)g~n+UphRP_EbD(7ISid%br{b^F8ilt92DR-meb2-y1o2d&d?hy7K- z=P$p&?)@I6WE^hqkkSeHaDqyP!hs1j4<}U@-!%Tb^itQq7V_jmX@J}-H79_T$M%=s z2;ouS!2H62%_WdX3tv|AX0ZZ1 zEo>ZB=`+3}V(UJ@!mz$6n%9Ct0JSRiBQp*nka-44#^p5OYCqw6zXx*0i>FWVKmM=( z+fw8ZVa~wKoKTA5{remI&wu`B+#E8B!V2j~uAmW-+bp60hv%fOATPPX2Irk>iWZn% z|MEh6f@X1#GyYi5%@ZZk(4J$CD!6FuhglU{Gj-z=W#hOx+ zoT`Tps~1s8V0b=I=GxETd%>5CZ&Kyo#l2^UVMaPFAT5}ZrE-~N=g z>5b=W%e?w*_x{TXC~J^@IGs+oxxK}kw{KBOKydbyMG8VeG$#$zT&5B2)e0LDmd2OM?4w)3nEB-h7> z6N7lboD07G_SgVUZTWW z_faWgjvIxLm~3si%e_eOnnv4ACv0gC;Ie!*P^m&N;FvSM{pK4Sjz=&NUjE`2*za~I zD-VAFc>Ve{{_uxCU>Js4OevpEnCBV4`qi)S;>C;e{HNafbPDSNl>L6}_hK)1MmN^7 zsXcT5UC-yvQzbmq_6U+bwg=b(ZKDRdMTj0Y7to(PfP93 z1+{bZJkfPe{LTqsBY?fs(~nV0)Es~-L41rAjNN{RtLrQ5$7i^CbHI>Z<8nXX`O^Uj z2b9wZMMn@4Lk(i4RT0YuBxN(8V zXhH)dJmH_utyXL8_0<)KEFa?Gc*Ho4;FQ3eEKJlT`>-rWPR9Vim2^RGq7QMrN+hh^ zpfweVdTf8mEr2C<%gow~bR8zugFp5BjWxdXm|ur(`@Q43KnvHa^bQVSYBlQE#S~E` zt@0T)o};V#oO#3s7;Haw$Mrq3CNSEXy^=9W!Tw^8tLsbb_ZI*dyZr@ryS*z-1Ri!c zX2#)gz}tPsH-9{$%*DrbKoLR$0A}Ry9vr-H3V;{{<0*|uhtjCfgho@;lx=j+YT?`t z_`1g=6y{a48_-Y=a{kl|b#P^sVAq+IjsE#>;nk{SfEO#dF{gHK(Pc_LO)y1k7)R`; z3Bx#I2qkt*7>5Cu7Z*s0vES`5jT5deE=-A4#W)Ng=P5h?JruNA1myYS4E#2*JUOUp zu?N}#=537+!(a-XIDko}a7TfXcqYk~0)W_*Q$hiXDZtEHd9AZ_SDgF3<7;rW=VI;k zIevTK6hIAQwk2bVe&U3*OI8Km*N|$H#kPRYx(`=;s^24_+-~I?{uFt0>v}b(Ap&cn zni4}*tG%Cmu+!khH>;=DWBYkDHzsKVxNWaD`V06PP%@c8yLs={(}#e`Pi_4k>5X(f zpcBcyLbVEvH;!9ZR_|Y}gW^R~J*L5bDbr74apUHtVRA9>atb?S&jGQx$hXbS(qve%1N7@$SE3Aw}k)PV< zU83#-Oct$t$oiC&!Co9y6%dezOWU&%6OcNm8jfOmgQYCnP0-PtOfDv?Tz|2@z-}Bc zqyf8e1S_x~M$=V@vD;0UCL8adSH%_p}$MBzFR zW)z$}(lLB_3Irq>D1xj4;Ldot2r@Htyo8h^vK(;Ax5%d>E_PFW-fS?%jSCD2+wI^%a8|LOPSB3(eYhive1R{&c#8R}U!&v+DP<%&p)fF~gd$5qo;`eJ921D9 zRUfS%?B2i>Nisb=(kzwiA&VYTsUc#JTY3W&@XCv-UV*v^AS7-{1VKn3k^jfFGz#FI z6oZfnOSQ;T+|7j}1y1mL5Ft?lCBoodJ&6;NMX+Gtgv17*PRW4N!M#3`KX(oJq!vnP z;euujWj#TJkceP-q=1ToG~ugXeu0!PEAl1F!x>QGg-x z_BG|g6dbima=w0>0Md^GRM%fWw!gqeM75yGnl7)uyWd;-90ctZ=e}@9cR*b}<`Eix zF^ws%jbIH}YThmZw9;xnuKCM-UJ6T|!{*gfd7OD;1W5YXXP@EMfAwqZ_d6s`?Oah5 zD2f233`iunzE1f2|MRbr=MhB7JS)LCCc@lRdlgmpJQ54>P9uUaOQ6M0A2>n`1A%bU zW27>Pv49vIB(fAHk?J6n)dIEZ)NWiOaibd|x3;2CY3qZ++ghJf@zxY;upWD%K2maxwJ4yQKc&l0`1qj?FlGV8oDK?-}nAgTfeT?>&?FO-g(9i z$7~nJeP~U`v%rlm_O8i%$KwgF-@L}*aHzQtQyOu3afu=`az5F)q@J3C-P2sp`q4cV z)?=!{7nLy%jDZPHpCqt82hrYv&H@?;nWRQNiCS3uZnp!c1Og%PCif?MZ~7^tz@zkX@klRfmLUZ+8K_DQRPBZVL)A$DDcM87Bc(>HD?5H5#*T(6 z^P0oO=*AT*NO;oXk#e4Hi@AcNDJ4h}C@DrZK65cm*o~9*L4g5;9e1+6>uT(@R8%o5 zP*lLAV9B6-!XO!3X0QXDA%6ghR0>d}$}A)nc|vOZMO2}=V1OcxjI4^nk@C%=HtufU zR#&zE59at|$k3j@T5_W8qTk09w|d+==`cB}}7!o3!}DAK1`_W!r`bwl`x*Yg~W z_g|xbRaNxi8u8mgU>C18DN;kx)&jTvNd-uADL_5}t`g;3Fz1Zywz!<|g;PUbkr_%|)``zzwcQ_yo z3G>PFP$>-179kUc5#ALZQmV5H!l~P*T7|GG1Je03h=^5iefYA+e~;$mq6bmd-fcZC zUa$WxqrrlP;~qh^|4vc8;qC)7*R;L|nbzJ0_g!P%;=Cw`2at#Iqbf}$XD|x(7Z>>A zi(k}&IW`8KPcxaPC^KQV+hbRr;OgSSBF>3Gnn09rN&|8!n06D07 zVu+_dw*jPV5W zkx#`GQnF`CRG?54IW72&$fQQ z@7Mq{`u(^DfBite(DK~=*l`$fb$R(`m2Dr}b|bLkVT_{grA}Dn!e7cRf1-Y^)^#)m zY9UXho-}<5KG?%W8CVulxw45&1= z>qoqgXNgyuO9JhFt|TjRlB- zr%qGNyVPnTpaTyBcv1)ZB5hg;9n9s!D12%%w4FP6B$+)EgS7x+PCn$tb^-t;0OLTI z(opAznN1Jy$txl_obr-}xsk2%m()C9L4+Zh_k9rRq-5T&4w_ak<0?lej>UMs0n~z` zGbUCHIzu84tQ0F4%L&4=$fvC=(9z~KmjW#XQODldIz|T<)p_^vB)Gjh;`VOFv^!y9 zg?c!B@Ju0r6sy%RB!-G5FNwU?>opXwy=)ZYI?pq{`|dl4DE{Ve{sy0a{yA=LZtze4 z^iO#8>J?tTe2Hhzo;jbieZJrCadmZ7onHuEc&n6!Aw2Sysv_o;!K%k{sO-}-ab z@@Ps4A}xn_&pSVr&po8}2$DXwhuJCs;+xuudnhZm!BNXI29UZXgno?qHyQOmPB3~; zhx~DMy^u2+?eiRJq3}*r!4b z1h!wT|IF@zXa%P-$OYrZn8cO1Sid4>iG~0cd~eoMi=Hu0C#D2Kc7cf?*%IK7N$~Xg z0>khno;`aCQN{K36)rEYa5x?J;b@dcRCfgmREiwn5C^6H5~CPMJ)r_IX0?rVVckL~B* z*6Vl;9)>|B3{N!&c6WRQPlJ|ifRO8Z-gp1*hj#td@oT{zSPH-E`+w}7Yp}I{Z3PJ; zQ<%|!C>RhST+-3BQq1$y!q}QePV@Y>bRr4niJ`@cM?ed-xc5H+G8 zz|rQ&L;SKfT22HwkPE~#8ed`ON$AH`4JA!5PkwPwF#eRhmX(L0!@=2l9ip1I%>oD` z8)g^*(Tr0V{Lgtdv5#%UPqL*R@atP4NH@H2LiTkCp-PW4!^1JD(jP)HkJxgu`)h$p zG4CKUK-sPjPq|{DhB=oCgxHvQE^dkOwLECa`)2uMt%`k&ck?`r&_8b!)q~Z+f7ErO zdJd2@d8$Pb_4|N`FisP6HUn5L7D@2==bwX_EuZ-*GNn0C8G8kk-dTgzzuZ}%yf zeftooYWriEex^PLun4n{XA95Qkb_GpIC;qCWBYlv#d@jx-9a?O_i#gvHgWS$(CV53 z7JLLweS*c|p7p!g!tUh%%wt?J3<;$OZg1}}47Q;qJHJ|a$F+1@W~JW>C0^We1qg+# z&diY_8bpjC5fT@mSiiCqOK+k^*VrMsyZ4rp^!oY<1|Dnu0w5e63@oiVs43)gGI=>- z#g(eZBdp#ktipinC;nbb&|S8i(#})GpJhsx=bNb8`_UI7unMFc{c5m+qY`1$PGH3& zPMklQ%$&@)MGVrx^dOHwP$3jH<06=)4MQ$KM;=#fe)pERzL&7+4$cYVTP*b4AnWKS`E@rvVL@_7Y z7%?G2YE4KP;)_Rj!HVw($v>&YOvq-W;=D56Nih+&*?adm|+ zUMA$6F{A4TcpUEd$B&erLCnb1 zmU4KB+H(`gD;QfozTlt+idG+@#oFuFVtZ{N&GDC*k*3M$eKC4}b#;ZSt83&upP=U!nbP(}du=l2$8gGCxm~~SpQ&GZA!DrRK~Mz|!CcBu!m=LQ zpP*^bWMEq^$66&pC+RjLFM8Si9vS~rx)XW;0Fc)osL?~Q=U_A?`am09#CrX&zIXB# z;HSy-38iG5PA8;fM))GxQ+P=Qae~1Gjfk`)_Zjc{7OGju;OcTSv4E3+kUV_e1LOtZ zG(c4`lNseoDLCHVfrv0ZP1vPy#DU|1er546{n}sOlN~)Uol3nBl=FR%=SF+{j9x_KYVH0OI+~UCxk<*ROuS-R*?SiE+F;;raD5fM!Tmlv$8x)Aw@Dm`^86 z(}dk_hXB*N6}+IeYdL=$Mtt?vZ*X@w;s5)mf5PqUErwyh)2B}>NV+t1spU2wnx}6O z!QGv$u`O^ESOS)DrT+U5y@#)V$DSARV9P5U>$G>8a)*x)W><3YLu`*A>0^7C&4vH) zK8cXEs=%>j2!lpaXn}}(M|3Q|SNQG|JmTwW1;&OTd(Zdl-?oI|wL;tXYkiF+L0jHq zOOfxdUlncl_@D|L`yZi(zZ-9~}glvH~K`1{^?y=O=AUHo|P! z!-GItl@C+o9qiEM{1Lf_XaKkYka{Bbz(oqwotX(KK(-Dbv)pe@*tBqrWPM)wG9>iB_iMF({gf5}dPvk7xkc+jhARLqJUHiEy|m+RoF)%H z={$niK;QtfjgkPpWq2X1YbY8WP}Lr^t>I0z?pgG7-a74RZQj7*=jXE#q8nD>ol zu=mTt#Jw`G7T>>N)bar*_x2$8oHQ`C_vlwY79gmHO$NW-h(_q; zB=~BoKvO3lmSW%xoLAOoS?%>USMDXPRCz>P6L5f^slL|lHP%5prqP$yugx&~{+V$P zJ%WNYwXu8P3hiH9b2?XPW&nR!dYOfMVjtZxpw~^%z^y2{hYze5ph;D_`YvdF@FXIt zjvw|rYC*b?dx3Kv66DyQTKA3CmvxlBnxrYIb&4RT#O$v`~6e6djOOenw7Ujt~W6`J*Fz%)RokX!X8CI;(7s)rJ#uEc||io7Uo_<-;+BUKwxQaq`q%@ zLztDVFHwBT^f{mqAW~2rToXW(rE(Y&*R)@RgkhL4qzqMtWa9-;hDctlot_`x%WGD0 zm5Al=1`JdmM=M@+I-O9wFq7dBR-`x#;?>hxEedm;-epUV?{%kTi~ZR8+P}IYhe&7E z@0%vOI_IU}eGD^NoAEQ!C_Uu%2$DXw2ih7z5LXr;VuV%E3R<{eBK4f*hF=qwO{VXP z25@$|ef1GxrN2ihr4qv4RlXO}H?5`4)HGb?H%DW6KU$q{QV#*{R|xf65;`=j)5^>Yo2pPwT6+zSTJ$N)LqFTSl&>0#X>^M<;MN`pen4jIS!!@#&})H zH32rP|71nYeW*FXlaNPlJUeCyut~kXTbBqhs@=DEzDtG)19eJOpqlGC70+E{ zfQy3?A|@ySkTT=?`VznW&99K>j3Ne1@1`BDF0P@X`2Fwy4W*dpDF9HK@bVYGz&H+I zWH4oDJ^*qAYc}Cdn-@)E?pg)y`}WCJRp6h}0%9^z%hsr?`PK7_JOrOqK%&qBKngDR z6XuJ(<)>3YzPkmT?l52mC;^Eus{ouJF0ru^lm$iA!kRh&!XBBbreQ{Rt7dIWOFY!} zQJMXDHQO`nLhCxm^8y$I)q*~$rVIfbaYXegQHA8}imhCuV_nGxun@$1P-x9lidQBN5RaXf5W)*Z0q0ffDJIkgrhX3K(u(y&=(pu+ zV=z?2iUAoTGLL>@tE#T{ornTto}{dR%mrX^P{@=q#B+2!pQ`L`+}#TG!RMvr&7TJcc=W zfhpAEK+UT-a#b6T5fCRI>(1-N)6PhEz6afLr6@d2xfBdy#xg1bi>$ZegMia5gpy^i zkrDxfT69HQ%qY}(Y^iFgtkC1EiJ? z$Yz9@Yfi+AaYTCl+$&fE`EWof1uvdF0bc{tH2Qjoy&oW^XQPh2hw#|KQk+z(=he`8 zU!4WiyscU$jynI=_qf+qGX*F@Bs2_%yaAr1cGUx zmQQ08Ok2Fs|`#cT_ z!#F}Ddo-8rvszg@g>R!+O@Kgaoi-Z~$PH{({~mT&5%uHjDVYj{1*Ob3yeuG@Z5#*= zY#I$4hGvM9$X@vX03ZNKL_t&pJhwP9inM&snVfG)vHugkV$bkh1ad|W>!WT%@gze%`FIutKEQkKH~QF4*&8m|AO~7H+cE- zC9bcp-8*_f&I!{rVi-n*(@Sg<1DHcMZ~VseDhKW{`pH>U0K0gi%dH~6_}=7 z-4hm_VEXWzH?Q&f^&4ne0<|e6E3~D6oQ2}(j2c>1s?ZP2;RJxBC5)6fLFCZj+(+1!g(pJ00k5f z9U+CGvNLcl6Xv;q2Um_2AW9$%NIHNC5S}e`PYM!^V4hsDv9RWp2*D^oiYz7!nqc8x znd*QOMebOw;ew>@)fd7Ep?UXFFtG@;G{v6T?7mGH38^Z)1i3Q97ETd>-qw6J0i^eo zGI@j>Ktcvhwo1PMYXlb3V$LfFTh|^Sxm4hT6xb0%Nib{7sRM6pf(ATw0J)HD>%qn% zcwWfJ&;nJ$<$l7|uYcu$i6T5zh#2qRzr(-(`yX&R9Wjn0RMo2IK7WF%i)TaQfYMlZJ%e7X>khX|NP6uGVgHi&~2uhY?R>`cx?6f63L+Y|n)V0CBF2d`ypncc9wEIaPT7GV9 zi(~s7rD2>iFFF`#NL1G}sO8-?azaoSy0v?*9w@c3($HmXsjC5YlCybU#&bm<;Yywj zJ|fSu0gnc9N>$YScx^?Oe5+L&YnMU9Dfi}g`?N2h=`WsEI_i)sZ}nc6u$z!rwL6rg+XwBT3aX-xh; zAUo%uNrAyZg}AT*AwxZ`0k7`Cgt(Uhs6p=|X4Cj@Fk8!k%E?n9`FWr=e?36hD}T*^ z>>vhdRrYEqAbQ!U6-yH-ZTw)1QK1-y0T<&40Itj)Ai3abzjp<-<-=~EWq>lx8_>K( zyFJ=@hRMe7K?@=`{#yQP&x{W=1;K!)2-78(;{Y?-Sp?7{SNYjBaxcEY(mqw7g+iuB zrK?qZ1DY<=FO1c?-)v3`*T<}7&HkDZZf^jf05J*mpv1oJW^ z`(PE<6A~w=7ip8y90dS%&(X%ahMpfXYU&ns8l@6uEu#&Qjz0RytPq_oXD7%E)Kn_% z4o^w~Fiznu4&0>e^Q z0Tzs5{K4QG^Qtt!%xJHtmFYBnWl$STw00o4yA`+M4#f#t3N7yLUZg;ayGxM*#ogWA zDK04*ic68=5Fj{T-h1yilV6$q$n5Oy*>fJVBGgG>xj3lv?u`Zs2>6FDckB0@h0I!f zF=jV3u~!vT=t%dA5KFh|`k-ZN7admXtfOM{TifGr*R08fB7~VmQfQ z8h5aY#&kO`5GH11YP@~lREDRHH56u_sgA+(J@h;^jAuq0m4dZOGUttXC~g{C(>Nkw z{U*{U64%gt?(8uH%6lcl&aD5tqySmINPLUkBG~AL=x7vX=ngF2+|1XAuu{?r8fqnJ z7As8aiY}eHxY|C`O-D?Q_09-h!md}H_GtXyBoljnfo=g|=TV8;7fa0PFqs5=_sPpb zjr?R@aGI4U99b8)oS~ydNOam@W%V^F2$6}Km3W8?ZYSpA2%^$cq@(MIaVs1(V9H0`M=@mwy*dsQTok*O#CI#5_Up8TZ*!SAk* z5u!V8c=n@UEh3W6Jy0o6Mb0sqPr8$kgp^*y9BQR*+9g3<{o`92PI|$|0lyA%b8il= z!C$_r=I=pFo;MC`;=sqpu)JXjT;!Brr$nn?E3LS!CZJst=RO=Dpk<`S(hNzUgq|duwjdE~*BN~(Po9e3SO+dx0ceAHOLRGB4)~m2b&E`g5ap9C( zN_F@rZaNm^2<&F0M|DqY%#>iqLyIqOM`$olmHT^NKJE3U zLgysok+)Pu;RriR>!4$uG-t?}OkWM*HXZjzu+ZPh+Q8#;yhnz1^p<6D zFDCAsb@8a6<}2Pvu1g@OdKZIG_C?+mMZMq3enXJS%MnL-#Fw+AMLMlV(EVxnmFSSY z5Vni&U=AEn8_G`@Wl+&auz(+>U=~4%q(NF|e8!X6%dhOpCIs;ZDjzIn( zoTcx&Fdxis(D`Et3C_s*J*6fw6sNrHU4}7zk_Q`lprWRBLkLPs1AFG@nZ@~xik&}A zw#!T-d&9_$HeqENQl`VlNY_beWpGxaEfH_W3C{asks>u^M~jHzUfM?T>OsS+Kl8SV z*%uEtj@^N;)N;AH#4%v0SIYl#v*N)rI(o;9>(I)7D&ZW~5cr)C+tnq;1IM;zKy#$r zCR+~=E7r^nD<;&O(35-jr}fQeDy12gKlB%J7&wu@kp?r$x|}*613{%!@NIYJxEV+- z-h|rPCT=(C#Qw~{fw!`|wU&08S4bar-i9^5Z_kJRnpjJ z#-TGb42gjprxjbnqDzS~=+!vg3?;fy*ZxI2`<;cSw-f@Mg4}x&8xPBPx0ui!kx^D$ zm%GNqNIsSj7`EV9usXLSBN9t<@$dT~GMGzRXRGLVg=ElLN2FoxXgn4U$H?&z#t^~g z>bX!Ycabd}cPX)AGOCwHB3xV5e$Vc`mn|czC3@%`+|+2d!(txk4(vlVc~7&Gu2#4- zVGMR^1^sMyeuF7yN(oT&vNo4#sRa%+H-|5GSdm(MwLYXX{04J?2%8?5C*_o)_uWss z^nWCaz~2?#aTVS=uIn3tCm6sHEgmqOJz7h9r^vvfj*Po&z^h|;+(iRXMV1FY7^Q-R zgtVF4_KcBX%^HkJ~-tDB*?`4b&$UCn|cx{ozz zaWcmevg+@)AuR_gmtKh)BS1SPl91l!r?zJbfnr^X)?4=;llN^tD-C;#_q>T7$1DD^ z$Jc$_2vbbyhEiFQ82?g!)Yu-zI$T3e9`$3&*n@lyjSu|)K^hx4OOf1<;v@p7aMc%( zB@7Y!PbIh|*$t%QMj)9G7i{Hulrh2cp$)@!%?MGGH{Qa#5A-H@GefJpA`rjN1AQ$B z>5deC?k;XS|0VnjZl$h2gN*p+K00>x#WxpNOK=smo;7sU&U>P}BfXffqaxm+gv#2oeS1Qfm~49PA;>x7%_FTS7$*;P2X zKsz~a-~SzWNe#EdTKluSEb4E?E!Cx+%^SXZ9;a@SxSf%Eoy*DtN~nrWupw!z(n6{C54hO4Y7>rt+x6t&s>RPB=wqof$;G!U)PC#+8_N4_Zh~ zuGhLXd@(5~?z7ZhxiD4WT#^~>#C5cJuT3T-9l>sH6cJV%ZO@RVT?Rd$ETl==R9+C@ z-QSJN#ucWropMK*h|9(-yu;=H=tU2dEjmmb>**nLBz&TCGM1JGMO~-|*ih49hL& zO?uIn6iRb6+v$ZFLJat4J&zL%X}U_DZa;F(G!Y*;wxy7~IJ^aHOE)5atz9};`f{2f z$zP;+65IPa`8$4cQWA>nm@+h$Q2D?XGdTE z%{}%?S})O@eka6fxC(K79Rbcz8pYjwHLG}t#Kdg+Mk9bh*F36gc)thBv|I7sOz1e@2p20R9M=d>WW z`>*!~B1o>i6>9;n$-ntC(dhcf0Pre*uIE8=l6YMb-xwWzY;D1jOa-?bU;!!-*q;S~ zVY7;+m&*Y!?$~LYCt+s7$caI~F2(^-O>qi=ss$NO9Qt_0^%7FP#0W zI=K5dj_rV6iLx>cT`R28>QOUp$bL0Wz1q{`tXuDMQ6<=2&$a#(xYX?Z>Bo{^VZus` z`>NpM?(Rk!*w+y|_|MHdnDAOMvQM1`ndzr`H#U(sIh-0j&P6Ua`p=m?@9cluDE~?0 zQDKNGV^ft&Vl)g~g1M0;&H?C0_V!8^-&|ZOveG5hG$E%S7Mv)nd34MK^CU+&Bdt-L zUA#Q|!q4X3Pg9HYe}*PKKJn(1JfFnMQ$#mJ3ElR0>eS(N8wWVkjWF~$X}Bm4MT z7tr+8EJ>%*uk@ZAa2vtiv{UcdjUYs={t0Roooz7JTZ$%Mx_z@85nJ zw|wMp<;llSbI0KLH%U_dr|-4~hI6!PF+JE?cRr?)P}w<^_9r|92OGud6IK6l@-*#*NfJHFh$A$FZi|tR-1{mNb#1 zFqDe6|F_^;`L|EsCh#wDjF?N_Fs0_3JhHz0HcyZ1-W`!=&sOQifTzdD>%NxX$9rq* zqnfRfbrM34l8fgg!`RPV`7KCx4NBK?R>KoIO6;yU$+dYcY!55n&xw1egNX6tisYH} zUKtkDX3pFL5>DL?AG-uegS543J7&7R!Wru+$?{l--YX%VnYp=Tb($mBTSu8LHINT| zE>cU)69AGl&P8bZIC_AYp?jXk-so+a)3!P`hxKC(_*K8d**{*;<$n1l6o&vY3QDBL zo>719-n{&nxsDLZp~|i0CQhBmU%z^KxdR0!MdmgL=cj0E*XSm9pYcvoy-VfLpwhv6#6Ji0b3uW1 zrmfLbR*9CCr2|9+_j#<2+x3GJK4Sxr6<45p0A7SG0r2uEiqR1c`Qy=VGZBdzB|jyn zaK?_s*Z(qMA_hQr=43qI8I*GAhQ;5liXKt9WJH?yxCfQSVyjM%|r*d^boEF@-*!+-}6m2WjDQ|<|i%(pJ zXVU@TYhO!tY}M+H;e#6&+p2x@mj7W_jFAK-A*Owc0aTL}7GxC&3m@xNmAAJx`k`4l zQd>BqKdGi`E%mQOf(ocXSA;V2{IM>h3lPYr&PFINw?xW`Fk;hQ?^M$DpC74N3J&O? z=x!V&jyB3!zz%{X1)WJYAk1JphfM7sQP!CH(oKA{dUG`>)V*XdEC^3%CY5!IGJQF7 z9+#E>v$#RK-|K2xa;u~bHcR!RTkg*j%0xHep*nk3JUh=^=c(7S*4{v7yfPIY6AW!b zx?wpj%)Dv|Cd9)-DHnuPTP$x`^;f;v7PH-6qKlmkf2o<#0`zqG?m0f*2$ucr@x6tr zv-Ec%024Yf>L!?6l*EM^XB}<>D{IP6r704!mKN~&B>!DQD@tH%fXlE|+QC{|t*_7T z`8%{aTf4nCsT(8D+KzhGeYOyfQeC;{TITeh7P<6ioRyVh9kfZ8gn0Uk9yA9^xJzB^mWS&?h2(HLI5Sh=-fa~iL&9UFXn~RMU=R3K|YB#c5+``;Z6XOi`1nBpg!x-*AL+B-U7q4jltagz4ytvJ|}&G=DMBt8G`4_u7tB_Dw0

NUutz5Mneu7{DjRq^8tjp7r%=MSmm1D`;yZ8(RC$ z&yl>4Z_Bpqce}e7f~eVwL)+dNt55dRc@(U_A1H^-T6VRky_mM;SFh9}+yXunHD8sJ z{S+i?EvdS*TRgt*#DLznw>31+7o&dEZB7=K5+q{3H(is3SMu_MUp@pPMaGUDp<{DL z(J}G%o@vpx4&A>FJNFcDf8*D)goxXg{|&EQ2KysFf|uIs2pi}%x0eaPzor&1(ds+m zz`Mdrhx|6|A4RZa4IMXB%I2A0P0tY?dk~6`Z~CZ5U!M4ZUA~F6dE|OCyZ@&I37QT@ z%irhWA34dZ2+l_+Wa(~>WzQA#6*$x70%#$BXJcqtbz#TM`wjh`!Rg#I;E@(K1yVO4 zZ1_&@%zEWGfDjZMfZqPb;x5G!I-ed_z5Ywnt)LLHM$M8SvF61xD!OQW`y`Yw~#Ny|3r*PC9` zyj3aL9wE-u9wlx|RjtogNn#$xit4t;gMU){5fTnv-YG;ADlJ^G@fZWXDhET*H`frcand`k2#k z=M-26D7*PzG2Rs>li~~DwH~a`mc7)O_QiVe+dk#rSUNtD?h-s@ui5R3i%~~L!Rw8~ zvj5DVDuS#|BDx>XH*Ml=kf&qI&zwd6)ftBsHVcrK$-NtgfR|Siwo_AQLm*YZki=cW zAu&zoW@N2@>$%ZU_2RTxWOBlK)z9s1))`SE%(8hbmAKev>Pl6fkOocoTa6eid&j}- zA>G7%vx)0_xL7jTOmyv+GDtno21vN<@|FV`lxMk88~E*8q<3!ofvb##f*X&s8BlGA zQ0-X~9w%lez9f}=6B1^G@{Z~)^?bHLp;(o)MDhZD}mcDS;Vlbj^Ocg3DvU${bToKmt8aJ zu3hItajx-s8Zz939lt5g5IS+eGB?0NuW8*YSsy1A`@>+GEe>G&=m-Pe4Gi&Y-QJRP zt>Z)v{bwXR45#1x7xW9*XUY+MmX&jL_YF<1c^TN-+oL~ff_*WD&M>p%MNz1&oF~=v zG%UT7VuUPs7T}sDcq4tFSp_;#9THzlZlK(06C?LyDebERo}(}1Sr8ZcX$QQm7gf*h zC1f;SC8Jn=Go636Cdr|#*8wd7em{uKTW2RNy5(1beqa)%AdMk^Yy0K}-KW~u&reBg z$yY=`Q=Cvtp=J4RwI2K1`>Q)`6qfq3g))C`rz zNcxFF&;fpz!=%f`M%$6+eFHGKA;7EcL*OO6{sZac)jZ!jDArMOyI)T#=7= z;;nsQ3bf^igJOX-9>d3@paoUqu4jqXIFV;wL$lS)nVZe`Qa&ynH=PNVh_0ABZ7noy zAklp9j!KfhelkgLlamy`!R9wS*s1^#bF%kDeYp3`vxvV?==EOs%HPnN7MgR!TALHAP9!`8BxJ!02c^Q{-7x!?=?9e^9K~wKFbRhUSH4T8#5}f@^oYs!EHMU zQzxcyt=YI!Ad6%10tNlXN6E#zf7;Q17_>7~GLzcxDR6)O2s`cY!It^-mR9nmHP-`w zI~ zb$(vAP3LagV0c??+mpoKpLk{~B8J{P5LoGV6g)TJHR1N{Gbbadk+I3n!J+Fn3yAt6=pa(y0*l^g6a}4LF@&45VM**0RN**Oer0__Wb!xl zxhG^%;`goyT5g~r`}0@7hKX7h4NvLv{3su(?tMVZTF&i3vk?*PNDu-N%8wEZgtsSU z=ovxxUOb`|F~uXH`Zab0RbmL9$My{Y8A)?N_DC$)WLiA9==?J8rT`o(_~Lp#1gwhV zSEDFBx_bDPa(0`a$G$pt)IB@HCcntAl0zU68(J>pckkZe;rqeXzujGq(zwCHSmAO@ zh+pO34)tiXwzjsrv(|rpK(@ zdEaeKBL6}Jp#$tMd;d%M?Js2pRN=b>BM_Y&h7Edh2U_#Fh^SYgz5HnHDdf|tnc5Sd zI(mBpPe2-d6ohM131y;a0`s=!Vcb!s+LdT(RCr6j(!gOghu_hH2sI{z_sHEztmr74 zLhKaCF(UBEyqhW0D%uG@ge03S0SOdNZl;T8|34Q%gbqK{iw8MfgJ~v|nHE!tEs?LC z&n8GW7^L2PC?_+e&C>FBLZ<0U9jGOhzOvEEPj0(_Xq$@U!7PTd=+nQIsyJiC0vt3! z=_1>+f@aj;NAvsI@5R(8Rveh6?RQIh%Y`L_EV8-n)hREzE`7jI%cTGpzQbL2AMxGc>3E}G znG6h(6i5DS96d7bC@8&BQG#;mZ9~S;v$3$K=Atep)X|hKh(7EO&&@vO>g3JZLYzn~ z;TU&jZAa$}ib+6@{zw>1k9!T+5$; zaJf*@dt9;aWA*v+$UTv3ncV(kiW)FV08ZNcxC7FafSL4ttG9>Oj|0DJ%whwq1V!30 z77WIWehb#DJLT-u_X~pX|?w*i2|q7%9bPn-f{5KNekrAZ%LzpDgll@^o?Q zG?Ak8194PrMi8M{lpEkcNcSU7a7@UrxRiY~wP_c?hfg1nuqhlG70J?mFdLa&NuueI zi!}YcHxQD z8jbG%>6FjT*zgQ`6tw#R1Z|X!jyaa-&2?UZaqZx5T1D@`i*ao(n}tMBoOoZ9-{b&0 zKiJ=K!KiYQpA#awiH&tCG$P8OQk?NLSXJu{HBhJ1*^3Yp-?n%lVj7QzwTKOBu9NhS65P>d!UD%Y*DxR$c=t`*W-MNXrJyw~H3NCA6HYTwC=w}Vmc&$E7 z6=d)8qUI6pQN_Khy`hupTVd!aGhH8T2@tc+EM>sK{Z@%Jh1%`+H5zPU5?T-1$#0fk zGc;Ww3>l^u_j4f`*3MHWmkg_(%bxZ3y2PNuA_>;Yjq&m4u~Q|s3?X>|PIx(tWiG>N zZERk1j94Y-g~ayVgZ#p+@RZ}daDL?~2oqVFu)rK-u7h{{SLW6w{fuMvTaLro6J`5c zVm*G5@nGSz^6rZScX**5Q?Qt@?}>!d_?R9&9#fA{g0$MU@iuT@ z^^&p9S_#7;EOcH_z2K9(VJ4US*gt7GaRaQc+=rf8vkn+~8Zw#89NlIgfFomMk^FI% zQ-1G|CcrwfIeYSHjnshjAr#^)oCz<~`S%OIiST6Pd7fXYT`K*=J1W}7Tu$H4hZ@ucJ3H(|be1h9bBsiigdXbfZ; zs4o;!>U6)y9T;s+_McMje{_d%7a92Ky2E8ayE{9D`hC4pVdUVvzJBNdME@0oZVUdU z_~w$_^g9E|zq!ATGZnx;mRuuREaRQcXbf|S#`M89Eqk+cFgvRvzT|8Sl z^|Mfks|qI0D8m`d_v0u!W1O`KkKEwd4kCQ+HjR!a9d{H-7REzMPYSbme4OkyW2IM&qe^m$Hh~LD_Q{WYB%spIb)C8|+R!hEy8q7{l3g47z!HhMDCNb$S z^{V6rItBj({yaBUi_9y&NK(^bMCMwS?8SZ92PNx_#?fjh9}9dEre+pDfu)m}k+qSv z8Ujn4UJW*Cy1z?Qj*lX~a#_VC6ecAmSH`4WKf0Z|zqYkK==Hqy*%Am9O*<{!m-hW|5>g_=29b8CRV%?+BFXZFb0!Ab(WoIKlEEg@Brt>yjUM3 z8_q4u_;bIOp73|&7i0yCTSrM3B5GpgY*hU${rf)GbzbR@%sw;#L)mc*|4bY>4mi#i zPpu()|KX1XWWhVjIIaFEa7CD1ioRZp-(+gnBfx!l^$CyvOSG1(Hm{2B6&%;fdiT!z z6RcmD-!ijQA^1jykQ`*AZ85G!tP--@Ov{Nm;uZ;olG9gQ8hw>-G1V=3OgQI;HTvs1 zTG4|K9CtP9w((?idVA_ezIILLDhskK9C-O}ZWulGw7LW+P1@=npLn2AY6YTt-7LH~ zeUb!W91hgsA}<}gAA3I4K3!KW4c zS@LV^SNcBrAVMO7T)2*1vqV|0If2> z{r;^#>zQ1xJO4b`{$>7FjIt+7^7_$}*bwyZJ$IH((kX+pD(yebN3^U6!uAW*@B~AK z111~&`NTER>U!sM%P08?&79bZyDmSw;+%f|BxnxH- z`{)gShUD@|hU|0QvcE6W+zM0U>g|&w#7#EwXPb%-)sr{yFsuj{hX?l)@7g4;lj1S9 zX1m&$d(vio1dP*W`7*==vDutr4XCE-iMuY1aPaqVT+m|D^-Ag~d2O#qP=r@yaBIbW zVtZ|xzh|OPL?~|A*?X=^ZG6alqHf8LlHxfm#bhfJp*{X7^=#~0GUHbMY=oK^pz-eL zQoDj6L3BFX1C3m+6zi+j^HErLK7C>QN6S<-9buD!FkF8z+-4ENSPj#=b*8v{q%n*VN4JC5Mn-@rgk@GBSJj!!mORNqO6VLzjR z11rhn>df){3ty=Oji4y9eLRTGWtGY9Uy<+MuJ4K1-Z)Ajc)LM(&39ByX4}ZnZ5&+b z9?WlDoG5iNEXg-ikO4p}4K0=Bmtj8Aw7EPd!a|3$;;U}h)tNU3rEIFx-CNx-1a}Vg z$TYwBJqacnRMsnh>`ZSql7??6W}TGem^#c;C;dE@ANX1D;OB@JD>F+J2S03f4kgSf z|E4zrlrgc??M#MZh7e({w&g*IKY{>l+`9d?`OheQEm_gs#g}UdUXZ~2w~sv&LX&YR zHcsyh;YZy`DC;RiN$7S1$ec?-0g@B` zNJ#DM0#C-+&PNIJInU0^+dY3dJFoxaqyy8xjWR(HJNDOm&5`;x`Ur(SzvNHsgWDv6 zi&akmQt58-4-m>k+_MUj>PlM5fL6b z8h;RN)m#l!qkqAvg~e629^NMaOKU$mY~H**kT6yc2|Q;GV&9>s{^B9}-SPZY()=~F zQysJJyH5aM;&7cK#$!AfLJF!tem3dXOGD0bE4mL%lZPQ<+DtMDd}k2$UR)B*MrXOh z^d5{XyCq#fGgux8zmY8N5NR`bmw;YzBMIAg?3O%pyfO~=SxPxHG1txw`f+{)&2()z zYGPNs5nGJNdU%>YKm?(mLST5byvfikGW>qMC;VlGt4eD@~DQT zEL2V8`3tl3Nl}taDI?Me=6>*&686Xatg`-9{1~2({tQSYDx~coDp}p+4>J~ui-s#H zsf@~rS03(r_Vp5A6mTW)ZyHn(R;g&OTVdL z;`}{sM~~TmK5?Pm_C76_@nV&aB~;-|*gNZ+5pr9M_0t%+)38;u zs=W8juayl7RXo=GWd0=%FC?jm>__de0efjI{DT8qvUhJV5wz;^>_prI?!DA0^#F-% z6Ar2Fc{De-+g7OzAE3|WsEHUTxslq$)fUr}O{SQhIsL7r%?nDZ<@Lf+8*PHYLUjq% zNLAme_O(-uSRAkgDh>*DzB?w$$TgbP7bE3<;yooZ5Y{g{H>nsT+e4#`^{N5o>{L0aj@^q2A99CfzsWCPa33{Da%+l z^SWuJYd8d;_mb9SaR-`kyF5a#&3R~n_~=f zRx1&N#U3CBw4Oft^L;YV(??>amz0PWB{$3~VkVn4r+z4s>1Hii$|Et)&k36FpCT^h z8>3)Wlo-CVC4Q*M>_o>@+%NQeH0vxRTxFs>_Sml%l?OB2j*0C!ZD$e(zCN|I*^z>U zZkNTU0^w&I_iCuqW$ouanskU2bls#3GkPPI=zq{ z?llHB3$p#{Y)oOM!ytxBAqg}|`<6IAwjF`xjx(e^yBm!GnFa0#5 z`ic$Nmyd#fdks~*NEI>6Jo^F^e>?@I8C<#G12uB*Ccw3VtU{fhSLyg8knPAr@&s~= zrSCW3bJ6N%yh4E#asnBKGQ?rW`ZP9TBlRu3U@a~SGaA94l@-dtd&F08u;Jf znzv#Bu*p4qW0KnUkCh=c>@Q#PSMkn~1YZ>@%|2G|uJk=|(?&%7O0mx@eb4%2G|;j% zra|hvIB_MdnH&6NGlj;U3Y#D}Y*5MqE&jb3TEmqJCw01y6z{WABZX@tj(3pl(02>ams5>%ODzIgbIX#D}N28ET^nDejMsv=&w@uAUtTT>q(tQjU; zw{ZrN_(|O_8cMW^D1q=Ue{IR-_wO&Y535JH)O6b-p8nM&!2R{DGzhVJn(h%=Y;Tkn zxb8V4{xWDd#;9Uy_TaX*4k|IQ0aLlHww_%>eD2zM`#(=omMj87Yqp7NL?7g#3lU7i za^x}1?E;kFD&e~0+TYOUjC6bT9ZLdBHj|@!*;MM?v&ZZ7{5kz-*}H352=;ufhLPnF zxWLs?ReZaf>_GO31g3pi0u;i~0bxqq^jlOcr0l$$?Y+0${cc4hGEfqFgt4BeDU*^9 zZKoSA0f>4PuEmV-{u<5v7Z2i4Jwkqv9SBh|Jj}q}T|rwH0qH~{TVKarpWT*I%^|Lv zfa4)M*gwjz%O-|rcTR;C(cJaWzPpoE>~{VVXLDCbzbkbKB0h1Jhmm` zPmn2H)$<2a4DzpzDsv+>ah>w&taC3e6LQPxvQZyd0#8bY?A$&u#2N&cuwBb*yIWYxS?lOAqhje_#FZE51Kz z?z&BXk8+Z21EY1oY;16;c>U*458CLW^XS>IdAgr3vlh{)Lrq5_+8&Itbp*&k}zK zBo^=W`BlNh&G4q70vV6w(HDEnk2L*$x$|P_9IoeRe_A;&d3k6h7FmIHzvevt?Ns6< ze4vrbY*Hr+rVk4q+75!$nZi|uIFCaJ-@d`pON;hXz%^eKvM{nH6X^hsjJF*GT|PQThWjGliV}}WlKxb#uoHh^HE(5+ zHTU!|r?Fx610S#)E49!f&$I^4zl~v}tAM9_J;>c|0_WKYdfnM>lHOa1yXlH^Z!1OKdX#q|64@T2LCQ{K;Z8pD+g*& zImzfCxw6@6G{;f)?4T(=#G7ko-;4 zx3=>E_KLlRjCAM(h!%f25<8NMfb#n^)iOwLcBet5kv7Tr9&FIRgW8%~XgZgC39t%! z9rl+8tcegkhB);gi~JQxHgstQtfZ5xty_wjf2hPE*Qjx9!fCG$s()%DT2RI~(q3aX z40Eb<*0m%-Lucyy9%y@zUM<^NJ61h&-^Ic4Zb%12eA(yuJ%fV4}HMZj|OV*Wr#D>3po^Vx$X7vFvlOQicA_j}?ffyso?V~Rb$`rKtQQ|P} zkb+^I(KCLiIdbm!n@n>G{a*%JWjjRwmT?bvFtqa zqtSTT2*e01N0>tF{`*qHHirX57mq3IeSeBQ#}@396Y>M;3pcJCbv~^2KKVT$#n+2w zVw1cWGb|-uX0InUI0*9+-%fJZS=DOz*I@{|HMtS+BVBU`;VyZ#pOBjj(VI6#s-7EG zm#b)eE?2zA!4VHGbzf*w1hrx1UXw{NicA(z2-LL@5k>}t$|C8{d^8uTpX#@z$NrHpW~q-wYt`H)hbD>(rz0<& zpWc5cp!({Qw})e$Z=hC`{0C|oxAAtC$ZihRQv=U$qPa4KJirE^+6xF;vGC%C;;1 zmv~8XfO0cr>mexX)@ck${933 z>WN{@QwfuUYR@V)@9>M!SjQ%;YFHMQ)Pq>)|Efi5;r~ORFiFomjxCGgt+yYHAe8iP z9cnstKk0i$aUmTPW+_^uWjowQj2^C4M#ICB_r;r04F(^@b87#^a6-yvOg$c zCx1O22u@jXc%!JD&4U$`B6n;K&*$KnN7AEVITWs-S27TsdyrE@9+%E?_@}???2^Jj z-p-&kxe-hX!xJnYTnZfWmfw4aY>o&5!rfDM_V+)}oR4rUpS3PKqr_zeL80z%(v-{v zgVoFK-vXjgs)d(NdSEX;ENRLZf8I>M`q)c@ynp_K2hUK~aQEFIa?{;yFS0+~-Qvh# zMqI)L*a%KZ^^@lO`t5JAVev!)q=n~!hcB+)LU>&ck7wWf90KQ<@sKj`tu=6wbskDh z{$gN-gB()mg5-KaNeD{JGhRBsl*OPXVHU7pbVNZ-{y!H0q~p}H^Nq*9JPhe}d$@&f z%@1tASl~rYBwupk4b&cMlhbcflFA3wlPhGu+`D@OzU|73gxH$eu45kAV2bm>8i9Dfhb~G=vN|^X{NOmiyxL z+ona}tI}ic!jBBi{;7~?Pq%i|l1Q&cMppt#+QcLPx-c~003*En^b=LZ202n}G!BJ=)C$-T%(6;GUgkfpHF&Re+HrYyXv-1h<$E&$#T06xE6M(X|`J>{<;E&O^$%DI7T6?(;m zbTSq*eF6(Io(N8(bKnBrPG_P@uvIUuG9sa4V1B!8F+k`=HCTY49`zQ4#{Amo{eTm? zKVvj!H0L*+y@xli(88X5@~kCfFl(?(eR;#8Nnqq>!^-TtxG z%<#-<^RCq(?~%88lA}LO{V-5M6I}zdU12C8=E}GcP9EX!) z(;thLYh}>2se7gUn>Dkvn~FX$B0JH5QCfDJ(<%h}2@^#aam+j=KDI``uR6%AL8uay zZTTr5EB@;qX|ah44u&Sr?|HC$Ft){Z=6!2fpL%-kj{kn}ZV-#-XwG;$O8hPLO*(;k zD@Pt$UMgU}AV~DHeE+13vr#E~g){rXjZ0VG z$1!p-Y;J3^7_O5L2I3R8W_ydEtj*8Es3x(uJISB@V0XajCQ&8cjaTRj z*N@i|;-IgdB@OB=qWKau7pVIv>FXm4CpF+^oagx&A%zj7oyAP?saB5N`?Ftsz#@z2 z<7ah^$tLYWv?~$MyK1ky5T*gL`F8(C{On9ih_}^WF-xl(_Kd;pnvQ^w_5SL`YuKW2 zq$ox%h$&dT#8p2Tp|o-=VV5~_$mgY<^3&jO)+nTibO&((Ej12xIf_o(-6#F6xH#IJ zTY|SqW{V+v5m)F!h4UInEi@XG^#aHsZS-LX53)9K4SWSekf>)Ikgu+L1F7$yAD?Pk zC{udYuDo`wq*@=9gRyRyC9vI3VXoLDb-~uwo2iyo)Vo}5(RPgAeIM_==f;cRE4x{a zC=^7(cmv+>$sd6z=kQfZLJYBgK_IuIvC{d-st%wrlBQX>IS_=DF6qvp1OWk&mK5nu=?>}c76j?;y2tO{`#e1S0cYOxp1s#zd;MM~S@Z2W z#;A*xlZh1w{~T~jwf=mh33;YSClJG%;UHwhdBeSRhcU;TL5MInrnJ0pT>TXe*Tq9- z8U{q`4KnZvWqIkg9h4y~xjIHH$+x-R%FXUf3-YT$vYIL()K zMBPJ_@U0lZpkRbR5DgO^88j9oj~=#x4_I(VcLaaqQE%Ph(y*2^SZSXx(ixPHU=Q14 zDVl*;U$QaiLhNy?ULG;(#utv*@dZeDB$(nt~Hk- zCNuPkSpU+`!e)$)jjwtc8E)ZgT42tXWA#cSLx6r;4l@K_XFh|KbXa6GSq<`8Hw3Kw zhNdf4%SQ}Tn3~I>xg?tuW${LW4XN~Pd2DjnszRsDi)U?$e~hboOPX;XE*|w=q{jPv zqkUotRFqf`71X0t*t}>o-m)aqPn4B|zU?1qUoo{cZ+X2pKU!9Z|H#-_nZ0Sq`rz?v z3XDNoF-71DI47&Cc>oN;((3B=1LyOYIeSddQcMo6d!SH2YLzBSNd;xN5_y^sbc{Jh zBC&P&GAI4dS<{?|@6&NDhA+RdzB zBuNPwvxKpSP=^e&vb%+e@?Yegr)i z^>+;l2I?d73o5fNt%rsT0WdsIPIbpY0sTJ*_~vhM>=u%%s;j%o_u?Z3AM!NwF@QCi zDWc|INBS|;L|W&R(_U}6VR43=&#T}}*9qp}8r!ZLuD4$4Y#>ih?CA7t!pXzD9^=W4ZTncsTs+%OeOp zGA$%FQY_JBmoIChfi-gLYqd=mfb|9<2i-YJf^}QB29DG~HKJmpnioxvt!NH~;0Qac zo zDN@r%s2j5WU!aNIFeN~X2MABBli*gdG}OPX7rsmWFSxyJcq`*Zbqu!N_uXC9tyB#f zx^dM-Ib=j>^PQ%!lhT^K_f-;(_WGK*P*mJs5Fxs_e(XMSRQ-xalEH-kxW!8zn>i?5dYIMbraCc&&EbTmcdl;0tv0 zxg&wM^K#USDG5-LF0DLwN+YH7WCpEydbVSOfnb4hr?ZEv`j&Q^@pC8U+KaNVS$&9`o z2j0|0p3!t5sf!}3@l)@Ft`zEPp+SR(p)*&Y64hwwI?H#Z9Buy=F2YbHlz;e69AlYg z({GR5`a?RKgbXrJaZ`9_hi1@(kXmWffqt0;#i2U@5jJmYC}O|&rhudgI71Ln_-hVm zfATOV1E=;ONdD!_< zPvueRf6WXb3^~^q$&Y5B&#YuE^7Q^|YT$FUGwCh%$4qo-wH8&S3a)LqzlJw}D`}^{ zcUQrAd56~A&;b682n$22CFmPiEEJEAy;H&52^GCLIUUNsJhNftNxm}rWW+E?&i7YD z*M@W11(g8|lAT1GMN!Uz)D>wwW5ZzFg3sUjTY+iG7y}f(dJEN{t_gj>gtK#RA(Ef; zubM_JmslPj(|z8UnU4_J(Kw?i9{5C49l-uTlQfinv>Zx+ptgEZ z8y<2>Tx!+!VT-d(mi>Bdb)IKPaX>QtLq=a5bz20uVAFMd~x30GKf*H{`9xC`1P-UDpYA8DTpfl?rW{Z-mSh%lT5j{_iSbp!-hGB=UFok zg9}ET9G5dxDTWX%kvbU{!qp81=-qPFCn(&pg+w1t!|CvxmDDcQ>~ty2vy~Jj zK&M6RBVaT$iMVY+(q5mn*XHA`YGTO$n`biT+%?OI^_i>o-J4i*?V58SvQ8}Ff_7wt zS7H2!FPe5_bhH>Eg-(riyg+u*bQ5!?8GwqQ92QXI0d+n)b}x5P-EBl|sBpdnONTaX zr8o&t;iG%HoT2V`cHdX@i44aYSEOa%j_{QpU3D(#6kOEZig>us11gF816Jp=W-q_U zF6zRcOeokfFBM~mej`4RRkv>4kGti0Wt?5{y|A72I@*+4KB+4m4>s^;@#WSMYD8QK z&fMqzd>MOQ=$BTCgjgtAwo?e9+WXZ0LTBznQ!Rx33nbT0?9p#ohrWQ;|F?nYE&u!3 zpBRZ`!8YhwtG3#STV5Bdk6n3FRw~S3>_awU1X(2~wbL{IG2olx)c+6yw~LP7L&cNC z%&WJ}pradq>?Mo9K~s&P#z(|iJGY~CD3Kcp)Q+i9ZC~h?p?^OjaQ6AA?t?Et==x`} zd^jk_(~}5cb8syji!Q<%*L7%Nk$)cYZTt8_Jxs&6G7)9tI4Onv%j{Tzb`LuwvMzMUK}>r^L$cOZ;|TJYjCpWG>#_ZgZURRGacf?5Xmna-|>@_5`NxVB7LUU)`nCfHA1)$9xC+0ULnMq8DunUYP*u8mN94PR;A@^ z%nJV#W=w`>F+=m&sRG)CLIZ~))qQ&o{3Sjh2jxY6weh{Jc^PvuwLmWO2MyQKVK(*< zZGy;k*cYEs3eQ@-Am+_;L9IcXkv<7V7iS8I7ZD3|hf(1=D z#HU1rD)JoVt_!mqn--{^{(jZ$N)69RX5tNNU$!Ad4E*$5GxBjbwH*FBC zG=##GuJdVkw03MY*v3wPmhtGr5hW3pgNx0EnaJJ|w-_D-P28wvpk|P%_l`$wR($$S-Pnx}p)!af z`l92MVpgWQF~AHY@=X;T*5)!8;Mk~fUr(AbaBgtw%k<^4gK4eTh}bi~{|~X5`gpr{@6SXJ_{#nvb9$2}X|8>zd}|EQ$mh_-!K8y+uN4U|?_PsGTLEs-f0Iho zv&Rp8YQo8J6rmnX&w;rm)sr^>(ec+T7SFGJ(8|2hT4#9DdqLvc1tfl1n)pBLA zEB`XzK4$!^wzk&2EMF(q5#z@t+%n(;NB-rgU^a&i7>uU@%%h_P|86|EAo~CQINDAf zEjVEclIX6soV_kKyeIa*H|`dBUQu~$x{NkL9T^>aL92T7s2pf%`#}*0&8T7Lo%qD9 z$AiZk*+?)%=FWynp&}^Kg3}o%Ku+pWy_klTej{^>EzF4fm;AX z&xeU`OeqWagv_-aMW~L4`P+Jc$C*40W^hG(A0&OFKxR@i^)jlX;X?`fmF&kE z;-YhXRZ1AlD4f=y^&UA>Pqb_OH}m#ptJu=|;UURJy?7Kpu#NE2wxh3Lrf?wHj0aBD zM@9>PXHaQ6@o2PUd~bJN%I#ouqIX$&n_K&_uI($^<-rG}{ONUvC9X8%x)=VPqXelzU5GFyAzTc-lowmt>;2jEqsBNF|UD zby$(;9DEzMOoS#61@V9NUK5g-IOtoP7;|7DPd80xWne12BGi_1@~c9l7BSP6oO~G$ z3&y#%BUV7E7}&2H!M0J(o@q0@k}1gaiVLvGO=o;$X_s$ZK^2#3i6PMq2J2Lw07G4i zw&m#KrO4W`z>;uHmouMNr0dON{b>5S!6+o$K2HA8q#R-$ol!ud-2L^Ite#;&=u`ac zGxIUo$dvc|`^+J;S>1pEsV*L2jwD$lpDg&eGl zd#I8QW`?_D)xowGT8mNK0ufakP;;<$lhbX}`v_)S!mPqpJtWHmoe#66n6ro2V9+PR zyqj>RDCoB3oZYK%E*Jp_L$1GFvS>wIPkaQ|A!7q!;&oNVq15*y5lN_ACw^cQr}qNx zfXdz?<~$H#oBKT@2bEGTs3(%ce1AzYFTqCYnNOjob2j$jux`A{)p3x1jEDzYn};`L z6hrZqqD_l_F4^|3*U(;%XA^uIi>_jyJs~bnKisK8S>v_rYqR&47(Z6jkOrz>P*EK} zT&-H-ss7k>5*D7kQ0<)#@NF&T`iX;Q?Pd&)t$=ZvX8hx^_l_S5TEx&5B}Eb)vEcLd z&KM_M7SuJ?u4!w(?m?QllAtPdJ2@$QNLfrRxgaYwu*HG3V%n7k zvb3!(2<-({-0EfhGGTYI_@q&^-La$Q7FFzL`XK))5E@Gd?8aKo&L-pF)(Z=F+5eQJ zq^Y^peUOaiy|tMYl}F(g%&yxSA!*gDJ(^glP0YQkWKl4wz2ecVa$>{k7}X?iJ66o^ zzoqoSHBQTPI3Bc2s&8rPnSJsOcEYOneg!e{lC=)1@G4H-=!hfvHF09Qc*l2Cm`-LA zZnMO_CX^|wGsPDNb3Zqj4HM$}TZr>&Pp%f$yz_jT!WB<_(hgg+F(pxG_2OK&ZzJS| zzh|gsxj!<#qnjJB`ocLHDb1;n$il1m2E^lh(q_%=ht=+n3j;A}jl;(w;om-Q@00v< z3jvGqq?VSjnIQkW)dL{>EM{2d%wK7;rs^j`D4@2SZQFeC_YHhd;K;q{cO~1iwDb?K zD#T<|Xv~^xh!ppVf>#M{m?Wya*v%#(r;Cyruv%NSUU6Re_l~OPN8glUw^OXa;n~r` zm7UjT{}RfvqF*U7wf~JJH|!FQcis-WxOSj;6eh&P63=>|(*;B^m?cyPehf^~EbQzr zs44&mX~^&1M&j4M{1V(2S_v+#nhVZ-^uSClbi?SzlQ%Npd?(8|srKSEhW)_>|6j>T zl8jRsIs+RbQrj5J+#^*44g8Bwcx!7AZF7(Mpc#Ksjr?hoBUk8W22nMXr# zrQQ@$EUtzXTIPNo*anud()10e!JZdevc7j+9$susW1F0X?u%HcKMc^`F6{%7WbutG zyT?7sEAUGgJ(xp=@HYf89T`bit`7pC$I&^e9w9r&cOEg&-w$o4T9t+qq-5RM$JXo= zhL1njf2ZUTS>b!DoB3||^^&LNQ3qegf)~bnpRNROK&Evn=ku4WgWnB&7l9j_EBJ#F z+7ib~S7-O-Ta8m;op|x3C8trrLyF>+cYAC<8wzcMzn(Rb(MI=~qQ1dw;WQ=jS^)1h zIZvdaR)ppkvmc4**|q)5ppZh2s65SZ@+QS-D&1!+hvuQknfNk6&D@VPaw1p-MtD|Q zTl%iVd}GYDkEb;ajWaCwanUMr1qCQ^1h>&_>Mo=W-`X85QtZae&#YEqoG;K zaqILCXkYy4aMpC2CcIiC`Tn6g|7(Gl+o&PcMs5#F^M{L!!*ZV&az)PB{a+Y;evDC` zqMSHXa*5W8sTPB~y@!d9KPk<~zAFY6bP~(g6pWK!GQ7$QeeL#5HT0C0%$CuMI zb^ZYxrV0{3!~cY!r-u#yYhHm+^tN96@ax^;a^P*ut?6Z+YwF9HNTaa3xZ4S?3Tq`@ zW{?O;D!FL=BxI!J4f)*ky~M@bU$q7HNq9=&AZXli^Yp|W#OlM~Q7lQPrlDV8WF*fsQcKhV#B9XTms}AjepcLN?s0b1 z-v!~O66HO!yd1tgiBq0|M%F3}sX!x=ZHJ=ZXwzFMb{^XY|2)PLBleRoSE62dmseq^+2|;z4nBXwG$GwmdY%Uv>-X1=!yXvqu=3aoMc zv8|u7TK*&H#KcNsov!=I)b2lL<#p=$Kn_72jULjk0Vy!f!=0F0&MrUrGv@{yi;KSK zxRAOkxw#@;U}_=wFa>#Pn(_^_E~BS8Ed(o~045&CnTOIHCBTtoEiQ*n+W=vP%OT<` z)X~V?(h^d1TEb-TWl4@vjQTOyTvU1y(k-W2k~ncgK#VDoDG3Q{9jk4(?GEP3ydFP& z?N(*jq2*rr-G{%Hmq+5q@z@XvysD+Qj5ptQqtaCT z(V$TqqlAL-8Ral(pjgHq!6-)oPko?n9mFBI31Q-5`u3^b2)#M*Qv3Volo*~UnP+GbJR}?Pzm;%>bc1u}9_ocaT5_C=i7ZGf{B;vA(bP+cP`3cx4#hN$4bdy z74LdV7akZ)z~Qx@`u!V&+VyHTI&vo&q;3NW;rs~7uzb6Y0LnQ~JD}?MFpXlM;C&({ zVe*rg$M$o}F7w8&Z=Tt<7=;gFFiw}#KP{IRUs4XhnosA)N^b6P0#o^}r~G9;FW}AI zyGj4NzcNL5eG99m+?&;DOH3=f5HUaSr=R|sHHB=GxqW4vw9TWdCi!WSn>sfK2?^G@ zen=&Df2eyu3|K&4X0~?ETYzF?JMn{}JYOBr;aqxkNa3Hg@~1C&$cb;2wZt9t@@0hm;8@A}SprjrWxI1J$3KdOH-YY!Fa5Aks%l?hR zjG7!#Ap4hBvA(gfQvl~5p>(Cy5BodfotRJH;Gkulm<&IygqHYN+rwfT3cfkgA>iC< zd)#X?$*^n&BJ=1xN@k6mTAI#V_Ook=6hPdHj^qXTin|@f9@x|w1Ew#ueIW9g3$pXO zpLNgUO{`hEOYw*;Mn7MJhf!i5&msUM?oJ2^(Z{0X#BJi~E#zXwIKQIf@6>T0@R5DE zn{}K^9cPg#E@TD@-FN`8&4plJ!9L~puk+BfU=B9A8V1?Oi9A`sd5O; zKt^%Z5K`|Gb^J~f1BMRgI2+_(7VTEjNW941CX#Erou-KqZ?UO${d|&urt+zAm zn@6>!N}rld%&@Z}m*Xc+1$txRvV3cs_Fi*sP$2kihjTQ#mCA7pcf)r`xc3X=n)3N) z36=y|8TWdf^De0;Yp@roCqj9%FiokTNf!}hdTPjI#O zQG6{ugBWLc(syNHnGY@F$HQPER?0Ziy>Bp7BOb=8)ZUPaPtXkz1!~AJLaM!nl`M#c zt3}h{OMso>%pNF#l^F89v~W#@P4Om!GVx<^6kipJy&)R^KcY&Ti@?>`u&x zUWq+;7g>9;Ax(!ygIN6Od?68_4XQD9Kau zCSCZ?RFs`4kvHMgWK1$SZc$|C7w92y3Q2M0243O9kW(C?s}4i*6%HC5%4iE?YcG+Uo>r16{y*(=zD$R;ymr5}T$ZB4!S*VwqdQUm#AH}z>G zK8KpEXal<6fk=sh#s38I?8`(6>HpjgvVW*@;ZpQhZ9UJsJRab1`!swnO*gisb3)iLhD zZ1YS=>@S^a`)>Tq*_M9lZ{rY6eQtDHVhQ$Fd{LHAp7R_3z|kd2hw0i=g zzbD#V5#jzFGp3MvkQzOfBOoAuPc3F>=oJ8-F4bS3r4j0(R^?cZ{{TF=> zkPbjoIUe|dLp)mrumeDvfPyy!ERKe$&I?_by>COvXkkGBW_x{*qb(%dsCs_w{+{xm zO5k9R7e-C`Q717sr3p|Efu|bJ%R1vS*y49b64r&!VIZRUm@o@fdYth|IG#jpALx4r zF7ftHTdn(uJy85nqDQmQfAa-!IqSNV7&6n&-JLF7!mQZZO2N-wo>CRL8Dmx_F8gAa zO>lDEETmI6ZM^>bdp6%(Wd)sYAy&``r(1w38d#*Cv;TR0e>N&kBWE0xDoDe7^~1a|M+jYgmB*jS;(6pP%N|IHTwp-++Z`i&1ph-vsBsvn3 zSz#i1g(gC20i>~6&oH*aL7@mBGHe~-#P#X@)lN z;8`m7@q34|(YzvVU*)d9XWOG4L)Qlm0gFV>CM3MKq0~U;%fC=J?3Oo7frO^1FNe;S zew|9Ak#J%so8>fGCu|cLm3EH=4RZaiPU3I`EE8wd*oY7>Q4?(jC^D%g={1m9l5(bO zXlS_Iy!)`?N}+ceqfwIxH4yk3?&$9yec&FcS#Ge-|8$BS-G>hRRzpz$+4$>)9UIs} zYQ`0*?QZ!9Mg#Q3DWl%0WHJ6sGA`;qm5?Lh6#LH>=h0fWys#$$?3-T=1B7z7Q=+Xh z0@Tn2y6xLt@m>gpe=@1&3C@`;(eLal;bEr*O#YkdD=+Dj4=8Dg@_bn_ObH#(8l5!- zMxBwD6NDmP-s-(0z5uEn>JT;bQp!HWumu9T0Ym}}TLjlw&FrTd>0a6S#`aNyBwVEx zKY7D0WU`h2q*h*)cG1rk)v9UCyz4vc($Oa6`}=nT5`Ukj&I#+E0zNceS~K_`8C&K zf`4>z!g51^A{@}|4(ua=#{=x^G<)BXYzSt)0#H?WEbIm4i)8Os_#MJcH5?J^{%ryC5w zP`)K=dCBbR{^98YW2eyBn;Dd3nh#fe*!T78g%9#Xa+Zym8|Rj%rfsao zI|zz^e@L$xO4p6=Nd!|qX{%cB4#sWO)}$^NE`{Y=KqQC4N^V`JJf!E=3PEZlJ>fdh z%N@;lEexiYMrK7<4g3LY0XMw+gwmWD%lZ>w!|T{}8-z)>}2t z%%d8$Mg2*y8QrS*^wM-Jn1@RyWSF5Xj1;pOD2=bg?h)l}H_u1vECKGuhCo?fW_?>* zpMM(~{`&qt*5U!lzpTB-yB8JnQ9vneGo!kSo7wfM@7Q`y71!~i&$}Wr95fS7h@H(x zUL=^0=na68+)h0r6kR5o_zlgkJ*A*pNa8+T`yuS=wi7ODuZ+T$`#w`WJiNgmL0kXQ zHImR*|8}u8?5f||hVUZK-X~nn6EOY&K8m^x)XacKK^)wxdN0plc<`SAEG-hSF;|6( zwVA(R>}P6_@y4{0CT7dL7YG1>&$9Z{d4)R@zzPVpK zpPYL8+EBF=>oaj+YY*k}4ypCwa&bua=OP<0bNQH**(?P`Dl5+f1X==+aW(n65iS0y zkZZ8Ua{?+;{cm&uY{{7VVU4Vx*`Kt88CmRmLG<6R1j~!Ep%H`vUMp&Yd@ln^u zQ;$4kA=u3wQmz*Pb4Om(sZUJsv&nwQURn9k=1rX*u}%F;P~0JpVFj4EYnb zz}FvzByLZ8D<4f9KW+^f zBxi5-nd#)yYJkMkNIN_9jMl@u-v=^5zWXRrsQ;29mm+$Tcwk*A#Y?Q=*qsbzRhZ@c zi>;;%Q!5I|Gh4sHLJb8wEg3h8{qEzx(wYbw+~%m%M^GcP@~*`~C6{1P7-lSAvG6b( z+S=MW7WsYB0D1JJA1JXx4&1w|_ul9M@&cZW)k4sB!w^b}@|<;*FQR2MRv?Gm;nIBn z!5jhz_I$f``3n$P7#P4&2?7hGCl|AZ8|&-;9A4jsWoE?{@Nfj!aUiH~Cks8Q%jwZb z(j6Qpyi!%yU(a>T5pKf_B( zAa`kHb=?tQ_Au!zirQ`29FeAy?T)@ht2`nDn&`gUwW*>!?53#X#EtJ4-S#)3|W zZ$*Z{Tdc_D!@kU~i>N#wYO_o%OHSmnI(wSl&Yyy$i84rMDaz51@1qRdr$LI>rTQn; zlz!kaDqhKc5z#!G)v4(kVBKfllK#2$#aWbTip5U z7EHq7m^*mY{1t}Ax_I;9JX=%b91Fsx*H*g%o620b@U_`)1FIy7|A@>f?QG2q^iJJt zd*j;Kw=;~n3}T~z^=5rR(pMm+))bn0_CA4E%}!Y7XP%#5z}>7Z$OfCjGju5t?WVcN zb=2|=`>%NM9|^8ZrGbk4(7KC;_|_l%+7}`nnHvGK8F7zTEde>7Y_;1lufl%?{cM~l zjOx$yBagj!Y>MNLrgc{7LO}Aci2mgI32X{P69cbvI1_V)(VaILDu_hEA^U1*Sol|F zUx@d^G?AEATDn6Av#vq7&6$Ey>hL*UGaQgP`k^37Vc zjoz;SXZMnPqbn??)~I)SdOAq9lz6PQR?vNZcL}K?z4lQj;9$Fa^=@la15@TZ&p^$d zb`~5vV_|zni%idTIDq-oPH}eTZa?mAeZ1j1 z660s^_QkVFMBmW$!(t3sUkIt;6V|BAg~?{DBXdYBsu={CoC^zT49bSX1Tx6(?#M?S z4A-UylLRuN=MKt_cc)pfx(dA1f+1fv8xv#+laazmQtiA|&j_YgQPW6&=N6;O$HFLDhsO-b$_uiE;;a9=oy zi2n8z`tIm*osx(CLe#e%fN(mx`JsSmwK`gWrst^j4(INHD%$j4dgJgnemN%c(LX#d z2|mMx@?W}@HS(-reyF+~zP)AeDJj3^Ui{bHv^HDRtj4?=Tv*tM$bFb&x6$CSq%75^ zL9!eur@M9+6C55ebm8)#SK>amKK$*h^7&zp~HoMo{`{mFI%< zDOBgSoU&Eb!E2o+m%~o1&zj~^-Sx6Z{KTH78ySJR($d6fE7wZ~iER>@HNgl?Nxz;K z-gCIEHpb$&P&){6#Z|v5T@5&(s5;L1Q=4=-|BmS@(lV0i0}1;d!zSXn*FH)wFXY%s zq8pa&N$+CT!nB8Ux7s@6|JY@4FjYMqy>=#M05j1(vfPP%n z1=jf?ce7KqHkDgxuzTnIcq_OUaK*&gX(;@zlEsy+kT}|T?5APUyTGcycP-zAYjnP? zyvc3L>@sTL45J~GMK+Am&U5``|Go-hfeT=$VODd!oV}1S>J4M*oT}oY)+se z>iTaWi3{tbgo^Z8?#Njb9t5CJi?fmyZ*PaFVwgk`D<90(X70U9$Goz~5yupKy?^y9 zcMX6kd0y_5t13Xbieyz23JWNfW>No{ae(y~;Fy^h3*WG)R2L@DvIL z>Gb*pYQ)*Yi!v0xT1RC~Nqi~Z_B21qzx1lTxGArhdOVtVqHkQ*X*)vXF3qYqa4Y6d z5DUL3Yh^8S7tIYIZE*FOukdj^NMd!1w~+cffyV@vr0a|%9X)yQST!X>1zt4c3?7rW zMo@eEI$*RwFCjdRr{?-DcaAXoM3 zeb_eKh0p@CUjsfrOVwPGsgE4fIsTx8qC)|<*CR#1oksvJM!UODX#7+^5;csplb0~A zf1DMC`dWw6-ad0<&jI>v8Ak%2>jU0zgdTEGkeNZn<24=$9b`A=w-6_9exvJ&0~mFa zA9n*DGWLg(rBFkJW$23}76O0tK>rlQa{`*$`Q82$3m} z$(3F?@sM!1d1wFk@&^o-;vj8=%FX&@zmXz7_&aEBQ{e2>)iNP0%xC`v6=z5=7 zYm?Zq!d(Y~@SU_Edko$)?()rgx=MH3hBa9x=$!9+Fff$RJytws=9$^&TV~{Qd`$KY zen{xNS3%#8QcdMn!w78fO0JilKg#Wt(Pq>F6@{uuIRY13h1i;>y5rtn`A^TA-^9`R zvUaZ)6Q!PiZof2s_5tyjSd_KJGsY77uyo;fs>>EHl}YLhw2fI{5ABM4z}N@n8m#^q+!-u5pC+()8se~ySlmt{#|-uUYHNkicgFu;QY`E z9w(LSQ@eBFx8^{G5U?<3o9~MgP!p8SNr8T}hfbizvcKlJJLX$U%V*TK%XoTRe0P$B zsu7Bs0gb0JTzmaA?*oUK^}K2)PIVHhrrE4@$R#pElGBgP+|~oD;r172Z)`ag%yDbu zH<6%=KNrK9`I;IqzuoP>O`K{P{!1F$-+)e{xP{{^p={e<@ms&=r+hT!c7$#8Yg}2h zg_I-l#(@BKk-jH=ReL>CCln&^7Tf#wd6%>FX8~!^mwv}b6vxySzf>~TjcUppyqEu` z-K1WG{`DQccYE^1|KmX|1(Skeny4SCX1>8+eFD=&%U|BP+o-}uEO>B0>sOCXE)R6=e(D0>&rwIeoSSu$6}MMz(@g_cnXk{5n>>K* z`0K-_Bb&oU|BP>a^`mV^q5i9El0u6PB5hVV&x__Xk@GVmy|3?!t6TE(Ni(WX3jH)n z$8`&R`k2T*AUpiO7XYMTdHt5DkZfvUC&#bc8BNH5CSC6Uk@%RAxLDkZul5~Fn3pyi z{F0Osnt0{t)$2;Yxc?%2NLlIna*@BDoKUp+;kEx&)9U)AcbHR?BooR{{?X&pXsP`S zmSksaZ**d)43A$%6h|;Lm-A4J3Qw(j^@Yd|oGP6M6XQfw` zUkC3QLO>)i3{ynGaIFlnO!&@wRWc$pSnO^;r-Aho7v`3>d7{%)AqU-S0f!~xB- z4blWdS|WJpnlSv`SdPWQ4wM1$C)*IS#=czP@eLQ zcJK$#X~?;>z*Siv(P$u{hzW-d`=Ns)FS5~pSCcp$OI)vf&u>mdEQ~sc2_6*aflA{Z zYEq1|v!j3i_R`0(0qr~m5gg!NPW9u|u+-{%Yn>nSZh!elp4>%hEAgKezFOc5tB5R{ zh;;nH$!rzCCm&RaB!NJ5Y_8dR^lI_yNc^}AE)>sXl~J4TKJL}BWj77-fxfTpc9Pl{ zQ@Zn|ihsNfKrU^yWng(8#h80}T_ONGDByd-3d>b>BxehW6a#i@=uub z6_RUfM$u=j((I1gx>96u%y#so@gOq`I7U#s&U|VXD|c+**pSYzVj|>k%9_YLJRiNe zyDyjHo-RwDd>{M*-qBBi)%v|P8WpBUKGyustZULcAwfx~WlTBU_8M{j?CMg)omifP zMEv=c=ZaBT8`|yJ@+9twc7dhbzVCN{6F?8iC96Q3L;(GcM*SNgCkemvPKhewa|(~bfA2b;FJ!76fnH*OjcyKtSotnA}Va4#Hz$jbuXN-7PgY?v~Ry{)RUC^Ewr=QB_T#ZlD7QsW9 zgpM0OprAyHcs_&dDlXb2LOfK2R@W1~Fcy?LSB3rClpwcPphO6fVsX~lGu~WGWL55h z$j$LoBIeK1T2Abh5>@I&2H($~e;YCtsuM;>K_gOh$NkaB{)Je=Ogy}jydb#{$fKk&H^52M=qXIqF(nys27@6}Gh)KM3 z;w41~E*@NgSTqg&)$u?*2Vc+kI-E7v!C?wH$P64xvf30I_$btt|2pR(kLv}QipQF2 z1SAIrCYIbFph{1y8RW zn023Y2T|A?VF?d`1nZcYqsLLh zsKU$hZ8v_R%HMdtwPVn+5+@Fk!pvkMGbV6DalgHB;oKfD3;Ona)ftx$uNJO9ejI=grbS5j zh-%{HscAiA?nn=)=^67Z(6K$y%Wniq6~+GH%mJpr8|dj}u)maL0E0 zXz>F(V5F?f=j`R2{5QnDY$$KF1;d~Sa+q4# zvH*P#5#4(`9YpIH+#Z3KsgHa%pS!U*Q^?m1E;0SJ`co4}6m8X2|E<5)1q#nC%O5sq6M98nS$h*{ z69np>)<+D#2WArLftieffn}7@*=K0mwUuX44Z7*{Xran%cJ6cu$`SD4vbt}`6tvJ9 z5>x58x3({VL3SB=VMB2es-o(Da6l<7xoNwwO$<0fE-`0%QbOns{iFmARQ9G+KIV%s zZSoDKx&==W3YdnX5KPa-#uyGvndVb=bp%P?lSg0ss5+jEVpNprc(^*}0MZ5PMFgt%;O#wNUAm?&iqMSwtT8A#tX zT8u=+mZGX zDxt`*hr6MaLTd7xo58zaBDg9?Oqk&DiO?3%(WmvJdRNe0{Iy&+0IH9@qBrL}F%XkHIYH$=KLLFAy#10Gs(<>6#EEmH<`QqSU_?6!qr?g#$sLMbbGr#8+ zdXtVl-N6w5j&vh@`#u5oW!=Dg#I+H=%K0B%{rK9}@EGA%r8hWczj$LbJoHGZ7{U=n z-F+Ui^zB;QlRQ`J06=m7LnrZK3r@EP4K7~Gx*Q65Yar)D?JnEW2{6Pf*^tWbp@}5M zPP%xYuQ~*tdeJa3F$@H0D(#tv(G>>fK51ogs!wPN?K2hgjfYnTS?_Pw4qa02o7;AN z@6O+Klz~d)G_Q|DmG|g1C=8#Dg3Yy@ZB^Dv;E_|mC1a$X^sOcHPNuocUK~XNH*P(C zS@Y|}tgXGD##1AxLhx}++rKFCC75zGu*;?y6gX(5xzKV&a|^240Jt5GyK{UA50&g*(PSljmWw%3jd|naS^F@P zR!I_+Dyu#(r7V!XSuJ-TS(|jwYcXwgbD@lw+tm}lFjX{rd;8PJy9+e(zt0zbOpII) zYgPl}6EUP$E6Q5}qc@a3@3^{#zjTEDgs@GN8;6?Z7}LjPE?LeurG#a=ax`a}qcM~| z+y`WDy!#PlXf47T8Rr?rUUJedna zpfqR>Ju>tyF z{pr{pKp%RWW_{M3x)RWH=^TF`a~D<*ad`+aI8D_?U;jKw8$IRN-aCHx%(Z=lEqt(of$9%P5u%-HyPuwo_YsMT ztfgpFjbDpiB!5pa`=0S8nOK5?GNpE)nR4O}^}K_IsT#IMyOO^CMS%^||I+t!5}a@; z7`{jZYP^Mkn5D-10P$4GnmBh{2Kh5;YE_tKj`#{`CH=eTyZ4fR;^Q{_=QUgpZ&odt zR}2`ar`DOX_T`6quQcMErS@LZYM6J0u&KRR5}3=okcsAm@;KaDqsQ2}`#2S`Q~IY;)61yK`YhsVgFoOX z4u|qh3`!Ea)^6Oa(SAaRwWP2%BCbI>EUB{gZUKk35EAQWRU>=Ml~*jI$%{00wuJ!G zdl&x`5ua0T_v|ZNro|*u!WLCgU^(|i2uZr(^K9mRHs)g6bq{Yi8wNtd^6PVf?bX&B zV~drQm5shgLW1%9D&;J%jmPGWFG@!j)`3J{!q3ox;a%WVWIQJm&5(20R$wTjNSI0qqAuJ`WpjG{UWObHqlPZsEn>vNl}m`gK!+4R%F|2!&vU@$3lgc@o_1$Gh z*e_$lho#ghhfchL4R7uJt@+*`3KWl*-iyicS<=uTh;r>^8Wnv*yw?gqY&aQRu4wHf z^f*_RF)}kwebdUiHItQULUg+IM^0ImXc}HKY*ZpyWXwTS(z6gd_Ta*c2TaHlRI66) z8UC(a@bBe)ZrAm%^AAp1>x-uJBY5)d6q;kjUUp>~C7(a>hwBb906E$W8C}rO%BRQR zQMw)YccQ^f^i?^ONKVu|ovnoFKYTokMg-ov`?piZJEVVKK^LdLNxA>a6e&jnrH|+; zD1Jn`k<-LpN_b@&m7@4gUQsSg*_M?fQyvs}Z`#WtZ(WLh&*VslM5HAH zv#dc{jba1gd#3n<&U{XS>ZvR-k*}?3_aWh3uiG&xDWB#rm+XI5c`DmElfA6q7yv z>~EL7h8wvQu(G3D^p&eX9)T}o4w?c%LsI5yud>9#D!yMLo;6{R zVzpEJxgj^N@xM8gB#%kupba?5=$(?2N>v@yl?q zl2O;HOA>tYtq5iZ2W^Un_8ZUKa=-KrFLb0YcVt?cE!{WYwL${!4Ottke>)};;i^X9 z%SX|hX4Vo+R_#>mCX{ZlftQNU|%C^|j_!crQ%GGq?yAkPszBP$l=m<9vrYyHr&TH)Di8GQl zA+gSlSCWQyGYz&a%>R=O%<4m5%4AGxh%&I#iWl zN{U4I3?o&0j_pq$L$6hjK+*=~#Kn&LyR_$<^?htzllR$2^Gd(h-CWEON=-jLXM_h9 z+L|xn7dsLC7lr)lvTsDF^=faO7Ysyb!fLy3N}DpAsL$SIZbjs1pW!ZezULx*ienEe1CVoYv~rVW{)BdK^_$eFhjS1 zlMb`&BPah**WqjVHezm|vPjx}u1qkE{=1FKTVzIjRNN6kld$~vShtRfT8g}(r_G4Y zQqfzh5X`Gg4S#%B73`ehza2>}q2$l@6lvg5Q?9JQz+y!B*Dgv?I?yLc9C}R@Y*ta7 z^w{cR!~Elc5(hRdRs|Doo&qQJ$y8`i6wwxlZJURdf(}!wm(hd_S^h4Z2!Ur?yBS}y z;35Dj4uZ&DajhC0iBQN-qtat8*hzsrMI8*t9k=Isu|zV0;CO1Q2yD-zc6_B5Wg+R# z{l-409{kxmxMGugLPA0SRI{UhKx~4u<0&Ny-?3{E4;4AB&3b{b8n$=;7x)yt+!!&v zg>3KMp=11D9JLT(cB$ACy;*?I8~Gx@*~U19Rs`WaU`nfRk~xSGx;~D>NU9bzui_+W z@Yc2bz6b`wiXUe7m|LpX^Rk+V4MYy?`whx5+7Cu%bpQ8|LE;G*L`)(^i?4YyVi3pN z<@+0epJoT+9$ooe}4+xM{=C;+w01&R6t^9 z>K}a2mhI*O+8%xq=%|XyfJWVn)X{%}nm>(X<`nltn2}fyVC*`!3+H?5K5jFxOr-n;}yxAjO-m{ksV7-v{fx zo637HXJ^&pS)@C2=b=HE-I$@JXDtCEcYV2DlSX9r94EDB~!D{nfhpj);(;+=LR-pRfUp{;(d31A_j!* z4*h^MjNMWoU6H_oi~-cLXvg%(kuuepkRwZvOo2@_0H{|GKy$2nVVE2GC$*VIEPJCa z&G)Dm?d#5y*S6+%OZjh?S@HF)1&-DBc78s2l6FTXrGD&qEC1zA>!w7VRdyFr^~deY zsUgW{$7ou)3eb;{VbR?fqI&HLR|fSqXn@p2;JDltAF5aHMU#^=qA@B4&}p&Cf%v=qy$6 zs;cbkqEH6LrsWFsQ~h7CY2^a-%(>|?G<$R%Hq`geugl>1;6;8eR@GA5;x1#vaAmse zg-jAvh*&TwQzVS$UkQ63RTa*V2RD1DXxE@I0UmuE8|XLuNFPsM@%0O!_Kj4p6^jpy zq6lW|5fJ_nB|H=r6+CuK(EG*q+>6memK_d(?4*yoJdu%FkWfz8^C^}9!8D~b@2Tz@;5|Oq)fH+$TRov z?S<($$0rmL3sKajvJ0OZ4Pvw*iPVrphM*+fxJ3_H3}cYXP|7=`&}KGmB1#P8@e&la zWgKV&mhKE=z+L*hpY{JdjYh_}Fmu@0y)F|9i8c2Z%CSW=6?oD#XYqOct4{`lvuL5H zs@-blE0L2u9Vo96j6j0UnaRUQ@cJ;Nmxt%ttEaTCEy$QE@3FXG-G)*(htmFC?Gv$O zM64D{#il^}(Zan9yVnegF_Id+$N zPNFf!6&ab=*%lIj#FVOLs+O1(3B4-`FN%CRy}6gaIn_ml#YeYZ|uwY-&WsbfJ z$IVdA_WYWd{w0%BzI;s*6MN>V$XK&9rIqJWomCFRJfjJ6ip5zKl-LWgCdkb9qs^Yc z$ar6Bgpi%*9t=Y);PqukTCq;?KC2_0@h-ocgU}(AKO9eq;S{O zF&z1!wW}V#_1oXpxkiFZGmbk2Xx-ejxK3OzW&H+)Ub(eXvD9#_{3>=iJ*^t3^t)n| zpH@dV28bS3s`r503xbx@e9lt-XGvt?!qKS4(C>6EC>aDOl&aTHL?xO!I{LZXHiPkW z1N!){dDgf)ude=ei*m=jg;O1$ym55D32$u`1bkEgd3bd6`RVh-cLP-Bw|RJ1$1>eE zvfmM2eQqnCc)AS$IHJc1fUh4&cjDl3Awt$L1%Q~NG0X-nv>DZgEv=_a+SoK4;NA(u zBD|-|B3L}E6)uL0q&$!9d)QZlS;j+df^};yPb_n+R^#gCieUL9;Y6U;D1{8jZv2uI zKq7MQQo3bC6~Djc9ytetW(8uN<_vUd(ryQV0go2+3EQ@B)Mr!INgZ zB)?;Db5fSxuWvJWniQ)p8k#6JzDVzbtrgym1P$9~yI@bLT7MN9$$+BG`0ccW77fOs zgG%lGQ8@C*t6{ift;-EjlH=JJ96)S z1Nlo>OsB>>1WUnBB2C$alc#&!s{`{z7xtJoQRgCbv|PU5(%7YpWaQ|nO(!H6@6}yQ z-3=>F@@q+vFCWZ`qzZl5EL=d=oH>s5aoGZpN?RCK#mg!(EW!SGZH{=li};wtVom zMbHmR;(=)#$MT6>baC~GrNvu~2vmySTYkN8%A+dbbheBbXf`Xi&80BxF5zNFXh9bHE<^Z( zw>=CQ^sD%RNkilkdpb>;e@7Y9;V4pQ61v3gvg63g=1YU@ zU^EbNf^LOW7b(QD^J)`Rp$c$eq47`W;eTr=as}lMhu)VHZpc_>6^zG2Qd*=fxF8kE{(SjWs4Wnmbo>^zKO?4|ffEUh8Nl83tdQl;S$;ot9dxbGSE>X?umvx7 zmcm7Eeq4D1yK(pTBt_Gx4^L|q(==!3C%U*EEW|Wz+>$lEm1}v37Bx>Z5j;;$c@oY!H{Sm5YuFi zAluvQF6I|GHbb}IFEN+3F4;drhAY6FT82+_(>>nVf&t;;E}F<-bxJ*Mt5Rhn`E_LhhP`k9L;PIz~1?(TrZA#Lf)Gj{sHmE9LaxVl4^J-bGnmZK_)O{3~}!6fHBu zi-XKB4QDL-Tq=68v7&JX>JhDklO4MF zVWH$9&wUMtu`VA+oziMdi*{NDl5?v`;ooB1g^IJwhgQAPlrxo2Ln`u0;Jf%1JRoRD zgx_4nl-mm#Mnwf7{v5O+ts7jX99%R*{5^DIkDj_eiucnm6>#VFHgyDBgA*cVOQN=g zNF56zN?LFT?p;JmI3=!m!^fk#F55Yq=iW1lq-YHYqIXF}iyN53~7iwQ{acUT0 z2Bs>x#mM2F7HTYTeUG3BiW9Zkv@#uKY1-(frqEoG zg7$#%7Ubp@A95(`&RRDa&xfU6-R$otMuUdIq8PZwXv7j%dcChmBHI)QvsX32i%%lw!rzq+Bc<)GR)M~hIE6W~5+~7Gq z+$GLzvqLGNVRb=;OyABfY8tsWr^aj zl)%X!H!IxZ#{B!aZK;$Y@54iKmrrLyY}@HdXv650+sXc+ZD|H2TwwhZr$w>iSmJT^ zGRl8bb3|2S-nlwKkKq z>9hEljr#E)ekqt$_V-p@dH@8*8Hl&e%gxH6f~Y--hGMH6eS&iK7e5Z4!@Sm%A3jd! zsfj(r{!@{)s%Ip( znv5EUm%iH-q?#3w1@TZwAgS;hSE4wufJ1F_{-{MPE!}&g-ZDz|ZrLoV{o`US`jgC3urKh0`EC_ zSgd=K{{#87Ku|317nzGP#lG?RDVcvieUGD|CT+;kkS$^wq+eqc5)zh{f!}__Z;wrU zrH}pHCYFvrwwP#i5%>)e2XoAbvDAxJ4(ShwBG>||W*pP?DbZE9oAa_INlz;p55)8q zzL#b=ef}(z^8w{KHA@Ff862MV^v^Q;l-u5+a?>!yG1GWB*hX8En_Q6fGX2NZQPzxl zv-9NU^J~%+?7X<|#3=^j5IhfZf2bhPDBpZVmc5q8;co6ef@!^?4mYC!1?+vHAkt@krx_~HnirL(eQh!Ml<>e7P_ zgWY~#n=Cn8Xo?bSG@2(5y}TaJI0`a!@C%losjH?#7DWiFHT|Y|VH-1i?8l38G>`Kk zQmDd}@a0K2=?ER`8cJ~hsPAo3l2Ayzd%Jr^7QK3?)~s5+*}Ga*6YtN zxW$##RWO438Un#QozbQ!NgQ46O=K1>Mv(L?pB{&bUH;sUicG{lj|wZx8KiAbV_F88 zqKHzq*c2ont%g(bd_-(AnN|(%nq$B;CXl}yaiktt4z4es)g`Q+rK~6QDX(T#*2~#gYII zxeiIAqNdqqNyZ_tRR_j{C`oryXG8DZD`w5Y zIwe}27Z;wHP6C-Ch=B2VWzC*Vfs>qkEdco3g(O#^31fd%Y!Jbq(dkdt<8a{U???oS za8r_zPllDH6qAUo)KNX{tYn|44yDiF{+lA(DVjbdQZp z-N=^pXX(;plkkU?6m0;-hI4f`Z9=`1!GYzAUKV3{$#R6srSYfsLR>U6`EYv5zHkgJ zFRlRh()^A~EFI8NArqffhkoS+d-=nfGg5_1O(Fx`jG)Qk08>mghywk49DgjIt@Ly{ zdSSD1qYk8fvv^aRy{&TRdTD``4I~)eb8J93UUB8bzhHo7mS%BjQs`dnlEg7z&1|R!Ep(efoMEA(!})$wAeR++S{Grg zCvcoeluRuNq7gd*96~K2Q;Cm<2^Q?OUH0xFCKwu?XAjHTW2lok|vI+0KC6K_a>xJWqAM{||16Js>Xo`PD-uTJEDMx_gZ z>=8GU{Sf$QgLp;)QB(@_eup-1`bAw(xH_B--2zWdNmayDf~ax^dUcxJhc$qM)K!fq zfhJw%MToS0!Ic-g;_bua!8;271k+7)D_F**!HF-vib$pO6p4>AeIl6(Pk;4GR2601 z88H-bD_=4zy9Pvv+>c|;Ddw!=FbLWq;ws`J89TefjED6YgE}N>Lc^W;Z9a!g2Ujf{ z*Dg~jp$UW*AAUa)5{H=1kY)6FiVi^o;`V@lgzgZSnoXO!k1*lYuW`7v$~HHlv{l^_ zwOlH9JZvaZ@8=pf1}b}uG`(@Afn|>7>kde&!5D0MXgiy{|3V-@9Q5|P!Kj@6bW>^> zEgU^yt6nvK-ZqLV?n74B-10wKu~iQcMT*bg^X$2txafiy*|dhxR7_r!6ia9*f09jp zkchTA>zX~I|6}F8Mwb8oHp~d;g9YsL+xOGNzNX22EFMv^zVph55UJxcyn@RpyWFdv zpA6d~bU${`2*MY|n42LQU8>fJeJ5=ORJ^vQl`+JB`OmS; z-$19;H3(uN9Jc!NTBAIk_V>$P@C*XvG81d6-ZB#*!dB!)wcro=qaM0PWOH$3{=5J= zmWKdYoD0C#0=9V0k=H0y??ws>Zen%PP(LkAU zfjr~2MoobTg4=+G-s55y69{?i8>a(l=uH+@jGayPM!vu6SdfAt4uQrTuVkfXRj~`U zRh8voTA!VyHi#obDk!qf@vbiQ88Z~K?kAGDnofx27hT>~2Dn5U`bUJm%sgDD-Vka| zmfuLvo`^a2>3bI-$78Ud(Q>*dkmefZ+fmdQRvM>;BrN%(8wO=|ba!RV?e*!pbzYog zaNEe5S~sur^M4t-om$V!xajxqe7e?a^SOf*O$QGQd`wq-2YmCYvGF~LkkL@0H;iY= zm6y!swh1AB`3PA{t2eNp$%AXMoPBd@O?$d)WWxbrYCbqT9C%?fWMo=iZ3vLZ4)V>f z*h-kFtgc1(;6b{gwoRrkvPtN6r=uEAgf=!e!_&FRU^^-TU4ESd4t^J;0{+irm7Vu! zcnA^2ul~_nFm##n$uw$iRKB?>c$)0|@+>KFdwb3N-0A;>?>y(Xn_j(Ye|F>lasz0p zPW2tz{{bMBDU@4lrMFj{d*S%Y2f&7;>6cSu^5NYRzkwoNf|aUhiDD$MOCY zJ$i5X1Mu`Or7yU^dyN%Z$nbvo>xnCtoP)V*U$=k=(`QMx-n94A%mkjcIeQg>x1aqr zVn5~{FjXlI)Fssty!=}WF2UkGtLUPT2ABKa7rmgoTrc|%fchi%8k@)==Vu^#VtT8; z?Fq!}*2j`8NCW#gHjY#I#|P$wjIZrxCZ#$L-2IOwxS05qzngI9cd}*{Iltp)wWnkp z)ErnZna7pPubbi2)s4og)1<SWof*tol&oQ1s+rYJaZ@_xVw!4EF;l9{7PN2{^9yWHogiy zj@bo-x|r(Ju6-x5fnR!i zj5D^cF>=@*3r&pF<7w*$xG5E*EBHLuL1mep&B{>-foh^fY%7=Ln?@k4u4dh>Li6AC z71f4@j|U&NRp8x9UJ3I~*B;ca+}CBk)W2#y#?4Md^>!dJ3i9&>qp;1|6x-%$j;pSG zABvO%>0VkNgWz(*f0n-2sfqa>4Jk(a4P*JlubgIzn7ga0QOPJqpN!;)k~-j|UxuH9 zu!FhN)a1**Sr^?KO;+r3UZl}@v&qt3ftJZKr`(sE@ajwJ>o%ehU~D+dyJ0gEG1T*^ z;x#bW&zXfdBL{w%nDjlF^+4y!KuxWc6CFa^6;TdoM#h3^6;^@%?-8FfFjB)^*Kq zS{S`p5v1OQZq>GKPK;8LwPd+)|HL3WzfsppVh&14{MaJ)k^C(P5-7REYn+GV+OlN{ zml6wCUzPUvri2XdbB;%|KIz>4oLiA89*#IRqZ@5%eF(>PSf|3F{svlxrYhd2!Q(A= zIH(iDxg_vdq|ldjRD(Lz7acJJ4I@Hr)mWf3&>f^KFOn@R@Lt_z5e6~b`+H+J255E= zfh$8k)m+pO28T|IGV`{f2vRtwf#_>OOe7al#FH+hfs$G<( zY46xD)6Oe)3tSx27*24L!$8VVl394cCy9!grpI4M5Mw8ToAzk>SmkHVJh?k3mPrgsNIhqvnd# z&nr(x?7|s6j&q7lT>a*0%OJLWN#$$BN(KAkz)jehuZb{am= z3kFUI3rAeoG2YxIlhbX3WHXKwzdZ^0SzqnFl@qz2#wdKV4vdN_Dk@3>cMs{N+H4*< z4c1jfmx*5SG7QQFz|=q-)O*cdg%HHu-SX{-%CN5o{D(w`KJ$(+71kPiUsc(9UEe62 z38VI&`AWmot)Dr$_R%XR*tfT5y+~DBCl~(~IrH&0=lp(B%sQWx-RRh=Pmt;5fF`&f z2kOx5^@LR42i`V2vPHDyYG=NmSQdWX7Ty9BEVm9XPyQkeT5wX;OuYHda9TuW7C2~E z$0Z|i5tN^siC3Twi%Jz0*mQgWKRkiqK*$b2Kg}6qkQ_J@jv9;f|5ne@CC88~zKt9G zl^1nE2x~vYGo}8J#fv*KF(2WO7g@-rQ=xXn##_`aXiQB79OQsgpJSE(D-^(m7-fb# znn?b`604LwYINfjw6q6L0rkr1CgO=?17YqrqAUkdasSlS$-Kx}(ce1n%upEMI}+Y_ zdbk0>0Ts*97jzKMTy>zA-^BJ=IQEHuEbs+LyLZw{Db0zbe4ehf60h%@NUPq#P_+r_ z`1i~sAD32j=U``3=ShjGr@&JD%IfORqUeGT#2?3U{&A&+JMw3oZuX*h_v>N0Gbvd7 zy^90!Ru_8i2ZW^~v8R2+M4CNJ={ES*k?;zb!+}|dvLl{>(gFZX!1S4L^YuQhGU~k& zdcpH3>yHGgS{iTrSUU!Qb}2y8?co2Qm!EJt4`}eXSK&rCzz+vPIsjh=j%q9V!s1cl zNSeS15I~vPF%VW9F}}$jvl8>L4sm}zX?SKmulNvGc*1{&d-c-ZcHLl6Pj7}TSo_iBupgLBwb6^>S-HKs|XG-(yRN12!wi=UP6 z`Lw9}_hV$UTSj3(@E6@9Pv+H`w?Q*$$Tu$aJma_CT2L1gY0dWSJ%=@lU*UTb+-4ZV zKq&|XNJc_bz2?x7cjKn>1);&|*ZWGqXF^IUd|?^%Uwg*(b>Dkv!0G8J2#0${T>T>@ z)yOy0i?ol?q0FahGvobC$RiwqJ1J$6JDzvo|kbG%#zYUvyUI zou`71GIb~Pl*)xqsj1Vy*vxnoiVBs1ArT=24gVyNm`Ptl`zvRWpd2?QvV<^oFhmUN z4M+HiQbKqzwQeJe_olJ})rMSeep+k>k8zsIgg^82)G;>J-Q5`H@o^03b-X|>vM%wa zMgF6L#}tu^YDiM!(4v9hN=zp8xGB801(5qtN@Jq`n4u_OV;75H{{4KCoYr(l^RYTR zdfxSqF)P0Myo&cYJj=|yv{1>hZQHd5IQ|EktACh&G~>>Dff%O*0kE9W zT9WlkIiLUkh{HwkV0ytS>(P6=u-3-Go$6M|ptiT>`$?jwRFzeP*oNvL_dNf)@cAf_ z+kf3(GeE=I^$X-6KZ{8t7TH;)vqR~rO$WrDh>d7R9un)H+4-1V^C?(8u4T-%3pM|p2Gs1L<2g?>E z!C08f6w=BQS=0M<+PIY>2IULL5Dmtndc(iC&~ODX6Yo?~mxmjI)H z5+P%1$kGEnVpyHeR}Nfct)I}%E^q_;nw~uUWnVIvUP1~HwQ!dRuSQw;7?o{u{!DYd z7sr8$a(D=Bo;g-#AAAX0EzX%4MREaS)fzKIF`^$u)6YI?-mkpn^}vef&$#Mj6q+tj zxWkifS+HAm0lzbgc0fagFh>e-BatTde;rHoPbQYt%Fv8J_~@4@(S9VOPK@;lts&zx z0t%6-B=dOUZ=PV6kd7Y=W!Urg_s_MN4p;q>MSV8_12H)^_i4OdLJAnU~bT##46UE>m+xBlbDa{bX$uct8Tt zT}9o?!9fYZg^R9%Y&URH1lCw~bq4mj3WM_9#>GGbzti=~7+8KqU>^WlKW*5~1<5xBQ`ygUm& zAFV%src}H1d2rGE9J zK40RXtYKUJB)rG7s(`NGqP2I;xA(H(eRNe)Vx;j@f-G}_ny6()?Hp36b_9P#SG?Dr zX>dUOb9bdXqB^Dv?T3R)|G|B&*fyWST*V0Chm3}a#CtnWb_)82Ij&kn!C#c7ZeD@g z%M)fxh)u4-Eh5r~;NB`^Q*32Wt5nbqVle{Kj}Z<+fe4~)7fXYu>G58lr1*vR=@Gc? z0v~_l|9LQf&_|5#m{bDgZG_$no|A(SLhE@)zT8}c@CIa{;E!Qp+8;NDyTK_$PJh9& zs!`#nQQ>z!*qrMoIe1#M?y1B=9(9V-_2$Xuo6m2nLD;ZTM{3Yp@CZ^f6*mii;Om_o|(0#)(Vdg{%abRbH!o zl{b$7^-U2XQAM_0|Mf&bKOWpOYe?l4ZuIF_eYt98mWvM9{xHBRB-FpTi4zkW(*=sL z7Yw`F;xa-&tC_ow!snrir@&rhZSj+#GNb0c-NH5M=6s(823xgaefZ!a|4z;IJ63C} zcaztZEDMxCEJ*Ql4u&H?$_d$4A?^}tw8+g`H#Jo#0YdOnt~JTnxLml+_YWr`)yfkv z&y06Pj~67Tc{2(iypO-R%L3Dtue%#!?sTngM5erf+bFce1EztprESca9L|Q14+0n~ zUP+c}BCFlR_<4MNIS{qXF4H%71fPw9hs#dpTr2alTzIyNqSy}ZJ0v%i*`^(g9cK>K z$)xOx%vC(R-3!@q9ueN_K#S#ipCU2m2xVqN0pexdR5M;$cIU9u% z3mYV&sb9TNO=_)e|0ZDz>5e+QcfV8I)ZO2X!{<9>e4 z1IEM?9lN`UG>?=zx2HGI%viWL49Y)eRwYr_iZ-!sLo%G7=c$;k4v^l%Q(`5kFkn0R z?$wjwVzorj?cIctnPR$C!sqn2#XjF-{-&m#(FKhHM;gD?>u6uTMDUMi-S~Ir zN5Z(1{yu3L^bz%bNu3c352%#}<3EBNb2Ob$f%CL51LeIxnW7IiHu)R+QR&omsmN@f z@fIQ}2t}3CU>2uU0dhF6*?D>8KVbi=Kezi@Ynn*LPbje%jid0^y_nzog#6adHkH*U zHAGzxEc2oCD(YRNZf*%%h+h&^S~Z+nAsi($H$YW{Qm+7kiGt9;m2 zYMRGmFI_m9%KiyBLqT%_@T}tQs;lc{%#l?7<=FZBBfhvaLUhdrt=y4OZ7z(?Zp}`X ziVAE8Q&ZJ_R^uBNC?i7b$_tmHLYX^gUs@cc{`fcYn+_jgq&}i*0+pdEg-Wi=&STjh zGN}=vH=ABM5OZ09h98b!i|g+`FY|nyMYCe2xaAR4db+DPtO1W2v&*+nw3xMDXLEFC zrVh@rpL@|#9Z|;(kxlFy4jvAX!LID-YW1U4G7rmB>^&e5DeMWnB@wX8GM1TmF-!=IUX8s#7-Xtx?!zaF}-Ws`sYnKJrC>Gy~k zlVycI`aQQhT?{x#+= z#h>WYg$Wz+xZa~v^~9c!HX4hWtCvB#MGbDMb8O$Dq^@~_X^ng;5Ek6$nXsT2vJO)dV3fiw?%`?6vV1*8crR_&O_SWuXz*_VKd?( zZtl-lZj?J+b}7~He`vbOm^Qe!-6F-^bx_=4$Z#9Zkl{WYh75NrGTfb^0|sokySo*4 zD>h)b!x-@Od6O^UM?=!2sodv2m#Q-MTFikQRzU$v5TN^JuO@O+%ukGS^aBT10M7x~ z@XE(><&=N7#wBbKZ-k)4I7WX7?2YgPRXWu;C;3lcsLVWTnx-of2||t&WPV&Nz2OBZ zfzP2v74PF|m83~Dn{I)}hmVeUSgGV;=Zh_BS(K6Qn>GM(u?wBVS+{==c;c2c+EJ2U z-Zb6%#+ByzqQetc`G{kX)5jUY%_NsRGN%q&0-uGythXe+KR$2Nt;!k$N=i`zg=M2N z2+JyRtb3x(X5I}dyl1IO@*qYu*uQDC&CH25L^I+A0Je`Sg4+;OH9+PvPBhlUH_#v0M_;z)l{lr@X9o4_cQ!5z^?xndA&T-7(}?%-s7SP?uOdfi7i?~;bd)1O2aU7llVGw*H@L6;gKvGhYk=kTR*7k zo4nqv-hz5~ic*$vK|i-`F^;pZZ}hDlGKr`(F2eP6*cgW6M8;G^JFF#0+G)DMoGnwOWxyW8C*O$Tj8w}xVC#wIUYod9{|EK$Q33K_M zaqPXV<4H;C#RTsZy!2x4<~kKWJ|UsjpwijdIg#$QStujBq<6u7Nz1_{t0=WNQsyEn z98xCu%YkTBElYxDfIV)OGDa9Tnl?4nK%^e&flzYJFM&UZWPmT?fdz`Mc2$5Nj6Hi(`3IA_kk9B9rr8N^hX05!rDJkU0 zJ^r2O4JfW8`O$qPEsufRP9S&N1E-T( z#kOXVS;x8$5l1v}PRo7;2jJ)Dci4u_Bjl93Reyl^@*ja0hCZf=mszae#H%t-7fgqn@0b!u0q#H3K$||u5@I;HB8<< z?BL!QcR(F``*WGLkxKVCX)V6*H1+1|gAyVh3D&t-#W-qWTo&|K zCYO@JL>}e7c9swv8Ww++CmDp;ScJGTz;Y_x39Scs0$V|2nl%j>01m;Su2+nJ-SHd? z8+A3{SP!`iBfChSM9la|WctI*xw7jUN^2|6M!pXt%vB9O-+z+7ppKJ^qJBfQy|_(V z#aU%Kiz-Pb)XNeenGTRaH4s#$jM7#QpWV+XiR8{I{G3f$-23yyI7SXRkxok}t1GQ1 zs^=%(aOFBtFACXpX3v0asawas3Xa9B3a98h6O2=Bn8{6RXrv|RT%a{i^1LP(8^04cDHOlm9-s`OUHL&B<(Wzf# z>ru7iNX5x_5o5!R#c;M&rI%4m* z9yax@5i$%0s_;W}#&Jvs_l965PzxRam3n|GQw$XgEQKwi^uyOhi7XTBd7b^WJeU+O}U9Tg| z6(xyw@WC9UV?R{m(&Fw+wTJ3RF^z*41_XqP!eC}c$ctw~v^JGzHevMfib20@(KHF` z6?+Y$QYLPuekv;npdd#!@lhd8+QB{y6%DVfQ2qQj^7aiV^{vyjzyk4+9xlS5VYU<| zryQ;+`ZuG99@4L!%V6cNUMTD!8)L1)yeXIB#PK|LryC5ZU@;}<%_5hbPBlgEP0}8_ z`rgX5=50#2l=pk~2kvZDywq5+Fwn%v*No^8W43z9Eu73LueT6!ZaT*B7<@%mc$NEV zIIOmwZmHAl014uJ!L6C5prdo+LCG*L=MQgXQRQl1vju0wqh6Q5*f{O7us8G`WV zkd;1}&u?Fge#AhL2MiAJfe@ZWD!3q0LjhOLo63J!{1Ww$3-$(R-KGixwE02(gZ%ym zh=Q`kSm6zzdgqi9QYq()J=}kQVg{XOGNUE)u6M!r(#sNMMQq8=pBf2h>HuWo%*|XF zk(M(uVc$v793VNI2YRJb82&dz_R#}4Ao5MypeR8g%ZV=neJn}wH#X6Q*s zj}zTYX5-&wy?3RNi-iYBqO*K)m#FzCgY;3|LiIlFHcjD8e~wJm>alCy5+CD09~C={ zpcl+_l1em|bFxTI_R>gD0cvY%t;!-}Vqy{$79RT2b(~ZLn4>(VBCT35;>l7~ebv#IbX-;%&Bw!5OQB`V z1u`?$FOM=nZ?2Nt)}=0jNnE$SL;T|>voRAMJ_@qPj$en!^vWN#){TN}I>ju(w%I)qd%5TipM6V8JUp@mcdZy`ci(U@`@K@+gsUUQsV^RA=dEJSYF_Z0D_G>VaveM9^qSWH#0}#xiOy zAa4}fCWgn#$_l7_9|RTpzzBr;6q6>BM<@XNP`3CC+y&4t&^Y=ga67{rXi}~hyyK_D zeF#xn@Ea0m3x21y<~V#=P@stzK|-fi;g!ntSe|R7*Y${0EUV9{qAJbuV6dfUxlJD% zGIGa6(29VJu3NO#7bShe?gy|hiRJm+5wDi?*AScNxELwhi5-k+NV@}hc%Z6kGrC{9 z!hVm_U6NntqP3MEqF$KLm8aay`H+d!&na7%jRdJ8IgcCwlPv$OxVb9X+PGmV)n6Mp zRLd&ifNy4imb-0e-cU4<+#5US80PkN-Btr=C)Y z=g)j9q4|G*=J!2q-ix2Gd>Sk7;(_7fwV((B&`2Y%U2HcA@hR}ZtSEvqc$p{2^s*?@ zh&yPgi1?M-hdQR|!3-0U(KM<>3e9eK7TWb%XPBg}p26{04MzWHf`tmJCUP6D*ymb8 zo@M1KZf!(1Ds-@wv^x>l)25{^d$YVFU&Nq5A6qk6j zv}H#ucln2ndtTo5(|&eIVsE%oadg;MJ0~OlY5!47re|}L6OO|)J5lZILE*9AS-f){ zQ363aurbU*N2oR;`wyKYR(IA&`WW@r{S$saxzjI&m!yr3F-@lfMT)8Ari=HyW?8+) z$>vmRA8UJgDM8*$KWl^>wSXzKat~%b(>Sob`A01XLVNX(q*8Q(^C#-@ef;b=cn}gb z9%x;D!uon*%VsHC)y5kZOkuzwm|m8n#Is;TP!KK1tEyl1yGceZgUEacQkhgyGd7`P zf9zl1Xz)ucI%qxi7GZ@cv)L%mOOjFmArO;-l4>I)TmIzar1xvoroPZ93@L2CHaW1m z6P=tV64Ww}*nrU5sKvM+xy)5_^zLyT4E84B$pZBd5I^JdDafos%Jy+75qt#kzsR4H zD;h(A_!?K)8iczFz&U(=9dbijY0h#nieUC3I}XigBL!C-M$QFSVARCa!SW!a%owF8 zFqL;iBNJFAmDD3jQ(^-7I0aF5W`Fuh8Cvj^n>@0ddb;8tkMK2tZ%C^}@#kg{XMT~s zj(xWzzNW@_r!dylzZJ1~^oGb-`=zRF7!2^~_3x64H}fFL?`t7!Z0wrm=7>?tx4*{h zC6vkc0AR&SRn|FsA$cRPp>mo5PZum#Zs1o|b%B#UnLtun{h%x1f~!|=x$zXLj6(1X z4&HHG1zhrhXw>CTmNH6MzjBka36R_gWls)NPG_=q&_Hr`s4Ppd#C51yxp7|a`9TA+ zv@~jUMUHcFyA%P-Eg>7VH84p^A1BUoCvR6d?mK9=rtkm4MwUg$`jkaKxg=Ej?=%dR zMmXY7tmShrr#bHpskt-(X-bLIICUO|Kip)9IkX=-o~h==ouwKU2vMLMFqy^A^-}nl zlPEswJ*vUr9d?3gO3#5gjEq#h=q?wfw@vdFUMEffMkFgao02y&#*kNe-4Fl^2nKFX!b*%U$&N_Y+xV_8K) zh|p=Y!x;t=ccLll|7HfFvh@BiDa86Yd!Bq3@f|NTXG%VzFlecF0R+j?>;tIJPz)RO zyghsCRC515RJV@K`gmR9O_n{GIX1k$$@}-?`v&8Pa@}fcv5l^J6RzHYOivDJTUJ&= zWE7y$s)%F|hnZ7X#G@tXfHFOXAwJ#4HXyX>6n9tdbXZ9|lSB5dV@THkB{@>O#z?kh z8V37gHR0t21oT@YUIE|b`w^SUEvZb0Lk41ja%96RJPY|U6-yMw%*a`cDMIj#7SvYN z@7pOeNAG@32BQy2j*?OtX~V>a5Sr?FgG;s7tj-0Q?|-qqjk>9~`l4A&_R&r{@&uR4 zOabwWSP(|@myJI7#NhnY#eR%|_A}ukQ97>fErC`!^PRfJM(>N}Md|<-LSbYu$^`&` z9T8F5;?~hKbBP8ewy)4(V^>uR3sF3BrX*D)@wAlt&|^2Zn|1I7?VV@xfh)bfT738D&2c*f#hxaO;~Ff^+OC06)P8DWiCI5QgJn< zFMvF7q+-!deQdMl&zMZ{=eP}KbRot|#wF1ox8L3tO{C%?8glF}3ZXmzu1u(S*o@j4 z3qo!;yw$5sI-?itz8>TUbpd`rSg%<`7##9~FU9L!_z|UFIH|AOPf=oiz2)N8?g<0* zw7sN-LUCDQ);Wekm@A=a3h{8gSD<9~k&EjA62ZIPvns)y5h4C~Osu!ZdpiLx)d4o& zPWyvVijn9eXBFXD20L~mWC*<|?p?i>s|vxTDl%^(jI`GuA=BP`lrW*ak#`xWc_GZ} z@WQ=_pVwBW@k^zhI)c8FF7LCBu}RO@YF&zLx`7dbT$)`gK8|E~fGZ#Kk1!rt@2%bl z&?d^V@VkO3u=wQLccBO%Oy1Pc7A+sn02WEf4V&F|V0v3Sp~2m=B^{F3_e z9g9IrQ?m4Uf9o39@w+B0l+Z*(M7%G0QOwfLii9n$>l4Sd15VrcmrTq-C^&Br@R=%f zk1@GRGpBLHaLK4OJl^q9C(G9BtRj#8p>fTe^xQLwN9aN&rBAAH-0e|(tR&c<*C0~{ zrD&ZH6@5z_3C@u*ZB3sB(9k2v$S9c(lTs#X;4CpAnX9i^b;|WnN8xX@^PzALGa@8$ zq%H*;#h?x)<{0@b1I|JU1p({?;r#YrGry(}yOYQwvcKiGS#X{hMzm1(q4ljeJ?-FG z);`~|ua38N8+UdOk?aiNuJBbIh0MI}Gkaqy7n|h*p#zFB$EXUc50H}F^fu6F3m-!a zb8uoyNYj|b`?~B;0D3sVn zk5hN`ysmox-;Su9Oi7BqHQoT;4l3ub3TJv8w8;?OR>eUVH0S-13_t15(5s4RK~1!t z#jQpo?kCi=NlVFfAN`%2WlU(Aw4hAbiVR@j|Fr=1^}PPOKb=g2UI7`L#$!@ELzkjA zh|)CPTyObBLfLck;b2xssIuSkN>YfQIMPi(wT-}yftYy(f~s6;@TfqF+8_{=+fGOa zMnri+v0c+C{2Czz4xNGm7Qx;ribu*yv0+LL%DwLj2ofN~51r~9#RChzzK%`jLW%RMb7~TC34u374~Oy+f9r&# zULW&c$?_itn69k540$(8qo}Eehld4)gnW9>pNE6~p#)yP3nJ*gr05PF&*18=c!^RzsCaSU&c{|`d>mwN`q5Ky*>#fG?Ec_)(RwQU25CIF<7s&h?5d+H7tlG25! z)+iZa1oXOG5v=%sv=s?uTUoeIjN``5osUM9Dp>TrfZ}8%CQfS*HtpY2q4Eb`Uza66 z2$_3OxRX;D5Tk*UM6rif=vYEhdu_R0fAqvuT~AWvz6QvEEqgR>g%FV)^oRiEKtsga zVpE;mWagioj%z?u85O^kjg3Kf;YrE7i=(LTX@b$*dkEO`A9b7J(G$I08VZ4kJ{y8S zS1in0Kf^{ZUe)F!f@m;HwGT&I(!8?LiQKVNM?4;U1@OVVyT7kB;;hwUuUWCZwE|bh z3!3DEeAjMI^gHf-)+NIxae0c1XMP+j&9DW;^ZdS9$j#057w06#xXH%)tr-O!W46t^ zI_*rmt#gC)-)%xz(H_z1$L4I0_aA?8<^-i)3YL=A7w4)n62K2b4?rwez~gwPv3URH z59Px)GV=yM1f80%Z+TU+FgoQ$hwfjb)ML*=;ooG z?L&Ih%k~V$$?^vuTJIkVzXWXUUR>b9@e9)M$bz99%CE>N$k0E-6!v;B?UTV{NM|fFflS2|hg! z+c<-uXEql6n229C+P-$3<4O0p3xB<*HeT9y^YrUD^=ftMdvt@Bhw!WP2;ffm3M}ll zHaBPFS{W~Gw;tq;Pnl1B!HcKnMC?RHA|(;tfl1Luy6|HP1 zApJ%);i&m7C54+dJQ2x06Nq4hETe+K2;f8-9cjB|ha=$)9xZ`ZC3QLVtA*w2SdTiq zgqBnLFZ+$c5ay6yOU$pSWp4{ck436=l_!}H%|GoDpL!Y6$@Q>+|K?!nxZ6UNzp6}G z$)Qpt9yca8|` ztA$nwM?M_f)~uSLD15@fNq~dJh5$TIFR!ooO1Jv$#Oik)tf#-2K*9ZyZuIs_IZvPC z$Jj+i>VN>qkU(>u1&DaR{z6v8D5-vNc$LgEX+!rKDSN`)dZL7Pz2%Z7lT1zQRttox zLj8d$V_Lx63-f)g_MVdTkGESZQcII?eSOzuoRek5JQRw(+9cJz61%9*p;?g+mKe{B z+e5(<9wwdFU%wYix502&w69oH&f(CdL6vms#i2#&6?OmejS)y$Q;#@d&D+>$aB_Zr z{CEm`PK@DOtn+@luN(SfN;vZd7en4A>vasRgTs)8OOqSXD;<&e7%0PWhf`%PAOR?n zibngMWj5=P*`Vk@D+8gJY6bM*5r_4sIXX~;!Uloz)DRS#Z^VjepE%*ASgkho{jTEq zMUIB_gBX7ULv5TSB5r*V<$L^Da|$Y+;O%5I>^w(|woMKi_Kj357Q1z)#N^*8DgVBO z-e$gY3>`vgNXZhkH|alZN1%UR9u~h#7MH+8g!6d+eRH{j9>={;YKNWO-QCaJ{#&z$ zC0<!xR~LcAL#RX~#k(&#nzmVFpPp8iE>@-j ziC^!WUOmmez5It?z#)zH2e=~UG-DFOcXtS@+jrI9UzrdRYnA>l6d`C2v{ywFi( z0qXGDv2+&iH>;rRA#FF`RoSf4(ff{Xg}a;U>k+Moj*eJ#${E5p*(wp_>^bglLtYR^ zmVkJ~*;#>eM6l@Z?Ocy?vA8lh8qc|JeB!Q?cGKB z3zYNMJfIlc8=sG^1>rV|D;sASEbVhggz$Bu55B*=baMre)z|Y=2kzkk`gkzzF1nb* zWsrP@*7i)Ey6t6XOaMoiq7Jwg2`y31-YN zBse)c`z@_T{M8`g*?S$sYklK4QqKsU)lj0b?(DzT==J2oW%zO5@0S2K(@;`Vo5PPl z%Tz?xt(=G$E9mh(QEuWP7n&IX^jPTy5GEIVIe;k>GtksXI>QHqT<9vhSIKYTkbu?wR@|eTZb?C$A3Y`%uq2Hk*WVs%_j6K&I8=2JBNk(h{sR8zi(BD(nUBAw1-~xK{@ZQ&dZSMpLx6ZaHDre4;P^wzG^%xZR0l*+Y=2 z0aC+UPBm9x_%BOx=rD;MbdACuiPg7iawejZ@Pq^6rjQ@ z2c}T%)hN`ML9+Px1ZN+m%=3w_F`D8$pfjrlD5g>>s!ueoB%9FcZk@B^I>f3B*_?hvNDy!^wMZWjXJv14;(r57%( zhUF~R9?VO7yugvM0yL_;z`rb_PbY4+-#|}KPc5$d=s9kOPt=>dBSMwJpPrmC(mi}}EM+Ryt4Pc0blC{@@x|qh1@8NgN{pcPMTJAeewU9^LDWHa zHbLQVm4@9->wj8}Ab9j`JWjyjd#<)1k9N3BBM|0$A^5*|mABI{0N-Z2g?)LgIN$z?-EyRBG~&vAdXWvEZQ3zks(7-1ZFurpm2{<3 z&GKNA{xzAM;EhlWbE%eOLClm1PDu^TAeZ{vciMrkB^L3ll4g^M@xZplJIGlGQk<-3 zEV!XrH)lOOzE@EwB}}_kKxdjqUutD-eoF?{>Rg&HaCvP`WA#yu%Tpxc!i)wQA-Z2Z z*_QqYSutvfEqcU_!ylup7s$ungshXTb>Ev9?v>x_xK>CQ#Z`( zgN`X|N2?@e_3ogFsNytm@wuk9HL?^}OH$+MCDM@8BD8lX3V<9zswiach(pHAC93I< zLm!aFkI+9yo|mpLjjCaJ?10&@qGs;xRA7oD$(mViz-elz4oRf?yxV@4@LX3^ zC4BYkekg#hFh|%JDz3Au0Fzmx#||3EI!~;%+A{gah9g?*%kXSj~iWM8B_WNZlRRhsNU7L9PaP`9~i%EuMXwcDrArPC0+8HCtgVr!{ZI zdzlx!UkJ5-=6{20h*^}wUa*V*w)VYc0sf0VGPot&qHgL!N;s6@q zcPg@0jC+h9hMee&%hWO-yqrOUZ9RyjSoY%|AZm!q7rn3|e*jQRoNT#B=qndps4Psp zIR%Iq0Kx<`lZe!{eTP&LF||ktYd-W26eByZo#D?Zru?yMx{Ia$Y-kPG_a`?Wz>VSU zbJr_vN^()d@KDmob~srE1B&&v;H^lyh*Edd>cAgR@9kmi29j?=d)L*1V<)0rr~?Er z-d~y}e>?JYed1|*aTo7N3I3WvoGAGI`iiAb#5SR!D%ofrpQn=@}jro?cUPZxrlafF{t=+^1)ADKBQE&Q(Dk5C1)*tmRDFYy= z35YWQd9+iob}{>642?^&mayDIfzvD!FZ)*b7f92^`2Erx^wi8nP9Ff5Foagw4gA#Pi%k@SBI=43E={xy_64cd-69FWfKiNDVPnsa=r#$IM#MgL5!K9tTHg50 z8dS}}G{>JdbjLSsI3sj(1)3cr*H3LY_{MH|{suVkt!;Z=HV#3`(M#yjJG76LS*$FY zl$fVc826NrxQaHgEUV(6ZHM83Y$QTF`-6GUqPCualvaF}ahW6y$HnUSyf*s`Q$OU$ zfzcZxTm&&U1xlRP5~BlSziuqH2&klN@ygoOClSi934$d{ zNcBxxtL@Bun;ToP%)iaH>#@VhfMS+^+5R9Wiu0klWe6_z_| z)RnT}{=1ENyg+p$Mtg_W>vhr9%Z++ScZYq@i9md&p-+Il*Ky%0oB%USVqx`xAAfk# zRHBKt8jNWlxC$b>5{m$&)yJpqenO>V2JfH^z6nbJ-P}K&Sn7-U{53V7$uUET$!1W~ z1{lmyt!uJQ)Bz(BXH!t!0gVcXj$FNQrCHzXcYXgz*nEuXC4dvmtfrcogxuIaBsazkK zFtbB9Su5+Il5_b64hZR)lD)-Kp-dIp1r%p)lIql0s#Wh62pS!RQ4ahLa|oOY4}-uy5?J zE3L#G*SPtJY4!$qYU_iJ_}|=KZ!DrB;V|9MLHY!-i(!RCcW<9prGC{S=JLIL2?h zWVcsBh+)Yz1&{3Nef-C}0uIpXvLXTK?k(AM4(*&^es`>egVBPRneHhcgsi7*3tAy3 zjwML&?GBE1tTx(berSkf$z3Yt8Y@ejDn3c9TFNZ1V{CH7ugdGpJNLypKb?ZWWS|4g zH1PQQBh*S9+kb>9UkX(vMVggiqay-kj@bClt#En9A{!>f_L?0Nfl-?~MRxd^|`-`(9^HFo0IQY4^MeHwOk0m-?jqwZ%X&HBJ7gjh?R5F>dg{JbfI zBQM7zxOg9iDBAaqqo#Av#NyNsfxhuBy}1Kf;@(XnLM`wrrD#dw^>Jz!zP-x+NPIoY ze_{FC^``T8=WzA&YW4Oh+|AZJ-(7WlQQrNx{GoE|FNgn;@+b1n`~UoH48qs$& zOZ_}u%3`wu$@W62ciV7@Vx&7aK7pey6bD+PO|^=^L#PLu+tmD_849U6?L>vX!8#ZN zF@(7>n_LzJ)mi-d0|)6>)??Fx8zvIy-2G3GFSBOi`DRW|Bs@xg0%8%(Ed@(qktOYU z1Unx_kbN4qoJRu6rG{gMOe6h9a9Bzb2G^hHd!Z z-W7V%qV{2b0A{w?SJ&MgT-zN@+OVm8E_mG)g9(frp7>wQFAvstYTF!I-d1Gex z$9?_{yK1>NZ=$r6gx*W-HObzw`lm9R7RcR_#moZ*j$pJ*|$pw-x*6V7x>C0!anTXaDdzCBeP5)XhZt$Bg zGi-M^xd%ig&hy4H6!Og&KpCFv-Xlr%vJ05b(`cl+2eh-MF;5jLFVz)6{>k!Z)I;BK ztXB0q{H}TDw4XyMl&QkRr5YPc|K~j9v&%~?p{Sew?|8`1UvYnb-6z?{SuH(?kQi5| z|7iL&l`z;8yT17NV~sivBQwP1am)(xT~%&|proEfdfoPWPI9AG{-v7uBYoFZ+QCKq z>j9qs>wS=fPPulM+?G7|{Z3A-tSYf&#R&7G;gC^Iw$>h8{e&xiYDQY4$LZqk9#+0o zZSLiT({DZEipUJ@G$Vy|zK@k$0F8D;NHNp~x{2|=O z=hl+!0GvB6faSLix^v$b@JO1V3<@y`>xoHtxHAYPcnS~pE(E0Y!pVLNN~$-(S$GK3 z-Vyq2Fbk!f-*?dbIf^DLXC+09XZ*f~LFWlQ4mHWWX+EHz-;?(tmQxRo|0@L#TG;2B zM2-SSL(FGDIN-20zhIj}kAp-|Olb6KS}0-~$@@)BETX69Z}Nwo>89O~4uK_)HZf-8-X2$v1eiEvPaQnK z{jM(lzj^b?I$s6|)H>{>G!(6ozyzo>{{H(Ln3TlZjCmx?5Z3T&&G$;qRrF~z9J7O6 zlYcHJkU58FPl^JygO(x)vvu{pYC5ie@v~{BAQ}bDGycDAC{q?G-Bw7y- zZ6$x1Vo$2qeiLDq2&P0Y;m9b}t0sZXD_bIGB^YWGYxHNb_<=qtQ2<8_cRgnWXAfyP z3fZ)W=nnEzhg$&A0>4`|oRsRU8~!|4Q`PE4rqF~D(*kl7iWD?B0oK$_6%)S_w*C$o zxXjp1EK+yI3`x36rl)G*!@iag3e-N{2Gfg$5qyZd#Wr=)mXf8lTLa0crlo6SdDkDg z__hI<?Iwi+g(_kW}&3s5fFHPaI*ZkVlp7p_LW=-%7uVrtQzme{359OX1%< zgG%@(opEp2Ho2p)*5I8k*{rLQwLMhw>8rFR6aKP?3=jacxUJ69!1kVTysAOjH<#0wvZOadZ#Z%Nv!QG)f`ZVHG3>sfx?W0G6! zr~0XZ6FZ1;3t?{XOvotW`P7dgc_itK-+;`V$ay_rG4_y{Nft0dDC_&aA&FKHJS`Of zxBaoSse*$BAj$Rh>Bl=^6&j@V9o2SSSZr{W_bne`9NKXI*_us^u-v zk<_?SZNdIPoczAoPZ9kgc-m71^qFD{fb@ZhV8X_Yih89g_SjtORaK{iPT z=9ALc{ceF<7R;1SNBbVP6tSFLAqUnuo@1ANYY?-5`i!1L$o_eaQ64pdX1zdh4j@JV z3zf?X|0jk3u%6RhNzRr1*3?Y7XDz=Im;(shi}%bD<4#@zuSg8~t6MB07$= zx{aL1nj$(+Qr;)evwgboIQ+f`8RfQGUYmU8nbq^Kmb0WqjIahdWyDqPndd*a7AzNh zO@8>4SvnNGgyUpbKGqu4I%3%T?c>mMo~fTQKE&ChE-u6iS9qj|@+9x(u2piDU%Fr^ z?k_nF$6V*7LVgdd=OlqXZ$qO=bH4HN70;kWu#Y*PzORBiD!`qlr9(Oci#{B}nQ zcVl%!**#Siw0;MOHP)sMp_VTcNmcSf@c7-~l0Dp+VALA;#uEpddu;;|2QddlRaJGG z536ME^I16{4I3LTn6$kfP4LS!Kei2%yx@pD2uhA>)4Sw%Jp=s{gMA$dOkAKHLuI8y;^2{-Gm_Q_co>ANfwg~cj_W!wOg z)CsH0Z;o4TG)FHl;{W*vM4xZwik9;I&RU)RZk(cO0lc5qw&L@jSMmb}|Dph@{Wgv- z2qZ2E9x{R+GyakD?tXf`{q%{r`;cuW|J3sUn(O2zVd6jsK=i{zbzWziGhmZ6L3WLH zlxf?a6ucY+@NbVKh6*xRZeb@~{bV5>!Ap84v=_K$?>)1%0-JrGcjMeo+@c|wNgwe| z5j7U5eQn3X6sJ=GF?&)(!~2Nsw2#dIrdKj(L6@Wqg=d`YJ{mUDtN0$eczVXpSNDjb zb}|ZaiwLSvg-6KjG2%0v$|7j`y!<+-B0{kDdNoXAVN_%bM*U4r&ktAwXz2O??5Ty~ zKVpi0snK(ozV|Brv~K!#Wkw+x&0SasrNev$<= zl6<`~-d1ar_A;kT(O4YG%8pdx34`&hp|GE+P;O zXAe5vq!Y3n%CAH2nfhN+ZUgAtti@w2f$X@DyvpJSUK^Eap9{s0h<^)H7Kx>TBTx1$;rG5JzM=m%@E z)hk9!+!IBT6J!eE8nR(cvTKbO-zOzcl+}mN8ee0q*K*yTYe;Is$lgaAsH?cknQOqN zfaEYq^?+notRI*qyz&Ff2h7$VN3^G8rKNj7C%cf_(C*i>Qs!{F96rr6f?3#*T)I>XDN?sL6ZnJ8xDGihC z4*hCz9R)jnT0Q3%z%NR~RJQEU@fQ*ibIf^T!bDmL`?JT(1H0iM(6{E3?*4wde@n0a zWN-=*ZfDa7`-$hvbxw}7gkS;~aXb)-)Te^RGGT?PwGRBBYx z>9)vDpP0q-9>0XODe;Ybmh}dI~Nm+glK0r+4Qt}+$@%t4wy<4VtPIC5onS{=VH%h02u z{yH~*m*E9*`w_Wk-xx3zTny2QUHjr8{3v@0&-V+0E24q|ZpiVrpU;C{*;e1#pZiSt z$ddS_1(m*K40DNGTXSm=YN+)HvDoVhd_JB8`llWGJ_0uiGzwbpzT zZT|a=*^|U_vJl*f9KPuIxZAVw5=NZcMQ=*5?BjQNlYC8g0OOTF_;nMs&T9 z+dtgtMvfg^9!Dn9MT&_w#?UOsHS@x+uWePKgtTM;g>OsT4vEP*WUC*!mG`P-?vat# zD-P8Wt7&M<2KWVwx}}7cdXSCAT;o5=I;V{3{z5-mCZCpO=I&__ey4a>Nr=LEy%Q;E zcY+7p>zFXc4^`E(rv-dHD@w+;70%PxGBDlP7UdY ztEbW{d)wUEX{Q!WN$Nyf2vKWY8Iv{eOr=RO-{nL-<<{ak<+_v5057qp*Cz;=QT9R8 zy)Z#2#qchGOLc8Esri&0S6j|33w@mi9L2n`Y9SO7N2w7)o_M>gRLx!(=QzcBh=6SM zcA-$?oYdKk@SJhEbo3l;gU+8CYomEnJg>vu2(;)aaP<{@RF)uvWXxt zxy&CbCHLU^RTzlxDMgC(DdSqzSQlMlE&{Tz3x9xu|2IAH>wEJjeWALs)g7x zVMTO`=U={oUao+`PBS$EOJD*=+R5L%M(v(Na9(wxKE>jS*uaJ zLz3;^jz#CPgLI+qx(DAT>uwNz&d{CNJcFX~vRiuX7A!jBmk0QDT#&&LFj?$+&v=Z)oz#&vI; z7Ba7)P@91tdN*N8km;03Q4E}_};F1 zUvSKE&$x0GwSx9?IU20lrTa#2|KP!Gjpi3oP_hk~{OyWFDfwHT{lgiDbVs!4nU+OK zO#v+Tav-cb6hXi@Up1XmKm<6lm#p zo_FT^lgXdVWRi3Cx%b{{U5iX$!|6+N?Bk9%o!vTDR2y7*k{R|sJSP!c-Tl^m?g0%) z3bFMfvGZ0(+#AZGoT;mAPZSZ)j(V+M0dWB~y&EKOnKR{4Zt+W(RP=D75#s8}&mT+X z)3Hn=fBqCcJLf%K=lAyZZt-^@fa_VipZ7^8YZgGRs8%uTx#cL_ldF}hk@PHMh6}2nKws} zNZagG@*)VI*yI&O3ZwtK{t%4MN6V+&%K*O%CcvCyWW4O3`FvcDsjXg-u0ht9ANE;_ zP#`8d1fJ+QaK@?ZYfdh!J6nP52_H2tzx_y}%*%1EO_mt4maWdIhsIGG83MXZW&ZY( z?<7};hzs|H8<7q8*ZsFZESOAP+O2|Tn8c+j6@*yQCW08jm5aj|gFo($kj7CkLFO_^ ztJB9%2#$&;P6|&j5??V%Zm$!ekRSuCXZ`JnXhw-cTkMU~+nhHF-7aCH1}{a@a_Eft zZ>94v&?F`i`m#L8{fy$pOW^B{X0>h&W_w!}B$uU}KGD> z0n0q;QHnbUu{4spRl2w~4LoJ)-}SNWYBm|Xqe+QA@z^7W7``o_6oXr3;7d60sJ?bn`Ul?EnDn0?6%6m3Z|E`|1#VI@+C-1{1U{Vl zzn2aF6>5zz9%*TE5ar*Lz}}FyUqF%LZLDqM&n9?@?Cktu_vc;Da|=|CZJ^u%Kz_Bg`(!btbxPUQUGb?SIO#nq^ojtlTb~ zrPZnL7>-k&%(NNd{*Oz&0cocIy#9XKHf4Qk?W?`>f6eaB4z=@Um*2%bAoSY07o3U( zQZs<9v*=Tb=u`BAQ)f^o#=D=jfBz#ax37K#R>;5qD_&a=Ekq_s8j3vWl;W-oITq9! zG40FJ((1ylk+cw|o%CV|74`B(;L`v!BL>e_RXaCRHQPN|>}+93fOA ze1wV10me1^xNst2>gPWL8f0`77>azCPo8SiSXsubo`iCb20_!E2#z-n6X>X&a|6t}qgyJqET2sh>_?(a``D0IBi9lssGHJBD^xA!laU*|o z;m5Ha0gXVq%{467sq~&ijnYytA^f2vA<#s;w8+HxQ3~Of7~vLTO}X zY~+y#jQ2LbU$)ACy7*bh`ukao(0B%r6f$;~x9@G&(IgfpUOAz;v z>9lWs9^0Y3(A4npYAblV{_*3RvB8w9fhe=^FjF%F^L}(oQ#cGlIY)3Ky>^4Rgc5vk z7~+{O$!8=kM^<6F$xu%B4dKkzs=C%1hmOZrNo$$hHohY%sl$I;-aZzK2kz3pRzwfL z#Dl~=++Y2rGu_yUb5TF*5Q}Cdt8Sz`7_$rBXO5q?X$m;z`TK@hj=7Hu*8O;YV-sz~ zs}lPLH9d!&!9@}wJJyWOMW162u~LU-s34jD*o%ad)^C7#j+l?gp31$_esZ;{Fc|8+ zX6(7=_E}rYu#1tVxJ(qUm7wKeRO;GW-%kI~@$4PrurK~Q%N#|<7%REg`Y%Ik`s(Ii z@bb1YjB^Cw0&KHF+fH*YIrSw7=3vZiY|;d#IK%5K8=UEXuB+*163n{(fW!BsdZBIKhxHt5C1G7M%F?8H$v{Wk|vmYI^z$YaogvC z1KxX?7AWgebQjU~hu_H`j-uj0F*ImuiCv{I`PH3| zQJ`JiRKMbBcyr#!S;}jI>d@$>WlG5r^J++Rqu5FI%qW+hG@v}uZ!dhQbhW-$TKIWpI?QKL}by~F0?E!52-kP|Z5R8L$=6&tCf)Sw^PtoV^eU3}RZ)qemU-1Vta zcQQTl4OFDhR*iow{glEXQ=ps`hu(j?mcpO}X}cSbdme)_Gg1-6P9Ax&Bb0@m;aKsD zNupNoE2x1l)ikRKbqDj?@p+O>vmbOmIwSacWU8QuA+a9GXsOE^X$0_AjxS;rh{*y9;VTb$ZI}7whC`6AfRDaMzr-Tad&L6s+-$S< zFhiSo7i^EVO>;dED+Qskh(i30Ubhl73M-)+MhFa-qd5IIcYX#!xQMzF2IHs~^^J)S z)_MUhiNar=%3XwV0$R@#tDb@IH;7d404r1J*{!--TW|9FGy;tZiW(FY6e_U3d*!LX zH7-nb^^NXCK!pviKp{+nEL5Le1;m__F*FjlvVR0&5^tDg$M`+0jdx`b%>N`axND(3 zk=ddu_wYccXtIrpkm8?38y7jhwv>Qq9-nr3*JksV*hpT8O;=NKYTKT87}rYJN{r5g zc3pSBf^61+E{;mobarOZLLydO?q{*B>cXf{f}QXQi{4ldo`nk}LQ`Ag#*C=2`tWlM zlt{DLO~F__@sHzF?n=5*jZhtryYk@0a9=-D?pMRv5xkmIcIw$hzUMx9|B6bOFxMw0 zxMaKROdiUwclbZjuqS!b$|i&Xv$@*gFHoQUpNR*OTiU`qal1wpy0=WZ+umdZWJ~vE zePPR_j7Nqm0la0b@hzeyr5(Em07a>rBEcyulX_{XG_TF-^@@sCz_eiG& zeJWA-DOGj_(66PG2MrKLMay__r@NIr2Wy+#s*{_)KYL(2v*%ZZy+-}o?cBjYc7i3F zrmTH^Z4xs89bK`f-hxrHY+pJ#ZLLklBFj&LJ>@whw(zwg@Q|OLNKGITwp=~wZJQDJpa&c5RpNk*BD`2(TEZUGt*0!V6 zb;jZ=`yJ4E45>|iqF*e-Nh(V zZCSOQi%txOY9_W8oi@o-L@M#nxFMU%rnJGwOt8|F1kQEemD@VYe(4(yiBCvXZ#vGJ zgTA5WEwAoq2P?i^CdX@{CeI1+1Mx4FQzBP+qp3uvz|5^L31Hu=8t9*5%;E3}u~kLp zq|xDC15}fkA{a1<$8=hP{XqFySF_&R$>(pYq4l-ToRN6t#yvf!#Yv#Z%j7F+PK zp1z*f|H&1oe>8KwvA&-n+Kzy0We*R`MsdN_|BN`bOjf2&uYnsxD#uJ=fGhIDi{{u- zV<(nGc>@5=T!ALZSyzppvb$E%6+3-ZCwyIi6!T6Wj@p>-j_Hde_~^`j38A6%T|WQK z3D?W}@jeJ8G25(neeWKDU;KDwYfsG)hs%4|De(cPl21*2f$v+_M|G?UbIR;KUjX^` z&;N;GW<@w%_O0(mXa2~}wLH8#eq4XaL*YAxPf{dU7cjHR?XJ0YGgK;u-__in@~8P)}AnM19HP#SZZT(vcIIo<$c~Jp^#K8y+uRH)PPPi?itUpd>zM~ z1&5rJ->1Z;k9a5L{eoNf?3~;rU?JMbhQS3(TPTRDUZlO^QU9wj0T0caSk*F}BiaBB z_+b37R;VWZ=14Bpc4#mX7yG6Rc|K^CS7&j)^$8`}vQJHj`8&QFQ#N?*f>yR7sJ40D z0bn8ca*P(h_W8ffHYI)UvSA7}E>9#-@P~JB3IZ=BR{0!Zj-~r8EYUoS zOUzz76i1^X?v`5(W}0NkgxK<9A~Rw({5g0qEN8UtQ9`EzjL@ujk->w2q?o;;yWxrB zSF0BKDt!nTBJLL=9mm;p=t-*n&9*9$l+gwlCN#q@tENG|H z+_f(}vsP6sBq+BHTX*(bcgw6gh3h2yhO+1&nQnjN7_Kl+JUMGZ&c~!8`0(8P-jn;S zaHw9t^=Ak;pWf)Z{2Qcem9hcumHbZy;Te#-b@ zLDr5gt-ZO_hC*Is&*k-Q42L-cdFseR(P^qs!@+Hu zgF206Zj(n+odpv~;R`!*gfzBx)8Aef-|& z{kvh=&%6Oxe&<((KIu20^*yo@{W6%BawP`@4z7>{ z&@}EHS*QZc_cimEzdA4?@f&Z@io8xWicngMfAx{O>%;d*%0tGH=Zf=RJw(7dMrBWq; z0-LvWq;pEityswn@uGhUQu>WfZQ5;2I|6H+9-q|{_9-2x@Z|>1tPoo5BbKnD4^Ov_ z;6;C^cs)oQmnt=kN=2emFG6uPglWv)g8{y!j*-A}v6OIfcEIiNK%+7IB3E+jUe|@! z_OLrb;!q^z&?In)BG=mUr!5(G{}Z7xhRQccKN)xrWF1*;zx@YurbWH`eLBS_5@sdL zLl7U60$h3s0BSBdlY67`+`g@`^0x5Dr&ecfP&xrE-X^!M)e(tr=&t`$C=)Kbk*FV8 z-!UY(o2djI_9k1UIB#}4iZfL5xD=8TJ|Ed9Ki+br7@++t|RczQ&@M*g;+BlN25DBHOIVQ?=XI=?Icl?gqT1e+pUnE8@QB0B-H*iQ?J;yIT@1(FZr zLaOKs zii^P$U@YMk7nC~@rS|4LrnMwx0U~{>4Cbm_coPOyS)@?(x zKZ`Hr|D0Gn(*NO_c%~kI9oJlW#240rl@6h&65bf1C8uMdX7zNKZ)Gv+lCU&gsL2?O z`C!dh&3Z9#V6n`U)Uhmig|-sRIq??MI6C_8+uoP10+AQX4ay^V)QrcK9dQsRg}#-2 zi;}dg73=TD;%+57cmfm=uxam5KP?O1oc?93n3cEsLS70?lFc?vdhSYqB3V*2*1nF8 z0u{e8g8vHNKbil1X?R9LiY!}K)O`qYX@ck0HJ6G5C^6NcmT+m^xh-1-O@8zpxaSA$ z&6<8#oUc2!N{~g#X}Ab)&a_$!#S*v=M|s2it8O2EMVGXYUlz-bSx}^zsbiaPhf@NW zE=>|O42-NBEnHPKA1p;bg{S|;$Mg$!TDz0%uX)dVw_g*_iLH@Xba86c9Y1?NQPy|e zpyvl%@CQCL6%5CbzJH+j_cbBtOb|Z*#XVDGZ0FGGWdP_NjjsPVZV>j~u=Iu`0Ft?_ zaN{5sQn;%LPcj6|w*#JI@bvs3>oRl@-+(v)u@tyi+ZBH}jA`KIESQ#nsVuu7>>7^@ zMcRI-BwP}O!R!7l$W~l40t-K#Q(UHBe3@rO^&>B~2EF#YdqH+%(K7w_FIIb=@M^>% zJZe*lS7RikV@Sz!codQ8^s|VT!J7k4Vc!(oXcRDm-#rB?6_c2nawRXQ;U3)u`TZfy z^IKtYZFT2A0;=@Y0LH8ZL;^Q8eNxh}_anL1GF2EBZ1%|@N^O-O9pkHQG`yU=X%sZX z@Yk>)GG}tKCaQ|M7xY)|nw9$4(Mc|t-xZP92wRpS<_WI#Cn1#UL?PItb%1)nQ5m&W zNPdW-knDuo!9}e0^N-ot_k5yTz<$}mD-NI@?f&^gCdmzyIyHl&YA(+lTS(M$bKPC;={ zFylrk*kWedTCC9jH=b{*y8eS+kt?X=81=A=QhlhX*5ELgW#+gwIGXl=4Iyz{14qr5 zk$N5=7C~VP$5{s=bRaFb2Kx2mAq!!9H41l;fKZ0Pc%gt&#`%2}Sf#F^V6gDiFDS}% zmP~jN1|$9^WO#B8whTc8Ss<_yhrwlG5IoM=97h@p`wxw|Uv3JI6C8#e@ig&gd&loD z+w_Gq69X>a-?R0-VPHvQZatyjL^1pnpZ=ibl93PSkdRdHD7hC*H2EUoI*H^>2oyuC zLG!TmAJ_-jreQP{<-xcEt@IU#aiko32N@UK(A5h<`n)^)-FY>T(iTY` z(`)b*B+m&o@iAyK&{g4}#9(~pq&Yo}wYbnk;uT)ziet#B4-sqr7DL-a%e}W7O^OqOIAEWLI*NxCaf~0=!4+?ObXYg zM^LmZ*r!hMD!Ta?HuqOfLXqBn2BsU+rxqD6pQ_8H0HwvHZiIVI?Ot_hncqwa z^x1@N#W~fba-q6Vb|%vr9&vZSoT&o(A)_nJc)#7xqkz>2(K@*4eK(xdZc>jfD<~=- zxDC5b)J?CcW@fm!E;xFwyt-~C+5pz96~HJ=p@LTd4CWTA6q2i6s9#w|P!i>^xJ9z^ z&Akvnm$jE*fzr*%d?9P6xCqq9NZD_Jjs4?kHQzj+m;=cgY;z-i=b!|we4e@<6r$~Z zB)xvc}l^5i%F1Co#!h^}Q)N447OyN)8+jcA+}ci1gLN6)B#%ka|^iO*%eImD8q zUWfEf*rG*06bi$U5jf%;Ytl-a^(=$L;Bw}jK&`(ZnKjo@t~><60hGUiPSKmBgzY`b zf4_Z%F8=%pJn9@A9K4jypcs3|f9yi}k2{l8ttNUL*IzkStVrU_> zR)i*@|qd+NI4l&Z)iGShbbT{pdFnOP^ zlVn%VL4G->D*B|A9JQ!5oOz*f_7to}XiUfsvb`B*^?fy%7E)XYG^VNcrc$x4R7>ks z`J>S|OmiLaI6N^WkxZlE3<_y(mxbk-g5P_12x|N42!~opSN% z&b4ihwc9ipo5Q)ijS{lkAlhu^%Vnv2^4DB4@W|E3nzIYSkl5hqJzd+h;0#AGeI99z zo6U%|!LAf33fJAxnpuI|pE7*Ck%_6wrU&pVvK~u45l1la4D@)-?`XSAhkxLibx&5w zPQ_Af|C&=E&izlyof%beNGTM!qAS(EY$y6}71n`+l15-otLrFwkV7YVDOb8}!73%r z%G@TP5c7-bB$yOR_L;VylNWgz%r(gM(K~)m9DIId`S$5$!~BP!DA8pecsl}>2QJV% zw*Mv70~cvFx7AVVZRPL8k)?~8;$j>oa&8$a_01WD9LP=~v7eTxy^9$)i3&wtXFQvB z6dBmBPt2ju4oL?4B$V*M5j#4kv z(VW?ABEdln_g7BEk`N}sZ#tGCuLDJpv0N$k-Oa?2zl#J9U#V(QY{C)fX`9nslOG53 z_2KmkzDu=5EC`(>%_Zinz@tszBo>h6U(;%emHFH%6+eD0HP&+FhH%WvJXv?iq+7DCp1NxpXM2ZUGY7<% z5ZXF&-8g(*JmQW#wCNsg&}>xnZ(Lc7eb0xIrblLR5ewJ7+WNl>Yd^(VpB|Byfmi8r56O>urUx$35 zD3PSX6vzAJn-?kuBjvOxbQUr~F~D9>kEW^sIZcKmOR2SVwHzA2uHijc$uoLg&YcpX~q zsWOw)4d^$N33N79bPQ&7QYeqZJJN;BOZik`vcnj95^SDyNhD(p>@{0)#J5Ouh`Gx) z%aPPanmf}9y7|4=r>8D>(`zHSWqcd=ryt-=0j_1>i$VQv?rM}$Wwi{F@VHGms=#yI zptYdsSHnWP?D=nKbEI0CoHdRV2HN4wezG`3ga)K9$xtZkl1X{>RD~2X87?Z8S=6^r z|1hD*OD&^mEN|uQ@bl!t5~s^YfznI_cYT-E;(5Aal$%$p{!xp2h^b0d~snGY=kG&iHK=@bgUR|uF5an;pd=jE-` zC+8Qv3^cXkQc@HX!yYi+q3WVGFeZg)VPw)YHv6^8uTDL4+;XdwV%-|kl%b^F?$Y$RF1Bi(!?A-Rk`Q#z64uKp(yIB>A@~_FBw`=FL-DF4OrV(T zbkeVc%$u7tJFapGq~V+HQJ;(twO7VrMk6{52z8dBWA)_<@x0+Y1vUx(dA3u)&ttS| zdm{5dgQCg0`7Ii3)8)9OEoW*iQp$jGUqKfBIr}=o0(+zo8K)iDYTD3loTn7Jcszz9 z?1JMb=b;u5VltyXV_U>zz0cJ_-Id2@&hK)aPwB6d|2AipG1_yHr_vDr(lYP8y7X4n zLije=HfJSwE;IKuS5j(==yc4MELQY0jeO~?^sX0UeyaP-^5ke{8~1$=0sRJlWK+N+ zXU?>1gJGdNg9&H|&JA3)X7|VL0TY>zGXkt$L_}LWV{5gWgXS#nz^3(`0gafopSW^h z#SfdNw7SQe?Nrk5i(gK5Dqfa)X>1r>#6CYWh<1C?5Pstx{p;$Iuz)og5==L5Yw+op z5x~MS?DU7fWYL`2vF#B%5Y9$7rQoSWpf7;64_M? zP|Wdr<%U~=8Hq`y=7ylcFide1=H(Do@^?W^c(A3M-eAew6!-uFpE%%Onzad|j_ zg*2O@IV4E3B>_C26l{9AQR|9;B1WzTz-}V1HY*DHb$TDPx~>LdDo;t?zn&szxBk~vhF5HQlTQH& zYpRDCh^)Ar?-#Yuu?-)RjiV63UEcT1>9UcHSb2P#S70~qj}dx;l8Zch*B%sJi-oHl zfVQxoKhmf71j<;^mBd4m5L0y=@jZv|L~J2gFSEi=0K6k9q2CBoKbS~uzg>j>dpOlfhv$O&r@2J zE_HFuP9!g(AJDEHJcW=L!+>POjiV|3WtCj}G)`t^8JJJwj}jd$s;zRhliVT|+1UU` zeTD2E0vJL~zX8`E z>_5lKhtFk{Lo%#X8L(X8J~-32#;J^uG%h4{`sq&U&{F(12oMpMaf8?3C(*R_yvPl7IfGm+pj)vF(UDng7-Me2>@6SiTH_U0PwPFB z>GW6qU;4S69O*)XL0hz({aRk?)%0g}V*EkSi2^_8bOO1u-~I^@eyt*&U~bVIL&neq zRSu1sjx(MkV?u^EjORRbNsK16!f%@*E)owDYH_K|CPeACBNG=`Ip5B4qe+B)$xP># zOoh`lnuz@+q;C9SjOyEYdsUe)QRdhx$pGxYF=C>nG8!NG;RAlQEY+{jCCg9#oTNnK zMb0v73YYTkrB%{X0kfE1$kv21tlx51*TY_~4|TlWGi-mVPNgSEN*uf+$fUKFDtE-s zg3POnnk&KVn7h&ko=0}V)zBjR{*_JTlF6RtlU2bb?SMHk4Z_Yz2E8$&5rj}U;h>mN zLJud+u6;k-w>_O+zKeHJPwqK=++U_1p(vz2SWo%YxYe|48Pwp%aY?#1aDGoQQ>3nM zb;mk;8rG9?nC5(vq&A(U6Z_Ld5x!6X}@lv@5u!Lrts(qcDg>I+g1`W^unN&-|i3!;nfbs0vL zUpd21Mn)Dzb^vS5E4ncj3d4tuHJlDlAI5!UVd-AsZ?Fjmi7|v;AR$q-v=tr@Nb~gZ z-+w7VjaG3dwqGYu6oz9+v(v0s-D~i5aqzZ|KN;3zs{hQ~z$c|VZAtxXJ=CU6f**x= z=1GR3U-^>SXh`qLO$v=ALc1Kl5y|}e(_6Qm*ET*~%pC-qa2lS2V281p-9o0~*)+0~ zO0p4`m@wSZLD-3swYNT5390V7RWWIMmNKY)zPk`t#l2*a%aGD`1obnQZgW;bg6wC= zDS=scvZlt2;1FM5yYh)>;jb@pAWh_wIugxg)`MCelC^vC){VF&+--CvA$fA%LydH< zzUSOST68J~wTRuZxutj2-!XsAm0%-eSIc}5<~>!eKA;Mkz6H39=846l-Gn1KvjBG& z8;Jk(CI!r35zGF-zf-CmQcgx2a>bzoi?^G$`rDYxv3OLz<&j;%MIu{_k&Ib3Er@+o zcIBw$*UVTb_D^GCSnPhE^@}KQtm&&n22;|rsWiSUr?gPXX_$V|lnVX{ zuk!HG{x7ts5Fd25wyOc}(&Wl%^#h&jmz{-}Hl$3WJSCNoyp&GtE8)1NKsG9rOL_Wa zxh|U%H*r%=Bj#-ri9a46mCpTU4G3ppjgLb@MpRB(|A;tBJe+oX8t>hFAX=Cn--PW& zv<_)!V_L!EbXgFE9=R4Lt2hQ8MJ#ppyN0{K)O#^`)7YSb)C1hL>7Ya$j+#t{eiaSA zR59338%MWP;&ivMqEvM?wMQ#>(?%T{6;PuvM45@S;Y2d_ zMDj3L_IW?1yZ_zrD_?UZDTz7sFHlt~4bN$o;K}`9hcy<4Co}Q$rBWEe#v*Xit)wUa zRcPvSdCgTO^IS4hyxc^Y;iB=A;6x5#D^jP*iB8d&*s7VlZCZMULnmTVx##GLBQvMg z1CB+ozVBP2)+(bO0!b-EPE2z1E$Rq3SZRgZ&_D@o=w2auR|q`4ixkay$-HZJD}q}0 zr_{|1i?jl6n4Y*gSJ{tz$$MXZGxZqW&`Qu?MXnDQ7JY*?fBxiAeKm7!fqK8J`09Be zO~@nGrf zQ&P8lijUUZc1nDe^r(nS*T?gqnKc2`NaXSJDR=EPdS(L@1X&{}lcIYz@Wo>i6Vc_) z@@%$QF&%v4y~>DK2w&d?aWUKc&7?=yL z=1mkcpH9u07znQ`MU%bMUmF#!2baPI$+F)7Gt{uLj=n61K)zW-Gfj3siW<|dtC2!? z;amv8%J?i5Db`b1TE-Jc^7!kyz*3zAWWd&Vf^JlnI}eTx=qs zb{JP#g%NJdJ#Jke;+sevuXZ1tdFV2VNMk!48RWio zck5Z3zQ=Cy6l&)AU;FwAU{rftK29Z@Tt1v{{Qhwy5=mt2Yjzia3b$HkG&uWuHv8Ik zV>fejn|C=gGqZVj|N3^rB0)H!;HAAFVDJda{a@g~?tks=)t}qhgpZwWd&vI-XaO|V z-WOA6T$&~2PzVAUve|tB%q-rduP79@X z!mppgDF>gS(V^4y^H&jme?*Ar0W!q+djM=A0{VXM^9fs)4#Ep-jW9PnPXe|TJDvhEN9v)W5ESnQ+%W?aUG_=xVq&MRpTI9EB_F?~!UBM0AGPShnG_DoS4) z!j1ymnYO;?3Hr==<(+9VN)n_ieW4j4PF;wwK z4p6*%>?CU;B;dH|kqXy!5_CB)#Po(dbZ+{S z#gjPqX3navs!vTQ+v3?(mK-drnAS6uvTE(>S%ppe1IPX655VL$=bpst=XTzu|643< zti`5{Wa0==Va8X6NI{>Ay^FjioVE8kE$E1Xd_EE767bi!RkE*+dxmwhRqpAsZ9ixi zP;M2{HHvSpu{e5udpWjkz@NFEsA=p07!aV{$UQ?r@|6*5>CRR^Q&$ny+e>>GJaRSd zCTcqPGU>rQB4^qz)Ti;G`;B%L37vy`_vV1uuj=Yj5>M(JBPmMV{y*he^b~e`I&~Fi z1h$}WjOSD7Zxgp`^ywpH&)Hn;zT-)NKk$s>>{H`l9G36k3DeQA*{%}JfcZ)K{q!<| z(Ynh$z=blrba;x4qN(vCZf1mNmk+iZ48(Z~9F6LaYj0nab7&=+HRYuKqp*>DxEi`b zWVOB(7Q!o;efiisR%zaQz86jeC$859%}z^biK2g*SsyE`-zKrku2>Lsi<}Pme=R^; zAlsrsn$}h~k-&RQ;pd)=kgCw*JZi)#YmY9V0`$$#qgglkU3V3?i2zJh-}`03tDfLT zwvKZ`E&9fwMIIo$3-DD6^fn%!y*@bleQbvyAbcoN5xt4Ub)!#8;Q+KUzOSVJKJTUA zv0`N;bNhk!)&V)*6#!O=9Z6yJaX0`d3y3sKQ7=F-*#nlRMq4E}Y@1JYlmp8(8GVoj zLtZ~t`Pc=Ggx~7r(1wo!uk;1^`8m%hbS^4KfgLlzbO@NZg+hpLpD>%g;|_wafA1w& z_;C&bOPUjX%zmR@;K|Bj)O?{p%WOCE1fls4%e_sy<%=den&IjjNDPCGoKBN?Y3%{q zIC3AqbDDZHXtT`|4HiPr{e*HZkgmABO;x7w<nl9)v3~;3e_2eP(1G}tS0n&dDEgQ1{%Ti-frb?X+j_F(^Mocw2ZlmzSPL5Uwxr01Se9rG6&&Ws~Msp;8uH*oh(k8HIH@)JSIGzMCow_Z3Rmb1lJDY71KN z5q2&pD9*2i-i7+R4arWNA*^KT2@`ey-Us)iQxlIPFih>uJ-BKuS{z^~EEV+sdCFQ~I$r>X%=X z5+o97G=cO0rGFazyf{i!(pQZrRr7Bz$t9wW<iK0#s0#a7hNh)Xj$WByJML&@b(%u-Lr(cVx%>ju{M7=I-l#l9UH1WhI# zC2F8!IlPlIa8eTNW8FB8?_JjeTn`9mc+ZqP;>ih@69_k%PKBIAjm z;aoj5j(W(pop02SsN!)0mFA%L!;D|1F!!F7T^8`^f*fyfP%GI@D z$h}=vfCzAJ2M!;<0G{8_PM_I35(!#N#GGmUDeI=<{E+$R+>jxAxHXqW?YcM1<*AW) zGqba1 z)A<^JG#}~Kul~*|c*=So_%n!KtoLc!rKd{doMPm?ATe;ZisV1WflhrSv+L~7ySthA?a6%~2o8c`KRv%l zf0BoGT|HjElNlW#m|#a&1tKA7t(D{UO8C>8NRsGhRkhyfOTDH3B4^K(#=0BuQ&Z4l zTv~@}}7>c(}Xlq~=Wp#o;ia@gslypGf`t9X})SqiBXY$KbOl?S(Q$+YMf(QFy9Uhiol7BDK->g+ZU*QH>BK84oy1 zF`n5xIQW^YqdDiEy6fBoBzL@M`!_mq&|++6KIU&U%auX=NeSx+bBI@94lW~Q=EV3% zNvsxH+hR4CPxx_oMpr_tM|A#IkfKR1)W0!gz5o2}SsHi|aP#I~c{|Iv&v3Ax=4rRnI2lc-)k%#pDck zErFs&DKj`H>m_#fz-Xn_>1xd)!R)IpLxZPC!KtntzT%D+(_UpCH8HsCQis)r_RfVTCiNRP#V1jXGIG<~B~Td;?OSmxZa(VgPA-SPk${ zhTAe_(0Dg0Nb-0YHKo4l0UoMe^~E+xzK^0o%5NAr%gjVzoh~z7Y<9>P-!#+J3^Yu}c5dAt&wM1_FDAH~{2M z#_{)v<(t%1!(2xCDuvCF2Nc^sX0S5}Ws`jX@)}*w zPY8It*rYS5?va2JS!N6$?MLM%bn-$$MtkwIGXwpbu>gPn`1RL`S2n_1{)msN3nzW) zH9v?G)-D6hJ)p}q3Y+}PMlv^o2z z9B{<}ixh~{M!6>sOnUC3zNQJ=SLIR}nY1=3vQt=-iV4J;q4)<#6yX(l8vn365=UCH z^?K;?itMz}Q%9C(6>ucD)qeZaV^%n0V4UJXM(TIC$#0~-+m1pH9iHvPOKuNV14`z?<@Sr_OK>CO=2{E#nXqaZU zhwu1VQ^(xw6r;Cc$_pg52(O&R>6U?aepcJ=n;K-U1( zV%ja8`XO5y)3 zV;RMixbaiB(m)f^k1dy@pZ_ZE4YI3}=-E1>il^@0as$R4BBRy4n}f+pfRgLa8KNz- z;;<$Xm-w~0IAADofKK9Hvbqv6qB~Lr*ZuTD#q}8Xm~B|Zm?UOq@rCqHo8cNmrr9^C zcqg|pk;a?1)?qAL!1V}NE(dQ$)0S7V!a1N#W7PI!RW%BER(gIA?`XoT?pw25Y$an33e%57~~F}uoKbj zSC+OJTWKH@)TZ#5`9GS@Dk`of%EFC1Gz52dg1fuB2G;-q0>Pa|65O2-+ylXaySoPu z?(Qy`%Re(~^&1b+m%3GT_Sxs#{N#dYXQxQm>gc4(GjE4pXlQ77abF3XWXQuwX12E+ zB^Ol9 zybt45vyS~>@=7-t+eqDymOZ_|1WW_;GLOYCfO=L62V&7Lkm#! zaSRV)H@eB;RwfE&eC+t_eZPx-q#mK=$|9;?tz(51>Xl9!<;G3VUYIjR_e)`M|JJWy zv)A3{v2)EJtNt-ol{T@i7jekJSGZFHObr%2nOX8_z+^zx3PK#FF8!GTHM~x3KhI3_ zG3;g7f7m_I&C&qHXlAwjdp#f;-Q#4&<-E}Q`&sX8UIPkx;r$J=Av|sG-a}j5-u8R@} z>RaYiNMch;o*Hn<>$qA|2@1&e3-X1j@Sp;AgnnSBGMWc|7rAbv*)Y-x4J=!7Q&ArZ zS;l~$f?zR6vY)k3xzK0E4%uWT^Dt9Vj!GBwtEPf)Hp?<3vb*QW11~czo>p$}{2ID_ z*?TsoG_KtC{M2H0u%+<$$w$6iJrDz*ja{b3FINWojS8Oq&P_@O)~z0b6A8PCb+<^6 z9rM88;Na`yB7+ly)R`~o!#|zfG?u8cYvNBg956`akP+1$4LWWN?tiR3kSHT&F2Ci1 zZoXxKa!v?cHCNt^a!wS$w#_}Z52SWHTlt;`lRf{sc@qEpMvVfLu&|k#nW;Ngps@^t zkN_=_iKG$j9!69OFKFZDjqC9x+z7_kQcBY^dC;?L{X4Ewf)5pJtcXrR%qZsLFIm$Z z2fWQ$;IIFLuET_t3G)Ph+{+ZzMsJm8_|sHFUsYbh#{6$3;t1!-KOw7TO?X|#@h8UF zMW11P433gs281EKp(4YQZZ8r?KkPKPjE!=_J)$h30~8Bgx#oK=0#)eXOaK#FZ@f8d z6PK`N7f! zl}kc~IntIIHJQ={OI5;m&eHQyCBASb+IkhI>!&MEkSp>%Cr@X}RT+oiPrGVkgkvyr zB~kIE=J=Y3$x&yf)YES@z(%;Ma>9BfOmJd=uj9Te92$*Ij3ziTRzeFh4y zj~VvjXkWP_(fNL2Gqx*KK&rf)b9u8b;9db(Rseagw$?|lLat37rBaDi;iqscVv;ocReoY-+%#6}k{3`nJo}>r z*y|5zn2gvNzJd7-BbTW|2J_mgHH~gNk;!LdXXu682k2c{J@2(rGxJA%Xhu-s73(Gi z&7>FRMEa_=Np|va4jHt{+1h}&-?t3POboqyD3?P_21+ZhYIAA`L^fu9eSM)dMQd^1 zZ$$l}V45wqx`yFeU!0#0Vw5KcpObKtoWGrB*@CijXD?PJ+*tFza8JU5CKNxejh)$H z(4MCUSi28%{R)jS>@ess^tXsB`q+JC60T9;wgS=%FXiaSnQ-$#Y!GYq;^n$muB1^z z-@_umL|hnfgO0`zeCzTnYiG)k=o42vGEgfhDs% zeyr;qYwr;Qx7FD1ye8sn9*r({B8PoYa>+Jl#4)Nd>~>7d7%6FWEcED3jDq8S(R?P< zBB+QRE5GItdmt1G?IWwcw5LfdSKpo2tc+7)i2~|fMjp)OYQDu6hl+f1)aGn~jtrza zd>X{W{N%YAx0e+cC8u#6146Z3Nn=L>v-%E@e*8y6ISKBfApZtJhv_6igzEYDeL4{K ztP|Fr$G~*IFJBbu8%`Ptqe;&b;W0>S@m_F;03G&}xA9>NZ^}XE9M*pPEHD&Z$X@KY zOa0o``Ke8`7=l(cVm-6>`-knGz|M_jx$`jdqR$o=HVrGY?PR;~C$IckLR~_u_ooBb zi=#7b+Qm#CFXm#|O-1a)e+5-~vtiW4CIhDXu4AW%OQgdxnQe4nD=6QNO6uwZMdw5Y-Q>zg0?t}Rco1q#Lu+cyJ25d>X zn{1unR_I?o;8USv#GV6PR224zu9{zk3)4U}96PEoFnR%aP$ICIZ;7M)@vDq0!3h0b z&f!J2lWsTD$PsAgEcVhM5FB<0c-n$OcVq3T4KDiVLTGvgCbJ0oQle5Cj+8nywSUssUR#S#KuSeg-A)}Z794)r;8nEXz`1afCNr zNK46)zrCd_b8Yi-U4hKZxTx(^^NI9MO;NO7m3$|R)~TeX^mMk-@aHOV{wSSj3Hs2Z zr9e@VdBu>AY6jxRP>Xgbo{bJRR!naL^|eGec#UZ(6Hq#*Stohve2B+80~UW5ze38g zhLavM?tgY7)h=QXss`MWZV4l_dc_vLh9`&1_*e!UxHN`god+s@cB>xM8qQfg1XX3o zM^FYj4G)|h`a2Apla{arrJ+TSal62Rtt0hKLHCsl zeGk)wmp0>U3paOU(zy~On@I~9QX|QW`sIPzstMZp=vP5ol85Lcfy!eK>WvULD37q$-WArQRHi1ka|C2Z@7)~DCpzmfX5#v>F_uFY1nFCe9Q~2SVih!C(r{=R z@NVn=SSuce+CZ@GTj82H$>s8A7FAie$Jq-J*&t45XxxvRkRqO32-e<0>ez?jeh~Vz zrN6WK&STIgr6hklO^o)oOA_*LKVaA9RQ1O-HCj*tCEH$&{xBu*lj3n}a~ z9y@I~XiMF8&>v}=e@~1(Zx3+-rV~b@K_-e~s6k4sVG-JoPTkYnQFjcam4j@<7_0Vf zp}I=K(otw%SR6BVZS(cV@#Q$PHAqn zim5R`)@4|W$JzRFgR%VHogc>fmrO(b?s!O##N62T?8H}%!*3t(5KB|H&5`9XzI1k7 zfAnL7a+NgUFhadV%#GV$sn3SK+ry;!uRDxsL}NPxgSHAtBF$Co)^Oy z;=-Ki>z!4-w9O<^=n#C4bVS3D2GyP11O1Gk*=`Hh_j;b9f*|UzlwC02z*UR4RfKdX zHz8wv@8xe}dOV|XYdWPlvI(xyG3=PpQ$UdB&(yI0j!^;RLniL^Cjj>=Wn>`o0p^83 ztn;Hw%);KL4dwR=Op9K79z_m?18$>VPr`~?Gw*O7g^)-usv1HCiq5FW9uWPX2LgQe zo`7$^`39<4o2>J{qziD~Yncdmz4AOLOkH*T*S@BIAa8dfUPm3Lp+*s;5+U2jsGXI1 z-a?$fl#!y@{eyr7&)7@C0)^KV8?_#Eo3=IhmGpoQ!I{z(%m~&dhtq&M8aefX&$IgK zc8qS4MHSF8M=q%Hs|kgJwy?Y3Vp=IpRpDT~R(&}CqcLwD{RtEYUBsgtMW|tmRglp}8+z=e%2)7~7gh36WWU-y ziY7T$sGT)JxXLkWn7faeRIA7}Rl2GOnWO1hWI|rWXrm3ZN&zZQHVX}8M=f&w^o68C zVzhjN|I=~RaBl&{Ne$jCRb0dtOQmj^|WNg6G1i`C!_lr6Umw zN8q-)4;$f;VKO|Vb#CApYIJeGdr{167-*(k*6lC#1vIX|9PzKt75ZiW<9Hz>(mAdx zc!FdBsFL!D!&cd?+2Xli!QmUyO^E=r$W^PB!wH|Wd9uo3C#;f~DlzOrXpCs#`S1wxMe zK*P0@C_Aqg4lBjK8=-)Xb>;`1!Ynl9+2Dn4FvVg(*W#SvS@A7_>?k9RQ0@{xD%$2PU$Dl;&ebs!?BLu=jUEa zWrThRBzt=IiMFFOhjKsyc@8T%K2+C^>|A~Bs5XH_JAK)7*X&yIC>vOg5!-in6V{^sLme>i% z><(BuS3t#9CgScr9qJ_x;*B?PUD9&mlW|zbygYl9nVii?E60d)Xe?_9?Bu(hB#LP6 z9;#fo>d`&f++AlqcyOW$%(~!9#tH2tpcl(TAun`O?3EW6Y=w`ioy22oqGPVFY=KMEiZno%(PfOcp9+P{~z ztyx_YWEJqzMZJ%ToM0he!YfXt5q90{^$! z4FwQg?(g~TX814YCWUl^d`jJ@Bz zZ90c?9*;GUdJ`5{rPB-d4PK1Tvix&m_Dg!{jhZX#NEx~Y5Wrdd(@c&+bsVrNYRwzxZ`YS*79NeIGiFq&lIHx42?CAHYt8as==e~!@r5umfodg!=0_QvL&DF z0l%er_lA|T(}M4?5|@#$Qh78<^w1Y+5K}Bn`1mjo6xO@mD1IzCHYquAsh}_@aRSi0 zf;gy8;h_@Pi1bKcbGpwhEA?kLewi+}tJ+7RdUo2gt9y+zXv*fqx+8uQfSzj}jQ zRk6B1iZgr=wwwIWH~hd(Gi*Z(L(bjXwCO|@L6PF+l8&Eli6;J)3B`&9y5Cpo2BG;u707-3CKOAHI7TEJ35Qoz=(Bx z^6iq{AVK*N;e^OPp_E8Y!?s(r@@CM0*RMiEYP(^A?%$MLDmy~SBq<{_zy&a2PsL~+ zF#BIU_<~bh6gy_{Aq|LaslG*{?{Ov)g+Jz3 zankjl1MGIs}NS}GQ?Fsev+NCPqbpRXd9n@j}-q*qLmAEr#{K4y6kt>$Oli_Y< z$p_Dw55)V@0uM@5Bt@Rzp8SkO<~KGl+aJchgR5pJ@vM%4g1)pktJ_k8t{A!JqBmUC zCQKR$gykhIH56Cd(NTOi?1rLnUJiRd{IO#stATPv21~&61<>7_eK3qHe>)(^h8Q#$ z16B_QAUtiodSE=in)sD*K_TNOaYL$fWP(Q}jN2oKgO)c_R;31_fRoQpwyR54f1z(b zZ1AZPm<H2bgS0gbagZCB)L#(9lVtI^B_`h6NyNWIA-yf}B2>)&NLTT}7;R|?uhRCK& z7@wM%6Yk5{#%wuF2t}RbBFOJu@%wM!`9lG+Tu0sQ%74XU+nFEhc(&+2mZvY{8^!*I z#pmIwzUJo-x*d<&zCb^=`;A7^;4q3|{`8i8snu6!56n9J@i66DYi1uPXr)nwpNqqx z9XgQCY{eb3Q#QwB3?VH`lJoqb2#F4^WK`m&&Z92qfBwNcfiwbVB`Q^s)Su(b=?fE@32r~cbt$}NKr0_ z<6UyyB6AoYT7HxvHW?uU3eDuFGpKR~;`luM4p^n%=1ASJ1RiIreFqF?jsX~Mn)zjA z+rqXl?XQnVjW3TRhE2|J+S(YGP1}D9w&|RGY7vH$QW}Pk^O7n<`K#brRFQZ z-Uz#d>k41}s@sXu#E|fL%mjc~j$@@K61F=Y9>||4OvbtJ8xauPy8daGv%`!ri_mbN zCX-c+g|K9mZ9Qfs*h6PiJxWYWURyWTXRDQ5mWzti>e*?kfsOcc> zBkyaL%wDCI69-#!)3hHkHrnsCT>O9yia^vd%y3;Yu7=M$eHMkkgz9MxN?Ipl!9iO0 z?u$gd-n#aNS^pS&@TeN@h7&dOu|#JKb+CNeqIq^S)+801oSE5A%H2}lxuS?`-sC$`- zzE$#26Gy35`OI4m@JOU}XKI?=eM;+cjFpkk%eH?oIj=Jj*@ojzmWpebB_?{qG=A}e zEfAQ(KKfFAoplMhA{msvSFrI7OIb_m`a=~`_^dLcGo(|o5jJ&mnbE^0owlOr(*>Nq zD?KfZ9-bk?Fu8W>P5S#(P1Jjp%41>gqr8qh{}~WnwLjf3__7ljZ*!8%`j!(J4Eu*R zPlJ_+V&}&#K46y-N4k*So&H#7GI=Egb=&Jua9Gq~(*?Wid3<@epkvF{jU%pGbYk6_ z7pfc2w`Ei+p4lX*r7Jy0NGQ8vj3mUE=os-S$^2PB2CZ+FCAPXXchqq1X!4+He|Bod zu`Hv>%_k(>yST`Z<$H-t>T~>@(fXs04C-p&4r=cy8cG^`@G>thM8Idt;Qg)K1kH>H ztxdAoK%{ak{34{R%*oj~s`3@EsC9oGS$xsk57}`a~c* zp!nN?NoMZ=JDCvfhYKRqfs!LMgf0=OC>lXl1+Kq>?Gzx!oST^ZV+9ISO#rB%x7=dk zq-VT9HXYQUh3tgk=Cd!Z0lEj;&;D<-uHAbgcTHV;k$uo_@w#De162WAhSewd{hn>!AT^!@QMDqS&M z*bD5*DeR0wt7zss3Jhe#_}x+Y7!N?Y;kNMCacd=J6~|5qbKB*{ew=4* zMg}d>5#oYIn^=mAZzhF)*px2*`n;6n#vjU|3lBjHRE24{bUco7B}cZ~8B=O^t#6 z!Vd(i&vFB8Jy6)d?Cq_4Mn`@=mA#{*9k=(z5(dLSA&4qvHODX%R)6FiY@sAHac{7! zaG~IgsrySPrfo%-U>*c=(tkD!pLbkSab1lHt6e09i%8GOp=FeHin-7F11txIPTJ9VZO$@;_W!Q0xlV9kR28<4 z@ue6hIB;^GX!JN!DEheu`LjWXvL{`iMl%w^xrH^tg0;{`>k&d6E%Q^6@sYE<#Wdsa zJ*TbGzm9=%r|w7~pgsL-hsa+Bxeh+peh5D!C*7HP{gDPRwa1)b2ji_82loY&S1h0| z->t7>seYjr8@s*b5n`vmZJhs68bhA*9!JRGZ@*8gZwC@=-IrEOaIyi9EBe^y%XZj} z>0+wKq;Ur9--)dAS%qAGllE$bYGbIerubtIv^<9_Qg_1}l&qJ}S1Di-_Lx5ff^PPc zAIx`TlW%vN_Qpy6Hs25eNWR!eJPdNoZ+iJeJJ#Ppwb#UPnXkN#EBzM-(6HTGv7#~B zcvXh)r&`bj4O$wVHiX81EGHgbTe_4>D-IoUv5BFxOTB^IDPS{214!FHITZ;-rYGWw zfaKXRXH_$p14Ye#WV56oEbvjz2YZi z`E4au7F~C?9N44W6w1q;NaEq{ehxH8*Y|D0f3-vp-+?HX>UFblDZDIo_n&f{Q6o40 zd`OBpe{Y^Gp`&*rN7)VJp{+iQdzd>qIy#sv6WedEeexX7;U*0%z|ef!mlgdlhZ69X z6Z^hCOazd=@wbfqA9frU5imFK0xs|_zIQx)mj~6}zEJ{z(Q`tP+v->}3G=m2EiQZL zZ$`W=$2V`vvR~`U$xQYu*XtWe;N%L!|2!C@VBN}06;%8;y?aplJT7SN6L$!Mcpe0- zcppiHVB+HxUs>fYfzswY#1R52lOmofh={8$a>(1CX3d)n z^Ns|7JXfLH1seM^C2=PJn&z+!HE8;qt)LLPz?x4aB~#SRh$@79RILm`ZFfoA=@dOR z`RJR5XM_9%wRL@s3QW1}hfm%9fKI|nX#$d=f2^!*!;Og{v==FR4;233D(o*E-RA>6RRLE^dz_5g2l9jdpaIU zDl5g^v-%N3Aos~a@?P8!|$}TKb_~@!kFRSSvvG4{yg#tc@Oc)Nmt$gSKAvH zcDyoXlw#vpq=fr|h7LX4I0cd=j<0V(y^}ZJeza|e^RHSQ^~X=Gz+1aMd%r9BWP$IK zwX|TCMMUpJvBPw$?}mhv1cxuPDf?)UhG&Q|lD+dotBBW>(UqmFtlv@~5ZH`^F}twk zcAqDj>mEiqlU9=t?H@>q)>4J{+mQ3KM_En*BO+RX1WauRVFvs7eb?L^ZuvsLtAMgA zBE7Igp87kOkiU^WBiYJ3N&2X08R@Z%3INyDB zyarq&Chvql))MYbDAN1QyV)TdF4yx33&Xke9t_Dp{yGu>reaJTJq)6IB~3*ty8URq zMtepk`de%5)g`}$Q}?}#kGgog(ftDC0~TC=c04mR@tV2!msAt0cXy4$R>~k9Jhgk~ zk-8{r_kG~_W!Mx1_?))3EC4M9Pc}4E?>+897B}C*n(`JkCBPyDK4Yx!8IYIi`z|in zi)N7O8$7`I+ky=@M6v8%c+OwYBlsE7`nEbOs=kHKkB{Zw{%|a~roOH*mZ945B|^-Y zA;N^RR6)Y7>m&h#mdV4aCBse-siTqmZ#7oh6XKp`KZU!`<{b&%@L?04<`wK$Z8C>| z;t=ACXqYGyP49SiyFujfaDvN%PKY4cOp;Z2FqoT*FEEN;&NU-#H1U|H`&SZAl2Grx z$wf!d?2=Tm4{D~`wRfQ$Jqq^H{dCjD1_6f!a_L{;qOUXoq%*npzlW?p+z+4v?hxHy zhFz8%UtQ2^7jau1Z|qYAq{WHwt6T+f4*={|RHgsT+Qqm>`@2|Ce})Sjm@ei*omEFk zqrz<@Br&RPy9VQd8(l|JyMG|yQTJ3VdpJ3JVyt={pB!&IKfu^KD9?T&FFu7zmn}P( zL=S}dyw)DwXCAm{AK~52$IsvATn*w64GxCkQl`4vp+^3R(sZA-Kbt(fBrnIheZ$V3T1y5g)}XJ!+fq$#d_Po>FN9ThOLNf zbbfY;Up}8Np*~rb$bZHVGpSA+D94u42-S``d&nu^v3?XkKFsl9blM71A^8Aq5&>!$BG{L z(2~KyRlw3OOXiB2~(*<7O96#kZIeBujP5%a&eehrQwjiGUnGHpl-lY_tyGoA|e^goA- zjoqIXduGwf%H+vwJ#DrX%4p=RXaUU(%H5;5c`|4I=63C0hg^{AAC{{Ir5bEv_XP&laR>lag^T zM<8PRd8Y=Cq3VU&+_A{m`g2`3h|WGCh}{u)o%>q2S*5#X*TBFotAOS)ZeF20^SBkX zrrwz_0}KwODzd?@|6N>+mtgf{T`iy}*rTDm_Uqjl$d-vpp*Py~_3<(2@q}W6RYMlD z0QuPvkm|g?CkhUPP0+u8-}xK1B$NP4Z*Rz_lnssTQ3I-qo9&ArG%=!IlwKdC{!CqU z53u&j&yas3Re@RpZdkTMS7}$GBl_9nq&Z$2ASQ_J^z_AQlAkSCzP%N4EX93wY4Y&c zLNH~2Np8|%d=I9TzeDbaOf-ha->3z|o|u^IF>u!E!xD&Lez4LK%fGXAGAdz1AnOZCcquMqWWr9AOmUKlhi zKTUrN*GZpPpj-khZg1P7w)RH4byi?y?~y-8I%@0RT62css=I`NW8mIu`!56xP+ZpA z43?K2f8(9;u6>Vc*r}`EGiSC+drprMEt?wMIzGk*pwY0LbU9u^A_uy*K1(6A7D*76 zts%PX?o~!|ss5veGf3yc+FI&nwu--|-Dlm8q>xo3y4(tf<*n7W{G@k&b)PPP+K*dL z{|6wHLb0;!#4(eh?G-5Poy$O6HT)OR?yms8Iaj>HBYF7ASf>HGcQ|~;-47Sc7$j5# zK6qKIGnFtG@h~XA(bW>uS!_xsKXg6j3GgG1#6B#a@ z5z){H=M;4AgdgI0asfWHUfzXXKe-oHTfu5oWJLc?6ZOmn4~VaG-TUK~vAa#&F9vjt z=Ke!7`P_QnKmwr=&H-w4v|v}#gS)1G>>%DEJNSg*HOR_}U+eYsU0J*}%Bt@9YVJ{i zn9lwO=UqCI!RsGNte^ij1_EL!pkoy$8Ls-Y-fu<%X>VNz2S}NKXHa2vP-aV^hRxM; z(2nw1=63IE@RbeiyZa%Y#thSDKuW?RMM$gWT$3=GM~>4WKaATy>_pAzGQ7&nQUM|i z8-VeL<_Z?JS^?61;zJjovS}aipK5t8j-0F_+WfSwDYbb+-op>-RLP;o4X~L%N_!Oc z>*6X0?At?E+KimQ!o&M_&P{ScWA1YN4R@U8AN~YQ*_|;eWe@S}4LTxoBDb}}kYfc%*2<8BQ0rZ+(zksKB0Ajn0ywIN9KkC#P zv`0f+0WO6}16O!+*#+Vi7Erh%RznMxzTa;}C=t&=>V%#PR|n!OzXc?;n#LqGvMb^f z#Cu;NZGGLzlb5fxLe-HLqOAnuki(Nw96=@)maJLW@2L?i+1_*7l+@To=;)mDhjAxq z(GR^SSlt!bvaMxUi2TS&|Jv$yC#9d z4*%QE7j2q(uk149cXB;QH5`&DWnzgVitP=*VW?9Rva#R63f(;4?Pn15pp~?#u9C_{ z>Gq#rbJnyI69l^4n3;uXwCNB>qZKgEi90I14?VVOw_U?%8?pEA6w}r%DN_(Or+O3t zm0iar?r~SuP9G*a+aa7e#16K`Cq5{TvPHT}f-osf<@BOeDbe~6k)yCTqy>NmG>6s# zGi_kG>dMtIao&lM%y8jWCe3AWZz~IG(PWl3s4^~LLYA6lM(AC+sA6~^tj3OV9Q(VU zy$ld1+yX5!dPuS>yg10s6dC$&6=b7)U1{#Ky$K}}n=uZwxx^YA5c6Ix5i0_FY{&;2 zym90Zq88{oy-HSxP!N8>Os*zX5VjvN7#vhjw*{hJv#?~xrxEYS*$aoqn}S(fhOmuN zG^58vNxGfzO6IWsLfWPQbMcf^+=;^kL!xub%94s7kFT+-Pri8jM!DC8co42Gdh9pp z4%pqKS?grP2a4d@3i`BQCP-K@6M;0iEy2#Od@Z!uf^2par9x+q;DArbeHf+dGbbBo+%^wNOOU>iM^E?Jbpy<{#c%U_G3%qc5rz{gy4L?NcyuspKyZ>t*z#B;<ENI82z<4F*<18Qr*0Sz}ZE(W@Jk;x=3QEd97LcbDx&0!k?Utj71}O4z7= zkoKe;RT!!@<_Gxh>Pu6TOgtW_Eb3%PoH-1^hoQ?jlhlp5ojt49J$$O$TMws=%`I|D zB|6S)zffJr)`(vxX(f#2$yKAR$geI7@(}XvAAJr z{2TA8*6b8IOV5#!pd8ER|8B-Xvga_~SGQh~MpmfJqb>|x#ww6Jdy?sETI1vu2#cB4$D~AQ z0uraz{uMoXJ?sGAxEt>I^z8LL(50Mfk7eI{OO$E9E@XX)9e9=$y_URh0#FjXI|l-v z=POMHibZZp|6Sk@-*#d6gWrOx9_w!(>Ukp0U4tS{yQYu>y|2kb_TPbIv;gBPv4Jal z9tsWwew7ze*;O*xr-1m`HEbVqis9W{Ro_0CL4n2L+ct>>Zi7c&psupK5+bZDsS|%l zE;gi3aXionSEL_T&aUvgP;E%;1FXLlSP84}XCE)LX;AQX)JD!Qf9l*!ZbK;&hQmBX zXKpcaWY(8Cc&+&Lx;(x-ZAG4bHcLbaCnhCZWZG)VTB=U3PNCCGNaQX>TBpcO2)5NE z4LJr4)tnu)_WoZfC|-3g7=BMaOty6PaB-Izo-n1un^G?$C3dI;xWAoUCBuyKAu%;r z4j|TAEsYqbus?`lc`otHj`9&RDV?%#b9sq_pRJVY@e&Go>1WD_gK%LPfraZEE)|3i zbLwoMLOOLIj5?}y)MW7|Y8#0s#7#PDKeMQsUJMN+z2CvwNj*N1ul)|~oTd^_*Xt}$ zuEz-HTCMP}*O;ResuujU#%-L{`&*YRM@{^6OJe?K^c>wp@Ql#P}=`Nf}e3#pWj6nQI$IKc{X_yW6e>8&G~ zta6zS99K(oNFKi?4%e|IVC z4F?Wr}w(Rw4f|MvM zVRG@ige1sA$fr=C$23=Y^an%< zq&ymNKg$P;kJY<1xJ^#{T7BY`cOrp8-Fi`aj%C;)u*iX^T7(qu(@Q^ae5Jr1s^AqS zt)34$+$EY9%p9*%CPiO9`S5}{}gFb(lW|g{emxQ-9(x9g#WHmm4?bIdp zS$5&uV=K+X=I=z@_x{tq6)i8MPalz^lu{!#ugylvQqq;cq=GAY_MJU;@L}Q@+sdq| z;QNCkyxQ=qLjHi>AWPt@a>w%Z4#4fNnEEv?s6pUP1?=B;7a}@qx)MfH4_@89I-hjR$};MCM$Ro@w%0Z)W&X2= z$FFr8odt)o@VP)sFZ67P!pIBDRa%?e6#>It^$`EVG5%UP(U2nAU{hS{IGibkF6zC( z2iX2c*1hIuAq8lkXkQ96OkD22PYVAY>#Q9z;0+86f`zRtJjTrwXJ+-#m$^U0ee-D) zy1HHF7+6{0OF&&Nlo)^bEBpyV#vxL_*#3##2NWFv8NP-b$FtsR8H8=y?Z`Yzx2z6Q7TL+~NVK=HY;9u9d7>YDyh&tkg%OGEST% zcH*1;g`$R{QN`vE-p8kDo$_O0`Uu0MY!%iehIFDCn0^klkBK@U=8P08A}ZuVd>3Lk^09dzjj$S8WI5JsYTfd!M% zqjHs*rHsUAp6iTL=D`PXNUFJkO0t4aJ834UPEL6^RjS}Y^5zbvQ|AohCWKo1k}5pz zV~*?Nd#EH#&C_)xF)lM+7%Hqoi;0q}&q`U*r3$a5&yX@#$e zdsHbyhQFZLG8!^ZFuj3R|Mbq1drJvv0M%ltaF)B15`Ca&0Lr zhI9Q^ydT+Gx43LB(OXif>5R1J&k>!zAd&)ap_pa{bA$~zj!OWRwo{gywq%bOkzpm= z`zR`qfAQTV(HtjY5_$OQ@AG}Syln?Q-2H)03|Y=z%PMDIWuzta&Fa7lDrR3Xp-tGLMZObnyBUYE_-Y0eQPIu$%S>A_ULNC{eWj1)pWheaP zLbJ~58FUKhtVw6-G{o)GYR)i}SSNKi%=a-f#9xW=fu14&)nWun;oG~rssE4!-@wqc znxVi1B4+KPl15VwqO^6ty~qGy)17o90U7}Upl=gEH+$tr#j|1X1LK_s{ClOqx&zjF z&FcBk%7G)wC!wnkdx%$ysJVMuX@^>Y>A)_m$2@swkPy_lJMO?iUlJtDhw;dd*;-lE z)`n)9l^sH$tO-*x-+!37U0iXbKVc95*&+()xdH7Sd2;!DxaOduGzK(=t@?x3CE>M6 zaChbcn2eUV3;uhL5X(79e#LSw$y%s2lxad>Th*=%!4W z%5vnUrARt@%ui(-egGF|a?-k~O-rtF{RLKAJGd!GO2HH2E5KyYzVXAeFFP}nJnKiH z(8>n$$tEuIR8D6--p%?$Q=aqJoRR{avjoKj9~-;hPdI$%t_TQ2kkK2Wc9&8 z_e$$*KU_cp6f*WX;r`q1M+7J(fE^Q1pnLz19!4z!M8W;$|D89pxCvP}JwtdO*{(TW;CfYqPf9KewLX*=7oSKYX0Vj4QJwGek;T2!{ zM$M_+Nd*O$JvYPYdd(1Z>^Zks*9hpN2DS_GFjp1be*1Nax&)0+OSEQd`wTjQo zJAan~sQZDcmfGkcSH?T$dvQd}_VhOzOxnc9G?ijI8SYI~NQQmQ(D&cZ))r{`oZY$` zxeYCTx$B`POr}o4X$SmKee^L9=JvT+OA=v z6BOVq#WwanplQ8pJCmN_T8n3Y@mSKEOo2JYl1l_h;DY}6#AYx`!F2H%EEdRxVhQPD zHHI9B3w=2D?|Ir?D}T3{3m2Y{lhyU}$v|gqzmfs`af6bQL4*wHqxu+Qk)f`>3U6R@ ziciHQ>G=1}pA+%@V@P88l$JD5Svp}zs7SHl!B38vWSXPg1vDSX8BBN$eSUC44@$&f zM=QTZpenQEm~k8y4q?Y{hj7KBCuoXx$9snK5BBMYhke5eV+({(@xk|kUAkBo2*t$C zZIa=jU@G!Co|3NmY-5NS=MpooRgs@%OJ8l4Rjah1y;h$3_w7v%V>rnJv7_X>X{}I% z(xzk|6y+P~Lqvc0z^uQ+Qu9aO7dmYJg3cbsKEz}Z!%pcGvh#h%lCO$0@((X2RmnhI z(I-_@W6A-!yR_l;p&ap^YVpT{1@S%)dQxFa+((TwM|*tQ8n0mtRMpC@rw->oN}bk_R)O zGOb&Vm_Xlu7aCD0jGGaz{bFB2kGkflgUWzYPd@y+8TN}gA`qJ(sT}g_#57dVCVIL# z(1SF200Y<9;U%LxG5e=)c7P~&yKt+^B^i`tmu)^OzNrn)Z?NMt9vC&e!n?8W8+Y8YyXDl6TOk1k&+KXwXp?&5+G{UE|&g08%eCkuwx^ z+7I*|Qro<1n;W4t3)^A^ywyb8$(L{6zO`u4r5=Ix_6kR1)0^_-nRDdOidcY5_59^W zDxNUJ{~YAgFN&$S*+M`G_ZnLVzurr2vvtVzyG% z4v_}50f)iIl7G>|({x-g@|ey7p5vIhNaPH}cm)e72MTn_;G z$LIGh=0~Epf3KnjrhH%jtOA6_Kscc2)wM14fuq61z_W|Pf5ayjRU)4^Vrq0h{BqXgB-CsLu)IqW)z0K?5ml^0tqK(eBtp2y(gz@17~fN{rx2jr(li5@8(hv|tWY#n{jKQt=qSgdo%; zoo87?^XV*?WcH}8`QPAk>Z`-I6hgQiV&-$)4LG7D78SJm*HQ5jz72EyJXkIp%{U%` z$HyY07V=jc!4sVNld3BwaDiPG;S#kJB9sNy$nch>;!?tUJ04P6X{%~heLDo^XZ2kg z#JPlH0l${RY&2nW*ZR^{g{Xt@MlMymzIZ7;h8ov?^u>8T%91dz&1{Wm_Ig_^_%Be( zd8SJD(NxT4tS7}{s(0|VcXW_^%f#7<_Px?XClWjcMar&5deAJ>L1;g?3pJ2aTw`@- zt;FRE8V0@CgnN+wpet^oJH8(lRsh(NWwj|H^pKrSL)y|gALa8?K|;|DDMBIVrtI@5 ztxM#E!aDLe5muW`qmYc^${`W8_BkrmgrRI=KkD*U;h9>N$`uXlcEGk34MUOQEH-(w zyxLB!Xib4nr1X1;?j6mDbj$QhN%;x&840Xt_Lzuhb4Vv$pK2tzc2wWi6q$d)3au~W zeyp0ZxiXrXS-y(CDmCqs1KlU(MTF%0s}dE{n$m`fLin3bZYvpI+nF|oePU+jJinin z_i(D7pk!yn0$4rT+Rb)%Gjn$E!TGjIoi*Pr^qIBmB=>&7?SRL@6MFfPjGP*@_+8?fdMSRW#Gx ztMwcGev6Vx{`ySB7e`!%#e1;Hzo%7zdJ5#R*^A<$W`QgyP;LGv5dIG>K$Ks!(B=^k zKnkE1LKDZU9$AY%qM19YYmWxp2E*({WWGoF+X(Kc3HKv4yCIL?i2mBb`x;NyZf%!I zy)L=1 zUd|}FAD4vIL&jchSzzONP-(+2-snwz{&1JU_g{VkX-i7!d7Ii=d7+UN;7G1y9^@>q zPP>g`_~g!!^V18v9wBM+&xwGX+d`xMZDyTjf@sD)u=lT8g83_?E>ZR_5AaV{c$Z^`*P9+Or0JICYxGwaeluO@q&Ozja$aZB{4#>@!lc^-A{C~#G8*jaDHRuiV-ySC2dxuaStB#UT)dGKv`&;N~uNhmI)%oO?Ur+2E&FQh1W zDA}>y-kt;<@B>+UG^z+EIlcznX!^x2ypPN?Q~$;MI{GT=Ae{Y)NVl=b>SRgql$%ng ztIrhvS($c5`IB5d@E0(aC4J@-R<+$t)C~p6FeATLELyEVog^i7F;q$ZPzEg zcc$&0%4En?e7Uhd=#309OY9643A*xZ%s>t?oQdRLdVc=t zH=6mH6Ib`@Bb)`aH%*>@|9t0Iy(8-HervQgw8+^h@Y2)ct@suV4 zH+%!^ApLy8=)GL%h3&A3f~0L%<4Iq{jM@d#`aXW;BJthbow}6Rsuyt4+Y=`b;L>2ku$t;T zi16ELBjerqJtc?R#))qsMhdB2mUr*NEEQ{2=9_ED@J>GoL=I<*Z7CNP{P0!ao2S5l zr+~pe_x`>6yO8opEW7TmsEzA8WZIx5iazN_c7rYa<_NsHCQ?SqTF1itC>gq924u9F zEm^r3OV(gZMPg9=0~6XeNilci4kBn`ZM3C$KPm!>cinfp`O(hV=dUK1q?{Fg)mX=; z3G?xzLKHq1s>c~^dv;AX(=h>ATe75qBWLPtE-fp`MPC6=5X2KTE;pe zX1-c1+2sjXuAr>)cQWeKx?>K3U)XZOmSY2YEex6T|J_cI)$smxQ~2}Yl$aOCV!4>i zP#Re`VjM8_9|pPuX=^BHn2N^K2kyNw#+F`^Uax%p^FmE5X*I`E(5vH{@+2=DJuv2T zysU8cw%esE_~TdxYowrAA`@JXiCc!6(ou2)U*{L7L8%!g42GnSw9sZa1p;B z0C1@l&fUADwEWI4&jIYN!}be-hmbv{qDJ>I7F|y81fdcmV`YV#9ChO%&9b*>^C!)oYnN8= zBpw7em={ca_@_c$)&Dr%b2lNqH}K=*WUlj2Bd5Q`he)7V3>$|paTo}CqmpyUcL`=C zGe1$6?{CNtgRW^5)|rQs76l-~6Ar%a{7xN)495+;M&1gBrPemqWW|01I##Z~_dXc* zJ^?GVUP$tlyFn5E0ZO)hQ?Z!@{|Eg@4{yg8N-gsh*#gj(K$}L1W_PWUMO&-aEupK} ziv6&BC+FG%8t(l|>k&@$>K|2j_KgV-df?#>Sy^pt&$zWI_e7o&Kh?qsI@os!9RqIl#IIs)))jsG4B%h}#Lg zaP>8=?kxoULW1b=q0;zT)u#d#EbN8&p?fU)`S#6VriVdJXi}n!ECUQ>0LG$Ov&&k9NnHF+C`k%yo5C)Q^f+@%Ss`P-j>&6#xSr zx-Q#5iOf%e=%BF1v|lGP{Jy~RK4YBv+MW^E44*o2iOb3g%NywVu9y5~!N%H<_pf!} zv}F&D?hng+qK`aBN--;4X1i5NLF++DiON?A4(g^rLp*?z+OXSG?&J^rtk5g1wLy2} z4wrWSLM?b>L$K4gWfX8PxB|#gEVYTnz{hJVA;9zcYbsQ8TR;6A|yyisi5u%Mgav&TozmLrGLG4UHa4ENmWs% zO@Sii?j3)7lAl{{{uCT}9^$}@$>jfM0X#}Xikp)I;5427HkdBH`YLxBV@O8jfTL0V z`|Ovm_phS2BpLfXqbK7ieb*UHpdsJO=RV9YU%ntiX-9LWJp&nRvTY(NDC(FgZ-p}_ z@y)jtxZJl(8ihKIOkHe9Z;p#r4bP!|Y%*RCR|!O|Nr{QB-rhWGgmsG+^)rcX|2?vO zf&3MBT_#*I-ilOwmpfk9QI)AtO~Melx9w3)#E0>ZPB@rKZfsbOXMH-tFR zy_&`E+B1_QB8ftHw(2q^)dxfwvmo)+Z{&7uEMGTtONyOVj-wstK1t{E>XlDiHta)N z+P2kO2i0)SaQjiBZSsujB%*!x+D|C&^ikY=^as`@B$Tq5&gAt&$V0FtijLx0ZzaT! z^3xP{wY3=H8LCcEOJwoVuAf;z9JoRVQWqerPDVVDLs)Dy8?`Gao9;(fE!UZ0c!YDi z)P|QUR}_6}sS2epj#+EmUQH=c%~YCSe(Vt={{=n^Jm=FKfd2EFDc%)Jp%G%{lk5H% z=2U6<4ESBg%WkwsZ@4}(fm@S2szstv&QBHF6_lLNfzl!kl4|sBXI1~;%93WHE z64CPc^doBW5Hh)p8U%O%e-EBKBYJ7jL?%nhrqS^iab9Z9QS-lpx?_Bx&Lhma!#j(o zmy5^wnTN@#D6avdI@WCuk}+<$Nk%O+Ej|qx!rEa@>du^-91h)Kj_S_A7*qoyeZ@Iy z5;whWOuktPP9Tz4co-kVzmY61)d1+XufO3SZES^|l9_(MpMZo^m^tDWcdo>4XRT)S z>?fePTsxl1hx!fsT|#T5c*KTEf709H~ush?BZH?<*VWjJe2H z?WJ>(iyezO|EpYltX1yTTTcF>Pd{P{$`^_g=kHn7m+#W)*>Ak+T!k8)ohjJ&z2r0Y)4A8N1IR+zT*R_2p(B9O$60yb&*!{QD+o*)_= z8y)zwWE_GJ7CPy!$~)Yr+A| zd#BpQ_)s@3OJ3iA#O-MgZWDFLnjJHFk$_5@3o>Xe;%O45GauPi!}&@)<@EhI{rVM^ znVqI9MP1>2^6X}=aeK}7ybawBck${Ni>+@1XaOMRdbSL?w+#LsCl1uwJ@BO3y$G4V z1AA!ZT(r&Ghs=B0ohOeQ~@>MRzh%aCqkw-$&c20%08y-n$ zSYfJ}4dII$C7{+3KH0uCha8*4?A&3vp9(?j2bR?BrJP? z3N%yVV(_VsU~(8zMNdDDoLfF;ZagB5stocT&!ccQI>eTJsum7RnAWdBOAU$5P_;el z3FpSjhV+Al{or#$u<`i3C~NT!J|*MAfsG(Khc~E4N^;uKgYXMOn#B_Gds7^$ZMXU# z$0y`qBHvz-{l}BfpNS$Nk|#5l`EWu@5{~lx>TeTii}vN;knm&iA$FQFB9$WRDAUFh z!I@h=fTl}uar5A8-b-OXK)_tr=wKVtI>_pBPMk1n)$~=!`p<%5#tEZQo-t=xl!8=| z7%*=}Np^aNPO=Sx_PdviWJ|`FTYe%p>x!=KVF)vNtLlfjFeeMsprBwMNP`Mr%#X_TK%pX!1h!Ov3uMN}*M+MkBAA;6eF*mquB9H(KZdZ@%Jk(I+>sFlJE{ zoQ?8FN=U83-@;GXNZryAeS)96IG-Pc%+IwgSDov-H0}{uT?wzEUd<#wraUXm$0zj% z0|2HLkAON6_u!?t#jvsC4*vA(^G^40oN*2@M65O&TXEA5%<|)&TjvnuCaWM67$PZ! zps{C)+4@cE)@;ISzhkF=RUY7dXb*VTbVjth^rb_+Vp|Kpl!iqT2~tM=-cB;s&1ui( zkdK!UKTpU`K|J^;cOAv{oq-V{?ICJd@We4G!xz=rMu~CmofZImai%DKfX8LQy`|XP z&b_!Dw;PANgEfC=#B^u66|=&UYAQs?xazfX_6K_1IXqV}j5J;XY|_0gf+3H`h09V4 z=D(?~CG*$2_yFw&PY;#Uf=p^kmJI&RC*yfBlIX_Q=#Kt=dDktVF0d_68urU;ADW|W zdeLmJ;?_YK-U(^bDkA)=J!A2m#vXa<#9$(zd4^uh)iyVV=^BEOzGJP$4^prGMlpVX zHCaX&8omtl`$4H`&8Gq=TFbqrJ;C{ee}f}KpxK-vl71H+;-mk0J(p$CYqmCW#@yM^ zrZgzG(O5*hU1`leUuk#>mz=`Huv0*L6jP(!m_mFwPs(TyTg%i<{7JGR6?Ytd*s!q^ z!x$ZAMx&Zy03%+LKOrQ<^%o(die4$q*B|rT9vqJ0{0qw{X~%zPj&Y8T|0zMN>4xG* zROW#|1;0<#ROKHHk{eCUMF$UEj;UxPqUn*yNGOrOk=8diCy_7<3hSnXNNIQEnJ{Kd zF7zE?|1u3Nghq$t`!Fu;up9K^#;R-pA;A5UKU^xp@l+#5E1Sr@QxI zmg$J&rn0&Q%pp!Awy0m@*wh+3E<$zN9C-Gaf5;w0s=`#RbCnJKI{uu_omwn&Sdlqy z-!5UqTkSA@tWU7PsxgyruZSWmNY580BPEqIMs7F^ES-4T%ELwSYJlN-Al|WMduBz07DSHPUI?Z(EPx+QP39`bm}dr}>|| zsa|S8>~!TUEhPLK2o}ciJ>Qs2Nvx9_@Qk9i{1y7+6h18kKl<?gL|S`v-KB{c)$tvHeDTP~sL1#CP8HB@B1pM>Hvpm(xnV4NhzBS&u9_9qfu zQ+WNxc2^~%NeO)E)*pJUZgRn|z-k`3)0aU2c5pK*nqs3E6M_6(C zkIe-fB8(wjw1(S}Hx%t0S`I-!alRp7N0%L$PwX_l8n6)fzTP3R>j*5W$oX zLA860zY3yatO0gv|5Kgw@qzs4jWz4Rlqqe+rL#Ym*1&0TaW`Zkc$vAvNo_Vz?15+b zUWw^uHQ3nH4nrt0>b)jM^Wloq{t_zwc_dS^lu}m!@B;&@KVT4VES)OKB>f68a7#&~V0UxxNhSPD%B%>Sy&TwO9Di8S0cWPH5DQkUv|B76h{^ z0DK0qPAkeKc%QWM?=LT+=1ao};C}>wgvWtH){c*D)O6y-wf<$2|rn z0x>S&BGtwTm+Iz>c9xA@F0uLtNNN!P@Zc}ouNPAP(1kX)wv-tiN96zHEdrC8?C%yNC$?;<44vh^zfuZXt~ z#?`;J`%0x$GMUUB4NlR$sWN5F5K38))a;DAzGdHS*5BWPqNP@!2c&U_lr*)q5An0U z8R|A`w)cYDPB;_ z+ml{N4Q@cw^bHF;6rQze)`2Aa)7Pwlwd=?9(|P{E>1l2tL-MtJHunN>B-!du=Ci)8 z|8BX~XB+T;oSM7enXrp&7+oJ{1jLs`76H6Fz*^&*-|geO*XQ^cMp4^APf#M-aSA*Q z)e3hddE=+kq>sZs+d)wPfyduJ7I>uol#SY&2#uO|$xc^Iywf@q828}%yD3;j)_i&C z3zB;~^301@7o#XvU%r<}M`uJu)qLYxkM6cM@Ti~53vR}7+TAZnQODoK(tu|!NNuD3 z^fLu)q@1BDM^XrCqdoj%gTk`z;(yj65tL;SzbE*vXL{^y&|3>DmqXKqKU$k|sc7+= z-t<56Xmi}Quu0w<%9>%7`2Uom>Y~g~fyM6slyDvY}vgz#R;Q>dPMXq}km1Nc5K zQJG5ejV`%=;y13u+{GzI5ZVq%)per6!IX&#g9`j&J}KDjq3sv}8sBqkhcWhDUuhxu zMo}TImu-cSQ$+?kD8lN5m>^_23lC!s`~gNGJ*r~9$0H$#&5)NTJq`+OIDU)V_mL0| ztqK@&P7ZS-3_@y`upUg?)lWn`ggq4uzll^GvWwi;cykjSPE_v6HppQBPQ3iQ`@6_# z%$p3$BC1~^XFyG0EsZlwpOY-xt0L|UH_8XKaLsKLbf~*J_PiG`&J^D=#n+1&Z`mb^ z9=kak%Q$QD*SXc3_G6r4o*9w4&MFb4yHS$Q695x;;QxBFzxN?^Js;2dq+XFzbW*L) z1Y%f$kuNZJ=-}>s9vGkQ=KeyQlw>9<14=|-VE;wT`1P*Zq05F^VuR=BGY^7bU{GX{ z*S=RnM7BhT&=d(X3*;GdUkA#d=38A4yAIU{X>%?PQ?%6*BEh%M%fd>SRw(xw6VQtB z|3xslQugEK*Qx5T?%3a^iKWEa6WenVQ)X-_I80Z(&w0;@_=mVnFV2i-w6b>ID*$CM zy|{u^Y1H*h-34axcN(v}H7zNO# z%;8)bTaC8#m=5c$jfEGO#Ht_yEy2*LUvFK%7rR_^^ zuCsFWkrJ0st`Xp(lul)D+djWKnkKDZtD9guLie_JJxY~(>6M4OBnI~*)PB*tsyD_NHvZs%9S*)|C zH`G2qo&2uk+4f9u)91bZ)jK+FpRnc14p)i+(8#I4Yn0g++sD3>GbWS+gC-$vxC3MbGAVDlYD4S;8o6cRV7|NVH+KO{IkSx4> zxUv~uxmj}zO1Juh6`Wv@euZq#0Q=#a4G-6T|F){OVFX(Bcg8Lf+K zl3l`D%_I-2KEjQSO>>)05jvb4_Lo-&^QcPa8V7dB^>P93hE?PntlNorw_Ma$L=Eub zXvAOoeiY<`;qf%m(|Oe{oY@Y3TcahE8C?U3xDP3E>5gAE_x@9r0ITgHueTaNqcXs% zb}FB22{@1e1|3$6JMaF$gKZ^cjbT(MX{OwSY=vi&@oTwh!jEf(#r!#laK-Oq*Y9}9K}wRo;kwYyLFgu+VojlMp9xIGvi zO=bda@)2)t;Z0GkkM7j*&pK4e?Kh@l*m>vLd_i{se8(C*X>QBXGeYeh-W%TUW)t;7 zV)Pl&4oH60N>n7|MqbYQ#qsMLUvBf2Ls@}p6d<(> z4-X?4_jbcVMnTQ%jyw6^_D7R`AB?A^aEj(l|NcGt7A}6NdVED<`~G1!>Me+pdmWTK zNwb*7*y!~nNIEnK6uJ+9Z=+=!7|HW)+qyc>nHuCBh+x}w6*R)JR(xW+SbS$-Ds7}w z9moxFzPyb3&6$^IaX0y%xPFU^v(5vl$M-ixrAQ>=UQ57ugQx6z;5maA@nvqvnDmmc zh18w@==_`&BT7=h*r+LSO9nCIkPm=~0?f0{-riwgStjLf`_CV4f;c*YI0R*7u?9BiKe=?RNVu@P2(Q zk#0;PGaRCP|Kf3NTK~q}jeMU{VI@p2OP+_7c7Gm_7^^9vv-jC8W@tQW8HY_tR?ZQJ zwR8DzTTZ2$tXZb|V1!6AN%A)C7X?3|KoJ4_Y~b~C((o)Yx#Gq6u6y&}S(8^{pdg|V z`S;@S0{A67O0WOZAza@3dORY=S%v-aN06>L_Qa;%4kO!eB;+=+bQ=^=mO>WC5&2Ky z`?C7)X`5YYr0;YNlN>a%!RrFe3t-9e;H$8SjuQDp)vP#QX$N>ERadzI-NGZP6EnU& zFYjt+clRLh4B&3cWv=cQV@fjYbbkXgtnA_875sWkX{>toj(zm#xHXUG6BYet-!7kF zlj%xRlyucT?O->Vu&T;G#oHc>ph*!z9JD>4Ly<%wJjm|Lr4-jkx)YcHh$reu^3D-m zv2SuLKji)8wdWVR-G6-aYpnxx2l+Nj?Fy$DViRllqHzoQITv6DEPRQ6qTrx^BmehK z69@6`@WFLLsLZdzti4c0HMshUkf|7wKq>Cv%2dMmbQC&eZpKSw@h@`ro(?3!xv0B1 zWWDtHyPwoBsv7-eF6&)YFG+Dqxh{yutflxEY$~TxJZOcovh! z(IZYbNFB`bfoKi?x~&-v*TcG@=gO52i1k$*CtJ6=8lHA5AFOogMSZ9ltsu3o=YUHj zYF}MIxxhbuO5!9irha}Mos^tJTrr28OwA{ z*$e5IoZY6<;S!!NYtkbd#^M4oA4cl;b*rx*(8FnG{Op7r;-R zktihcPEIs)47hKN%N4sq4Je1)?vgj-P8d9<&c2|O(`Ib=8ZQy{Y$=R~zLTswB#Q#oyUxsWS`5vc3#$K8!&R2=?~8y&VA+HKWCITzh* z+%immydMoq)!$@H_nc+B%MmaXfOqgZH=IA8Pyl7%qOX(s9_|C{=ezrpIMB-<250Pg4tB$2B$cTOgVBE-h=otEFDfD@7W& zDQ)uX!;L~tfuE0D^>pb2&HV3bGp$E`V-2}`vlxQK#N)foYD0%>ayZ4&ew{7C%#w#2 zG402{x}&-{-yS&W#O#aSKk_w5eMz4NuJm+p(cgcM2iu5oa_T8G-uMk-xvsqhj&dL~ z!Tz5%P1$M*ach_X{FYB{juJr%T+W1#o1`Ji>7jZIGt*j@>(Iuqt&V6ClK6@5%Y24U z?WCT|eBa#&$5~e6fUsksud@=dd29DL70$uj6n6WgB4Hkxh}9`V{cDb6N8<%gqE%KZ z6d2XdR0GK7QKx-C?eqk9^Vy?PVny_DPpQ55nro|cWqg!@M;2CsBmP9g{ zY_BRtY<)E!mmk+*EIfhc%@xLI$?>^=Un8Q~WEAI(HW`h-7tXo`(*_Y;Zes0BeM`Z* z=TtCpuY}1Oi=ld}Yh4!Shwx{ZJRB(g#-0)cThH!y1m*epKc(7E0WcZ6#G*P1&igSE0o@=F7 zy-Wjz%-qg`7xK8bzt_o_u2%70){|KYmOzs5xvzH6!+ze;E&C7H=h8k z<)ZXX^u+Ig+;^G5qK~NS}7LN6>%6;{2<)K z6x3M1o+Xt%oB2yhW{ADqJ@NVrhmHH)Pa)m581T-~FVyXSS8(y~y}xe6-JA;v@#ojC zGNw%=(!+WhVK`hZBX~kH$?vS281#gw3Mcn!SdIWOCroEikjJ_IH-Z?UcCLrXUt*IgR4h?8QFPsm}7pNNX3#v6uQ7-MFlFAJpjW zsMv&Erud@|wF4qu;dH0vRWN6@y9wD>OuhcDPw#oXLfGWqWTx=2d>YmzS$uw_;9Xtq z^ncbq(2hpMkh~POA88FAM@cqIuQ~> zWytVn8i|%kq5%9lRkN9^TOH?oaJW3Y>gKNi$Mys1Bc&Fdkl!`@O&3?-_e&p|QPexz zWCaclWjs4>uo~)1IF@TrPy!Ln--l6A>TsCL*H?m#b3`SL0i5)zyEm`^^or~6nd`R{ zCxI4NUk#Ooo@#WhuZ>$2KRQqM1tbfMFCOPORbUN{t$%jh_S_m%zplH_@@mZF;wWo$ z$S*3YvQK^g^#w;1D5eFR7d353!0Cm;0g=bEMM<1OX8!cE%1u9h9QynH`GwDuhfX0H z9FKcQ+w)e8@zSF^s}v30|NpZ9BZqfortzkzn3N|?PVCY-W$JQ!t-Z>F5lZ$u>(7Ij zxy(c9GkEn&+B1TD*Aj=4;K5!-tLFvZ(QgygDR&<`VrUgw9Nojsolwr-a81u~%<<-- zH#Ro926=?#<&kz?z<_4qaOto)G)zS-8R5QU*~b6(;is$D?MX42N?v9Wsg5u1Fq2#N z8M4EJqJw>9QHziWMq7bp(L)D*(QC5Nz)HF?Jd2^tP4fSqYb-?gC7=viz7tw!kntoEL$Jf`xNDmM9ZwI4~-3W zB!O3ZaFp_c6VsbK-0mEr=V>Y;;~YQ01Y~K7mbN#FL5L(%WY3(f?j`V{8ZBpabnimygc|HPxT`8K6u6T4fJe%zt)NK0yDr*7RbEo7CDka3KDm3Sv#GoK}EZ?>SIpd!53 zj3{-R-{{`r?Mr8{zsdiVP+zDZGTn=~TG3?v&Pm8r>`79T5Aepw40~qEuqTh4B%A!w z637gQSfg)UJeW{d|L?T)cv#M)PN{pM6?^5LyUZl;Nn)PA4do) z3=R^Z##6yOj^-0+Oq1Xtq?9f|ht5Dsl3C!#C%gYn<3H@-R>19R@$5X=m5-ovMX2yy zAFLciO@jqgmYc5q)8_<6ynxQIJ7m|q9}ALC?+J&s8(!9$1QDrh4;$j9pI8i86aTR* zH;!|9jQ6t{p@5AwNOJD_M|L*I{p6X05c_}@E_;VgBjdnBQ381eo_#sF-=0m5%AH_U z)3p^s`Y4F}%(l0;*Ko!OheM4OE#4?DXi(z(eV$CmOQ6%NG@19snU{CAP$sa8$Zwvwv z8E5HbD31p;cSBNdS9xpYEwe2ko(VB8?~;EdRp)G@F@C1slu_=Ili>*UsFaI`aw9-I z-1Dt4?V`5K-@@IKe`fg-Ymd0dh?w0x7SIaQD!H7ZNR-}j@<;SDfqNv|*i?q7n5vTX zv%oYDQ6vx28|bY0!hN^>i-r3n=S_=GX&^ulPBryhxI zNHUM3GHqL@OA>+W_^^8j2YXJR#><&(?nFfY)vxg0pl1T$O)3?RrAsz~X$*v@`}w0T zTtRw|MsB=^y?HE(AIr|fqOelGb?M8=JtT?#W$@7BbG2fu=8w+A*6S$Aw$!ze3Dj?W`Wz{QAsye??3R3%5ioO{vaMHR&X55u>nwWFTi=F) z38&)O(SZIhiqwTb=sg5}O(+SJT57otnFo-yu6%fxZ|GEwbZA`Ldj7(%sND0}7;zyY z#fq_gy=**tW|swHWfj(3yldZA^iH`De-%6})DbL_mA_@K#Xgmv9A{<^ki`{2AkolN zltv+|9X5Jt)Zt70Tq;9tBUW=7aCRR+){UVQ4P0l?=()^0tmR%2+P7PsNo}rG!r&}S z7w_t)5tc-_O{fM#W8a;&<}X6b3TDS3J2`*3oq9)aE^Sn|ps?7^MwjjAyQ3Z0I#W?;6m)Ms`Oefgzr4k`sYPF_vnMbCNL&HPL+|G_ z`Xtrm9Emd`RbC9~++gUJ(wDsYkm10@N5_Ps;O_p@$v6F4MA^H-yDu+zN=6}MSY>o- z>}$udgplj}GBgG|kEs#ZcUVONPsZe;7`xqJ%7ZnCzs(@^Fr?B+ELr_| zagpwON92fLKg*Bm%xDg@-iO#<-&{T$0EU9b%jWHKFgy$b_{2336c@Rkg0fZ;eLgVx zwft4OKQjIK%ufM?<$rIXLrHr0nraz{Gps{$=5C(?G)*NJCW)cUq1c2q0_x+Y71&yg zISHYTvWgM=LEm_o$*IfT?Wmb1Jlo(Lu=${hl<4NB#0uXF)yUOPJY^!l5~eg>pIZao z$sS86Z>Z@7tE&r-t-; zL~a;SJ^U^9H>^3YLEhsAu1&^a*p`*5u_mO)rCLhi7jVveye@Tm; zb{?VnH`?J-NQSRHf&X{+LupnR#fp~;5k{MUV8{I}Gm0$HGb_+O;YwAjo|O?J)}zU( z(q4J*`BeZRG}c~}UmNU9SH;esQn6!U#N6T3&}EFWmkpOaIh#tRq5mT#G*)($a33%_ z;Pp~Jg)M_w$qg5s7NR9*cyGhztX#3SK2OkKywhRvRkQQ%MR@uWg!;6TvpTwdj7U7Rk1hvsf8D zlJcDk-CYBlvAv!vn;yd*kufbyMWVrcRdq|U@@8(9KdQs7-}Kf9DOojLHq(|r3gM^z z8tc@NCNpwv&R<0JHUEraTj)pj=FnleIP9~fK5&0x1U+d-(!15GH!!t(4H$n6VX#(tO19ohbw;EJ2-&h%KolqDAS{<@V{ zKy`yt&$8mYaunlP6c5S^{9#v9-9X-|9$~`Mi@E=A&U8=~Kt8x%#=d?~<+=y4_I~U(4QO(39Kd_kW)B8BBW9j1yPi`6CC**HtQE$J#l0Z3tvOk>gy~!ZQ5H;WL$Xs=|L|OxW zY1Ys0xH4pJ_TU_S3>=-Ev7#vI{-DPBy`kQ*1VXHu`cHf6^s2`dWUs)c*UcjY@MY-z z{zYv@5)(>=F^-){gK1OBe@2%M=+F;PKC96o3r@38Lg&SGyq-$K2btU1CXd6 z+Zxy*QxlIi{;VbK|52AD(;0n!glO`2<7;Vc`O?pC zS#L}2NZFBJ&H6WZv(_##LFITjQUJDOOOVm6ffNf|Xt-rFL&B){$T1)w)w=a%I@OfN zFDsx8*s;hxsc-5gJ<>PBy39E)ySh4<`SVyUy0orGcc5+ ziw$kMkvF3-@|g%g2K(;skI?ktU<*0Fx-pvGzvtFaTk%ESqtue*xk5qwwI(vAOr%zr zfW$ z^lxw9rQ1&dA-@;A_r^jxR~{e+Pz@DLNEoog_HfoFN;!fip`8IZK~z>vd(z*^SXQoUmv)aW-i-e27QM-X)Z`x^M?5+w6q!VdY{`6iHA4j zHOPKnU)TS6hKcD*H#YJ?C6=aG7cO?R;P+ryNKzPAfl(9N zG@4EbuIR~8WvEgV?ZERzZ$L*Uq&kz#CAcurjLRnn`UbaD{SjX+U~tnr?(5$}W?(T$ z6&;BS-L=(tfM5OZD+w8w1`lZFft(&jmVAE=%`q*m=a-WEo2UFq1slBb1ApP;K#j}( zGQ46C<l=i>P5-Wu>UF#zNQeCE6j_fo$LLH;x*Fjw-0Pw6 zx`s_FuI-Y1vf6>j=5PU*T#Vv;PUwmm(gysecv6h*vKY+8J3!ALm{XzybCIk6TszTQ zyZ!MOuKg$eC^}lj>>y}qYN%+nhgo5{wpbk zEG+TUmG3O0EdPTje6e8kEc9^D`lx)vsUWW*g-N&glffCb7LqUZ567*&JkgI-LK|LT z{v8rP@DS`|u%9+7GHA~)vx-^GME~&(+8_*QUYK^}h7fo5b`2~q8#sPOBEtyqG#bjA zBpo6Gl*6F*CpnO>n3(EE-o+2Pi_qh8)QcbrpmFid_YyG$rYX)DB=t|{*GBBz?G~B? z{Xa_7MeG=jI>erI#@GQ-T9*YZ1^MBiOfwnw0edwZ;XSn!7LP_EN5A6(#W`#^$Cm*t>GA z-UU2;u}@5^QgQ>?`%3czjF>b#S~=^zmNFlLGi}mCG=SFtao-q8>b~70ze6Eo4ERv4 zHJV8!8VrK)q3y84_y%!Rm+{Th85+U5agS(jx@K(~dr!X*rNS4}=)UVe6x8D-t&81; zeoO?pIuk(Hts6joZF*tDr6c149s{40&}B-=99Xwq0jLoZni2i{L-$}HkAj1I`l+gA z60vDAO|EEB0Vkr*Xb~?ZbtnxLI~H6&^rvyk>Z@~}xLR)6H3nQ82|bjwUkGN76_rm+ zA4fnRS5^Is1n?<;ae*82izyrhXJrw(&RDeT?}Z)DifM*fND&GA*xWR4Q)}*UQd`FF z*Y4Y&<67|Qf;XeJP*zCj1i7j6fQM8UT5X1OE#+IJu{e@b&8%^e@+S=CDUnfVm(R>v zTZ_<2C)&l^#C17`-i|ccvBQNBhtTlBOAWzar>~2dARpMD)xO{ePwXEKFyf3yBnpY1e9*1J0wK9 zySu*UJ?A@r`8N-D?0fHPtyQI_^B^}%V9Ya|hj$8F(H-OE1F39hqf;g0ou>uaK@@0n zPzv&fJr%XXkx!*n4ug+@du?H3`&v4S4gBx~UTW{R@(Ub7lcgqpW%^MKLAe{e*DvjYrVLd33}9wN%8&t@gM12VjtgKGOM0^g(2n(HcrE3piBc zP>=mAuwj`OYFAp2rfLfjIO={*0i@K`uD; z;^~771i?8dn%j9M)(pn$yAl&?pW!auWa<{KWGz&$flZRWo?~h(;s@Lu2G0=pB{sJw zA}%Bk18Si)pXiZ9ah3s4e*TAPUXS}rOSkw8T;VR3d@_j%8yBKkH`~x{Ekq_dG2{!a z{+J!)-iKa`R|Lb=R;a5x{mI07)SLkVotcBuGU4Pnp;&~jRQrZSn!z^S0wH^W$0iI2 zo^eAT7T(rOP-?Ujk>xr|w?198|M(DY=ux=Pi-7DEUrtxPgzSOxyQ*jO0OK-@;x!f( zRIB=<>a6irNFoHMnYt$6*x9P2iTQGI*CNcu8nzS)xgA)n`URq3jNoVv!AD`NL*fKu z>Z3KMUi+Q%%U$4jlWp_(j%`!uxdy6!$Tj3K zza6FvN5-_+!qJHcfwUehIqPuL?xQ6(fJzJb`0j!HmESEjmZ6Ijs$^W`CAlPsAoxln zq;tbunmQOM(e4cyITm7OvEsOY-GU(rBs(uBssd`>vdQZCk#xpIei5Oi+OaeGG9c4F z6VV!avUM>cVb({*X^}&d-HwNvYW{KP>0r~jX95`93RG`&IxNQo=6H@ax=*1jxZ>dt zc*+SQe09STCUD}oLWGq5Nv zga{Ty_Vl1m(v9Zm)bgQ>`58Y7wb2-sXSh`R1z?KX(UQ>cncja;Fsh+EI{dHe;?u%a z`jVs$o>fMP@_Q7Cd%FyytY~f)%#eT{7)an#A5IDj5AO6Zn)E-eF&dxy&(2lZ!+qMQ z;H)DefNk)&TQ4$Ic!OzYXQwjvE57_~3C?06L1@AU9!x{HX{)IBHT2*rBDrmsZ)Cep z#bTJ?%CrxsaC38i|Fz>+HlnEHtyZm>BtEy7U;ijPhf1}QXy-q^RmKp1SLbm3Nu%g9 zIU+j;hq#nh_3UYiITXJrwry`7R~8f>NB|=+Rt{(8vTxE`?}-z|t37L%iH^SW2`#oX zeKwZbViESehsIH27VKItI7p@uu-5fKw+D<*0Wl(++Y+&84o`>S^SrrVO7-?*s`vD^ zOXg9Z+b8z9w`li?Z?L6z{7C#?jLy>tkw%s*>MqP-w%Xg4%)({=TrGR)fnlIE(6ZSFfsdLbZTAFHrEh++w5k(@(~@+RkxIBgOPm+VE0-$r&fB*6a)ys@!m#{E zW(3ld*1s_ju)b#v^wK`r_I0l?j2f!+IE;v{;u+>%)KuMBBOi2jRxMV7GT%tIr&&^2 z3YAE=;ePAJRtb#L_`C)rn)#jp1Mh|Iko6wOI7Lc zL3x7aKjbvif>FH^a4|~dIWaZRFj1FVI`Sot-C67SbNwbuoxNKN z+w}vMrlvjMvAKP5SK1=X14LVpmy|FTKo96TyC&Xq3DwW5tJ2f5XxY&1pnl91?y{*5 zrVT4UU?E?}`YcRkhP=Nf$08xyrBP>am_fJH8{I{HHcnb<-DODMCg+9+t(a^})@a=- zr#K7t1!a>a@GH-4N++q6X95bM!>QQjcRrO%3|zhJ{YI5jN&H8 zCG%}0$klE$V02eWicvI4Q1M@Lozc#XknYEiUrNRu*@b;w?0TDj9en2lr0}H5mk$am z|75i^`V%L`%&9iCQ46zz#1q__GS-vJo{)Xph!3K>4$NsZ$%x4yVIeBbVPsdQX}zJ`v9R{|17603|09SG2gch#E@j~OyBG3=&*!l0 zn_GY{0&r4Vu>#dxu&i|fw6^G$H$T~BVY${hqs`W@^{D$_>0skp&N@Q9`4A{`;10+) z4aPYIz@Nf#Ihg3z47vUXVh;T;sbyrNzLo~b8baH{7!(S9824ZMecC%;0TDkSo_n0r zIsS&-2YBzdE}!LmyUfk73$0{%X0EC4&$lszj|i$z31RW?>GSE`h4BI)rc< zl>U5eqOrkhx$f4-XJ5k)Db>t@5)liIGGm{kL4i(j-_IFJH$Lk}F*$QuZ{yMX&2ncU zxQ%)-3-*N7)#N+sIQwi`)5m93tF@Pmz2>Guq2hC%nvOkw`)=BX^$uZ^E;~?d^=f*N)oQ-J>KpvKn{>RbgEv!=36vsSS+e)TF#|NF#Y?t#uk@we5LB)Y@;6) z-3QB;gUXVYs_YCx?+{cJ{D)NJH_7B1#i2Je#v?n7y@IH>up++C77&l&d>-LZ#^$g83B zDVt=ffTzyhTs%%4=+(~-%D!qVP60F9w1b}63K(Mw1hd$`dk99v3-qU_dFrLHf-5-TtuE_1yLP3tU!$@yy zMeqY%AxLZ!XB`e0*)w`}EZK@v4bJMZI|8d&a1@+ZZFZkMT^DG|1lVyv5t}8$s?s)& zZ%}^Y{Lsgc^>BA*9J}!e?KS=yL#j7qm^~!%uq0TrP+fUG;Hgfi3a@z7OEf|rNSwuw zpAC4td-i%N8aFt$2pTmH>ag1Wv#%AbS(Iz#h1AyhYFJ~0~( z`+%S35^T}wpS>FOb#TD#%X4${9lr^cHLq4K1;o`S$ zqiDw9K&?2wl($ZPq<41Op}W4^abGMGV_7;`AM`y(RDKi+)bHUn@r&Tcn59wlbiSFa zysv2d@zs_+=^c|06_L~8c3OT+{de>fbH7g-Ie1)B9i;|ahg~tQF9!aPxGyKf2FAa1 z)(YZ8pl1hRAT zjC^ZT4J{UnH(-i7O;w4k%C7>92rZJAF?!(jwr2|#dEMS|N5^n>znG&nc*)1HN!}Fr zp5YY+m-a;_>wAe57kBS4;#WTKIKPL0@AL`eMyRz|tY)x`gP+;ec2nTs2DfHNQ7Kute|7d!r38Z`0uav2hIbA{hZJ;))JTOp&eV8^|Cj#hiYf` zkcJv#4lfUZlPOK9EE@R{^Mk0iJ1mucX~=v^&P*$K@*6nJMd%AlAX*LC)A7s~EM zX|m?0FWB9?e?Ocqr~2RN4JjO&cuR_MSl0<(bM3Tl{z}5yzQMGA>*uMcmT}51X>27s zTsKJXZ0PI{oI93Mk-eD-zTjvu_3+_q%@lZ2)opf4+o1c%U@}*#H*-4Qlwgt1098_D zIrplHIdk$H&y(+8qkrudpzqEmlru)V8s_D!SmK%B;QWmG{faOscacrw3ud`@bC|qm za^9$~Y`qQdDSMdUE18Z0?KfERZ}EC|AI!EpOcDR=2@%jhBE3u2Ne{IJj=orLd77n0 z_*S#Z@MqYLmmV}Dfdb_Pi>R_3_1>1maGyK#=a^8D22B&BHggYq*v^Y-yT|6D38XA8 zK1>_wEfwj#(8s2YnHq6KJbe;s*?JNf9kclhF{EQ8(#wtOB#=3vY5Oa9Nf~1@ldJgS zHt@3n7qPiBTyR0HXv20q2uu~KlCSMCh>;ZtBar;In?9zViv9PtK*{9>vVY8Zo6Bqe?lesoOXn9G91|n5}TEuy@Jw|nV)NfyhasW z%ZAVIE$s2Q+IVr%`OjAIGYyDT$q!^#hWaKuTi>UI^FG|Sw|cDnFSRj@YZNH`rqwkM zu~5(S`@h=tL3x+WFLXG+zX8(RbJ zTTGcm#iEnC*RN!-*!yNWfm_;!pUkGJdh+Nde;%VzI+=nKvF*@3SBOp8QJGYb9riTB z1rBw4N4pcuNTv4m#|QDxq+ItwqBW1&S>@dL=1n@rvtztNjFSr3961?$PHujFvBj3a zeV+-9ZBC8-{RxjTbd_XNXw5s|3h-t^n8u6J}4h&b#%n5)KD?6mszp8%8-THp*G z`crBhLsx#4#3N)nhDgCAfm|4XOH!qfiqCTvo0aO-{l zJAP#G{%lXk&@*1YpU}`RJQ-_55SqcMrz37M*$U5+;zZ1 zd5|ako0)9Q6?ru`Kby{A2@8td6?ZhSmSY-^N_zLfZx-8;9G2e zJk5_e>|GJiEQ^jBsZXFMPQLobDy38kwN}4=kqszB(gjg=)h`tT7F9!`J@K1%)4X4P z{)LC*gu<7MIP}b^K^1yU$ja%nA%C&l{G+xI#`E5x1ON{Akrf4``JC%%EFYNS_LBBm zUz_@1KRz{e+2rGN9s<6h%GL$#OLk!Z7HHG32(=OjYd@L#%W_1wP_mCR^`xOKamYFV z4JXg6N4UbxYSFc+f6F>%o^D;d&j|$p{E!>Ui#y@P5ajvK`#7L^yEpS#2wt8Xt^aHn zhsGv%)-RiBhwp1xnRW5jS7Wp6%s6$A!UZChg`*ADm>xm3RMp7!zy3zR!hI3=Ol@@^ z2q4NqrKue~h^G$ip;Xxj<^ds$8R%kLIp^_;kt_yAj+K$SAgR(UQo#7n+Zgb3C`~Np z8KZRo!L;_dQRP;hsz~CJ4&-b|4MvuBf0|MKS&4p4NryHlVCHzD z9a&L6(`P8V?UEWnG{f7m-g46318fG-=UWp1@++r2#Fc;;iKt^o6`)u<{nBF>m%3d# z@k2r61eaAc`FKYx`GpywGLsn1U`$ZBXWFv?BMPmMvXMX zY*=}NR(KpBr(y}8Cx|k8WxlLANW<4Mq`epJhV{`5)28!?#D$gc+C{(E?0N)>McOrM z0z5+GM{&)MpumiBPlOhGoc`A7AAoGG?M;{L%@c)KFS^a-oX#7n>VUuTZfv<`fs+J< zd2lpe`+=XlY#QEH%vm3?AF49SbH(?OhtzM&Z&ZyCWC_)%Q5ETFMs!3Vm9}}f1{}Gu z(AT@h09NJs->uYBl0PlT9xTm1K>8Wo{sHpG zuAv9$=z6tLraU1k;{+xlX4pSG>$B{b2o1RkAY8m4n%Mkc`I0Yv^I-4wxI@N}BwwYk z{ra3-a)9cyb_$h$8XwaGZ?P+rHbPN>s%e;x30bOMwv$FQB5Y%>psQfeqWB$|hl!Hb zHm2)MyGd=KB`Gk@m8yqgjVKL=JOg%)E|nm>2^M$M@=w zW<&|WfK%(tgW7^!hD@r6sWump7&`mv1ci(Frq^o&!hDf}?|M^~)WK356L0X+X;D#W zTv)KioUNR`IMZiT+)&J!&<4Cc_JALMmYfX`);K|n>Ls^*3y4d)*Bm<24E!Rpva%i( zA`<=bKEVc9ifXUDcMv2co8If!l25-41D5*1f%Q*oFrOq&ym#F~A-9S7Z0y1vl&i1s zCIiOb&@k`fecRk;TqDptrZ^jK5}i4$oPjLuFy>)s%dSzKUf~6_ZH~LXp$t4Gn;NiC z$-qkh85y-q;fTFCrnGa2EMX@Ww1nb_g)MF_8UPa&6|Q${I$`<44Ag-z1*9$3j^^)< zZf>EvQhNIB-Op4`lY)R;!HHX3;VaMTd=ta-xbK3&Eg6l&lrMRmZOM(B!g6?YN+hMK zsO)ylBgHHJpn~&#PFsl-vyQ;;12^(iMHEIrJmTZAdr4z!>+igmM+<v%u?v=G0J0^7z*9Tvcl3(Q?{SUrdo$3{BI$--Ss}+#DlQuT5`M3t5y9d6eSDP0cSU39 ze>6lb)bfi%1C1VO=-}US%$p}>s~^Rt(xC)QVgee=ds$E_i1Mn`gsnu=h#m})c4MWa zD4`#UJSL8&&&u^ujcJqiw*#8+i zyrn9{{1#=0f?RvhpJ7rI5uTv^MFy=_o+%aCXlZ&IEg}IBnRb&xo?D&cpNd1jXhJ8NfP1 z#o-}97qa~=BoZ1tB(~SmIcCy{51-^ZsUEc48~2?yx^KXH1VQuLZ+?ZHvA}Q>k1WOc zJ53V;KABBG@4c(~MIfXZ&cz*s-ngK`vmidZ*BvI-Zp~x9Fb_c&I_G{e@^TeOu25a{5&bEsMk>p94o~MGE=;Cl-ft@?_on0R{IpBTa~XTDVDwe2mQbENwy@D_|3oK69hCY zg}pAB#`6M&;i;1!jR*Rga%-0wK}z4V`P`g+V*=iCBJ%U|19b&3dSeD?$l)jy!pgc{2A}e2nMbO${h?R35W*Qkq$*G(KwRcp_PT z``_`AGsR0tZn;OT9xuTsYKC zVeX*vfYg4ay({nek}()mvx0_3_kMQ`*P*%e>~PRTeN$}(O}dzZv&FAt#iU{JtD2!B z3B=0wTUpaNwd!(Ynh?vh%%Y-2b1lB~LXry;s#JE9W)z3A)axz}d3jUNtux zDBzhNmn*fr#tG*I4Oug1YfsC`qxr$_{5Z$fNNEF1`_${Lv) zzmR0hAEXyW34#vYyn&qzhiRxWij6_-GMMPX;(q<>hwVmyeuSAh3nf;CI7OqLFK8!^ ze?T#JtVOlaOO>hcYT^L=?&8$^(?#D96Fz17*%!G2YvkMvUA+xD@JVDmKbc|}W=vF(*teH*DRdw(J9S5Rg zvfKr~*KZd;mZ;Iv1a;K90YZoi>|DkWPjBz?$rWo}+bC=UzwlmTzv>D!IOz;giUp^J zm3nx<0ZC(Xdlw-61@DjpbP8Aoi^rBzb?#S{??E$qutTStcNE~H3AFIq4}e>1IyuG! zrtSH#>HFZ^d3q_Rl=EoP_c$~0Zrg<%QB{T;l<2#yN<1BQW=)D)PYh3ZNUDWziSV$3 zy|?u$+RE5#T(wCbo0maSv4f>!))AFXj}|NhLsxv;W>Ki(Z$fzAjLwCsL%zIx%N-8N z=EV^spHS|+^9s$t(E5Yhe!`W-=a7rj1y?IUmF51-eZeHi-eKB0>^b&u*l1$l$ALI# z1^ZoQ>+s@jB2xLeyA4oZTTp2-gHpubig7=~YW?58Ff+;P=L)_Bv!Rw+GdFN}PNl;D zx%8mfIdybZq+qAURM+hU zZm4)|V*A7KTVQ^2duCEuTnbpZ=I{ZAM5k4=*4*gic`l8}sR4KsjL4LP$}zBt41^^$ zDm_u!H&WX?BSKFLbr!TJ!hPY@&yR%dFKgb9&o>?Y(~KWEwL+AayN&b6dH7{#MQ56B zlo~rtkR%RkR#uE2yn^=Y1Du1i4y^S)8}zh5UOjEQdv#@aXUTO&U3uly+G`&0Z9lLr z>wgBGKdV6OcVkOS&<&;kZOa{m@UT?F7ewA4f=ebx%st9zWA%^oPjrl_>vI3LMr*S{@!YhxD&+@`TU9y|bS(G}Y1A%c#!L;k>kp|W+J1;CMfHiHB&|u@r z%2~bY1-|X^uQ!df@$O=30qG$HsU#hqXHbq@U(n8Lk@~?iu3KA0hm0td z2L?*L#+Ej5(CQ+jByNm8%WYTXA^rF*O2-90!P1l8|DAfBLY>}R?2RDefHK2cX(f7r z!jqA>t@RweC3>5v#z;aW7W;R4({0R#jaDu_(H9a~^0A_}a%v*CrTlT}TB} zZwl6WHaNW>P6orDjN;l4YILf8Xt6U4v5~n=I}PHcA3k8YyOU|mbR(OH?Q-S+X`CHF z{ZXN2EDKPc?%V$L^fT)zg z_iq5&A8fP>e}@0)=sDg;zyj|?p^qf0kTl6`S*aJ(YUye^C`S_UBaA)I3P2KLgUDoS zPqgH`?%8n#f+Z~4y{nZF$?D&kM1!tCDBuh}-G1_{?{0}HU1pw{K|x{8`d3*&CFs5# z{r}l1wVzDRU}o0K36S-o5`4?j6~ZH{c1J(-+mn^AXXv_ z&*BQP4D*R414I~V3ioHFF0~C#KaiY%jtSig3028sPUIslK8^?~VLB}YG%1*17Td}G zT|rIzL-RXUg0EB}0rVI!Xk_N#UObtk%Giu>u_o##OafPXP&bMYoSaja*W>&U_nIe6 z^IhAN-F5G>=0g6b=G~uCY(bMvhrfR2o$Lkhx=+`hJzQtEWk&yc$fjHoNL4Hrax#fk zsRacO^n6deNCRDP<>-zTIb-?Gm7q5i+baL*rjYlGUGj^n_P<918U4~*->b9OX9Ud( z4swS~`}TpcbYf<13YgIA9N5#Gb<7 z@1(s=?u9C~vuIQN5m2#9tiT|TTg1lew>Fq;MJ5l!z*P!OB=oIEfJ z!wa!D+Q^D7m?TumI}R(h&o`k?o5y~$+00~^$`eya&Se7$AUboRz^BPy(S%!EVQ*e+ z3^!&Xi0WwY;%ha3Z`9IuHM4I`J^SRKxyW_va7T>5(l#tF5E2!VpZrj^!>_zTQh(~U z2;CaavZqyGxk0|LsrI9X)(So<31Mz?HzBMlQi&PO;|3h_2{7+S4IjJI7sVC&%q6HH zD$4)Pl9sKkuByW0^ompa=}={B!=E*iKXCg7`$5ub1USFA8#S1^%V-Tm4~$40+#9;K zw#Zujo`jyBfGSyWfqr_!ra|}dv|CqAwzZd=udND@fKzEhuo0QH89!Ekz+eQ-%QLFLB*)m!Y^VS6N)V(udyvGzOSmOEjm{A`H( zZZqY}^T|t68~;J#hQJi^JLjA5fl8u$bTTlWUP}?IOt-=QoznQ@OPcpKxng-)DpMqt zSb&!GFdNN3Tgs8qC0gz%ga=VniL?uNMha|iZ7qr|&(^=&Yw4RMYo~t3tG_6`sGAKH-ZsxT!MuF$Eg8=yFbgbTVyodm%2^t!JyS(R1O}lhwg5(gNvR8!F8RnA3Zi?pX+!gY`d9e>CGROGe69g`ltt% zs9-hwzlZ`6!f|hK>e~vTrDSrtR0rGdwUO`io z>dg|p?K8b3hihchi{1;6)w~EXX6{`@y5(;Q>e=`U4GC75*FS!08AZTUQ}m%83h>GB zs$1QO-0rg8c}O2ROa+`gU}4Hp>;Nm1;82Xi((v zfVx_W)e~Jf9sNK)?U5q*fr=B0>mBj%0!5HsOD&%a1=nyY{mTT;QQODP1)vF#`_3Qh zM5MS5R(t`=Z0;+}FmACtYgzFHe7NjZM7t)>Y{|(L602YcjA2N~ZXx4XQFpPHCFjvj zxvtCdO$-6i>gNes4pL9_Cv5{vagj`Bv-DG6a^JwyH*ynGQTb%&l?b*q#sPj_!yea?tRR9B-j za6QNhF4c)OG9qyU|LNXir7JOd+@69Z9OiB6Js!5n17M@30edc)9$Nxd_OB?Fa|u(| zF$=6~p8>Z?(Ywpk0j-2QVGoD5%Q6_z^?M_DXJVlf55R^eCnuL({-6bC{XZ7Kkp}oH za4wJneImC562sBnNV@*to!z|rubPXU5EGYwVplQaCi%mO7A82aJ0N%}>fg9=KTU9V zU?Gv=K{U|$HvDdU>mS@V@!WM3T=Hq?yoI{7OU`KWhwYQT z1i!p{`P4RQfm-)IX@s?pznmzCT>tWmE}010@1ja=l3y3C6zwn>w-ZRQOUhm;4E{So zA1~sh6FVbW{kr}%QOf0)doWHf{RGYHAb;_|>VHZBh5Efw>ZcAIjgfe0|5fPBpv>zh zI*%{O0rBOS8@!^%af@TZTv1b(zIsU@VyPZPxKN&8Ck*lRXR(hrfqBZJsUGdAwY>QOMif7O{>)*?Vqdu4Oau5I=1s0wo}h&h4!r&2Hu$Ns zyZ%KFgmwl!c&0Fi?gpPsVH*AhW97>Rv<2ZzlWIHU z*>yjP1D!Fydqoy6bT>h$f8ulwOUr;$$|YZO@>0HN^{p^gAAbBcc+ASG=mOeYDV zHnccpqpK}PsSAGo@Y5U{`P?P%Q+=Sb<1c{^2pfERLW2i3wy95*u0Lj>supFGoZF6D zJp0b6vCyLZf*KN6JDeyyicGh|+T$nykJ zE~{m8ZuV?K7o`SG`gDR8Y#`RQudy7LC`mD_9D7Z$sPd9azZyTWza+hK z1N2DOJ*Rk41GsW#X)1`i$5&(Lm==X*eedoFJgBCIIz=P~sB`Y$(xBnfCHfTY-w8s9 zC7H#DHl}Kra7J0F%AOIG)#HHd)NxhxT;CIu<6@#k+q7+2{PieeOZ}ii7iCCqf1rur ztB38&&%yV;67lVtU_0o{7vrbX74iGqx7Oy^N6RH1&^sl$Y4uM3hKD^fbVIYuT8#OF z6_bxc=Z|qWHiIyUGhvhJ5ggNrG1AM=ac;Ew%f55Hb#g(%=|9%7-hUsFL5@P8jrTY` zDv5ho)QVVfr|fsJX?Vd?Pu2c&7VGILH}~PWbSU(O^5ClZG|=(xk-MPmKx^Pj+N%Ll zG!Y>Iz+~Y}r{xi(y%VVguk8C@I{oSW z%*6_^lT?yPh|l{vEa?e5e8cofgLKTx?kCH=E<%cXmNNw(?qx;L4XDLLe)g{_ind7F zH`Jv|64VEjjBxOY#BFvXTJ7LSpz!5iwh@reoZT!J(1IX8`WVFE;Xo#Ka6g34uJp{v zgWZJ^{&h|7#B+LiT6*9P9ZbiYh?411`wc2ie0f#*r7pf&04F0M^I5q277}7E5lYUklxYP$6J%9~^Lt@|$$gpA zg6nG5a}|3z-AJoQp~b{ct_Xj_0e7EM5JGJ1_U-PZ$jCPSWerL4l#0o>GhWgkbjB(Y z)3(qwj{eG4o?tjIK>K!pP&}&R8scsIb6K8N5_NKb6c~{K zQ!{iLlpQNAU86QZnMHOrw#YL*o)5hq82JY}K(R%Ggm?nGIaxx%bvU?2n6?Z8(%CBB zVYR(Fc$Q>O&t+e72N=jd2zQd)%m)6GwM6xSXM^UkuHjRWwv5cL zvYjn`3r`D4$lvFp{g`x43)(%?5s0UnqpL^Xyub8 z{c6X9*-CYV@0WBGEQkMv$+8mt=V1s`ZN<~f$N!q}#r3g&`&c{>4ArD1y+O7ndGA-!QV;RS+47vz$s%b>4T_%| zEl(85(6(!dxhcpow&)G-4Q$CD)RZ@?|68hDme`WJW`f)2q-+d;Nrz1cunIebeIwmG zW3Q}Yj($>l1nqiavoXBUSm>^UwV0EpMz9K?6YQ9rCaKqCPY6MqPvSQ}efEVV8RUUd70 z>dXmx{h#^v?e(I4*NA|SQ1?>H4QJLU5U$AyBB=N^_@js{YW+#Y!>p(}$$hAW4D-@+ z3N!N4SX*urKw*46K*}~XXa2%{T^hTV6)JoFwz!UV?UAPZFt?=Y;Pj}$zq`)j-Rf-4 zgFvfmCLCu+kG*~Xx(@UPIk+JJ`m^GDLm?LI*3x^xZ~p_6@*?QH`~hNk!0B2~7?9(~ z+1D4itR4P(PV2gw6okIv%=M9isIf4vx>F3{ewkQ25-7jmPqRaU9S0hOuuwu-gMt;o)G!2`&@`%T-R3O ztd0pr2{v?F=Ox0Tgj5{&N?L;bP@vU9Lj%zyb7)iwRM71;`el(%zf}Mcl%4Gp+|z?K zy+<%Y*gPBbwdqG#Un@>w=knbh^6_$8*oMiZ2|+TOt9TAJau?6-YbQt8IYpxjxnb}R z2+!Ka$K#Eper&2HjcV>{y3p|21nJ%%J_r#q3>us>P`HoSW%$-PddJg|eT|N-!^5>@ zA|pZRBk%+QUJ-fu2X9XGdrrg7=h?@{y~X6E@o=JiB5afzy>BRwvxWY(dB3XL10x`= zynBKG0d)8yJ5drG1*po10hr-V)W3j^F>4wiheCYZ*L-2zjzZ34UiA$FPBx<^Js_>R z@LR;zyewwKz}mIbC;27q+#R5w^K#(-)G=?z&si`11B26Iwdp{Y6GcFCfe-f{->GIs6Obn#PqN0U|4=R#-GMtAe2L z42hzDzF=>t{FDRhyN^Ed-PmYqZ&W3CMCQ!vB9O~|s})4$Dw}~z@Q~E(zZRFRWpg%6 z4Rig%{ee>gAz|J?q!J3OAYIOvuK^|Z=%pX+8_C?gHCew4{fR!&vdi^VJ?1gvtZccpaOn<59LxJdS^TTVAE!l_n zlBiuKEw(jFHWU4U@XQXDmAr4nkz$EJzN*nXVjlK9InP=y*+-jK@X`+2*A>pDVnpk% z!3o4Fq!tjBtK5A{_BlCCvoEcr!yr2PLZo-+B(zi%KhGaoz1(LlM;0qLTbFlwx!*K~ zCvq23e;e8Ijs;JDcLKORTb7M$BQnoh&Xj;|Ccu&C^b}P}Y+7NW9uIG?t>1LYP}HDs zM=A6x((Ug-V~N%Hn6%8yaDP$R%)EDGwURi?l!2SI$Hs>y)2Odd#o@NdKk>)as!1Zn z(1zMzW(E0Frlex`PcA||XJ>3A)@lj3SM2O_q5_C&TY@S$DH)Se?M-IbaYl{pTnvP^ z!e5FV(ECheHBIeh1A397`|A2_rYv4Hb3eHMxeVtrF1mF`l)JhrX=foLv`9#iE(ZVJ zC>x_n_U9=sfhhoi5-|aMVsmy5fF7WdxKNnq4c(vp3-iK>v}0d=m>{}e!&Kw7cp>-gRHGtiK2Lw z*vwfHoSW;tBtm^!|D6O;B!8h91pJXGx&a*bHxLTr;zD-O1P=5PAO8E(mTZUp02k@^ zj0|_*o(sBIXYaDN%MnqoNGoxZ*tI^j30G~jcz7>eSg4M+36DS$5HwO!QnKEpNThoL z(rT2ybX|$+uX5I4?bHJG6#B4A@kOfn@0Y6OI)dVPg=w&lJ_sV>WuAYve*M2s7*Y&e zwRm;Hq{IN`0))`z&qK=Kq8;yUf~XD@L%QB?#1W|GU~h7BPP+$!)+O)PlCzxOzn-HS zQb7+9jhy_g63Dkl=(urx>QKABekcDv)J+Nb$*>P; zgT6B!=Gy)y7H=*9ZQ}+}Jh-lweKp@>8n^{7(oKail$OK9NfeArLI2q$TwFN&Jf8If z2P}I!jF^}hfVdQvd5hLF!-~cQklr$Le=^UvZ3&QQ&|;n7RfO^|vw1`}*srVu6V}0@ z60yn~5x{;PxD`?&-HkP)gH73HUahOPhB+;!=E220-}42$n)}A*CG4Wev7d?D322*dJ%a_>WsgFqw3}RnJw{tUhsv{om1)sb=3a0ex_rQ#exMSqGAp{Z# ze9-b4+IAb#Dl926UNGD-U5+YccqYlF?e8kbyGP_h-Jb^-t)5Sic{@k19V{$!Oa?Bt zloLq^^@pZh7^_ZpvcOmxXPt%~#O#J>Asa}#` z_C1T^65d>kOkO2>m3{i5JoVyF)pI4|`s;hs9i2BK!YJyqYp1(7QV`pNNq5S0`DW%e zVnQtJJ`z?U=dV3o8$fX(6%6R&fT~1+L2bmGC!r`V4#O{JM*`i~?Biu?9Nj%_kw5nW z&PFye3~?ny{c?=%H16yB)Tw8qz}Yi;8s>eeU|@<;W$XCz?297^bT^9yv&MG}x6|LS zK!JLzv1;p}y;y|{iv10}?dHD%_iVkNhnxZ+92~=O;0rFHNsA3CfA|0@Kim0BCd1Jn z&^X)0UH=eO1yW5_Cob*_^}cl|anfql-=f5y7sbw|Jwf#Y}a5|Bt4# zjEeGoqxB43!jKN#-QC?Kt#nEW3ew#r-7O8$jdXWNO1Csf$56s~fB$pNT6|(Li^Z_s zXP*1sdtY1Wu^1Fz+;V=kK|D>fk7caY`hUl?2%JqBO@d@FkrG_MPjDbDjhSXf1kR3c zHzCIiL$(4Y->n#mqAhW-@ZM8mtKDnAKSRWPwY!F3i3nCZM%VNAJLKJt60{tkA+pjq z6(NkS=+2aYU4yn&SSC?$pEU7<7Q+$Kz0HU-f!x(n1DF5zV?gk}^7VRGO6!55{*DgU z#mFSY7D<=6HR;CT``ZlMOFpBj_x~Mt#@UI|Y{BK8?1xKuE*}}vtL#uXvKva7E@jFq zn7|%Ji+xa~2M?Dr9nhiQM$|G0A-BY;qhc-rjU;x6NpE7>s&J?fDR3fv8 z!JY|QIwuc-&3#=E;v@0C2ps-Rbbh+XcXb^k*HcK)FjtU>?;<6KMT7D7pFeOUz|f6W za#61;5yE?@e<=}z7`iPTaPA$F?nDiSX_$SW)s<;ipU~OpKMIX(sE{%h)a%)}PFaMr zHDQe9Q@7Dz5_js(x_fELcZAL(6p>_*R(@!| z@>^t_&p@`!L81u7=PIMDBN3;^VUZ{cumCDl;y`6^Rs}5|O{28~=witjEsWhnc~Uth zg2HJmld!eEOmF#EcGWxc>~stce+%FkCgzN~s&)xg>>$n1>#G@e1s6s|zF$`Xa{+7o z3nTIhCGN^P$Li6Z7Hkx@q6ZEN==~O8*GuB>+)p58e!yea!u_^LP07q!R38afC82GN zN+OyChd@zQm?*z6rpuW3g()CYH(8@I5``l8C(LHmGSaPf!D97iK_iS*Y9zn1yu%7U zVbX!*$C)(ZK6QMBH-(YbU+{W&@qw1#9*;2`tzYGsJ&O4~i&h516#r0>0wnU`wA$nj6($-T$s$Rl{1HOqH2H*Cv4`)|-s|QW zcIp+A31>BjT9QPB2iMjWj0OH#9+EoPAg7p$lS%Ly`zWP=g{GOcFVS^VJ`bZ3&zHga zWb+s?E#|Y5a+q_Cb#{cN?$?LTD+)yX25hGmJ|d>?3mo4Kij6Yfewx3unhlVCQx9Og z9UWazf&?g`^T>a?)Y;{%E{Se8EE;TQU}QkXJnI+IM~sCm-uL79jkQMSDgIA1=g5=Z z)S6{96;Q6xRt1biDFbblmNtEh)jP(ZKnBoX3z_1HbC+4uueA{>-wRl9ttrn0snB;w zfF3i77VQI&M5OvEVq0j=(Ls4P$o1TilD%U3VeWyjNW6~+Sc>1haZcH zQvC@uRT_EyHl2Fvt7EKrwKlpmL2pBmOf7zd0C;=s?Qff$Nl`79mA8q{gX*S6H#nRl z<6=4QLQUE?%-Ri=lVukBkkGB-J~K}(z{ql-4T^6p+|cE*3skHDWTepnwr+I$=fzQm z4iC6R*Oa@C%IoUI%kZ@?60=!%y}VX34&+!8D8A~Hogl`c1t~`>42)Pa3&I|j{s=Ih zKQ&nLf=Ikt!r-L~A#W(a3f1a(vv`k%aU0Lv@2v!L``E47Mb?$r$~lL49G89-4h9Ir z4mD7iCG8+@%WUGafHkC#Ak0fw3&ntGfKed;qbT81iN;|8p4AU$aTT`esWg20OQN+O zGAFLI9Bs~TpvP5x6Qy?HYT~{f*9Pa7DoKi@2kI|BQ-Spba>MXybIs-7W!S~W&da|i zU^3OfkZeA*AS=Nz9I}o{l!$mRvW!I#5ET-VFcQwr+2}PFlLrEIz~ajD8fkcV*d~)` zB7(BG=jaGEHWm}NFh&>(!qKgOTXK9Yb;JeTGpwnrl#?AuQVVIKuD1w1lzZ z>B()n+m<}#Ai@1WfmgUjg+fFyY|Xd>M88#I_Eqf&#$t63JUrk74nA*$&7I>>xl<>?J zp-jv_2{FvApfO*d3|-5_IwF<|9y*$aduNmvIVbLc8m1&&DV}I}C~!Fcj5R4}-c~+~ z5~E{L_n@L^3$8ugQzJ|TH0Zh$Lr~(xy-`3mnMl4Upvn<~Fo0JV*zCYgv-Wg_6DZrd z4{`P;cxqic*%L^5;0bzz)`3Bk(HLeqo1R#chAptV) z4Kqs^(fBRZxXgoeP~`R?AbrWKl{}wP$^?!XTeF_G0gY;SONmK^PuazXpOQNh>?R{Cak&`M@`*ulErZ~sx6 ziNx{lP7wtqUmk_Dp%b;rL)HwZ@h3F?8=aXxcvEY+WdYPfFt)e!;VRxCv@ ziO0Gg$=5{4^w2Q1=SR$S4k?~XRb_*D00$BV&M^5;KtsoljXV1T6b=C{O7Z>`w9gm1 z4$c2n9$g$gLwN~rWGE02cEDVKaM*x95ke^&yKCIw2`?R>lRq?XaG5-x_B?@~^{_iQ846fu#E*Y z6zJYnAT;1*kGydy%n$OmZaV=+Z7f5nU<1qjE)|SB{I(+o-pQz?Ohe zPGYm!``|m({qTsf$sS1*y)6(f2^w_?>N>YL^fdt4CGKuOxknNj&h-Sr6a6k=MGuGv z;sgRbnO6}Fs&HRD%--eag+0TRq3gI{F%NYJq9}M`Vw9K?0bC_PsLd4? z&=QWC7^QhEJ4%8etqCeZK=5F|J9wD7CXr(lA40-LeS@2S)E#_r>Ar{q$qZz~k5!(+ z`7AzYJ^O_HMj5Hng${Ndnpl#Sn}XCr$<83L0?ou+c%fDWh$MIY(9A-SWr3GJ_dBBD@1f{9M6gWB~U`XMm1M>Qx224ExU(+uu zc!{ey+gPn)BY1~5sdYpUxH3a6s6mQ9k6r*r;}wX)e~^S!rjda2ZGP|@b znIAVbbVRh?f{^FNE1{r4W5FTUC!$UM``1 zJBPg>MM<9y$%V6rwjp-RN&O+U08qiFJDFeANLbFYByh~|Af&$-5Bw%)vknE0j3*9P z-n<`I4)KF`F}SaWm%<;7L;Cc#o^e#S=a@G4ji^ld`0fXpaERc(hQl;UXJ0_F=jn6; z;t0~Gl!p{|Tm1^3Q!!%^l~64L$+4KZlXxurA-RuYY)(#pvk0qy>Z<$z)@|1hDj4>? z!OMNR!4NH7LSB`@Ixg;1W=3tI4#b3hs|FyU&M{PQu79&(A(mBWCya28?AbW}8>9ro zRgK}{5amZyk4PY4X&dlb|MT}RTJ;fxqES6MooqtX$EMEkGq!}|P@gu^S{Q?!HKFWb z)AU!@`>j&%@()LD?V&K%`pNXUUpA9dn(jJ;6gB*V&$CL+vbm)vMCrmnQVfpWq${Ke zKZx^?P}f17c)f|La+Ih@}hn$JoA9mW%T#+Y~tL18lLxcEZD zA?AsB%=RM=v()CTO|wB|YDIcd)}X1;ynu*^RJ-NPXRJ)D>lmgH#-SE5@P1;uchs#_ zX!S|0F`Hz=U@UjI%#Don8t>yn`0xLF8EgtvNBNhA2+;{qf&}Y{FeK-E^9n<#wPoHt z20N>6t0B&jF*mlxQRZo)0UZKY&L79EHPdG||KyjF2|op7<|5#ZTT`%#P@ci~y!sFh zWR~7@u%HQ-PtfJPlVx0hJQ+EZUuI)1#uNq>gNT3BSxO=ZJL|c`BZ!k$WPayWaml?Z z3X(1hu`IFHVp9ikHU{BxFE%j}s%s+jS0~cztRde2Z4<*!Oq3#<1NU26-P>%>O-K1s zsCb%umzNMFLo8Cate^gXE=lzgJI}3~;kiOcL3Lv+;?!16%<+!mU~}S0 zLx9Pr08eiE+n`-hH6!CVZQfqzu+_YUK0n9%{oi`XzxI@fgwSY&bgsyCh5%9EQe@y8 zdLltJ!-E%{3Y?fa-x(Kob#-b2Y~YVqr<&(#6IJ^S?b8ZTmegWO&Zqk}Lt^zspp=F+ zV1nKm4@@sqwd#OELNy90fm(YV2Z2)#s1Leg9I;zb1W>xQ)Q%d5(Lr4&LiT)FHyD-z zU9m}pRFymPFgh+TO~;~(*^Ne4zI7`{zVT~gVe~~P6j9aX*G-0EpZAAx9i{d>u0X!3 z*s2qwtBgLm>ZCL=dTy?bb&k~TsGn1SgIvYwDw%lfH<~>Y7UL~i@oj7NCq6jz{8(?r z*XUt(6L?xNbqhi1Xl0$fo)U0BHAjB~fekKG=46eRRmoZXSvj@@nK8czkA-hp(fQuVmraRxiUBvxW5*d7huoA$_>+Q;rY`w|^IqS|tFb*Y zpT0RA7k$~9ohep0@L|c}PoQ$_?M*L_V8QJYp)3k=UCjMp!im|d>p`(6xhJ8C&@ye(vIK7{hvaRU zhD^WHXsk6RI3mKp4yTBx6j4v8&6nV7`CWGXcWJgXL*L`~q(*z!&ot}bIgj+NUUaY< zevj_zSH+lp|%A9eK^5!pC}42;o;n>btXC-~|8 zTi&M)G#3&`$@LUPoqw&z9yZ!@q(5fK5JlHb zIP%H7t_R?YjE*YSHwu0zesOu>6?}jeO`nXl-fisMov!{D(R{l5jHCZfP3^0Xj|d8@ zcIdSCsJA?0+9!hOs;0V3Z_Fl!MMNZ2gtbMaAfBPr3jx27=6H}v)lkUj3 zo~E%wj5IwrKMoI?`q?}dO`~Zj%(gi42=!XWH>_!W&)Wct5y2|!v@6)?Kto3l8wI6| zi;XgfcV*aSGwr~9vqf?Q(LVyc%gBoid(81^>Dn|$<_!(1=)#=rR}l4%(I`J6L$JqG zKp{4AON+p;SLe{oOhOR|6)Z0Hihba)@#nHX?(1uBXJc%{^{6RD#D~bH|2o)FTRPg> zf|>w^ypM!@)0n3Z6+$XRgIAzTzJraOlUhB887Mk-yN`Rl#{!D~mhI`#+Ugt=+ySNf zE%54K-h>08$U$*7v#NlS%>G}3!Q)Z<_v2XNJ;-qYD{(lETt2jX;*EST)9CE$bRK`I znv!(l>^VX_)eq$QRP)lpYJ=>9^f=B?YIy+oFvxCJ1*Q2hcXVOTf#XY_%c~K_I4&BB zalh`qxpQP2(5qy?+>n7NJ6mM|Er7-#?zz0HID~IfE4L|4<(y9v2j+ zYNB?ijawK<#n*-Py1NZtsSYbo^V(+%Fp1PoH_(}sJEMP1O~&Mb$jRQpDB!efI3p_f zS3i~BX(QlxA(fRiihzt9PH|S-1yOT77tK^mnk*Q*Xw556Z){}p@mz?vA!N3FKVs*| zs@q#eIr6CG^Yw%O>Qvk-Q5>oNhnL_a4QL$9!KaRtAfWjqfP;Yzy2<5{jFL2*sHr{fZt{1*oJ@WEz3_TLOTa zhJ~ur2vZ@UQ>}A)$mSQlJgS=(Evcn1&8Mncod$_2;lxlbp_C*%CDcHY%?t&pd~0 zNbHA#02Zq`LO86s$Iu?fl+aDL(vbmenFqpj!Tn`9w&{CtGjaS)iEq5>w|cbvlG3r^ zN}g^6CQrzF4YX3FkIGYxhDCBBdLc)1prYCLcUTzGf5R>I@i2eR$>V&IiJp>RR^O*) z1yi0nWM^rgn{3b{lvST(k0a75I2%imz~Ls4dUBP1Krj0MIr;HQtlB%{?jY5Hih?sF zWrY%HTS^JK@y(Uc)M)haD!FGU`&1LwqX<=Id6tM5;gY3&th?YLFz$TY>nfBomI`2Q zfm2ENsRBVn`T|9)Cmb{o|5vjWjj~6FP0z#~!6>GJ$>XB^C&YZIjPtlO`)u2nkvUMvR*;;qyOpN&TyLcRh zAD-MecXw8m`qCyJLj;Kz*^GF?37vV}i%Y zB%ua{v%=d~ed>ZD(}08yIPQpw>$Y>ltI1ph-ouX$$@MXw&67IM@JQt#MX^?ZlGNc6 z&8h3a=kajGd$uN|SojCUn2^fxZ!ooL?$p63H~HX-PD)q}aq@N{niYsHw82@!lqN<5 zj*&=i@eBWvnD1u)kmEzOdX5rpOoTc=0f~J@6i|B9adPlLwK{2*q3W9EGU zzT113$zGwXXvdAG#@AgEZAPQuu%#2R>9xO~rnN$SI*p61S6nHGO6hBqM2Nu@|Ipah9A z+FQ1iok~54C!$Z6ODt(Gn}PkebJ2m$oCjF?;R}mNN`2vOH0Efbp_W_njSb6G>>GNo zI8GDpp@F_I-_5kyQm$`6-UV4^GU?~jV~3eG!9Sr!18qgiV*T#)BW z!=#X#fabC+44!&UW4(vOhX+p~*3r7yMthUfhr9=1zVQxBZ|#UBoDe3)@pEXFw$3_# z5WF|OOPidGI;#|N!#Bk6gI^@o$4N;O_I%2=%SE?a zAP@4pKOpcQBjXRQS5E6+3^;~uhTDQJqyM%VfDXh;RPP<~n%Dm4L9!9^Q099qDxs3uy!1)XthltPpqhkb9nvYEFD`BOmN z7P)nNIu2oTD_C za~UyxQ$&q6Ll`Rp;1HbORa|LSq~Y+=3B_OTsVCXlrkg%%Y68a@W*p{M50{9Y!kt|0 z$KjwdrU^iO`tr%=W=8(ogW8WdymueY2=T*!kp1#1w}|g0&uvZ6G<~j5A~V;)vZ`I* zM56GW^%XbOB~b~3<8RkD2Tb;ScEI3BLWuydpbDx_@c1mE2{}%7-y}@_ncfllh0U2+ z64=CdYHNgy&m%j+5J-{~fT*gI7b>I#Zf#skv&I~ex>(wA2T@VNwR?5lP0Z`IY$6Yw zX^p@bInVPd)*8Dtl5Vvh369$L=c6OH#H95U3x^|hTjgiPSdxV|VZtJ^{`_a|w&7f`E zb8U{fRy5}m$MEwaN7(1ppbSo1BJIgu9nD&E_h@PTl9bGhLI*}vN9^cc0OEu-m6H!6 z>wey2*AnR9rF&m;XS-G~5@!DI4MPcmI`wuIP`~jniQW{Xs%18-3-B-U$QZXk+cl9O zjM@b5q%%U%4C5}3z#9KoZx8Zm9#_prK(_&Uu>G#HHi0s|ypu4*EM9hVzf(w4-E`Z zQb8c@C8GoD@Vbua5-=TnoJiB=W1GW_9)2eieBtbCEE?=3ZWqqu>hpT}ITDI|DE=>i1=oDfE;5}A#j6Ma_bicsohP^>iBvNOlHO>XmdKfD1n{g>wh@g4Wq7uSht+Uv5Z z!nPTYHz9ob7#VM{Iur@BZ>baetZPiV`@EV4x3@V^07r#Ff&r#sisP<9vAmep8f~Gu?;Wb@a*##z4ua| z3JHoXvy-1klJ6_8PC@e`TB)}CVaJDLfaHrXCO9hKZ5k7p>bvs`F3~1`h{DTirIAf> zI#LyXmK3CbsHZwD2DkLhe6qO|rF=ME%#P8tTmpl_2%Tb&g|+kZ&(+UxADVJ~^NPFJ z7r$<;Yy14LuFbBwg6(t-jmaVLhbgI(8SovhHNr~kGW#2s)GK=;QD`*TE_gST7Xz

{DmT@kQ_XQjh$cJLcqw7c}xfZt=?hs67n+1ueM76Rdla)G}E8(5G6I* zuHd%jKCsNJANY}~&u#V3d`0sGS^7JGm(LmmYhk%6A4-WjpD*-Oa8}Mx?KGRm)!744 z1=aEGsjEE|At2plPc_P$W3$^C6|HA`#1dInHQBUdx~^y~OY0s?LW6g901_W@Ou`q) zzD*3NhvrF_#e2W}jrr`3QijQNNgQmR1M+eAsl-Q>-w?! zLXQ~WGoNs4<;(pf{&@6AcA!7~9CT~IkK@fHRrkpqbBYR<^})0H$Sr1~R^zW!9qWH8 zqSl7gj@18b?0Hq)#Uu8*mp;_d@!U?bs{4av9PSf|^Q8GU#+u4)5QtpleFeb+v?a1v zH!2w3xiUJZ)4FN1q5?2pJ>Z!5Tq1s1Z%Yw*{U&3*WKT;p@RX0uKc`koKRNlV6v&FW zfYR%IV-&vk=^OB_*K%G2)`MedoSfT@wx50AHet03`N_D+WP;Y)Yk<}T;8rW&E891J z{^P2n^Pdwx>lfWIydL|6Gx2qH7DlSIo>_ngAP7A`TlPn5=$}7F2Mz@ z$a4(Bc-(j+@NPpxLlJk?BJuAMWwOPwv{_LQBadp&&vl^ER_b1R)topcDwRclu>@rd za$+&!Txvf|{knry^FPZqygd;6#rAp7&K42${K0W;Tr=s5(Tso{$g(tqZoao>Bqwb3 zLR-h=-2d02C2xIN0ilXOP&;#Y`w6W+vH(bHN8x<$cha`CDdZmqRs&w0p`qH{@P_Zr zAqATH3^W>78sG@3c$(XyJ9MEZ$+^l4niA~AYa?R2zcz-2QBmm64^#eft8Thg`Zt}s zskW<_)fc}SMzzIkBp)2t38Fi$r8c?h4P;2<}evrLu z;PR4E3gv%Tt;xxY8F?(ngUNMpd^OAns2e-3sG0TQyndHH4GNj2d3rSY{Tmh-@(2@) zm&g#%m9|3#tf`8SIXiYXHh>uR%c|d(+<6z(|2^$HutBT*B8&p0O5K{iaKgLt6M)Rk z%#|@oF@;;pu{Ho6|BCrf@qdjF2fr%(7Nhj2l!-o2#Cy*uB|G!S7;rcUk8hqH z`7~RLuQzso#?5BP;a(p0%E3t~$gWUYtk+g>OK#cy7b>+C>rLS&u+KraK#Ci-AdiFKa)n+CPZ!x`#) zqZxG`;Cj>{Fwpx<5xVEhGj>c=m1@`Vd@1<20kl1x1_1TD<<*y$h4O$7Kyp^7(BCxn zwe<&*6TEeRDeiUD>zRA^_z+cMkS1S{CxFjLz*EE4h;vX->0&UMuLkFv{I^eQ~KzR>kot8hJC#o)=mfgwz zJ4K}$04JX?%u3)qVWnkgq}a0G=?(kOT8Y5HH#4V&H~jag15igFWHY@v&Nkbl24_x5 zb7&~a0=F@Hk#7#S%t!Xp7jJyyKCc#>2>IMCTmMH0k(rEy{r8#b@AHqm#s3uy?D^0# z;Er@`m0I2R+Sil0`A`2j^mDV?kwAM&ZIlWSTa3?_U|ys)ZH3{xIf>Dmx1w#Xz`}z% zr+7hWJ0E1<9Kgvo&Y6%_cc)w+AAq++P6Qi*k-fQzFAyePzrO>bkf7E*Y(r5@A?8}SqcG0i@J0RA(K2k z5+F~~-S_j_#ygJfIBp1}V@Wgn@woPLGYC=OL_*RM^I_4I^uPSjPuBl7oh}~eYF*wz z`8+msfk^Ji`lcuAk=&%eR%YI2%8xDGar>@Bz9usU+jAiHURE-#M5<6T#i zaP|9rRUC@>;*RjpK?hD92rfJqHSYF{`T2&CM{O@-`}cXQGgn65iO|HswKj%Lt6|An z)ezLMfa~p z@?^2pL(EuVJoG3$7X=%w1npa-Xapk?V|EKXs&Egk;ttKLyI`R;7|3)kCl6%2p7k!*3k_a$y2&fLPLTM&IPJe&38jUw>-AspX zPldD;E}6TRJ`6hY=yDe$@9a|6+UR3J%DP&7+V6gTx40Y-AW=KHJvoDlfjv1n<>={& zY7JaqPzj{( z2MJV$*ajx2&~KqX3aqusomU8@OHa^z9S`AZPraaA93@DrLl#WF%#sRrQNfT%lA@u9{M2tdw2!^uu|>Q17GEs*3ov+mp% zN;yhGjnwY1{)y#Wvkm3lJh`x$=6Zd2o)W-DU$ThG@h85cZaDYfZdO99y{u6WKj2f&E;Z?en@|jo9Y|` z%#{lQ(yQH^3%1A@3>iqbIr9B2xwO~Ec9RI@*wS@U6y!@rLz9hfBbA9?~wTp6u5^U%d1tGL%ZCL`&cUJVj%Ea5w>LY?J)& z*2w50{4Gs2vITqKf4x@p*mAhmM|Q{vUNK+nWWc zIaw1fGele=5*1LlRi074N!1pe^Ta-KqE)ILRI3ms8UQ*0gqB$`fJa#Q9ic|kncj-~qM zEhqyav$7IM84x)H`zIJfXyC)zd-ht?Hr!cJa(Mo7q6rM(NU2X#%sVIt`hXtsq~K-M znZlc7_9D$QE@?s-`q7-k6KQ4_h;$FAW;SknG>TO_WgFQew~6s6D4%xbTi@HPB9i&N zBMw-z%|?>JT)1;&gOS5o+nq@Sz`69zd$(Y$5~HiQyh&1@`g0{H>*>T%64bSg#=DMN zKszp`G03*A=JqPlvnWzjUrk6tiZ0&v?n$D=sq>Cdz-8*W$?hhH@gE4ndeN>!Z7I^; zW3zk!-JON;OB_9|dpOXZb>v*ZUhvSBexocNAg^mUQqoUB%u64uo5%0ncYN{8>%f?B zv0PkglrnK*WK6k?$=sLm3hA=A@o;i9vJngl`uJ3P$psqNW#K=-ly4h}4p27^WQAVH zkT@9pei-LNYDOR?H7C*w?>zA!+moHng1X$kCeLx8p5aCg5Cg|2>LJo!O~@#RB^`2H zSJ>%q%%#F)HmiP7lvNk+W3D3}Lf$xKx5Ng}emnZ1fNMnq(Yc zeiH!&GxR{;A<0>xKFqm*kLz*|Ij&yJQjpOetqUj$+rMPH4ah(iy{n2?1vTL@q_p3| zBST=dG~P02y^Q~)7MnRrV)HNRO=>@7 zarHScx1hhZzxqp*tu;9)F5o5SIx|i0>n^Mzub2A!>zTb-Yt9&N=QjJfg*SafpnMJW zgH>fkG;B!>-srdu0Z#A^w;}`Uk%Dsq!Ag6ebfl1rEC$gF;#GC5${CYVCYdk5F7#eP zo!R&K=&*{=g_g!jG+Z=$h%Y}phUmIDa*=P z8+4768$E>{3AFm5gm#1w6u#l?dWzZvsX)pr2@7b~X5OaT6+Z&T&01h^Xa&9FM{F;~ z8~B~V1okU3di-7Qe$&{zdej+R2BFe#f}4nkRb1qSmBdE$b9U&IKz{>Ss&~&A8IPP( zhub=m?aFJ;m*b^q$Xe53)y4ad1MP2Cu9ROp9C{kFL)934ZF<@$cC zN$U5%>wn?4$Cccy*5fhrSpn_I0xrxHT%)9splNuTp;3vt+V{1NLwP?5 z00Y-(o*Vw-XXdt;svZv09Z-F(&Kqcy1l4e<&)5IhI>5oc$aRq}-5)+?-{ypcJ6D47 zv9jaX9hHH`HIQ5=hgpj)<3_;2##}pE#fy4QE9%m<4^s}N)Ccc;MZ{1;OXWf3IH9E| zc_s~NfgLs*fO^~-z3)U{C7ZZrv8B}=ie7&-K}e_q`~Tk_Sl_N9r9VJ6gV#j{mr zUe^y8|1CQce<&>TB)21M-K6MUjsItR1`Mx2@cyV>6LqDT;PIJmKdn$eoFcEBMC|pM zGZommdR_y>-DealR5MS&P>ps1C^JB8JP1Yx#Nz-0DI={EDw@6>C*##uOmH|uB{&qf zXFAJ{V;|cTDwS+0I2H9G7iD|c1lS+zbQLtpbw6`*x)mID;)7q*8U9^r=|qDyK5lmT zW}!uu>O2DpDL|tL_C+i;WeQROx<88k_0jC+humnO2YE{M#~NQ4}Sj%{@{q~o!E zY^(0b(_Xp@zZvADZDSpyl|@vJ@@6Wp?JO7p{3 z;X1)beO5pqD1FD<^nk_WN%ZZ3e9E!F^{Be1D*07q#FVo4^7zYx8aLRA^njqZ8IBLv zjEggUa-Wejf>RLBtwjyNCR^3|{<&f5&TAm85e5h_5HiuR9E_M*qWG+_AT=4f+hCM; z`V;sO#ME(1rX}4)-k%zL<36&m_l6Uqthv~TzZ{_BPfHQw4Z;Nmk7RZCB^sIha2z^4 z0}ur@Sc_cu^0w?J=(je&aUrvYClgY!hqL-Y{13289Mb!}VBQY&4I`;i552@sQin;s zaW2{hndZs5jd3`VCJB6|@K)7C1rbNcd*`&D9Nu>|usVkvy2zF4Us4|ROU25*mi z_#I!qqiqzJfjpGaaLwJ}cS|$@F5SQX)%{FIq!2P({hryyC~DM&s=JOL1Vzdq_Nsb% zs|QRj{s^UaKeG_ZC^8&@H+}O*kwNFT^7p7-MJ$rQ-%K#+H#*o*+8+JzTd%13N3;X$ zv=)JGIEtfX8RH9--kpt3@BaX-5^l)`!m5QM`{fN9z!i`{w`zf7=+E7$h02e)#@zWQ z*Oss`am$*NfR@R2p|p@`>Det^8(&1L;Pb90f*Rw_FlXK~v6k>8Z+cG^nY_bZVl67%pm1Yv5=&>(6q)tj-A|pNXI;jGG9Q~&F zpxfM^wC-ndj*N+|PDw2_Qw+2Ab)c&x_s>EVJPA2_&zig+%hHHjdoSRZ0qPl0C2oHB zzry^(DW$lx%$AYvyOi6sQ6%qCqP{4E8p85_{!dO1P(^g5P0t8GI~2tDr`$~hSu?x$ zU3LSFGvwJsg!{o39|;YS!@`)XthhA0fEZ&mrC76mQ#EcP9Ek1`4u>621LS)?<6wZm zvGT41%JhL2sdr*#EW*ZiBH-_rxy_HDRucI#45qnpvl;KUC&CyBTU9t^vIbZ_p64j$svcktZTY}jOH!&6t{tEN9m$= zK+a!!w22`U7O*YOMyvaa)}EvKmtpGx=+R*oGYTAZLbI)uZwzWPL!<2?;62Bi^p?j` zp*_IZ#H7KHO;A*{xcbCkDDat$F>hsFmpY(%^)na8-bR8Fm*ppNtccvP4MjFV7q#-do=MM!rap)C+DyM4;@a!adkD9Ye%(O+9pxMtLHBjsKs=@-$H$;Y zeQz~GTDe!#ll1REEy=x9^dw4HSK1+;a^A_)fImRXae2d^l?83h{X!x4q0KF#*k(v> z@CIX-n$T0@{qWL&!KOy=_K#{xJJL5%A(d9bf(gasv#6l9F4Zkg1>e~R`_#;lZ(mDe z_J``}LMU7h%ta55NRajNT`m6AVhxNEsOhhQO@eD z*n~{B2rjv>?&c2b51ZFPENWT8t>go>v0P-PB+Vo64QEd14&v#LC{Q7&MUN%D0&9P> zo2?J*IBvdctVHn*GL@-PK=lBZGgj8vIg2;v@S>;!jm6Xaf=?-_(CUg+nx5x`a-o zpJZD|9{!g+o>fmDntLbZbZ&Q~P=@sr1l2B$(|JLot<4AxF<$QOS4WU^#JZ&wp zE$G4wb@kX(taOfl7=M8hL?K%0DbbO}7VcQsl4PGQ*2*^ro^!_C?Y?=w$%WO+Qz|UO z?afRIqOiHSzNS9-^!jw}ZXEeaakL<8$#FRzY6$yDewV1=-{O0 z6=-uJJh?T@eCI|wTGWt;$eBAOC?YbTKMvdUp8|-(^lt_+F^?v4N}3hPDRa)_yw?JY z+;<8|Heed*ku&)k0$Mf0VscNEW>x3sF>sQ2gh{?1QnGzvZM@+jt@i^S{{~Pn&D29W zyQ`oN_qV!-oWFSe>D~r?Y~7-L#|ZTan1ua(j1^NjZ7kfOe%~O(Bu53RbjzJeskKo@ zzo0Hd&*=C!%87F9b6U7~mMdIfF|ItC-1w4pnwqxR`LX%Ld>{@~3Si(ZTMgf3W{h}= z`P|3%_e%qBar-(OYG228zh69DNvg*?1E6~q&>PTHV*>13+uF=q4Y{&@wX}Ba58HHn zX*Mubh+&Bg8Z_sG!zhWA*2he8x%5wrDH`$(SueILPdKc%%`Dh3DO4V>6qHqXyNqSN zy9iFCD%)`6C1|VO$#UodO4cs#FL&_pi^swlk_#YgY2%IWQZki zZZynnYUy$RIl>(_`11Tt*|Nx1j_@r;BASCeobJ34zRJcCkJ$JCHqN@ODNWnf@gtGE zY5V%@P{bY3XEv9)KuI$wn#ECC-;I3uZ#a5w(5kX%)W0-rUCqS$J{N?!g97nADa)%6ToPkjRaL`q-7Z;638O{E`Z|WI!{Xlb z`O1(+x}fRec@2;>2LHFivhu_!u_u<(+b_+4IeYVje#*;WaXP}=Ht*);pD<7=W+0L6 zyMRH+bN!HQ^8DxRs3+a^hjp6>niv9iD-b3{Jsbh>uLasS$i{zO1M6Hstp{|d!~zE0 zq0H~I+FTfKa{_2xjT#IqOPLZDW%an?D9%Sl@4*r_n-5pZ54>_???n8r(wC1R=i#xl zpXa9CNW~DCtV=7c1#^G6c#qs81RAZ@Ei15ovDIc+)Ck}4>a-##96;dU#gi4BNt-w{ z+(l}R+-|?*CZu~J>_vLuoc{1GxNOL3sLVO%yT6|{8I?DA@^C@{zk?ccP*{?kom@P) zHZ?1Yxa;-B`)4~Ve;rZ@R^YAIFY{KFysRr)+*|U!x2=BmT%tyvR%|C%&H`}Fa#OAb zCHuuPH<`Yh^nNwAzn%QTkQ{Yud+7){Q&B-Hc$`<7++U!@??`-&K1V%w0TTt_KgsSB zWNQ}fep)}bSxL2Owpir(Lvs~4|0#x32cVJvgsP`j-dOJXp7K zR@GV6*w3!+JZr0COZ|r0d|%KceNE;2y8oEj(BNEMQ(YXGhALoPRvrmFHUMq|kmBp2 z({Y!rglK|I^H@9O=Xj=xgRGNfIg9sfQx_m+j4rh`7`l3?$<+}7MF^@2`+(KYY{v~#ck$Ja7t0Ta8?i}Ui1q9WAgC#9BmhWPJqAx zt8#6f7|vQlwxk_9jm6|IB>2M94U{3qcmm>el$3%;B7yal_a{>?nI)$lm#57g_xp$& z!m+Vu+u3`+vYHvUWJn7ZbfcZA*e&>eUj7+GudWfU3@r%g z@8^vp7k?+Q%7K-!`tJ$GIGzYd4As@u4C7AP7``?#O;$@QnB@#<_UxeDC}5Y)LWJ`<=D8mvav`B zvUzmicM$#sRm?{&+YbRgp8vY7KyoqcC1E3YG&<5|3bLVFPO`6e#^>isRM4LKYJoQ{T1K&wP9B#^)s9$m zyTyVp;b+>w8r zM|rIsG7rir{QBK-8O+;;|At7qex-?jw3+|kz98|1ZDo--v+s+T(ZWy8bX(Gj5GU!B?wVm*g_g{|5R zKr;wJARK}iv@?kmo*x(rK8HsL9?pAKKpE)=SvSJ_vjnIZZcn*;rQA?-zLC2zoL9f& zxvX^#YEpjp@x8@Wd+shjAL&I8d-v63XW=Zc#w;6I5njp`k&w^foJ;=AfQZX_ejRE@ ztsJ=d{3W(_uunmaAlFlLzdEAJ326$LO5$@-M@q+Ps{%D9HRgJTgJuUpB($qOOzOQo z%(wk3NBKxTVTyd9OGb<#ZrqTL9Uim)lq=e|LWhh%pZWf>CeZVK$utxe#+a%Qosj>d zqgI2Ku+)^hO2#FD?#4u^<*ip*2+i&j4PtogYHsd?`xr2>WMz?LDTTC%?TU}H1Czf+ zw-I_bZoTWPHobAPN}?XQogHn4wuYgd?c!)x%H+pLC9f~T9NQxD3M{z{w5@duC|CE<}HphdHI3|Ubb(2S=;a% z>5RJP<=NS{R8Zqx@9xY$@n9REsr_2*K`73+9KRf+e|%uvy+3_K<^3_R?VePJH`^^j zcw6#LH;!!azh@Q?ltgBNr^Wbppe1_(bq3`klVO4tzn3pP=@W^t>}R+$(x2$V(-xB56J=R#3~zPs(p&o}|Od3i2weiP0OvVE(TO-t5+J;#CP~zAV=h~bQ z3$qfIKTm1N_nntbL|!;QE-)ae=cfV@SyYP_QF>LtqvbYIabP9a9rplV2`>`;va=@{=I%8 z9$oyJ7lS_C73@8l1}~!`3&x`)Q&1fLo-CK|JNbLXP3-ZD<%>!alk){ivoNK z1`I+ffy(3_q=Z!6_{z#?9GN316n=2j{P(A)(X9^cKYz+5oD<$UJ3A*Hvn1^k*)Y|b zdH>12H)l7TSsOAI({G9AQ)th*E%a$xJzKKp=CxY3chs#(9l7wpR7LG?(q)vH{3R;; zhaH|w_MY4Lbl7I${&kaD8C=!q-EWoWCyhWc3RVzD$R-{yuM#KBve=Y^0P^gId|OQ$ z(#yPUXAfpi%D9@%-uzZ=FdqYoOEwFxN%|4;fuco`tGlz$#~rcDq}rMMZX^~9*_dWi zYY;Ynej3!2n-w2v>d4#WPDczYOj#DQgZufiXCH75JBUP*FvG3fyLg^w&MpfB&K277 z{@OcM`O;-MkU`L2nW(O~yd}BL3=egkAFYJ8rhrVx<`X}vE&K(6Ldq$2S5Z~Sqh6`hSzshvh`)f}Ks^3%sG=(!>dPZP z@DgADT@%2aE~P^X`-DU);uY;870Eppe%(<^ZxDp|h8thSF7&+*7*X*K@C1JbK+v&yEfl*uCX~jmd3LD zm++q}C!$)IS9baxph=5Q_<2ZQjT#t!!9Nq%M7L}Hv2kvV^RBd&t@V&)53n2`N<)hSvogR>XPa;0oLUmtFE+W!v`R8;X-#@dSc7(WTPR} z5=qv{5y~G>&7f(6;b-{ts$01bnH}KT(HQ{7HW<9h_Wk=JkuAX zy9vRu&Q)7((GfKI$q{iesTBjpx(8bx*rBrOu+k%$xA=RXMyT*8(W!#J)AB`0qxFms zta(@_jmMTqM;2}_Hx02xYUHh=B}g1`&E&2{{=IKJa9I6!HgIPtb;Mq6F8hM)xy@P( zO8w@o36^^Ul^{&f0vQ0yH9!4l4meg+>>5jR-xDK;w$J|rIsDT=+xF#rHXd_Y(iMwX z%t?Vy3s!ps6ua0TY*mVbHj3{siMhGCjjLz>IZMReZ{F+PW+INyOfb|Pk=B{dWy!Cbmx9PvrM$Bq@ZqB~rpkh+j^ zT+yL%Ai<;>4x>Z_i=BG+ZbOVI`xE|6-sepU>M{-goX_5|DbeYrHa08V)8=}qg5I9; zdN`-8JnR8>g#!$^94)ZyM6~FN1pB_9X`_#L(x@aVeP?F34L(53SYa4BU`>S~CZI3x zMstEt_E6c^^Wi-p{)XF(n_0E{OM`3IH}D65!tO5tuUz+3=@s0=M@Ll09s8S`{1PyFFASbg51D5JVp5H9YAroCW;|j}y%21e`irZ{ z4-BB>>gp6$7IrK@jaL5B`#3RBD6D})qfMmlzk4@IBJ0f~+`)$5^h@{mtT2N5xeFwd zjqBC@8S8t+0TSGPaj^Q|qavM;Q8VE#YJ;MBO@x(K9V$p|Yz+m8YGRyohjK_xFlzP) zFm{yCsqIy)Yzy06l>+QMdrd#c)Qvb_!F)1jNb)BLu1o70HvnKeDR)M6ew0G-B+8m7 zPj%fqjUOik+TpMxq2!V+1F80;E+2#PxY;hd_7@($KK`-p{qa78<3V8f2U`cHqSLi* zvjhXO;5=;OgKW5ng%_%pp;=V$x=+W0SCRbj&EvK(d?+CwOvLVO(AF~uN+?(K9Pn)R}xU-dn^V!Y3g6ESYA3&o^%#o?F9g3A=Fy-|zgWLsV}8Gmx8CXWKw-@s^*; z_s$*?vY$!K29;DNSyxB4z|C&v%@c}tKA2=tlSHk60OAjuAv=VE4@9mBGJF2V9r{^t zEHSy7ST~Ufn2n1O_7L1xrI-XyV7BV{}DFHIJ?o2go8d#D5LOqy`4GiFmCOn^oE8 zM74fOLbLObSwtHYp(lpg)|h*GLKUF9uFpQ^GM94UPJ*z+D6ylPelkWOE=Gl2;719n{rcOO!?@ZO71xfKTVY6}e$qz;Q>>pY zf3m(d)cntyI|>S1)uiE~;5mQZZZ3f+X-QV8O$OM?7+IVS!LtjGkJgn6Ym`vtYhQ=G z%FZ$cv}7pV$-|fI*|{K|JxF1g=rm0YD`dsql2yZRvD@&P3{tFcSo(M&b8O^&L`pj691XQb7KVEJtA!Z(C2(AES*P z6;^l_P5Gw7Z&IXXt2D4ay_{4$jw`4#9?nt9V0N>hT;BJKG`JcrU-W{Foz-*2Q3Bz! zxb;OrQ8gn>lnaJ9UN4?SXc}BQ_X-pRWkJ7!sGE!mlm$?XSvGRVMxKs&dq{l zR3#qaXJh*yE;Kw85P#oDi-FvQK35QF{uLaH;%r(RJneb zJq#FoF%2fg!TPiC%t2wa1OdCve)XqL0SUp+arAyLOVSIS&0w83*ukx|%`C(Rg%7GiVTe zIC%w~u;s8rGz7gG0NlrCLQOro>`D9>_dL6vn9$MpC!?o@3D$w=vRdWDC^qx0)zsFa z9~DC|D`9^#N~HmI>~$aJx>_uR9{oBeOhzW8iq*_Me1>&dx*CU9$MVtA2iBe3Na_l+oRs8Ebc5N_H7!_rAoEvj zdj88)z{dTO%0Zj-W&yv;#t?anWiQ=SSuyl)>=|%5>nZdc#k89=~K|Cm9%wfK$f#L8j zR91JiG0>q`q4YF>ZeX;2vAIjyq?htQUTW2DRIgvFdO;|_S$O!Id!MFW*LW+W8&YM8 zn2^rRlQmHXDXqx{~U#hzj{lnUHx) zfe}{Aq20szx4pJ;%#bcwzoTAAA#ozxj{#JR>PL&*=w$Vgj~I8uLK%IM(6QyQ4c)4zxX)ueE`j z!zCo*&R2Hbe_T6%4^T2$!+0n2tUvcdCV^RqB!pBDtLtT_LWh3~A5G#*=q2;6S_Mx} zc|nF$V;_uf5^vOz?bXF)Ynvb#V0M0TDNH{+lmq9DnRJ6Laxlir+Y3fjQu>`IC}NBj zn;lj$-$#k)_eEs@A2((}K(!d_Wv%f=@11vK}g#)gglEQsFZT63oBe|*5-=tWV)5PRDMcAJ+#>C zBhW-eP(jn@myy;TVfReki_+3wh8kWNF`(;ivJW-NVBBJ5)w~Z{t<0aAt3759g$f~O zIA_${JBwDi#x2o4^V)dg_$uao8~T%&0Hq)x$1skkqX7MhQEib6K&I)>Saq_m4iG86GH}B21KVvnA+KRqXa2d5GFk4`a#>!w>eJ z+aNIIPycP7H7|9&wW;O#y>}^MC@a<)^O%Z-b!Xe%5Tjj)wkYV-^ zP(=geYlP5cE;#$1>*8qnIdY{A@XE^`@G4~y3RZ_;)dXT#Duz5m;2EA*gcyJGM%fHx zBMf?J_*nmPLL9W}3;`G7!a6J)@F`)RGk;U>O%409rb|zOzbrvm5GoZm9237`)yK6Q zvf|pXkc&kPUjj0|qKVu%hU&YM&XSt7#07A76`<>SXGdXTgyIa=CMdCTzR0QFVfwzt zQ)I_=i(0^h+_*&)Czo)oymDcnuG58>HFdd0C<>QTR9i8}T`cq96^hBYjyCt~Wa0gz zaX$M$j(sF1BdcF?kYc_^Rml_FHujTU1%y;X%ox!6 zprr@Ia#%#K%PPT|{T8lhkT`XRv$3%*b9hzI z(QseF-Y?GeYLvHy6V#azP3NF1iUSERCT$(&8kD)VeT;xSxg25XpnS#F-Gd^=PXInA za{!H}^BJ(l|Lp162W%46i+2BdD$&r;4p&mATGWx(l`~5!uzzlBa0#TyUI<(4SU0;G zeN@ilgSWss#5|fIP#}w0+VL4m9*n-e{sb(;5*reHpLB^QFV<(>)qB;%5-E}>q_M0L zT)aitf8$nWH-W+ZI8A43py zQLPlbN$GTL3mxKt-1m_{zt+e}v6-!~jxs**I8kwh{Zyj#uNut zhy)*mb1(}Q1D#?SQk892;Wna*WJ|lq?3X`c-`L|yvB9|~6^U_-?~3i+7k8VOuGx;z zQO?&Zi}MYwjlbvDL88=IVngKb+w>z4#^grm zdO3RDR;)o^?oTeJRmN#U(Rp8bLstxx(q(u zgvb2cK@WI<2BK8}KJaZe;OQMO9|3g6YiwQ5Q{=|mUE9Cxnr4SFd+m>(fdma$xdWG@ zsA*{7G4rWg*9A4WZ`{FEWbLZ$|6yHuzI)Io;XvY-MuvAOTvb~JDwkIM&I|d)ut@B~ zHR~25_k|GA6;Af+R1ABFfcI52l$IJkoJjhfekTLoZ`;ihR|PTz$sPJ@HX<{1TcMzI zZT3J;hsEh;rq0%qbN#NmB$G`)vKWFS9F`0-&7DU6x+`C7lPnhMcikOMBb(+_4QWAG zM*P>B`)`w|Bpw_R$7`Jm*`3>mhxm43jfghys156in*b?ZY6Hu8M{4Cz30>LZBE3Eu z!JYz5LT*fiEu^x>{*_c;GPu^(D$L#I&j1@6ih zDB9Mwecv^&@2%v0LVO;t~~%` zClT`61Kus$hYz~R*dQy-1GYWP$87e~%{>GjJrHBN6%_awlpOAj;WheF2UWk+~P{;{KR_(_4Ozgs_4PlS8q4X6fq)Z)9H zyMg4r^{o5b5<4+|SKe60!!O8cwq4;Tg=C$2;70fD3z3)LzlNwmM~haA+Ovn17Dur8 zk74pK8bqFg7d?(oN2$=e(QV%R4sD)ejZtf%H1rg;wox=E#TJnQF^JSqlzR}!JA-fa ziCy0sR1z{)%qRI|^!Se}3%{B2y8DMq#!y_+t1}jl$BH@1OAJR=8eCqyX}HTU!FSrN zv=WUX-{M*kUwaMu3M<&*=@9-pd!3$kBT?FjVl<9#^D3gBl6@EZDkridQlr6J(%YKi z*x%0&Fzmbn0t&H>Cnt6Q7~HA(@ph}*3|Fss?8bYNuePoZ(7pk=$$+tSk`D+(0G{cb z)}VK{JZEd1&ZptzylD*6*#YuKt(+Q|^5e|gpurU=GbDQ(I$Sn}F;Ok;-2_`XkR*w7 zzF`I8DktjdS?ZZPQ5J^$O)U2}V&XVGBvv)YED8ell?9KT1J>~ija$2AiRmh-QUn%_ z9OYqg4iws>JM1-!FJwO|9Gey?QdFFNeQbF%U3G)`hq(a;?bI3z9Y

47G$n0VQ`rIMLw{`g@zsc)6@E9` zPPxmxgH~>NkGG2pRTtS|jfETUP`U*Q($eKlT%FBosPO6GFI+PDYWl;X<-O>l`_QJS zPb;l^(?ti2`}e$jkKcQrKDDR-!XXz|PqGtB-c`)tvJ>y>+lu9Qew)$~2&@6tVlFi= z;nC)+pxSdbxY)(8>}=su^bdf7!PzOVQ0ayn*yVTgbush$louEO?j;U&%;p_w;WEMMh z#`n2^v@v@kNCYNR=6$tlilTssO(A|^^9Cag?GN2)(Vajwh)e9PH`9Hi`-9{8>?0hz z54|}jBQMC9OyxAR=pJ`O`+RMXG@dpA>+2Rydx)>f>99$Sg;TJ~^s+Fd1R+4D5JG520 zo}tS(U(84KfYMuu0}H@s>Bhw_<(%K?`!Dg5M349~y|e8|NVh>bBJtu%^#i;s(0<5P zXm1}9k0j5fkVB8FyE_Q@lhf1e`*R}k zz)Ej9gbSVkDm8Z2IjYZf=(=_2z(mai6l4N^0cY>0@IpGkLU2%3*Hg$irg`J1%LDD{ zy%Dmg&lj@I4Z+#Y_I1{GCq#+{jMX)#{3DP9`ey~W(&!75>KkB$WzPf4_z17D7#D}z zYTDQSH2m_#B-*4UabH2HElM5)Xe@hy$hvEQW`TISDHFK_Di3J~o|9CBO{9z9DW2%Vu_|+ZmE6$`J?cgC*uMlI_k8Z`3Kb~Wxf-X z0=$6@7@HvJ@FM@?BMN&<^7Nf)F->`vcoR zAVLd@q)W_l6;9m1(8oWQM^@na+G36%;jdS7ACjehG|UvVIq=}`&?7-^I=@xxp&!H8 zWrj}Nx+Ny~ZD?p|r8<+@Ai(wI5(~06v=>jh#pg}(IXXIezP}0OgpnELT~4%Zl+Jtt zXqN54C>)F1ytkbI^A>{{w>2YD$C^EWp9dNyg8|m`-phcGmkyRNdrr zq>>k)=pq?bF--o+a0bB$WvY=;w~pb@4wi(NjEtT8NPMhJbnTU^5h ze&oj&uMJG>Ei%sS9D7kKBmUZp|0qZ@|CgY)g9A<_1)?n8Woy=-HH*B zC>Xy)jKC^Ytug^~_C?tTCx75YPX=1`-n?2q+^uo=ZEU1YvrfW|oI%8hf6WX9vMGRQ z8mWzYLGL@n-j{inijz!0od#?p@6RkOOZIKVq{+M*YN=dk)}5qwu+?@F1Av*-^Yw}A z`Y{uje+AzMv4Mdtoqf{xg0nMqou^?kKw+azu5EI0t2IQ{nxPGTPI(5bXGcFOZZ8LQ zPbR$k_5JR>)TsK%tj5ktXe^`T9BNfbVsTBC7h2jg^&Xe0T?>Z>kge`aS5U!>0hWZ1 zKv@63w2j`k+q$Ey(5Xl3UeU$dw&1j@==9YmD2dr!SpmaEAZQUFWq^^3?EQ+X&foW6 zi9JxvkT7g&M&4)JUC1o|w1x_&m)7b)Jq7BkT~=G9`SNm%9L;nnk$*ysrCn6-hw!~L z$sPs!@R@mZrXOw0#-|c_|4z9Fy;5bA@05Nlxc4!uck3D~a&VT_mi2b&%NrvxH@%lAo5NiZv6WG(mOtySbI*3O8)=UZ@4&bta3V(6?9WX1#Uxs zl%$C{Y^#eX4%^d}zU_0mj<7JypO|Rzo3GGf(ehmUO4UM^6Y=W_$aXQi$ikb7H$Z-- z6D>>y6K>294$=pln`Gu89v&Y1wpGrdS_c{?Dk#+jl+Daw{t*b&3^9Tf&Me_JbOe$G zi;eTPAq zPpipG{DHUKeNK|8JKg~NxsPe4QLTUXGRqTler~@8Z!9;844KqOtJ1~Tevd?1lc^%{tKrRrp(Y_x zyK1K(G$T7FluAY#?O4oTg=g5;!=yl&-sCRHew^lVk^0kI0E(i@4nemR|^~943nl# z(LyPs*fB-=6HHjQT!@kQ zVpG)^#ycZh+!+yQSj%)>L2rf;{-*X9LFrzwZ82@Kgxs7yP`U>HkGO7a1aAnE$)V*S~X%W?8gE<%>9J)Mw;D1-@?4GT_wEx_$Zv;Nt@ zrk+DiZ_Tl-g1MljVOjY~Gm!gg&ga}z=nBw1nl{K9yQ<*;PjaQTgf0?672Rstu02BX zlatCh%ozBa$%cXoD=IK)RK%FoaWm z_EoKCg%UD<=iLm)84>U~c)!;~a1o<6*v!4zH|81CoL1W* zRuU7hf?XWb>L2JcG;m-61{^ki*Mdhpo}IM&$P8xFKbPYW+WmI`mNoHMDyINAYf(qj zZLAu1)m&JlzddyRIKI%Jpr0ypYkF{4VuIJ_`A%T8qhQ(n)LkjkKiTba?lybbUQQ1; zc~6ylP=-}8P$x<1jiLJ?p?bdk-VY3zK9(I@4ZeKYsUFlDvTWMvJntzf|McW9q34qt z#g}$YnEk1|iVxqKf3F123b|O?N@l|+vla5omY;FA5l|$mOxM^}T{K3dm z+n(u+6zlI$IS}nYQeVx%rL-;RVX0Y8{le5WjsYHI{ED&gwZ@`p`Qqu;?%$5_*B#%_ zvTmAB6egZce@v~X4o-s=>LM10qzJRR?L#@g;($avIpVn1WAfy+l-0{^U_6rm)H3YO7{x6p@?wy8DMzfr3 zhK<0_q}}84YTaoc{Xpc`W8zo|asTJfpNrS~x}WXK-~9b2?YVa@n?BCDoUmm~i;C{;@@!6rc2|WPkUcO*UY^Cz@6y?cLQ~2{- zB%YGd@|zlB#w-S*^Bw>qE#1$*%M-bSxBpU3m%pWa2>IeWW+&Wiwqyg)}C6fL%$4Wcwsyq1dmS^B#`=7_^}hBfw^(Q{mg&)MU)#^#c|Py`w;q|U!T>rFI3SDrWq7dDW0Tmh*Tj!?Ck>n@ z)@#wAdo?n9(2%U1bg3)1l-d_2x`iZ|T1fXe$l@=jr3HK;KxE^fv+xkEMRQzOsBcFt zA!DI?IR9dG%d~PgNkqk6$lt}I0r=|JIGfDSs_<^^!C;(t{drQKyi5hB0g9+3PSH` z27IE05cWcUK|~nU{U61q6_6ZSbd=|F)?#EDE2aq1tQX{cC4*(n%$Ut<@#>{6+89iS z;3aBuf;j>VJQVsN|D_=Gv+>>frAkqa{;xGDH=)$K;?*qXW_S->u`&2(AUL&s^_)^b8R;-rd;?FtC!Pa0$yeQU z>dr)qJHnGbharKw+Qk+~moku%89e$dns7-v`b4B*tf;cc)qED)!*awgvB;fl@#B-? z)x{@>oDGQ>A3mR%n~@cKr4&(0twggVf=_6n&H6S*@2sNynsg6gkNxmRcaATdDQ-%rCnG|)puy+ZO{MKiHKjyaETh7%>?U1FU7(cBtI^&LQnN zknwpX&F}Gjnl?}DaJzo^vzE#(g;_@@6j@b*Rn|J8Q$7_N_+>Mpnjeimw8s zMok0X5>w^ZkrruA0Z6PeKvayqO&_sHK&e%O?bm^>Zuj%#v-ieKSg0r&$48X)8_!v6 z@i=LnxLm0;a`TqF5UA?+-xlNMpqpxjVIHPi_Li}$mU%lH7HBh+#fE0t#5P)fmVq;_ z$wlW418nr!!@n4;)1!8ssjUvC6KAD;I%C(pMhm0u=+We07XXr_%`LHe8wn-0 z7IKF=s)WJr0@g{cv5|y(1xLtmmbEI<9`#xj*-i(0fxr|kyc`#FDWb$|}XR^GRjc319keDWta zs8WKCI@~?;Q8|R}f13rL_O|{nCyU>wJaYzb#%=Xxnyg!u+dkYSuAP*yO1iw2`TXH{ z+JJq46;YqdT72K*HPGpWg62RXKMKl}R@!;Rnvrl0Xwdu))2eSqgG2-KR5}O~hb{zD z6H&XS6h`x z9~v2@q=ur7~BnIv{LY?FgY#s8tn*ue-_#+ShoBLNCqW)dCw?uRVEV#q|2_tVHdTP9q6vpf11Kv!8JpT8q9vIj>*f{B z3R!$()*Y~%a#4~% zXU!L7))QJZ>(`hKRMQu1Ko*OfBxGx=sbpQ$&<7CT@VxRIhRvSub*c4mEJ)qG3gxEr zGKWtRIFb7xSveJyt^S$vU;^gbdgy-`-PJQSRejz znX>!Bv`|6Hy>~l%tNoaNptu1(uhkL3x4jY6Sa1Afmb=xqN6>;UwS7f1^DLP~Aac>I~N#1`J zn6&HG1y0z`T!#Z24}sRsRAIPMd^36{LnDzp&`=RLL9cqg8T^)D= zYe%Z!!K5NvkF!>;hB9qy>c8pG6mBYsB)&SsQvS93Qzd?!G3(}_X^aFkR0X_U>vRRY z$M!7FxxDrqM6tYOs))Q=MAEiQLZkYjpRf1st$sBEwBcbg_uoo?;{)3%9*$K1)|Q$! zk@A9iY@j4sL3;S~&6lZA$IpS7xzvQ9i6m?o}J62k2r2L(jK!|!DZPK?BeY`>QQHOxp)4aTYKX9?Oix8;H@13*(oQQjrUxJ z%iS@kJ>kub#0_Ei(S&dfOoXG`a`a~VG2k?Es29YBFWUBHvA{K}(6(!2v;rki)xZ0w zRI z9qxctHF?m~YwVD8pP9ZDsW3Ka{prS~sTuDEzW&IjR5Ct6Jbi_A)3VOJVxLiTZ z!4YHlk_#q^LwoZy2UZ98cG%^ZrYi;aLSNSr9MUXCfV5e<$l!Tfp`&a;NZJ?8k4xxJ ztG}H5oJPprF5rP+lsvyXf~Y}C$Xuma41Rj0O|zSK1lG8F14i6`X{~0(+F5^nptL1` z6$Mb{Yb;1B!_Ow zj7+})8e=xQZS{<<@oX1RGcGfZF0WSn_7FV+X1Qn?(E)#!fJueR;b+^r@^w~8Z{C{9?!M>5J|yFaW-DSWwOOw2iY@Ocb^mj7`{JW7&Tv5E{YoES;#0D?F7RHy z!Gw$aUqAgn^L{0x*X;mNkJlybiamfZo44q1c3T;xXf8nW+!PFDAQ4gV#02e`{tMIZ zeLLyhA1RVaDE;1s&u+Y=SN$n{p39Bi*SZrB!Voj2Zudn!-G`Zfefwj$2t*u@0wloC zE*me8cF1$Rak~ZhFq~UKDOM~&?i&m!3!2-ynv~EVeq^kE{B}VY0&V~NDM!tgAo&DS<_V!8+G3Ox* z(&N~7)hk#TNOJ`X8&iMjGm_$E(Pv`R_nU+iTnLR7Zr(hQUe6OE3wl0a*fI6Kzizky zpCDM|IeJzG9ic$s9*dvQTIWDWsLt8_iLS@DF=e+YH{dzoB{JuoYl)q&o`nY$UqWlK z(Cz_EBF}#PyA(_WWe(WV;4c8AuWBN{jIs2ZH|Sopy)SOCe`ZG5H~YHk`XA4ktF<3^ z_1ggFE1L?J`ESoX{x&S4~Hk5&|^jsDzptTB-v{tgsF5t^;JP2 zPzfQy#+ox-zjiqcADncff5Vtk$wbz((qqEAbV*&SjmT@jh)IJ)7(4F!DOZ`dV1o*& z5njfWsCF|t*iNA4kJ_MM8Q6neV3|`?Yb8ejeU!S|O5z3iO;6ZCw0N@{;ddpYQ!C~7 zT+t*PUOT1K#Dm%U8B;<-5mT6pe9uo1)CnyOlLlKC6jOs<`X5n~s@dp2U`w(YF{c9D zP=CJ|l&o8K_gA&AR?IiEnRdHls*!ivI*YZ~5(QbBHx-?V{HF>bivGz6qZYmTI%G+K3E{V~B6dy(NpBB-6GFUK^g-5t8n}^@a;+9Y{iW zre*tG^X|NJ|I=AxJ5#;QUtk3J9WTB>W(%7$uFBB1?K`Ct$^KZJG-Bfyo@)s7%p?h zst;v^67=?d+I`eX)8@4Q2pvDBcWxvQ)k&w8dV18*dGP)|bv=JKjBAroNIgSs*L$+e zj@{>r01+|n6PYLk=1|i5B0J~Y;+hlhLVR1EG= z?uP$v+RNAZ1#~~W;N+($XFDs+<|oTb(XN(?@hNDfhS;9(SVk9AGGq)X7=Y7|BjI8TMlE>~_5F zc=i34FXUzqAy{lD7euqPfUosGOEWzQVWKF<0{GYxC?d<>;68=v&Cg#k`_i zO=|{5ah3&6R0o8vion9^e7B#iDcc$h>d24gP1p-|=YhE2x|&EjOHG>ARF7Xz&J1lm z$d3$tK7P&VUo9WgRBdDt3_yU<8jJQ!INM;c6S+y3O4(W<^ zl_SkM|3lMRutnKMYnw(bv(OG@g#(Z+DPsy(c%f+-NIZZ+TSz7gfj>J zKBOd>o@qvieab3m$*M`2m})^|8n*|_fr{Qw<|W{kiS4WFA~CGmsv9N_7v&q*XadB+ z=*C8_dN9jRQdt-~1qaYm3>Q4{J4IAJ^pfpHv|MH;I@)}?#!be=g*q}z7qWaCXsMLf zmC&09kXz^dA;_Z3fbsj%8(?U19KHq{u>)N%8F$|QBPiKPx7Q?Ny6d0tqv&Dy*Ol`M z8|78MyclkiZp|FY@00m%ccp=jBb{Os1g7y5UxnkS#ca=!Y?b&=i*6^#pJ@NV$o8F2Nkxmf5Odzl>XeDQ(_U;~&I_s^a>vFsU9puoMg}h8z*~eN!^S8h zm^1?=eyc0OJHYhs1D(XL-?%3=;B1U1_tSMmVCZ%~@i@E3@4Oqcj~^A_6WSycevw?K zxhc(aA<6qi0c$S^)(4<3;9b+*-EBC210x`(Hu>axQcpZm(R$t4SXz&g*Wt&HkZ-_G z%r{|Y;q3ePS?irk7iDMiuI=jOxNG@{4HOndw?ghf+RR;7pY|qj7ow* z9uXg)yw~dfx*lgTPRHkYs-q9QKrK)GDz)j%egH@%I~lLRAGWSq0>FCI z+SBnGLdhrjq!F(^Iu$t6{5&Hh#7))F)Fz@9?d==`#L4|Lc=v{q!r7_Cv?gQPO~=?@ zmSO?cUR*~|C@5vqQVoT3pq_Q$i>Gs)=m@QvX#p}LgY(&M2Dzgs2N6^c!I4_THIfl! zn}%G{MyW~+zE9kpIG(Aj6Vz1u8K8$VGQ|Gza1?G3f_3U%9!}T{AJ%tt#jvkq$6)TNC(bssB-dh7CAg~ zm%NgoH}Tni2ngsZ;C{q)H_A5EX()%(J4uo|WnHSP7}F(iiX5oaAs!0@QBs8S)vIk; z$?OlOiHsHux|He&nD3+nctUV65yj15c6QnEL=P*js%PG}i*Yt|F9&UJ(BdrWR{Xyz zSf@${vuVz6WcHV^OQ_s+osmSSTasf~m_13Y@8_|q&t}N9P$afgCj6xcuRmnOkt?Wp zgCS{TQ4NqS=D!;4KOhI$fwpu@v+@T%uBPsMvy5Zy)IXc`F{TeH$2u zJRA6S3Q2^cK)ZA-?)4rFX7ga5UkK~ZPrYGZj^L)c3Fi++1-| z|DB{;d*M4VA^CEr3VgJIGSkBI=QeyS?4pS1BgidtPBlx@cIh~{)H%jlUvs)jqSQti zAz0vKxv0A#Q!%Zia0_-_Hi=x%s9$-nhfZ%Q25Cbctp0f#XJ_CM7vU(?GoQ{7SJ2f1 zR8#i@JF;`!9ulG{g_LTchorti6Sn}gYuA1BfsGTFP!9L*Ntagg;N6bT@2_q8Re+`k zD8t6_u&J(md)_9$ckn=la&|!!O!g)a!M1T3k{DMNN%pf1bNbSTY3Yv#WqDa%nRS=5 zqtDRT73Z8RuGBK>QlOAGS5&+5#kCz@w#2LCra3?^ySg0uV>#=o+-8*;7j7gfp?A{A zOo~Lhz`~NJM!m0r%M=U8@moF3ut$GA!vKN#&P zA@rQYF0U_0i06J30d{W1`+BiON@HyE8 zb`UjR4S=iK`)|ms>7R=s*n7uFJYGz4T29urDbIRIxwImBu(AktiPG4B2}=u}Pm<;^ zpJK~to)|}c)~s)fzlkmjlTpXD)5eWBQdHjb@<-00*;fqa;Y1&{Bh+Uesn*Pvr1Jne z6=weoW76+jq+iPuRl0v_V@`36io!2#jenj~=$QyqwcV8Ziao;H;j$i7wNKRYk~N|`uu9Dy6GHl;-8 zL4fM>T(glePoNS>3H3FMj6`7hC+S30+Q@(Z!sR!{ms ziF_~>lGRyj4Lc!mURf_=%Ucm)EWu=HdU43_4tr!&(ILi2b>WU zgbc{F{BB{CS|{3A*jVl-L)4HtB9{o-tPs$(#Y7hHNLV;>19p&JC+$#RH6VsqvLXUl zY~JSyfn{v$PW6qV;{Nc%Z*O7$osaE1?viHjG4<)wip=;jog5q_1XFSH&8a(COH5UC z4z!q)-Lc_>gzhJ)il2am^q>z<=r_?_FUrkqy@=6aa}H(_Mz4tLzD{AZj<@qp-}~Uh zH{>$+YPRFpH=CLgMm)tPzxeSxNcpG-(B?Ys;t5^u*jPVy65i#!*dpZJFKc1he+fLF zXFLDi)Y9$R8t1z<>`5#E6bCb-ph@LJ(e5#V!NxKYlXl+1Ciy=exrKe#PCOk{A{fIS zowtTE{j8QPes6^Yoss0@D^mz<9bQ6MI`1RWXKBjl*d)hXzRCtf*xGC4zGxGFpch%@ z0$h^p#FT4(FM_LHKyD^QK@Ql?88v4V3=Wz;K2RLW4^;lsJz1E_(M9P4)!juY3*VtE zyS8~>MR42e&uBq`aGl+<697#E_1>m${fR{0Z-2?QVXHNumo$n3ag4q_c8_hwB@mv- zwjWggcwDx$i?UmQ38u%e`_ra>wsNypr)S^%r>%>q_dhdvEdv(Z86zLCk!~*5S(H*f zIbQ;U8}R8S4E_AiqB%4M@Ya48A$~6_Cp^4DI~Ra=u9gXzGg9v1#XYOv_e$WWqwmdt zxy9%2tx_fC64F{s$w1cUQ$TuKm4kss;$-Kfg>Rot-$71B9R!G&eC8q!Pp8OH@`rvPTrO2ib8<-lW&C z(ZI8|*eX~6@y0CoUJ5_H zm0|CniXuj1HP`gg9N+zy^;FIh*l4w=@;KW>%HMc?Qacv({>eq-ST}`HO}?tLFH4T( z>iJY;MVe}5G}`gFlB}!uI{DhEW__bK6j)7W1CAiM3Sh;MX~#W#)14TPi!Kc12 zC#?aS!1Kp3&MS5HBZ3jsnIRN7jd7EmPMH`uebt;0LFa>F{kus|U>kM^&&Ix#Z8n$H zvfMADK&U=3ZvEd!mcWOUo2K`F91oU7K`NKGgXU>?KSydF)bO62PEAW5x2n8Y;FGKq z9-*Ev9`|b`ci0(yrYH)MxZx+MkGN%3O?DB#Ai?EJ>oYgVI}n9%d8eDrXa_9`tGizUB4yH~6?CI4j`Ic4ID` z9LOt(Zk&`6N%$D|GNv4(+Zfie8%G^+p-|T>{t_ssJ2)Z&e3!5)m-}W}E4*Hv0frrU zLz*b!L7p8d0k-Z#UfXyL{w*o0G3RcuZi~>$Ni-9L4o;0&)uN0ByYgFqE4?L`n5bau zi3B3+DH8yurb=hL%tz}=-nGO4dPT}mI;Ra(Uv4T#Iy1y_48v8hFy#JPPBan3rYl(h z;XcpyA}bPrp+7AF$y!%nPED9blwPiBZ>Xc-?h|aRMwWIWm4&hAXsB!^O1E~6CD`H1 zh1cYu91%&x?|8>P_-Fg9LC=0D&BZFgh)=POmy|2|hv%ODt>BfOm>mbmKP0^&n-DkL zb_?k0ZrHp-dl0ZPn81G={G3UOFm+2hQd}b-J5Qa!pKGr-A1t@iQ&Cu7@MA=`(Fpq$ z*}Pnobs#eH*@D%_es+2Cal{6n0Xya&7ceN*@u~fF^EDkIwZL~Zy{&U<%Iw^Lf5MS} zs;uqkT*I$J^cKT#ttC2=hSeY;Da^##4HBVmG|StO} z9w%RR-n>Rjz&aNs07K5==_CucwFrs~g$$-SK2KzK=GgK5{sAyb)yqeJew^sD*Y_=` ze)#dIGPmQzMZiWT981KOfQ)>15#yENABQ11(V3J5ZqtnV)1pA$;RLn%6`dgW? z-iMDe^VtfTQ7SUkodCWHBZ8cq zY8?7{;Z4s_3dYW*i}EA|62e~d+0>oiw{)X%>pa{bH!*pvvI9G%jj+Mm z)@wYgp*t3?P*al?H0jNUjNw9b{s-Q7#aX5wN^#cT*U}-LWOZwksU`Ih98vaU;a#8z z2%^Sg;1Wp@s%vEC?bT0%TDl&%Tva6BP$lzk26REy*C42WtD4UA38BU>zCNT9!#4#r zSV=d+248qt)3O;UsViJDkUW+z;xAgdn=ecn2r9R0nNr8#Kt|M(I1s5RM-Ze}qhmA-S+C{8MoRwk$QqXzGQe?u{s08w37=wTIANws`50I`K0>k1 znY2EX_bn@S&225FJ3pU`=psK-F5#f+?}=I8V_{~R&bzZ*5&=saGr<9is`>#G3zty| z?{CY1VQGG~JISNZ7sW14&>TchtST=t84Syi|Al0t!a}(F1ZPWA?5fIT->g08Pmk>U zwiuF7{PW-SpB)N#0V^!{(_s=DrFupR#)j8|sulhRc$);jXLu4wQUv66K>Ci(-yQ7> zWuxuoqWi#&Tw36}aB&EH4W1WN-! zWnKJHd%-$UbK#O4EePIH-8neDlSJZhLpXlLmH{md=e3TQd}|KMy=W)GQllcS$Z9`Z zT%MNdD|(ReBnCWDov42!vzs1Ss7QFAN1Th_FZ&q>Zc}BN5UnAM4%76+9w*M2(JbHN z!v-l7JG+?CBNZzOIA(;h>2bsu*cU|f;6aJ*W&HnLP{6x2iK9D#*)q2!Z<0I*Q&LM+ z!z`sqQf_FJ{MDJh1o({xmumo*|9QP0YeYNLBN!{hKe8(}c27AqkAk8$`Nj0+<(i|= zC&G*62pY2oFg|G z=$<$RUQ2aNF8s8Oy$Zv|#FnEDkn7$E>0RPFgj2{zUN^EF!^riKhjUzL5*GJVcByqg zwf6etY~w_=3eq+^cG|b8JKfUd3V|sy$%vcD$d9?(-;%7Uxx4kXs}hu+2#oWGn>#9H zeaV@GnBih1@+icYZ+N($&dJg^8(Xhp73PT^CxBNP^^jE1orJqESKp)*)gy#6P`%}? zPP8P1KUotc{4I|Lv>$n`2gYU*1Vq-6`0%t}- zWeNPjpMG*QWtn)V2q8QL)0gZ=G$trSv?S$`FIg^DW%h=aOqP|QUGT*kM&q{HEnnxz z=EQ^}Y)xvCS5CP230cekydpzz#m^7!b$$gy5^N8|8dok1{Uw6bc<|eBM-z^xMZB$J zKrX=d?iJQhhyNT;S`&K59~3CQ`Ruj*0XmgNNc7oMo z8jdgqMzU!%=#V2#eG6?ludRp~(>13y4HPnLiBYl3x1sZvqHgNSCyz*lAz82)OBlrk zdXsiw>Ol$nVPBVd&UNd{v18)Fn#6Bqe_0S!7BIFgi9YCud(@p}EN}ZZ7`bQZ_@gt^ zIX{27N{d)27X4-c-k)L!$R7yP!#E2WKIX-Du>Rb=jHyiMDKuNpy*7Fw6(E#!V7~7= zD6KsMwU$vXgVZ;@!^#qcD&}p}wF;lG0LhmW22Ub`!_>8xy0@=(RHC|%Alff?iAF#b z>5|i0GahPN=jgWN+s^PZK2y9E>xvzx5HaM^W6Iu5l&}?Jiq-AbguI;B(1$^9xBJmL zn8B3xdpcU(@x#KxHbTK%Hy=eFPP#z|%|yEuLLPi@}?t zuMJ~L%$PXeC(L^&OYX14rsffP2)m@*)u_c(+*tHdN4B5{c{HL8|74Q+yn~NV@J$4K z!azRz5hd1)Z`S*A3SEIVq5Gfv^&v5U-s>9Z71Kc$>gPB#BrWvTH|vq(ymK^hqrR+s zdtR}11D=~N1KZm)MJnsAs`8mP-T;!{_VWCIw4bXMyp{6xLqyPf<*{$WWx<$LQu2r(46*{R0WTxd(4+h<(Iy_Jz`3qM_eumhC~gv_54VaqK2K@Te^aVk&JYO z{ceGA%y~A$1g}%)oG*cyW*YxxbYo()lcb@4HKOS`684ygI?Vql^(-hC&$uu%;(rYc zTn7JyPzOs0KHvl_6(iqqRGk;Sl6%Tx@p}uzmYCjOyao$}uJ2`jeweW}fzMQ5jpzJJ zK~0?QI=8ISb=v}e_AvFw79kr-oE@pOq~i}QNGd18i8d@I{pXA{RXY&?$;%vlb#gYo znOSJ31K#4~$du3kAwKp$7#@162%cy`60J&jY{QS;Rx7pic&!uD?Gb;~npO=Llof|eE_v7tm92!>q(GSSJ5q|sE z)@-ajC*XN0!tjuG``4Ht;_zY&pcLm1T-OI6KFs53qI^$->&jBO*uM%qd3Wer59 zxZZW2?~L)5&tevF1;7@aU0pv*#*0CUq5?qoIOK96xlHn9wVT_3E#l(DkHz08&P%(z zdQDEwD@y2f9sNJmk~XDv*ku+GVtQ4TWeRjR5g1Z{GM!sMs{ixYTu9l(Fe;Zd1PHDp z@WXB-!GKpE7~ucI5B@VYY zs;ORAJz#l}I$l(-*c%C-*lUT|vmJ0@&z&~!BIfa)iN*~updVd zt6u#?rKe_2ttRw@SI?=q#kxZL9J_o6Uf60 zxXP{O)o_ znb+&l2&ryDN%`)PP*|E+T;nTfKn0SZ($}aM6K>7EG4J-}#s$&xZ&oL@T%+zTO*ewXHsh1-mBeLTc-<=oiwI&pS) z=rU%5pYFbD16Zn;Ait+%zm2C)*mqk`#ZBYHRdyJ?SLVIKFBigfi?%6>#omuYp8!|L zaBa_qgW0SX&+63we&N=J|5*Ll^?uFJSRTWlQVM-23na=1{^?ppQk=w?JMDsy^#OrS zN>m_QI*&TzBr&h#@Q>jFaXvckYhFvxNpt5-N+YqTH1-e=rAJIA_Ik~Ln*T|@3IBW^ z#EkDV!i1^uZVP4u?sv|5Q7=poUBSMgLNwaPm4sI*ay1z0*&UQIaz2>KyV6-%6VKPf zCc;U$C73x$C!#$R83-qGzgKEj8hOwUu0k3c+?#q}mT7^NUhFc$wR5ysb(UNGNyXCE zc4DsUS;?ck!aVx!PWLtOHk!aim`Au%3{fwH#}gadEw)tFG{wT@9E46X@z#~e5Cpq$=c{gnK&kSyc4da7K&Kf7 z;;(k7aFhEW8SP}bP1nZbT5ngV z%}vsVZ$Tq8dk5UN?zD+68l&fDKEuo>*w{8D+{81lqfD#wdZ=YsP2>7gsaZN4YIb$( z1#&>+d|%T;4z6O-uVSvugUT4p)i$DRny|L{e%pmho*HwMeGSP|5$P_n(Q3eqZmM@z z*lneM(>A4^z!$BNfo_7Z0#mcTCc4C_&E?t^+Wfi9X~VVr*>1Udxq;4R_YhQFpP9SY zq>-w zShRvjvSra$waj$hHC))WY1z@$HT))0$A)&F!N&r4O6Jmbr6xWtU#W|NSq8TibV=Bv zg@l#H6CJ_W*L>fH%6z(hna&QDrZ?i9s_3*GSXPL`=owPR7#nRAVQ!jcrSSOigN))U zRevQ$W)N0LcKmH-^fwuv|YQchEOc49x>mI-radE(@c;H@Z z&67^CDc_rZ@VQD~@8U86SxM<6;Gnv(Df~XF?~l~?x-z&@jOdmHS2FBJ7VPX7mCFBt6P(L=u}Xj z$q5<$2NZ#)-N^mKIE88F619!@%Prxujs?(!H4i@sXxu%d=)Xs^#io!%m9)WLf@QwL zHhu0)SuNtwQdzV_9?O^U{_{yu;V7Bn&h+QbJi*p1Oz$!JZM1WYTa$@uGLYWO!3WVw zOi2bM)fnT7_A||XDtx4`cLE9!_B!IPgY&DRy-3~1vlWR1??LB6_x0%1_v$}*rBJJz z5#A0!AloQ5Q}_@s;GIOuMFC>=9|!^dm>mq zi&nV)_=x#3A^d`;lnk6?g&ri;*9Xjz z5RCS4lTUPdhelEH7%^#NY3D``t|wgw+oZMMyiak*D&Kg|>d;>B7L_f0Z|s?s9@*%A z3+N)G^6*Wpy}BFs+?{KBkUQ^NJLRqBxEb#bEt|J2_0MwIv1P_N3%URZ@>c_8pV2Ut(tLj4}0AM>|= zKPC_jf+-a0ACOVDoFI(^!W|>3bS5NrH;(OGyOE?=-K| zieT5Tng_t?w-ucK=^@P3K72a#ADMfoxA@nP{WXCebommX@2JDQKdFa3(Xklt??k$^{DGIbDy76@LC% z_D+8ykI6DEsf9g=t)wi%;N^ZED3Y*H-+t#U3szt&8hD5)V_+-VTK{9-qN$>UpZVjD z6vH@wA*(hlNHEcjsZcd57(h=ak>ce7)TZRcMupSI(&nqO^6NMMV@xPtj$ZOE)EZkc zm0n*d*ffn6tCd*?Hhh-S=>ijASbQGWj+%0@gZ>Z}fCHQ7AMr~a%SSvye8wKtro0dS zLoR_gNi776dshw=Tlel{);MdzLZf| zr45~YuiwMNOLt{W8*k_4Y`Q#9I{;G_h9!62^Y29R%DraIeuGmZiL6|9q$*nAeY|t< zKH2Whpn?;~3alAEK?tjuZ_gwB%lQ4eL`m$(OjO4_j7en(?Kc zVgvoI{-*Ij6D`PH)smX4(z9v%KSBKbYV#Z;dCj{mooS{pQN+8OCQMwoAPNm%EK%Fh z5gAfod-V~%MtF;Q_cUhcz^;&VQ4V%=UybqPS~e-2h!Mi~*RG)_<&;u+w+@t!GkQz} zAk~OC&Bp*HIY))_EDVMr((tY~hDDDq3cFU4bP`{#f+jXoY>rMl zV*diOxynz|&>k=Z%TA{BwcYZ^-ky{X#2=(cnORtXfOctwDH!Bq{VSsMsCPGU;dev5 zp1j7JZ)q0<6&yg?X0Kp?PdYM}&SqbB0z4BG#2y=o;P0jf-QG3}qpgWAGyV+hZt;T$ zvpp(5ZaFjfRW%p`wTJt&2i+I0f*vX+0q$ILtq ztQI&|y@2&TFJN7Z82*DJf4tXu)QvsdI!DAJmpHA(R`Mzby#*c2@d|gMNBoDYE6sql zUOtFpECeVAGOt@?bz(vOoZtIC=+CKsC(XSxPb~BVnhkB23d#8~+6O=XUQX_psdz`` z-uzk3n6xA0nHT%!QlQq%ph(=e(xu|9?Ky7o*_2_2k2jKfxRjNfeP8pOT0b39DDaM| zE@K!j%b_bI3j0A|L$0kT!VAF|aM{hrR${a;Td}5*N_Ju{TrNKQXXAcsAZ%Ixco3<@Cd>C$9Tu`ZdB z`5ApG?^OlVa>m0WE!fjlztLzjE{#vS_S6xWRkEpO$mYd^%m$fK|Ki2OV9|5qwTz=J ze%S!*4*<9%N_(>t)^^y8tPm>Z(ER^K zL}8YAZH+2JYf%5=17|R(Of|fS=6n0Y^}Wvx*)kEwSnP_j2J2t$2g~r<3ozv1QUlBJz$zRiQ2nR$Bv>-?{iP)Kmyi&A_UOG!_=c3ZK-LD$RVHgI&20 zEo)fJw15*o!7Aax*R1S0l6;$%@#%VQNTE4bdG&A}1X_Z$eCU}A*%@Qai|3%=h0OCu zZg#w`>1hSM<`WXiyTGrg`1p=k-r`MJUe`ToxM~0U29PIl+%m5HYDPX}V`nGrAl(LV zq1uYe+{yD** zlMaJIK)|&1$o=A;6QD96X8kk8vH$g-)h!yPW6~+(`=1akd~l15Z+M5Xw(}%=i61rR zTZHU!0*JK-An4vNhxl-~{hwy7sm310m%Rz0&8HhmwRtnmKvJA!Zer~UoF#MZ)Ui3)>MP)zI)_u11x1{q6dbcj`_<3PkQ zGZDn3n|Uuxw%f=OWd}*9{i|SC>NDmEZ7U0S!b%wmQ5g6z7Zzz(-TgdHC@ldu4!%WG%csV)sQ;Bj31q!v9 z8L}efCIMdFT&BY5hyMP4Dn*UbtXKN(azTNF&&lf@wssP^&wwb#e8x&FU6S4s5!@G1 zJHP;#rB&lTGWe!$617Lk(bLY*n`szV$fIp&$`W^ui|(8WsL4$ol62g`vKNls{(0So zwPZ~;zQbJNz{CbDV7I2>Hz>qCpIQWR+a^Ugkf!GhYb z1pflY0fw-Yi9~^RH^8d1KU=<~3k(NF9u8ek{}W9+a!Zduh=FovsEEYUDSK`I+EN`? znOlGlNg$lvKAL31+7qcMW__I40(V^ZUVSxd5vD%(Hdw!NOGdGibTRL5;i{%)hd(2e$PdEh5>sgfLhqUaw4`S}0! z!amJpvkp($&egYum@iLr5m>aUqsTCx&b?MCE>I!Xk1&p}|8y$k)Qxw~=aK?_AU}wB z5E&&STDG`2;)iSQtS+S!IYDF1yzeuM;S`FI!n^iznzapLTV~ff6`T`Ug8!8d<1+8| z$4~g(@iyX-cJV^(eJ@DcZh%>7)$1{C&jo4l8JC=oYSDhx3-F}}j6?$4+CR{}z1NwE z7FJQF>^V$&^Em)cd!1Qig?8QRp7H!IWnc*%fX#rMWIiY0;Xf08IeC$V%c&5k$^H_7 zYZF|ccHTcaN6|ZuaY?M$4CnQDKo7oE)no$Czb{J47~W3J%~x-> zwtKodRWH^|J(X=n=X+q4PQK=SfoWm!37~r72UziS-_Fm3DK;@cnh5j)(O~wcp)A zXVm^WROhm-<7g33(Ac2`s}YnldFE*`CDmt|t<-D6OGaKprKKU-kg*aMO&iC#jYOh~ z|Gm$9-0tE62)zrU1fJ2mJ+zQg4=aT>e>@GNpHS%4RP`@m#h*q2^R((0(LK7Jcn_w% z_6IFWQdhuS4D|TYm$_5CSml++CKNs?-iG^@ke1D0QHTd<9x(tn{k|+ zX;Z{VZcC6^T5pd+IPSPgXlkM_wwph{A7h+5_#7ET-4+V;e?$_p0J$Ro`!~9LKUZum z)7!j(dfVR7fmX;GY}~X0R^G8x14B5+8Tm+gQXPIty?d_|clSNK^zVxYk@H)Jwx>TY zm!&65FW8EQIjq#R4MJIO9EB-{L3d2CZ#~l$h=*hJLvmlmRQOKZOufoC_!4w+zm7BW zQeW+_>AL@0d3^|@I{46Du0Bk1K)H7ePQ5cj!$2pbL;#u!s!EUiVmZa zBI=26*qe$>B?F7#$v zuLmPRfUD^D?_UKTHqhOc2?{YXLg(C6J?0q|jDQJcaWT{qi^h22d(DcQp$I?xXZ~Lz z*=;6k+5}l7qRzV=QUqZ4kgD{_YhDsdDi&xr%-*%<6KLXch!OIAbT3KHrGt#Zm=idi zRxQ=9Z5pgdzLskYxA5@sZJwUS0pnob31L24dD%X78!QE#iXr=p>Kpof2f=gFhrJAd z!Uw9;&?Z=fW@;30T8KDFV)bv9j@*E6J7nPK2n0OM=rm{5(6{Hqf?sP)3Z5(}SG~4( z_MY>J3-%_?g9I@Xn)iQRXXv1m7LMtjCetK7X&sl1_%khcizWyn0?rNaDgzUTKi?y5 zxHMbw9X_qfXZ)y{_WHXLj{304A4V0s>uFD%An4`fO}Q*|`fh+&w8<|)S`&JsS}>1_ ze(!J;ee<&eBJX@$L@AeFGM5I2Ddq-=+csze zpI1iaibV}ipI5wM5fXmVpj*%!vwr|UD|*#XO1*>n?y$QEP@?fA&$}B`>v8M;ZW8dj z4tcqaJpl@*Zn8A@Ju!H&2rpce??`NyLnu2Qk|N6)f6rPLvS#k=?`s%@)zpzO@BHKE z&$DVQ-8B^UbD?vXZL$=X^x}!#ihhc4A!VM#d9`j|Vv{i5zIeRANlKd#F*74hOg+m_ z)`y<&pr7&jU`)F@X#5;7?a}k_WU6Y=aF=t=HMWf${qGYl64lOhCRVPPNYNx%l*iGD zT4@wY)Xm0~a=&)9p7|;v>kt1og>yf?uSpYmaT47KNBQjh9KPo+?F#5?&h{AIAX*_? zCvkfcf2klY_hs5=X7~pP!KmPD>^G&b%qB!0#&0>wk>4)c@?ivs$cgQ%ehTV`FXttK z#PaxqGnxBcHXP)cbwDkaD+PxpM*Xr8sPs1eRgrI0G+RpEr`xaEu-}ScVO-NFkwL@X z?IkoG-Jx^}&fVnsmD39|+44$jjGwu5`K2rdEGXMYUjKc2gDRI-)T0vHTsqypX>2Zi zO}zJyE?PMlMFxU9+!|HvC=-z_J-l_(fK4_EH5Fd}2$!Z;0LNWCMZ|xI2*Vk-QO}(r z8EHRe-l`kok&%-JC-JbPetw5pe7a!x6mrqOkL(z6l-lBl^?2na(Amr`jDj%$-TLLDgEoujOstn{MiZ(B696C#nWh0BP%{ftX7sCgk zYIE&}*>`MryaRADq0r?us26kjYYjX4VO0!MD{0ca&WN5I4MNjD62Gn`QIY$8^%asx ze3nYx$jC2I2%9E8PBwAipp;+af4|QsM>{y1JNW)mma-U^fUE8GTPi@kB9&Spf?w8YI|avKXG-fvtbd(Y4VhZozNWCc_3~~f zj7HV6#RNr~a3KhJ`m+I1eIu!KvXqAbow-p{P4z0ug!OKV81z9JU|4FWXb)nceN3H>q6i~XdV}8V`>ob zl=9%^eN2X;P}(=xLcA>S1lzA`!zdKvcs~7i)^PKVDYx$6CPp=!<7)M0%8U3)8tJOX z@4Wu_kMxk^*~KcY!}wG~53UYKa+7?l)W?%Fq`QttIQ`6-_~y$q+6i#t^^CZ1&iydO zW>X`!N58750-qRFYx}a~-@yBj=y;-e49DF81Prodj0JC>2@IWjuR+nG>Kyl4g_SeuP}w>ZCj4p{XgvJm?{tG1V(E;s?4(Ani&2@!R~oEnjqRm`J~~i%ZwW z6e3rl-W{Y7@-5o$<>>|yFuoRY@4%9`^ayxSdwG8$yMgIjf#omoi_vJcc-#m)fGGsL z{|X!9i{|Ah1f!cpZ2)YyrVRkmSyp&l?&3;Ihq_k*fl4A>KT4t&WyifvZgmYz{W@R| z(<}f;OD_OP=TajwO^?9WbGtN(tIrXEfCYz%prTesjcbja_Z=Hdg(Uh>U~Et#52=rfQpCc5?4| zm|BAGT2=HR`ooTDn&5`E^-D{H7oHJ0a7kLOG-+A}hRg7;^Qc#*QkbLVsEPEBOSzDQ z9Gh$_;lk zbY%oNY%HwXtr_J#?a;iqQ3Nw9K3Ql2Z*d9}h}_17USr`*%2X49H}j^Xi}ur$YTF3w?ZjtftV@yDy4s%*fLXT~C6la%#uo&PVgB9r&L@J6A(LA4QkE@?Z5 z-5_@EiuHA3OgBUB}1Gla`jnFr`8S9OcB()RuNvj4yC6LqqiWp-MuJtF_8ZmdjH z0d+H)wu1M0r$AP-eQ>o*E`|_-ko#+scG!0#!_Af(^X2TwS--O-*N#+7noc2{J*yXn zicKj1;w2BLPU&Z5aOcLd9=xHdHKd?&C?}xXrYjGutHY{Fa;fYuPpV~_Tmpk=Bp0U^ z2_S#lsZ47n_}G?zWvIzri4x2;7tG4gMkU^*3eI?YUs%k)kRnBSWeWmYNuUar=4vx6 zAwdmzqbd}O**7j80#TypzV?SVF<424=W8|@br6jqbjmj6nMR&ZFdD<6-^-15U|_P_ zYgf@N$4(m*U1{t8o$&8^|0bBM8fDjY{K$M{c9!#`{e}Wycs3re;5t~bNfO_u+Fq38 z_zf{iJ5>_##|QrbqHehKyUcWfV z)-%#P5f6oM`_yK4Rb-{St8f422=QakXOC2+8%$s`_iD zuZss$y(YUr(cWXW4X!$-9MyPDtJcNi1LZ;k0jFM$i>QfF>r(Y3Dy6_(To2^KpKyG> zLYyIQA=Ki9V=i4ieOi%8&k5v0U<3Cy8MBlr6`b`u^A}Pfq~K}gpYFx}Ea{wGK>n*e z9CBAZ2bVU8%U5#21olwlttqGG|3t%}!dKf-^UUaK@$XXU1;kNnVo$>}xPUbTu$QgX zuWD{-+w2Z{5OBZbDWtZ-AD9myoGaXN?fh{Y)>j|8)Cv+*|FF1PcxU6b4YqeW zDuM>qHdGVHK{C(n#=QrD!F+j2^nUw^>PyN4ie zPL#TkfwWH7=o)0&3@Zn$!gCX!v`$f+cnoB7tWPIFT6;59Vf4L#+HP64;kw9^M~)&bUO%ld`Oz;Sg2V_*%%6<3CSo|&@mwM?)jFFF^aAIUb5sXc0bhdBoF2x zWm42uF+BJm#PA#Ka_N8s9e~Y6+oOu9ZAGzEoc zRc!m}VT)$@AmH5MXt|KCgXP>iKP9}TnrZ|#E{nEuMi{g+uU++KIHD!u_a{5M@R;zS zC%X2+{RGWvH%AtCS(I1XWS2vTJa^BVO>nOW>hI7Tg0 ztUvZralrZ7lHX!YhgRUJV zVpgJ8JP3+zbK{yi0VK7 z4<`oGTr9h`$%m4NpEi1xS7B4VP`Yh27~g8pg#~1~`pNz6gGuoWecj?)f8dS_NzI8w z)^6>+=QN{t8q*53De!0hW0+5{ZmJL)6VpX#NnXHM}p22)tSKdMg$5 zWw9;U@t<82(KpppjEerb@i!kNb!>k3N~AS)ybxdelU&Kp%~x7!R(%8hKB4>F{K<)s z#^n#h_2HJC+34LuO>?;ovWPqbL_pYc0x&B?vUCxCurcF#U&Gf{yX{O`o?if=ON3+T4?q+&lF>|ytc{pbr?RW2a ze$OBN^Wwa??(6=1-udQ^75A&rNiQ~^${_LcS!RJ+HcEeiLxGPRI>ra+`n6a%$yO*t z8zp2WVV=4%Wa!@U`(}oi#S^S|x>btfW16$rXM#B;gc;A(4MdEHin;Dxios2!fN3$w^}p^4^6x@qKIT&{=6c zVH_D02au&FduOv$CHE*P6{p&AM{1y79H4_OsGs{ zz-C!2$61}4nkw@)80Z3#|7@`GUz25}D|}2wxi;@VMC#RCIGg~QKC`x+fgvG6LKq++ za9xY@gm^SZppgPo0$^?dtV45(;fn32Ndn&(v%FFot5}1D^7QX>EA7+9D=tCZ@w3cI zsTcL(FWERO3L{$rvOhk4cHttwi-%*$Qcq=Yum_Ys=a3qPR()-WM$uM=!f--=z7v#zGtq9eEu8Mwc|a z&p7w5JpWac`118weA4IfR2;wS4~!3nHf1Pub@9y671ahJmE^JH)LB$zH^IO}$gI8^ z@@85bm~S=gvPI<@SN~57z~TBvBtW}v=i!`_oqf#FErYAqTE$rs8UMz?p$`l1brRLP zC-QXZm0PLbs7khE=<~$t^{Jm|8oz6H9fJcXNnH!bY)eOY(%Qqi`NY@Tb!xFvt6iq{ zyKkg(?U@$0VzICijmUJ$Q8r)05(2u20x-ugcLhq5guoFTrFf2}2{f9cXExfbp&y4! zG}VOirrSe-#maE`?jTP_2N)%RcYFnZdu!>s>ta$Tkg}69oNvd3L8!(FfaKVyqCq23 zKuW#Ho-QBacEHY0e7V!Tn(gIji!(Q4$V@$BgkhmGCz+YL; z3_(W=>R*C7kh!BqD~L1M+YZ*kr;g)W+tM83YLuI@G$Zrp>FlX+8+Y%Mgp~6aC{2>ZHmCe+&N$x4))!6ko8t24C;`ubOXPCZ)dBd)E+eas3Y)b8#24XoJ>7fDpl&hGD>1H>OdyIP(}b- za)-@4V+grIhsK|u`1L))2Wa%VUoc1oM4=!+GAz(4Tm7e#KDwliMjt1a|;dTW###DA6u^y3Gv5qE=g-d+)aW0J5ObNI#Ac>gjX9 z_Unf#iF!Hyi+~6&O*qfw;ioJO|4vk+RyUHv`Ga)9SoIdI64-8~@JSZ`8;2wh91z;l zw}FAKtVr<0#60@C?^Gh(yhuaNn2SH9bMB|@9I8MQ!5&i6m0`&hEZB6<@!3zV`9#9{(gzn3`rZ8p)ZhnU77fN!Q?n^!fCY)QeeMG5~Rc_JRn` zUX9&;-1{iluELqBkfY|v1q3Ew_h9KEuDXQK6%uhz$fv*p)+HUUW_CJ$*Z2o}q@WUlbV z2m^J`Jv}`-(d*rOdQ9RBW154FUW9u8UU=LQ1%57TohI zACS*~ch!KlBX=eyCJ96eRjL&lm{~mWHeKTLIhpnk_GAj~=3~*Ohz^qJoN$1gnM%BC zJCW%v|H-AJGmVUSj_DN#rElB^lXMO22w{{(@>3u9{V1RV$I%t&6keHNsy1ObNrT|| zEKggx`}4v@le{dW3$nsx%sE}$93>K)=xhJk^Ly^4k_16!vS-f`YFi2_`RFxAI=o?u z=nZ&M$b7Un^5(XexNh873iP6&TGRPwBQwH6y$NED-3ecq{bG_dG_`)Pk?x=%e&hahky zC;cK|NG9kSXwt6zI{CDmpkT>}4C>c>LT$5o<)1p3KX>uoy~L8HR3JKx>3)xGLo#p@ z$lzxPz7p^;Xfk&@hw6wD7<`qK%$r90(+M$}+r@VO1o%s=`(5mWfIqoZ@8d(@!_|Kb z0;6XG*bMxIv)|3MHgNm9R$bb=yUDaFTndN3|6N?vOG(uND1gC0&TT+6li4j);02_g z3|n|~IqD;)<(JIyX>n`u>Ui7kW*@IBhn=@`jn@R;XB;ye19eEB zxJ;Fyd->{?qfRZ`+uIm$DM0a-E*@BMJGkRd?T6Q{;=!}CF#XZrSmSTQSHD?FXRmu+yJq9#?fj|n zJ{_c0ic|_{eQLi$4Nl^04@A91E0na5xzF0T+i&Bn+5{+&zMJa4bPhC|uSe9*bSI-F z&2}PqMa`}G1;JCmO>t4O4}FjVxJv_r%55*r#m%1Vply?W@yc;;&1@&?IP;3S>1l8C zosBdl#rmLHJo7&3owmMvH~ovGYwOfRpQ(dYPG}%B7{v<|YFjnr6m!f`zh);1;+Q=+ zpaB%$Iwp(P)Ug#USzKhDX2&NDuJ1crM>ZYQk{xrKQ<-~yfUmvzh9AM+1KyIiw?Hk? zDYA?2F>T`x#RoX4d4b*8A7)(72h2U`6^2vB`fTa@Q^oqR^2IMXC>KNH2j;|6N42pn z4dws%yiT-vkQOu6OjXdBAdx#OQN^)eo}VR=yrl)^<|s3{`&) z3qSjs;h=!CR&+Ov(m@OVDx@UKzwT4^!%j=xa<|`fJ9rzec%6)z4u$t*cU#OPKL5su z{S1qLnrEn^ty*2pjn)qYD1y?*;xX=saX&T}b8-LS3LvgF)US&`5MmG$M95)2AIpNz z|E>%jxDg8v)VG`)`mI%t!l5T9+LKwvwnk$hKl(2w+tASH=p3q@DU?D8yk?}J4u>Un z#v+?G#gSK%bo&-o+By6TTx5K@GsXGk`Z0oNj-q?)8c0~lCg)>ym9D9W6$Uo|fwSJ<613(h*rT9Y!p;UOq;JPl(&jxB9Ks^|cp0eW7 zx~=G(P*igP*zF9+S>z}!8;n>}eL3i>ABTO7IitvxKaf;=e}OYp=UOERM}Tsvzj_8_jRrm`y3s<7RbG27Sr-r)K=DqYfw3b{ zNDWhw%k0BINI+H#q3#Ve`EJ+;CQVM9Zsiif=58k`-fl6v+n+0}g;*x_rQyo&+Fx=@ z-&`rQzNeA>s9BBQL+VEB4%(5Q5sVgy&JpJUm2%)k4(ctF6VZ1Ah4wCM1cuq^q@D1< zf5NCMF;H2;rfMz?rpi%T9u9f*_--fMjm|Uv}87HYi54u zq%Gja7=eJuXJ=+O5}2vbJhg$aGbq#?jkS4KE%Y*}gyYNfA*)aT-?f*06BP+#L4;J> z$=Jf^K`OHaiTt-A3Zx?)w!*_->GOO=1sD2`Psq<(9W3U87@t-8{N8!^bZk!_P-O!B z^y(XaR-rr#(xL`go?)y8=m`lZA=BcB~Wp-aAa>Co1;I#uYI+!^Ssb)W=-_KIigSl)efVy-?C zq9FY_-;ogi16t|!214o$0i(T0L+H06Mfb5(`rODlQu4k(7q7#T5!5|;!NkAEqV#g8 z&}&GEM?oy_Mnk4v6B}q@^4WZZ9R09=Df^WUQiNV+8z!Ob{5kIKEac`Wtq57KUD2{+ zYW~q5ae=2{Ahhv*Gs7+v9Opw}Po`G?x>Oj; zN;-3+gK`x4%3l-=cg$5n>ofA0qv_`Js3Rr%;nFvsZCv6*zCbddT zaNvDEA>@>O)`8ca(CN7ZluB~FP212=E-OE<0|Zf#!@gfF2(I9ye$v7gx}FR61H^bV1|7|v+Qxk z_1`YIkC`nW8$ovrX%*=H2~X>-;2o?g+?Ax-lp#v%!n!~j zXoe4mpkYQd*=F2q3X!5iB@v{a6Tz>f|5eNly>+U;G*mT@%e@PqRL|BiV4A3BHWS9# zpUeHYblF@`UcOC7FLqEWL(xHEKW zK&f=-ZCmJ+Q%l850xWH8Xj@;O*0PUd=-4eU1s)Kc9(uRKaD7-^&p!(6hIGJX_pf}H z;qjaSP;+hr*__#TRRc{<0fn6Yn=Gj~w1 zG@g0SO^T=+)ZO1d$KRG0Pw|s5^_#wj8|QyryA4J^fVOgaFi=6x6P>5~cYH?c*s zxriEiyQ&))0Kj2=BS&d?l(zGUA_SKQZu5J&3vJ%4$negE+C(y0C9YYBZ@>BIZXYT1 zN^DQ(ot^^OYVL3(JX0Afm;S)_FK*`KcKT&C2Y#@OKfh9C_$?9(-up=MFTaOJR`A%r z|012M?4|lmZzVucawF-yPEfzLzW?nhg}d_qROvlvJ<^`B2}+X;to(*oVUu4s;4L$P zS~70U1AKtGWI*mP5bg!2{`t%i|1GC-CZ_K}>CFe`2bg@!ihGo)BAeu3OVqUl%7CHW zClb50ZkY6gSFL+brV2snpPTQF>@%w346|ct{Zl_2nd&k7oKFh8e)j~X4s{XfHP50o zs@>!das<8O;Dc7f1OLtOb#?DtL|pkZChu)jf(;CSHQ56U#ufW_4gg8K(9VhvmE+3L z4pR8P;u2cN4C{_IEgi5q(2w!gQ!&+gvG%+D`)1_NicJ7ldzJye1@@n%OU};iYa}e* zum`aBzobY!3v#d%syaLYV9C?@_0~t0_a88ytgshqp^L(Kmh9*=RB=`bW;6%#IMXs` z=}f-;85g?w*!GEfz~sA#N%D5n-xmA5cMV&iF^K`_r-;)jFLLwv79l}TJy65T7-K!m z=+`DDJ@%4#k+Fvy8IKzcdtO0$IJ=sCQ$2c;=7{CLJZrTBvHV)jwNV~d6o#rfQS&dJ zvY@9MD$$@z{qmK-v922Ok4$`b^2vr5j&$e&lD+>(vE7p@6?DJE@+GA+QB?`V++`MH z?ohcM&L0_EE|&sMuk0k4n%uX+p{qHy0{M#kt<{Q!Eslqdnw3=g8#*DfKjUGh5tYpX ziYk`{dr_W*Hlr9oT%M7IR7bWcw5@xO>3;iKB8cIOUo&B1|Hq-A>NHPKk4r77R`Lt| z=b7C)OcwP^>9d^viF+~Rwf$hWYgipvB{dx8IBr*mrg*m5dJldzA8(Cw;$w@!to@oW z4Kc9tielgE%(Kmkk$N0)3lEqMmlA*P`zF;h?A2p(YJw74S+i~tOAa+Y>1+R#eI&7e zRcg>EkudN47mhzeD=ZTAGq?4|kuKKC-b{I8>zhcTwmjM8@z|k=;%2${=s0MCfTH~f zn;Hwr(;Z1S>G=>e8@1xwgk4Swm{2aL(m5C9^%}aeTxQBd3OB|4!(znL{DVW&7FXX` z2ZXLInbPZL)$kkbZh&J%y{yS>c@ahDy1dm>$`KP6(@-PizrSlU4igO#xhe44&MEiC zfF+iwfE5awHVJx8%8M+nqzyxC>&DFGJFtOBq+J?*f0vZqv58)FrUFL#5A*^q`=7It zh3YC%CHlxKvvzKNF1csV6Ov6c`CN1PdAulEGe*j5 zw}H zX3JYOih=P?b51$gD)oBOOE2}M3SmLeN-s!#T8oq#rGB)3i!$sPjLkI_udxeB=oZ-B z)VLf8F@Cx}!p#=*gg_wHc~-XX7ODn0u33u2RT@7qUwQQuen0+M7*P{co2i>VYhXA4 z+HZt=qYVV&zIr3Ed+RpN{`#qNf!DKRdhhG4PA26;vDY6uUvzxzo>F+v8QoUW_i>5h z=tF2AyJEkFamfu6&l_F|a6SJ(KQ&Agk+B8H7Pi~H>oiP&Q6sPBxl8EJ+XA4!BC25#P>h6x@ ziD1)UTfe}shIejq3Pw?}qch`@vy=x_{e(l1q3VhFj70I**&ILB;^q0BsZXIDk%mRp zxMXCllvbrL-FwP)*}lE@0p zG5S;n5&y8E$x+U%JxJ*D?~evpP-gJAm?K*r0v|J={Wa(2^OM|V^hklob*!iT7vFzQ zO{oLUzg>vpGo|jtL%}FSwH$h)nmggI(caz6C}l?9m1?ksFK3w^QztwCa5;(fwWC>z z@W%CJdI9UCl2RuYK(36w`_**~R8EIzB1R4>O(olcv?IHav*+-M*&Z zK}zQX=&dR5%GiWI z!T7AnwkTt?MzC<)wZ0?8(^3qHnTk1))g9`>n{UZ!fr`nJ=%F4@A00~#r6Fb;d-Psi z4y*cB53p8F{;XLme<27q956&FJCcTBeAOHnu$D7Z$1%}S@ej^NPXFW9piyT*=<>}= z0Om=4fTv)V9nO%W;Ydx1T*bm4%a3wkv#Jn)o5KGDYi&qCyI+@{1O}LC{{;S)o55Oc zqAyXD$2`;lFzp`Y)o{BJT0fH`MhPRk>7>t}KWiU<-9{jE6U4}|fMSpo0`vwm*pnd` z%QXuKHe5NwE{)h6cp{RQ?El`E$6)+R7I*pe@8MY(QXJlmOyTHP900flfCT-Qm3V)D zPtq@e^{#G@h3$A>jDo$$FJVmQ3I9t)aVbr+^RuldOGmHPYC#rVbvq-8l=>~BpmdbI zw8c)(OIQay&`xs*sBz&;h}iS|0-==4!MUSQ{1W!7&9v}d$i>4<_l{W2k&N)jjDPs( z!<$s^tX<;(DTEX5mF&l1Jgw=|a&$^jtxp~SYbEX=1MMu}$PunMbIrI+eR1WCMEPb& zl)8}baR=?<+04mYa%Llu6sS{&n4c?_8B-qD_SgP9JqVOu5j%Dsvq~;9i#BfZpyr59 z(Tvq?o@~Jld+y_h-#C^PWE7b#|9W-*t2PvaiHY?NJrvvmrJ6v8JfJ~cb%|nkm=0Rn z#H7P|14;JgxjZ?(aOPb${OL2~BEo>gD*cvGp}oVb?BU|Uiv<5zc3k%RbY7$uO^pfE z;Eq%qx`|0il{-uD7xRBc{K&(F(fSxPo&>70+hDj?MuqqeByI$z&c^`Fs-6JCH@bkL zThml8ri%^q0(PYZkne$Imw!czNcgzkoMhkS#Q{yPOpn^pmn6M@7ZI3yXle-#GW$fv z2LJXpR(LwU&P(oX21b|cugE6jAy07y&RHmwzF}VlYTa4kj4-Uw+70BHcq`Y-J(<2h zeZ0yBcspw^nm-bZdNj9<4L~2_`~vupHfjn~_~_5Y8v%gjUkQy}lPcrEg6}igkoRjm zDgkTI-hC1*UNiw-V<*AyEW$dzrS`iy-zK>aE?zT=^Sd*(Gr=eZx-2Q(vpBKE!#J}l zIZ8iZTn>AAdm|UI0AKWj7JWQrx|gbZ_8PvWrhWyIYoOyl6Zu`Qut;YwQ7n#p zQl_2l?Fb;n7jbw&)4cTW*#Z=2yxB||`dkTbQHo@c#1dJWp^-hT`o2(AV{(w*X17gf z2SbLw&X4jOxu+@eXJ^{zFQ*RT#sZTQ+`EV=^oi>#&@^0RFmcvf84MHq{Rq!s_D!@#I+Qh<^0<|+o4lk+23iEP+6jM-e)NZZpRvkN0CSs{%UKDJ zMp>&#RT`GVtJ)^3njh#6b0L?tSL<*X!_*Sl#DJlMm8~CCmZRDf{!E zyBni@zLq&WV_4w)r5LlncnaVMciWVGDmHw?A@Ck8PNVJL!$Qxc6p4t4Isn;?8Ydub z`>}DqzTxrs5d1I|dd*!`^|mk3szIFbGjeM8q})eEh9yYOX&b*$N5hZUc3^J+z3<_o z9t^Y@|7$#OSObbZ!Pf}3itl%O77q!Lk&)|a@DEy-!Ltt!A(KS*3a^gxH-IMX&bPW( zn~@~DS^wRstM{wrz#(lxFx#b-Vq+ zfzLMS%5uK^K`xm90Qo`)-Cq*6|Mt`Vbe8Z-9E6@)(cXSR{^uQ|Yp)`%kGiDnzIu37 zZ_zivHQm``xmIfw^7ok^97@jjK?O3!`$NZc`QN_n;Ss)+`=1lJ_v=*!)M;PhNh~$7 zn@ty%s@vMyG8t#KB`ZR_xX@%@4(AI>VMh24E9d{T0JHNaf&<9duvw#ih3K-dT_Lx^G{QVH8Jq`k1$x;k|NEk7{QK;?FAJi{6)*87;uk-z4&P$$f9cn`K355g zN2}Xiqn6#hVzKgGCeI9#{H7&A_G^5__ZgSyGr`gh4B>>C_pQZ<6Q`Cztl}zoG$+bc zeJk*7N-9S%`4SZE>6&xrTMu7fB?D?81QZBwDXDXAr5XAHZ=91S3BZ}9=WO!thM&_X zEfonbIhpr#T6P`yBke}6Z}1KJk%loop;R|$K6;D7uV&OR?*0f+!%A_;V_TNu!`<3= z@-C>4Otbi^h@2@E;A37Osx$AtX*(f+dn~L{3((Vz>5e)N5yRl%wyi5ZSa!cBPVdhutxg&>nXO^NZQP6J9>q>7skw*S%AH4CjNyI+m_lZgkRN zWx*TsSZMZLCkG~pKD^{xpkzaCj~b=$%bk-W>|9B2A3vvXvu?x-`tMUY>7gPRdyU}E zXWj)fhWXV4VN?q5UqPujLv{(Y=h|qVbK7#Rpk9qGoUe=8N}6X`*p zKL%#x_UX`OAPLJqY6D5ZtyZ`{J*YsRRfgQ#;r+rTY>nx9o4c4Tr9KdAg`hEjI1k-`jjNXnImXmSu<YRtC@4#(`DKHUt-Hw??Msxl z+C+{EgZzo2h@bg0K5Zt1x}lgbfMM6XtDbm>)&(BP6a`FUfnPM&=8#Dhu8YSTAC{0K z?8>a39w|V66TNSu>=p>1gz_Hp@+9gV_3y09^qHzETyKdvbv;5tW`G9AsUBNIf87yA zxeEgH->;<6&ZFPEf;J((3%wM40;#=HGhVS$-na3>c^<@{eO3%U=?h7`Y z87ss+=(^>4QWJiG&bpU0`RL`J7;T?7yxHdezg zeLc**c8NKBzoaOR`}wa4`&J?`v-A&D;`=8;<1N-i19|cUNx`vz{6(x{LlZ0iH&^~+ zkDk@v%@*q>;C)3+O}d&R!~)?4He)P4(z+Z0+eGpFu@nVpvPkod_k_& z3x0_aHBUC`?i(U!WQ|b2vD;Jz zCfp>f+fW9WMw0wnmn9Q`vTyf-rEpj;g+D{9Z3`nxGQ4aPU_KZL%&=9}Q3?O{pA!(z zG&S`vNDPo*g&-p6qPT-yYbzl`%(VW875h7>G9z08CY2ZfdNGg6s^a=Qc1Y%*F!D0D zV)Pf}zW}y=V8P>vI5Sz6-o?wfm(r(Uki6Y?#U5buKg9HN7hSzwCMU@}rJC*Ipae** zU)`vyoCGGWw-24@JccWt{ldNbxR$#ljbrj)SR zl}(+^Yz6Vz=5#`OkN*5hIjN|GyKty{CQq9{*y3H5vl{R@e$t&|4k{DuO+(pGrpATB zCOx}-DUDuZ8T+AEiihPQKi`4%qCa$poWtoe{~Y7d7f5cGq8M~((Ern& z>5(NRgGAm3hg?@ba-XY!8B0{S?6=(N zBI4ZXtG?{&xGxlf_#FGY!%L%URXamlRPmQvD}!WoR4C}5^#DlUC&7SsmqYJzf-B3w`4y9zKip(|~&>9HgN2dop{A-|0fiDToV zuL%(nes7IlUMfZNedw{hPvQh4cBz1&|7j(%bx!m7PW^jka0p%S?LCFBQ_!@S;p&@UG%kw zvg$E+OVY{ni+((59%>$hw?VuHdkl!fT%@UK6d<*nDWx4iur-yu?!{T z2^4lKP?161uOX15DyQHa2Z*3G4tTgz!AwvO#sppY@hOXZ09mCM+o8}@L2 zdxyyG)3^!O)dkJ^(D}!T=n|_lzhi?{mc0Qjjdehpn)HBqX!ZRMU^_E9;!saUU5-9X zUQ;7%wQS43d4z?jZWh-#H81>~neR%0`sy1@#4-f;D;IXpCc-ul(+rQ}>s=_ZUN3og zkV-IG@J2Z}t)z=BafCjVzGuuunb?Qy|$hskzszk4rknq~WZ_-pZH;FI9BhQ~Uq( zPh#q;Acr%SziJvWt-=jxFp=QmwB9jcUZMO_hW2K=wz8W-i^#P7MUn&xqHD@>*ad|Z z?g9CzMjeh)pU=qlRcJ_F1KYSGHLl)wXia1oG1_{OwxTvqFCXrCPK~{gohA^NK{k-s z#DTXzo!{tG=B})k%nE(2!!(NL&I8Gk#`(T5dmWV0vRM!TU08)wedEOY-2MKkdeb18 zqNQoDbq3H>hpu9vWYe2JfRI3&6s*6#BSgE&U{dDqhOg=GwQ+EBM(oj^_$JQ-uZS1@ zCm-ngn@n8YXFM_uirv;kYUde$rwqiK;(C?m84UlKhHxb!7w}}xw|~|PJj7HU>)__IO#R6 zn$EX6Ps;DC(Feqy(v8Z6SK>SshvU$v>%_-F$X>spjN(X0vp$}`8piWI-!Q#iFBj7q z6WF6$q)iuHx1k)*4VA&tFnH6Qk4+Fme`J#Jk&}Dud?LR$Rc!_cL=yVpsajj^dH$90 zlWs8@B&xZf0P^$!e{5{*NA3$We_KJsE~k$t7C#Xw?UaBAJt6{EI*c~#d8*YBz(My^ zR7oCPJpE^wXz1(1tUnLQljPWGnrzH4{jH{3CEWD9{Nt~0RO5Ig5zz^#|e)cG+P(F@m(-kRRaP5h{7FzfNQ1Y`|(oBKh! z!ivUA$8ZM0vgA0hA31Q$x0Ta7%Rzf3U5=?09VqEUd0Ztuj|L^>eo*RQ7~H)_F);d) z%`XMz;gpOFPDof$e7}8r4#By0(F`|CIPpzv$!a}1cX)RF#zyDr$YZVTM0pNVmfE4q zYiM=Gi|5Au#T&ag#UzUh?0(QG{Wb<5jH12g^hf!Y1#f+6f>x%Bc0k;xG$89+E5&_2|3}M z{jz`E8}Bx}Ar8|$-FDceOp}RNk>k@%@BJb4M(;m^v?R7s6=4e?PD%yDl6bgl=yzHv|tC$Lx z5EsXdYKp<*?T7>UfZi7dbSEs!i!UiFrOmcWvL}+GE*$FW8qc7aNJ+<`W<3JSHHNlPCv*x`B#)(VGAwpfU++_=&OS!KlU1kL zwZC@+Uo>^D<-m(C`jSb&K26&^_CE2VC#n2MM@8DR{LPqA{VX6$b69)z9oxv{d>Vw_ z1x;kpFk5DM$U_OF2tkr1X=R}H&O9O@t-y_WU+(V1Iqx62F?LIHFHwJ9<(sLJl?nj- zA@=5)wd>Hg3MAWZyzbD9SCfIBeByw8` zelF$G_8!Ow=yk0U~5;pN&qbLE$eR=Q5wnbeSNdm4LHlq zTOGMZA2{uAI>K^qV#qMuCvJ6j^7jyk=g$9=fq>a|Or@ zqP-wpe(-r=0>9II?PY=)ar)5voW94~#~B#F<`+KREoOMKO7W3>03N_Rg2ywW$9}t} zVn?9r+5$)RS)}fpx9>4z3UhSokOS?Nqp~JuG@W%7bp)Dh%|}F`SGr^q?r@9yLql46 zdfhDQ@91|Rv_HV_^Yr%*YiVq&s*b5DxG_*F?ppr-m$UH^p? zmw`N?1Yrh|qq(qw4u9S&F~fP36rV-!_T3#WEZ{O*onAU92QlsF`rSA0a#;f2Jv1>f z;c%ZQub1_Lvy|lPx1-m!ij$vns4jFj3c}hsQW0M&D~KRJnSYQ-S+}GO8X6h`2Ze6R zb_7VijQA#zPlMmm^=HBxzU(vo@F4ADAmB{>E{~wzyhqLa2cTTo9@%39`cKybA6oCn zL_CDG9oWqCbyAWnhh-nbcbVQYHeP?3rKO64al-`CAOsggCHVqp{AmUSEv66)&znPn zwg1#bs+WbM$KUhn8_t3?%63d*BN}uF5s~ywiP@S+zEL3%x+yuq3uy<2ht4gI(89$l zQ^@ZT3(x+H&2TBtGsc}SR0TiA(kge)!VOma>nThflZWe>>QNA3xIH*?PHf89-LW66X%{lyc^#Z0MdO>&Zg z!TO%h%NR4b{fOu7K;gq*_J0Yr_JzTtu?!(`y3%_mHQe*dt!pP7jW4p{JNBZ{-?gNY zyyzBRr=oJ*dcmW98$HbEHPm*<+@95>E@hw)?F)BxwA(w($R1-h6>kuH{8j13jfLcnBTKIQ%!c zL?|jU9umki4SvL!O8%bt`7Z&arj+Jjg6;qpDSvvg<*d=OjdIKi4@_prV(oBKrcs|H zuTlKV_D^y796z;SY#3$5Z6RmG=i*;Uk)Nv2H#=0rXO|t8?e%Oeg_l=N_BJXn2orMO zz24KWuHxd9Fy{fc62$w%4)GhOT@jrL!))mF$o)2{!*LHQ zA>UL&)u#{xeU8Z8Xyca=Fj>26A|#F1vC@EjkNKjH6eZ;ga{D-qAJyj%kQt=+=~GKV zL2sRHK$5AeB2zK^^r++owrR|#Q4rUQ|A>KR+IJJ5g;NM(&eBRi@3nTM3vdUAq*IvK zsBLylQNdc2-O+x}h8CqVWcVnH6gO#PoL~EOFn)0yTD^6aBHTC;c|LrP{)PP;W!Ujj z`CsLg1!w}=wWUg41hoxBaGx)&68|l1ULy3EZO;DICVSgAIaS~oo;M?VXj6thoNw?v zOK}506`EZE6c;0^q@n81COgd5TjcJOg`h*rBpxH#P*C|wa{BL{&%I+=funB^mi5mk z#yS)2kGDy82FYYxet@|9t&bO~-cU_@g2QxkN3094gXotosIm=t)>`qPO1$V0flBXX zzptBEp}^5_`Y&af4W9VxezmTb&`bRITRy!KA4zSd|0ajRnrbH+oYt13m3`|o1x#Z* zv*D(8x3BIqtOmDH4Ii9zE%40yC6~7JN%PfP_EouWR-qHnZ0@oRD@{G1s1j+HfDw5t zM~SQXw}*~%auDy;%mFc>%eM&occ%>%WPl(cz-E$$nc=>Y(oKqG_6q&+ zOAkyP*65fh`z0UERWk2;Uwv;LuEEIsVr4-k;RGdkC#G)Hy|%&Lra|7!L`$vL+C%C4 zPYo=8GL%0iAAI;J^fWeJA6u>?DV9-?jy`|sZXPjuyY`@kz z3dlF$kXK98kfE+}uP%zj4AXyh=0{re*?fpI!JePOHo?;IEz0*oe94rNP;SYmpwr- zE7{wO(NFk0_Fi5;fP!K8X73kTQl_0~ygegz37zqh{9It~^QWA@;0I_t)U;=hgc&61 zV&WsSj~FA9gcq(2ZbZz2G@)sh>=_Fa)ndzqu5sE)*Gh&*CD0y@O_+Ry*FIF>{+qs}t~`AKK$g|x0Un+Nxc3_pN|?63Js!-V*= z!o`TPiU$rQCabAJ(x1F}qLYeBHLtu5ei0?@?P7`hWUH-b1Vvb$XnCU8ZKF>IY9$mO z#Q1|HM-cYsfP%^#)5iunDz^u%-F$Ff(J zYhH2Jd`+yd=A~!En7SBOf3B&=NT?7$Jzta4R}{%(I-yxZO>_=fWn7zQenHhpxKu1- zbrmkIPkhxEg}u!fs$LN?y{-PwDZ|1|I|W-COib|t!_G7iw&Gh$Mln!%7GO!{Ng68j z)G8J{uAsbg1w(=-9kXRb!`~b<6TwTjneD;&ar+qi%@ZJOenzuu;;G|W!Q0Z09qHel z>)#$Uais4!#0ccG(wH8Wa*`?`<{~&{6{D38qZS4sa>b*nFX#^|V&KhAxl?wzH5+(vFkP zPFyaZp@CKyj0xEdl6cA{ioK!0-l&pm`tdU@T+wmGMKTy}RKLVgs_>ezKo;h|5hPV9 zDOq>&pVNq4lU0v-B{PkVKws06}AQM*yAMSmQwb%nH?x zmL8eN47k+2=7bL?xoVL`iKhtfl&uXZ#{W)h@uHnIN&a$ZX`nKv4lx?>PT&EFylf|{ zLDI0@-Kag!cwNlipEi<~vCvL{hIpS}+yijk@Miy9iDs&-LB0tNE zzc~Y%*Kdi8TMn#M+W3?n`2v~>i^3D=Y_Ah{?>VLf4FH$1`GVX?BE|_h^y_e{r!*P5 zhMr@Fh|!0a0txcYfZC*f#YF_zW^Q`zJNiB>&6Y{WYUm2;C+&rYr#`;-xs}QOUr4`m z{S7e^?)5^z06zw`T&p1ZzOwzY14R!D#sUB0IUYUo<4jPnU@}x08%`_xu_vpiqY~2C z>I%e6I|%1Z1F7z-&RnN-h2L{tWfX_$F{~tWP|yG3h{&U+zwawwXZ`g1XLsuI#BWn` zbHoUxg<#&R^dK6maUVzizZs*f(ZhjXk75e%cGe>~Jh9%Xlj=}v~72rzw>37!GNqO38wSlhEK^#(}@kmdgd`0OsUC`QTkseS?seA{%R-sZX~aP89N_3j8>~q+P25s z3*h>J+Jge!SYowd8n+V7zXBI$8Zp8yK z_9G7K8YEyqz|bz=!#1Ci^NXeXo80Gg8)G3#dyKd;;%4J8A@i==?{V9F^55{(bgxE% zRajl#h`-Akx5N@=df=-gv=_qP_v=nXR*&oE84mUOKQ;A)6sUnUr}w zsjRjE`7eAm6dA|5!7x+nZ&HC277Tlt$Lra1dfs}Gp!2zs%Zi78@prAQyyw&Hcd5Sn$W12}^&0 z_&+T`8;2=c#n>%czr>N1O8M^MQ6MIW;3Du=tEeTgQ_Qk1L1hQTuz zjMjF#VWp|k+dxv*M7W$}a`~?Yq86HjPi`XEWPS%5da!u2W!79b9wPeRTbrjOwmRDH z*!=&5}e}?(Xg`>5^^`M!Fdg5rzQk%pxUL2E>$mjV;l8BZM! ziYXVWk6iA%hYuCr%roh%+N`*jEii|359pZo^$Z~j zsIGo)(erI4DJfxwjWH5i$SVnmwynzbKNeXg1I&XnIrCYB&i)Ie1FY=~bM<)las@ue zYc@hU4kM$Dud+bBnvpS&QaDKTONSbXq1H zx4dOOxDt7k7fyyLUA!?XVn9quS@uerHEM9Qj1r4pg;`qc8(uqmM=dtbs^H%NCcEG4 zS6KSMYtQTF*1KVZyU0~!sAnCHQ7*rl6s%cV-VukpSr3sBA*?`s+BzyPiaBDbu>#5{ zUr*r1JOS@gAZcOW^e%m&D7q{Y#3fOq?6BiW=;NnKR`tn&!ce2-fc)hf*T5RrEU%i! znn=Gxgc*MGpx!azOdR8TaTp)1PilA#=H-EGg4qQJth#%7xTy_!^V%9Clt-wQT7^Mt>ZeD-Q~ zmwfddTP1=5wvsRP&uFo^N_)$fO4XC&UsXVw5;En`K?oj0#xf>5jur34H_stIA-H!v zWKV{V+2Yb&2AtHtk(?h9r&1ubO+A{y9WKqCad-Ou?TkAw!kkNyyNHb)OIr)X2c_FK z@SyLUzkdXU18rq0M4*Pm2oiG~BT)#E%S%wO+5-ffHi1OYMr9R!>8U_lx}96zp!eH1R_lG9(rDxCfyqNABf`yME^AwU%lLaDCYP2O)yer^EU1BC!U<`1w< z#>kYa5`TGMi_Af=qqoh@Gp|jxL+NhKtE-BIV3}j%}s3)&=~HLy8o_Tl2;0 zY=>X&uk&a3y2X$R1m4m@@Pc-F72#aUcJo1#fE7t*ai z73RM26!DPJ-Z`b+M2$wxEN=+&*a99PV7XRK^Nsd3zs28m2@rWWz3=M;Yny_lKmMw) zqhk^*R)o(@tL9jU4W4<0LbNIfzHf_(LnI?Z9dLxExPyrPK{Gml-AzZ|%B)|ZPvegl zaP()j%Sse}n`7Z%@?3=GAqoY$1R6xr=!~9MYOiD+7%XvviS|5ea1K@e(#4_JYqk8A zCag(A;N)x#A1grtemM@$8lO=}J^=}QE00S?9u|iwWwu1kA)|CmM?;KQ{|a(8KhsX7 z7yDKAph9fT`}M=Kq?b2G=Wf*9a8QG#Cgq9X<8xFuwMUrLU>*4doCi&eit|oJY_5|FKhTTE7@U`XyjdFdnb~mTmwJl7AZI1 zz2bNP<`Q7#q8&Ebe~t;jjtpB2yjI4ahyY8QtF;!~{y-?37KgoC_+9bZ87PNnyAN4a zi+I?}OO#$nz9KVv-ul(VTX9e4&w#agPeaM-1r1t#txnJSbQJP6hBjFK%m* zjozPK*y+EWKB9-K;o0Sg9C77#7-JoH%s>sHtzwc}oUa^xUySGf!N2r)Pc%U82hXTT z(hh)PHK4m1u;)!KSMC(G?>#?R2L4;dXFW?Xxlckezr1=I58O>)zk4#<94TXpa0W}r zY&mpwp=&mUu5NC;C5ByE*7d{-BEi{$A!OiO zG1`EgpJfi09=}t3@WYIYJw*VX?9&H{qntTAp`nq$b|XX=V7|oM$t8pA2T~pT3#t1I zw5BT^{My-pfCrx2XTo4@)IbcbXGmmvdz%o537!2j6Z&%ri0SP|fE%Fbr28$zhSd8L zh9mV!8xpXdty7VB+#NYwVcmt|Uu19DnB$neCBX*%yFwrdzrnuVFnUHTZ>{mIceVYk z2rOypKFmE~tq!Qo3}sd?Sm4J^+zz6>kPUfLGQ++L^>3yl+13!9yL5a=blz4J5tbNP zB(O+&nY<-DZ26&zVCN9#fJ76eT@-*~i+EK2IRt*Kr#X8}MV;T|2rP|=x7lNM^QmI3 z#%zw}FN5`CjMD<97=U_Au}=f~{JiQumc1t4X19Ltg7vC+#Mf>%lNYscA9)5olfDu; zvR=0NusqAiP)uQ4^a&p?3goSgh;Xe{HOV0VHva0Lq0u-~-cAZFl z6~O8=1U8jCzVj|b$KNSu!N$a9MoJy&8-s}k&T;k$7REN58PqodSGVP5_vg!~AUVzO zfM4#AIpaWpTct(9q#*0ugFvRP#cnHK{LX~6|KYEw$w1)jmv)OjLwA3V!AU6Mlpl$w z?DEWl(XH=?&US3Mf(EaCuv^iN9{@yGzx!P)>Gn9MF4X@b!8H&xIi0y<$WkEQwd|^M=vfuL^qZ<#(~*aqwaeYs6yAlI`trJojI4r4YI*15On;FLUeK zA0s7cuqPRVNy5Fvw}^rX%^(Q%e|Na(`^r$mYrK5ll_R9YrJRcF5UojMZv^r`?XNQIoN8@PP97v8 zP9P6&jq1H3VpOJyAI$^%ybd$AS-nAx)28lb^aAlD^Gq*av1x)b-s%Q2g)nIkT9K-U zVD27!A(t)log)_}F&rxDJs>t+hv|DYOvpKkl)i*%2_#ru;?)4hI(u8jyx)d4$bwsm z-uFJEu&vsSa^85#x;(;0&iQ8^+PPMq^QTbisddTDbKk#`khN{}1!eR`^OD66u0CC_ zBbfmx%JUv#-`S`dg}6tbtY|ztqn87z?fm_{a9?{%;1EL@wuzL_%l`LDe$L|`ahAW* z$GK=*+cRLXK;LM;)Vw`jqIy+L4v^i>eg_2bTi2WrvQ`dySE1X0dljB?;q-~+Uaa_ zSp{k%|M}R0CoY}XmJbi7Epa>a znQUS-29*gA#%8>;&t!T$hKzl8ze^qnZ;g(i2gGd;Re#I9jF>a}GdAV(Q|0RYKMCr1 zMXYJIavnrvl4oHKlG73C3!_Ov3hj0>pvXo91XY927c0pcg?~qSoJ8lIA0qgp%zha!22HVtYwt7mHn9X`UK|o_^TH_~d z=P6WS^1jewVi25eA1XNjs2WB)4@E_5wl@(wj}ECkJ(>o@DnZ8J%Qa(y$a2F|#VKz2UDJFW zGFP&H^8%NYaJ3=Ft;@D1*~rQbE-7i|5VygB7)YgjBJ+D947NJ$`SzJa;-$Y$H0ipb zuktO%*cU;|xW-OIg`Vd*R6@jxfBR_OiTVm;1z~BaTDAk>LS-iMM>@msly?&kIvT7O z`c9|U{cyD3sdlk~HdJ0OAI)=`WxCo)j?7E2>(beJJI`t6KRntxDpyT^&o5vbJI|3Y7&efL=Q6Ap6W;a5m_CUxsw5VSXG9FT+tdCl?mMV&8Z^6dPrmv^ zjjI7@g!(W{nN-6Jfn^{MTaHTpK@eu&!vU}nSr7Ps!$`-BGmhvI9Y7sp<~^Rq?*9HW zv$Owgim?V=(#4F?2mhGOeG&;e5PoFcweDP^6_4{Etmwt^*yG%M-m+)&c1M}dE!<~q zKK~c!zkS6Lkw+RmT#dqVLjao*Q$a#ql}kkRl^49uqz32?t9{O0hWYMapGo46j*sIy zdWP5Etu}<56zAvCJnSU)4IX4&U8r7KO>1KxLLP%6Z5}r>5(EAq@=Fx@yvIU{Y{^^j z%m9Gpk-&VJ%+-IFXZpC0Ip?$8E4(+|_>5l=a7_rS`mPn7Ve6quTQ7_#C$dVGwz=zoy7ZdJXCY)|Os^trCG z6xcu`F0Kqp7916CQoV?JIQa7?Zs+AWsL8~cTRwW3cvad)v@H_AQUU#mO{+jsh-W+s z`%|kl>&V_-Xbs`+kkK@{I_;vbt;nhJGXF3*F5I7_yf|+TRm^jQFOB`kQkeI`3-5~p zw=`uH_N_5a|FSrO zJAsNDcFCyPv`F3i;;{R)Fu%m-%)Hi~+fKpa8*!zs_a@(@Aa_DHW`@op+D6k(lPC3X zC{XT=OZSZoBaO?29>;gN?bpr6H?73@wC9U$m3es%mkm~5n*g_SVqc$+%0&}9#bD3* zNek7&=6x=KWV_x~!Prld#qZP%foMfF6sPK%PTGsbBlsueAp&1kz?5WU%wE^R9eIiJ zBZ0kNKO|an?`!P0k1X${?bVWU-5nJ67rPUwlxC$3tSE9&lj`^f?2wy z{6MSSA*n#XAaJ}^pZRgW)$~6`Yj?u|^k5vA;3N7)E0zf@W2~%NrEPSKhU?sILd39U z{3P#03!?(-t^z&V_iLR8#(%T6hB4GdtlSWF_jGZ;d#W9HKW&QVpCDwy}X!e~i{ zyrzqX$B+G8nt9XbL9d`kLI_j$^XEI%7 z5_S=^dk-Te({4hfuugF}>9c7!0emo{KNq`l>=5g{ic6kc{sP|$Kt2WB&r_$N6>AOv zQKfn-q|EDF+)>j`CuLRhKIz)~WAPShpLPuv z8(30QCeMLul)<=^=5SalH_oK{*AVi+DAKBXuC4p&HE7gc#WD4OB8vFU3;d zA6>Z~MSlC`=3ACVaT)W1k;EUg?YO&omvbm?kxwR-582<3gtPd?N+bis?-tKko+?5X%OmixD(^Vf7k2vOlax+`w{Y_$heQ@+VziR3~ zTgUh^-nF+xanegdW5#F|{3LJ3$~v9ZzxQrxtWZpmMbh9#}nRSN6`y+5TF(m>_DH?`CHG7=6*rt z)zRtIimAkQCWq#I+~UGXnFu#^`i3bOzGyhrN0W|MV1bpAid@7kw6W_DyF?waSeE*m zi5co9q2Be|I+47{>v&N3lQ(r?ve>+nTBn8Dm}{(67@$WyDqwG$emf0g3kT1t}v@p4ahw$dz;-MYNfQ;#W+ z?x=QZYr}(21~6*k}v9m14$?%P^qh8>r_JT2>m$FLv03ix!p&&H2ytth-Q) zVTHkm%=FYx#oAVzoAEY`^v-b4zRDW1;=~NIAYS##qiYZ_=52k&r7oygTj;>m)&0+r z#zVYKiFIzfo{`$=+~wu{z5G4SAvf1QNwt&HU)&-|ifKSHo2PL0q^(#p=Co~i-Dd&J zFTbd%OB{QjR-Gn^F@~f}Pj{2ncE~$>>l=rXJr9{VcBjgL)w1`(by6`&xUEO6M9Men zpvLd7YgDgxCz5EugL`N@<4+I-M->s^ed-?en?+MiC1vMF%34=jG(znjy!WJ&m8BM} zSpSd048Xb8?K|49;kEz&DI_kdtalezRlE4W<9;JOp(Hoy7$#qtd8pmNNpsZin zC{K@6M&Ve3Z)6p={0O4qnRV*UK9Mb;h&qlbt70N-S6M^itSPg!WaUo61_F1du_l-1 zOFYyc#=^g^2E0Npl9M4a-?0yFuymA8j6w3d8=6^5NWHZPRgsS}9j#=gvZ3x(F->p~ z^4Wuc%VBC>A^Xg!xCq9a_;Nq)$plV zgAuOHZ22v!7{Bebd(}m__#G*A<&KLn^&daH=|HjC+TY{W^ChA!Lbr8J`IW>f3Ywp{24rVh;;V? zmO533mK)Ej*{9t#gSJwC3dn5uV?5YzkffE=#ndI4kjA~Hfl86ecis>V(F^xs3^=>2 zE*Zvd@N3x#hz03q8B0Vy!qTQ}%J{$3kJ?XR82rvFx1&4;9vdyoEtTPm7_F19mmI%+ z!mxS6@j5eXNaT}ozF8Z7ejE!IrkXu6%kS)Ka4OATtI^0HPE}UaO!sD>aZ&O4-TkMQ zijv%Ung4sokSH<;DW`&u6)m*kOsiR1@vwe>vGJ-zbuD|nJ!%7<1Z`*pqx&qB^#+Iia`!1Sxz2zYM3uGPQJ$EIr?bo#_ z*#G%a!jD42JD$yB%B%Wv*C?i82%yglGWhX?dJM;wx#X*$acgld?_r$8e=U_bYFY8d zd#0ehV>RSL8ts`o3ct{vOIPlEYB;raRQPte7FX2a3uuJ1sO(_wgwNdv!vWe)}x&b)HNa{2SaUSPaPjLcsBxMA!nT77JmZJ17)GHYF{ zL4DTGn5AI1jYY!yK&}`hBC8m9-~Y`TL#I25AJq_+g2FZAgR2Jg6@s1jXbHYUuh7cl z{VNbi-5M9(H$a6`@K|)D$4gslzS;4s;HI7V;~*C$u$aM%3Xm2k9C1>WRaJ*>Jf|xh zWwNNs!rggZ)L+f{h0woJDU7(5do5OQk3)B7A0gZUajBAeNxSMk%fA0E4MdgaGEJY! z>v0F3&UdsyCB1>LSwY+S`y;L(Wn+DQRoZ`!aY>`#MpNJ~bB6WSJE+AZZDuT!mi(4_ zkG4D;8o57$jIN3^-bp@QrnI&abvuQ*Q%XEuvZ_mZhqvN^F|`ZSDs4-%Km5m&l#CD= zeNK4D;A`heN}h*v4*qw&0~%}E^mJ}O&MIl4%1pY9rTYrMXsr!-hnO!aC#{AX18=;5 z`iV-ALTlDchs-CK#E*XEkmx{MbfhZuMusE|Rm=Z;;@^S0;##ZCpYwBEG2DFv_lwzI zQ2-YQAb4W`uZAEEv^p{(Td|C3t?TGh#wI@{&cE)zH&gYt*iUSJq-#E6v0w~?`n&yw z2{wcgqoK2%=dvJ(2JVS6pSIqhvVM`eZIFyzgB&r4E}QY&{N{SomP}cE{={m+3spm( z7&eLoZvR=ncXb%I5`S1!`{td|jmd40YDoM+tWT8X%G#XgKIQ>=+#ZB&?8Ui_$MMlV z#>`>+W(CZ}$%uXkV2OpqHV<}PB*_z3Yco<)arME3MqpGr{w2Qhe=cLc@GqE5f5CSo zAuF|DmhvnTrbHSsv#w8X%6|)Jm_7bZ@((8XIX!NqM_lNC#p-AST}fG~k++Kyz=EuD zWN075$akwgq>Fth!{CSToE!2)wr^A9)Ja>GRPS2@Bln#I^J}vEMG?&;y|+ z(kL%trdeE^5Tve!HrOv1mG?T&i2^P4#qBBM$z{8vRmdBLb6j)PH91dD0nwWiI8#RK zZK(3jn>3VY|JwhI3#E{uzugwCi1N8Q;hFYh@=z=H|SJ$m&>bVkwq)_<;`{h z?$sV5*3K`l>Zga++&KSGmRG-*)dhzs#r52Bb|8eyCUw2Dw3Ja3g*9D}tr5Xbb{jrk z>tdc9AFbG;;`IW?>wMRMTT;&X?WVQxP_ETQ;rE7VKrof`X-W3~yZ~DE)f|6yoKdE& zFG0H8zugPISkFw4U3diqOtc zap%ru%^xc#zwi32=tmy8*Jv5yEVgq`{>?-K7+rO&Cq0f`R6sp4^P`shFSxJ2jph}& zK3kaR)D!o&v*fbobk_Od;o%sOm(r8eOnO!$#bsR zsGcPz6p%$K-GT9y%bW6k3&}ZWdJ!X(NvIHRjO6ni2+k?L=(4}~@?fuX+PK&>LDcr< zytO$QT~1feWT})zDH&bmhK5b;MiUv@iTs@MBrs5M*1fBFA_WLRRsw~ZS>bM)Oi1-^XM#bs1=8cDP*=>DjCL&FB6 zsoX2Z$T>ywW|p$~hld9-|GVHXS~l)X+p^p5W6;Zs8osbzeg$uDk^K0h)CvQccTN!@ zu*Ley9;zKhUGo*t@|dMd&v~(2oaRKzkn2DUOikSW-Qo&@Nm+e|VI7f}t*23seY-axY?W!7xXm$4aj!d4c`q#FHAOG#qh2?-oT)b!4d1Mr^Q2oB zGnm{s%?d?g)=(Llagu|Cl{P+(AP}#XCQg{}r z{E(Ga(K~X;7>c`RO{t$ zs!I&V!!vMR?e%@iS(Py)c36E6%rx-C1XkVbD@NaXO$sa~6EW!hBr=9P!91R<`R6?C zFW>1gNOpHM6*oU?CBHk)1D*{kgt2Wuz(`kp=If$xkOjZJz1xrF0vK?>xmZU$-w9w6 zpnrXU{(eT0Yeo9?YiZVD0c@@l zq8O6#Ee_*YksHKcS;_1VyAkAfoObIv9126XyRfUznq`ZTL9aYQAoVUJcXC#C{~;hb z$sZ=V6_9~VR~OL3V=WRUPU|H^ zE9TxRF)6XK=d-apXJ8ULFzI9bL36>0V!K~_ucm7(jp*}o=vgl1dc{y?PKV`FjH0VWOBX+j9c+0DC+H%f`)W^oItFDwir#t+%5sGJ94CU%VaKD0x;YAb{x zN~ONea~NNRc95gHINlK8M0hK+SMxUXlIgd3RcUZ5%=y3H=pgJkkAT}+atB`-{s4QE zDQ9Sg@wL=X-wmxz;9~m3J|*(MLuc)S4^8Lr>qC9+@4U{RsCMJ#$-~Ne2HT*{ulr~f zBPQfzEY`gZE4eL=>{oN`P5Pb%@-$NlDpY3>8!l@ws__mx*H1tq4QU69smvT1QS{U? zVjE;(OMp4k`y~eMt}QE=5YswzJSU%@`Q_G= zsq&@n91leSBxCCrAXrrgw$F3-e>m^l+}ympKGiOectSWAIS~lxj-<9vEo4sa1kv+} zt6)C4{9wVKRNh#+x?REdhd&95`95YTFGg+3{`wevLsHLpq@d$7)}pY{{&<%OaS-r| z$o;!+{Gh)2Z{hN}&t<{*gUIs^Dw({C)r6S5tHzfJe$6kH=q%SVY7H2-aT32<5vg4_ z%v4akb*k#9Mh+q_A6{M4hzltlOvq+fev>D!n{eDv{vJSBp!;2s$_76i%V0fGm=`g- z7$**|IJ#>WrfrAhDB5M)(P`7ea*g1p879WJF)2lW-q(Jv$guYKCnntNL6jj*H-hcEcdn`d|j1E zp2?8PC8t-#E9I~X9c~gOTr6RAlm#13i9Q>7-Ot-#OxYI zlfpFQY~#i8or@vHDyq+GF8PnE5774HO1ybDT4A0~48?**_Q$PEj$qfoTP6V6hlwT> zwuox2%ac8$rIf=`nsTAFOiILfxerW)D)MVGGT_SPY8SIJI)u`IosRUi{A!0#?q+P4 zRh5YJE3$!-RT_PfI6W;E?j!>U6;0GK>MtQLih69i!$j?z*jRg$$0Nn{h9e8tS^s`T z-DvYkvRNxF`q5&sxtm8N?^b^a6H_vZi!0B#Q%WGmYd`y?Z*Mf#S-7Y72jh{^otiEQ zz=niCq0&N%c$Bb&$YC{I-K924PA<-BAOg~1E&O-CRx4)D=?{D_1BYx?3Yl~1iuz$$ zI7&bvCNZzTrHj+>FRjH46;h%XO-@C*qd;1_LNyzCOCS8Fr>d_0F6Qcu8K{h z15dDD5NYw{TxVJB0_BK;2y&eE*E__*Z-Xih$RbjktrnN#=v(y13xZfUWc94Ux*NrL zr3)#PJGO6a-cC!`AT@#Pz92d8d&|5qd?R}xI{MY@Ac@xS)pr`-gTqxU$>UAXmK1JT zKNF2Ww*kWm+@J#BQ;nbx8fDTcQ$d)a_C-m#G=p{Ml~mN zyO^B91Me2Tw$r1in?CssH1M%e4|r`%(eUV8xs+97zGwQ1Cw^oZ)u^C;q8XPNg zrdN;maQ@kx?E0>tAbd-#Pojr?#@u26o-^h`KsEQZ95Al~2N{ssk@)vLc+~=Ve!D#g zCQkAEia{Ys+hSb|-{4~SJ}JMmyKC?8-2OJx-G!R1Ok0Z%B6JS@&SG-iwAl4!BLk3z zmcQa&xc49{U#$E6DuJucXO+lXLsmKwNbmdTY{JD6qdyq20$J+hrKnZp@J_z_>p=8D z5j4F%FZ!+lmO7(|<}QOKr9qZ*SQD&w_>!BJ0;Ts|f-E{cHuOun%_OYtYrwB;JzHkW z49XM^HR#xZ>v3ZbneL-gCS4X^=UcjXs<>}K?@l*xiGo#8LyVb^3@C%?ZAd8G!tXd3fit zI@#diSi2I*rw@zk7cF%ULyx1+XZ1e#1&-JB@&s*vP^r=#BQW?Ef&`JG(tZ<*=->}4 z;&(p_mmD&OFa>j4UL5%Ur57z#kt#gdTlEyc%srs0vJ`nWPSE#l-0ak#Y7Ra)2b1t6 zam~MYRN9$*v+Bcit()AN8Zg z!A-{ZEj(#qsYSCFU9U)n9fW~i>9D4U17PI-qv2FX$-PE%=4iuGHOj`@-)7bZE<1%jVXA<~l-lScD8**ME8JD-3wkN> zb~S>-lv;3BrruuP_3}wdONv-#3+;Z;TJF=!oqzU5mJQFXA9#%ndFx~E%KKk-no@== zah&Ko)8rTxme!XZLg3Hd2Vh~+5M|47FCQpuU)n~i7 zOGM@uKWUyCJm@DYo22vBys_L#%jQOr_nH}SADjE(*Q>=x>I96{9JD2$&d`arOm#21UZFwX1|j)e9@!`RK_uU2z=!w=F(n) z*;l`u6o0O_Ztqse4ei*vew131f-rSfeu#ND@tRTt-o+*F6Y>Rtl9a!W~P}O{lSoITAfFfhEpdB)_!1*in?mAweU;LL}c> zr9-wFsa!7lbRBOahExZK&ttB_KcEW?F;I@!(tDwj>*?-3{IgHNZ6^A=L`sxpAx%Zw zJ3{+SohphD|5#d>Pt26g06HUR(T`ig+XXkgra9>yD5Do1?K=ON?-m~~tK)hqj}=Om zx6Jyeh;ly2pFaXj>;I%Z7O)`2=NuhpEYqQrR_lDv{63ml_+3Aj#;}6Z@ZmZdX@KS` zZV?nD>BD+R{}EVxiXI$%iD%?$0DkUU*Bq9*NB3zD?xPFT`{-B)-8qXA((gCs{el`g zP`VLW+`-%FB#7(~r9pHD>?0p&v$5Hy$5{cTGq8ne19m2&^E z1ITe`hf15$$pWw+{ZzR8sj$_su~}gmg-al|VibX--r>qc%ZO>0uX29RTwX)MKTa^jS8 zS^U$Erg=R0BjkJU_ab)^Ynnr+9dH2)Yytyi6L$r&(N+_@Gg38%%T* z7!))I7{g{N9IK~e`ksUpa?9dy`x?u5TW9E_cg8O7c+657HT~mH(Me)a5ppZ`M(`ze zUHYW?X26&z{~Bcsn#h#o>Gi#xHB6d6{eeMSD?j|k>@aTq>Ueo+H;QmhjW+EsQO@z> zVcjPgbKyz&M)X!tx**On)G2UZ|NTpN#iyOTWl#GL^kAT3#9x9`wi+(? zzDxpD7SIo5-d@CLgY#KD)^9HNX8I?SJ$!b82gal75@9Vz^c&w}MN)BEG>JBD-{ za5xSYicR_bF4;HZ8P_UFKbqZ0<^D?93&phKr-I|bvp?V>wjf)lY@SdlNzA0oedz^z z==EyH^Vn)H8rV{(Z+Pp~X0+gpbx8#|*7+2j@sAl_y?4-D-EJoZxYN!ieHKO+P}9JB z`4e^Qb#uq@!v4n`Wn<_X^Sr@~%%R*Rk|tJfhc|OepEzqbYPGQBp<6v}Z_k z{P*t|T9dxxyOS*ZLh(|LAD8xyf;jSE*`^j+ZLU~|4SRWwCf@sT4Oq}0`zSW*xvB0$G%JYpIl#6H+1uWhIQPvb#{9`q$%nJhB}Fzt zZHgfl;7#*Y0N<#~Y|{zqG4#E-3JXY+%^$7g1U-No4|$9t_!=%7EO{F5Pf8QBK=RK1 z-CFc?9FVWd#LFie@}-m=fnzhowPvq3KHF5;ii?*NqqUV9&Z$_L!EU z^Bk$rw*_}NP|ih@N9(*RZ|33dRr+;dUPVZ<5yrj^sHqm@lt`EulcyOkJ-;Ef#DlD6 zNyDiu(C+&7fQl{64G`gY5=u*f{F_zKOK=N|-N)+9KVmwbOp`V8)0k()TIQ$_jtI`> ze;@7bHaJ6Udr-jnqP%eoSUTIH)pS9=tWPZ1c*pK}`YdOtjJi2$c6kX>-a(R@z&4a0 z#imq-jc|gqNX`CT&Ou<|cvIegDa=+-DiLgMHUU~rR%}aitvq z2q-IddSH(;_VpVyXRPjqa@azNZLh)si;j{YA#Q+(x0)ZR*b1+@Je9z{;yQYSQE8q^ zaTFV8bPfi;f!UlA9i8^#st??cXkpSx zK`tt{x8I!L4+b$jV@h~*5zP9Yv#9_|+sVkJ-*@zA6m_+O-ruA*#b%kj!%o{OmdDo~ z-`@IiXhTrXHeuhax^^3OBT)XY;VJ4}q2hg27N2XGejI`V*%g_x9ih7cUdT{h0UN#v zI|UP((}6U5G~M#LWqf%vyTEy*D!AE>QiOd`FF*Cw?wnzq*NF^VWCa0)VzD#)pads! z$tEw|hwx+uY(w&%x6$N|XHgO_yf_DJjI2s-av?mTb2%$0H8pNufuS`ON`wcicyTeM3-uh|cS`QtHGh43fIm_5@CiE9nkYs3O9R8MH)!m^wvNm3w3MZ;!$3^eT1d!X zmkQW6ihYL%)4p8Ayue=mkycELKmWausN`TT9?&cOfdA##CnPjB8s^@P&x$ z@M21dt#E#E-MF_aR`L>~&!VJaKcnSVmn1$`nEdyY_uc?$yPNk9?dHMtVV<+;KpBkQ zI%mmqEs=RR9ohT%q zJNcDBspT+*&eXxlC;VrmUvo?CZ)+QX@{EnzY_(b%x>9@}f_cVlQJ;pxM`e{v!g&;k zazX+WI+YlnO)V@xj-(~g0e#m~m)&FZ=Odv;9^{|zEDR#ao&S^L*bkrpI~YA*WzxD# z!S4b{@K;7hhu(E)QM@F;Da!;foOriIYg#^c zb*8c1R$vT3Czn-Gch^LtSh42R)xP(4W2sbc@-_bK?d%j3L-z^lCFQ2y;nO_BmW`oH zY|p5zWv^?;>{Vd>yj*>FkKH*FQ3)svH#hG*jq$bUC&~g>_b1>#NGe?a08SjGd@`%?4 z(yOm1n75Oy4VU*#HS?lABV=w=6c`)Zo}(9j-zetTWs{!J~o z`XrPm^3-7p82%#Bf$+>b4ntF8 z=RdPLcfPfY21WqPp{LMjpQ*gsbw9IxpF5SV_c-L{(W|O z$_jx%sAy?g1`H}5jvB#WFtApBllbW(0622M(tE7Tv2;7z?OxTRy-}DNj0LeAF>Inc za{a02VT_jHehGF3y=dLX+CHSkxVE3bEw200=XK?0Mh@WJzRQRT$0j}7j~8i8s$ROg z?-o(&=*qe&rlx&d=lLUNFi0;1(ad0NY#(7&D|A+pq2m%)KIWsj3>%zS+fleV0&>4l zQ7xki|FnMUWSIxDa%Y|+09NNe_=jsCk(3rtOb3(- zBNx!Xobhh0Iy#dJbsB2fyAZ8*rWZJGS-amlSX#6T(3T07$rHzuL zs_1PpI(NeOZf0g@A<2P~nhG)RO9Z;bC!ot=;OT6jrE_5SWSizo)Zc;k{cDq=$ap2a zQE6Bjz=}?|#7e-}r6~wS!7?TkPaWBoqm`B3SVrA>A7)`1$HPG~{dVg%!2W-iUapT= zUidTeeuY_{DDqJ_^UeXQ$P6F7n6bE%5yk}crdp;u(@qPZXqRj+`4{AVFUg7G#EHpi zjhw$*`vmQOR(H?6IX2G+EEm10Q=Wbg?~nNqlV2l%PVA75e-JV7rqWQ644*!nU6Ifh zgct$YHl&O|EPfS|eIZFUUf?JQ=-aPtENC6*1olc2s31rC`vckm1>y`pI3CM18+TKc z|5To_iHTd_*94wOphB28CKM@FHO9=}iBs;JaMz8#?o0%LZZ4LNdyqIl?!ag7Ik_6E z&Xi9q*<*yB0$}?ZbJ0kS^{OkS(xCsx(_64b)wb{3AdQrChk(q`AX386EgecrNQiWI zgEUgo-6>MiCEcJjLo*;TzyL$@U-$Fd-uDwAY_7Gg>pYKR-$#J{PL)=5f#8nunDoOe ze_T)(UjtdNRvFQnj}`*xFOU8lXXlB8VX8RMT5FO5B{{_X4Wf7-)@ND0(_z;&*ynmw zMIS_*TiXCcvVA)L3w@Q^YABaT8v=;{KoI@4X+_jvg`&ftMi2O32l#2VP0e#>{kQ?L zfpSwK8ip35-O4sNkPeOi0YZg)m$Ki9_S>Mmg~il!eqJ!% zz&2J-d6?`SS3teW>AD~%-oj?tBYmJCCdnYZ{>l{n&)Q*{9M_6MSKTy9?T_}wo}$4M zlOkWz?NEu7?q}a7TqS*11*gsm{?=i%wzj6U@VdWteg;N;XNC!lmUzRn?N32wWPukM z840QpX@#Et73zjv9=-?2czh9okFdbKrPpV8Z%l%SQz)ZvSIeF0#Q}Jw-{s%;Kp|ao zfed*riKtfEhE4E?c8wGo7Qp16R`4~tyb$9)y-3~-mi!% zkOZyw_xBTR{ldo^^v%*>^#Q5?TRc3!T3gNPKb)R!%2cw;W~7KHGV_mcQvF)!`kn%ZJmeoEhEbh z-p>V=BKO-Ycdow7a~L)BwyN2rJcDyi0+c2EtT?eISNbBdS0}d32WkX6gRq3RoiT$j z-`DHg7B@b4K|m|!U752X-{1SLn~q}0EKTYy?TkNNuyJ?XxU^wbN*{X zjI!(2k|B4+Ax=)HWA{xOP)&+oavKCZYUBWi$27;H zhIAVvFV+qi$Lzra5i~jr!?(AIY^@E#Y%?yJQmS%VOd_E>Zoe2{yv5=VLn@7NAwLBu zwaxrcNm6IA7B|ASvWx5ton;jd$q*uA&~AV%u(JdB6(F16yZw|GY7UM*mvsao(+efF zR*tTe)4K2a#fQj2`$&oV;Pr6G=Rz6XEHl+ccDnrOU{x-0NIHo6f&8bD#km<_ z${t){3cr(Wxqas?>bo2rO~$$_Pk;9TpN37~Hm}+sg{u20ePU0?J(ZN?j73%SRI(PZ z(>%8vt5cR(CZG41_^Uo~__0GGm}lpZHk_}nV@LIziK%V2fOy@oveK&a^H&pbTZs1h zZ?sXn|0Ha>VBGcEfZen`uY`KfS#G&*&XVD<`DiUFeGDt-4KR&R7m(96XPlvM;x?vw^O4}iV+!!EU$dYp*9ma zQfe1GVBQP3rVNTYJ3E6DIS}57?U7Q$R3#wCpT3rVRXYvI6_d#mrf5EHa#>& zAg9`mCuvyIb)Cw0?@lOE3-Lg#(RCN{Zx%%*&Q^)8tk~U3b$l#!0y+@D!iIo=Fnx+5 z!&P4H#M+c5{2!Szdy@RZCYNd(amxvUOU;m-+28RX4>HT+MsKMHH8n< z`bW<8->ikz>iJ#-M)5G3&9?s0#Nx`zb9n(&$*mvTnI854b5#v`?Cb0Mu1p)SA}d!| zW=A2uNy4h(7KHJ9c~l%Nt^6eom#gb5GBo`_i~7G;0@Rm&_3efe9}No0_6@NpL+3Zy zn`pOY5Uxq5j~seX0uZ%xYc2CWmv9(56CQ-S_AH1htTcX^w`*%Ayfdm>u&p+*?XaVA z>_E>A^PPab2GGC5fFf_B#5ErHqGe35kN%__m%0^aq9EvhEum+*ZKq?2z>c^M?1XM~ zTF~FY#6Ic&Y-v%@*9(13564K-+n6a*!1)t(&+BtFS^9c9_uz}@SLHT4xZ;>D84tKa zQGjbS@a)b^r!UCllc-F9USx+N3N4HiD%w#m?6_1tpX55CDfVeFD$; zIIqJjzGD8o_9RG@H^|>-ro>{b65M#Mrq1nkw@3O3uav!BG8Ai_ziRVw27p~kS0uLb zewXV=ctd?AGk*(h`d{HWj|+rSk(m#dJ1_r*veP>BF+FP!)~NWyWiXv&U#xq7(qRwR zbiKE`^-|K2v=aE3M~D3NnOFhpKEHkuIld+QBvMlQ87KS{5?mF^;@cu-{hj}cyU~Qv z*+yFhORoe}}PwjmKLtiCEg zqVI1$$g_TVXRE58hE@mt&t4QC4~qDwYL5b$_!vMFkMTU_O`ZOg452P+(hY) zBE=k?#3(gwzCv3E@uvExP?d&0I*HYpp#jT+&a_w~ZtA4_;nQZ-=gfrHhF+uBEiUSG z=Lz;S${r5{A*VGzdA;8Voa{?d7C);!MLpyk!WyE5whwWJsn~s*9%T(GL9*lJ)9~3> zs=(eHA16l0c!ygc#bOa*aR+nuuHQKv+r6eK%TLH~g6uK8{MH{EdeS=wy;WB}blv{* zHR-xXwZQ!ysV6yGcN&vMwx|Js@JWtcHxZ?_*8@BOy)Gg+-)M-u8<4#u zJi2@*ohgXyZZyd^Xy)WGa$AOSn)#joF)M3RZ6YfxohAWAck+lV5dM`7J@4!`;!f_% znX>Or2=_SR`ksWmtL@ZQ1tyZ=4acmXMl@>I1%n>AxJL4$KklHxS$2p1-A4TV%L;w_ zN_V1q6*f`z((B9HMof!*UIL;_BBX1;lk<9^1Gv=i|$Ce_cAk_MkgneJYJVc%oEO<89fS^) zIb_T$zx(U47Pm$B+6=i3cSQ9e#0@+7)VR8SF7Srzh`PZWc_02+C zV$wqo{r;;wkRTE*=xBjj+Z<(!%oVIOTR=vMRK0W$=dolK`jI<_+wv{lRV*F{7 zp~5P<9;XF(25Ezw0N5o`)AwA_8? zKmNu4NV`Mt5syA`w!8PT1r&7CfL(B|%whD(4gZ#$g;^ctKKsMBqWPM0)b-gxX#?(i z$KWyv|0=^3ZpJI?CqYn;f$eCe^kK+EDU;8VC{6YL&!gUG>Y6B~BXEOO8$c%XVZX9# z&zTmd*dH{LuHQ{l*9j98FW8@=o56=}6>~#wSBTv) zcK&TV(-ha|*k1Ro8j|l^Q)B4L3+*FRm)3WzQ|;6-6>0gtnHcvz1%>@Eg7u4EClsCf5NojV*AO68P_A&B zIPG#tdnq25H$V$-zwYyZ8brF17rjwy6);6HUb)P52p-(CW;@Z&lN0~#SA5;Y?!5j! zTuXd|TeappjZ&vZ{D@^Ek@H&V{5ZtJbt{;5;nZ+Xsrk&^cW^# zn~YeB9NANy_x2ieoZ|@i>^|qHgR&~EXN)BUy&w%Qu>F!Rp#_q^4yKF{R~EZ-^0NE% zRArw5mMCj=h6&23b$D$t4ny-KvhQaeJ`9^()BiE^Ye6(6?N+9p<8v zPWovNnM^WUC;c>VO)86kI~x5uQZ80NSGS-lQ!Gc}DAF}4Z>fc*x&c%YYPSArnVj4Y zWibIJTuSow@Y`D#u-^NrKmDHY-Jn* zF0Gy6ssf7geXIO9kmNR>Y^yj-Wcz{0lzD%xmS+AC)7g^Gi%q21*g~_7>_> zZm|RDR$Fwu+<5U5DM}5undfNpNSf?&&HZ^q*Spg?i&f;?KX|wNznr;=;BN2RNNrKj z=dP9>4Cz95#^I&jp*!b~dTx_b(1b4aXCb&qx@Q_u8YIEP5I5lhgVC}ON(-hqxG)A(fw+XGh>ME$QSc(H#Y}Iv`tle;w#_eLCfXG;>laUhbGv zq5Zxw+VLMH6Sw1{pn!eg=sUC2(oVz3ns{|opds*5*D&5yjMT_ss+}~WG;DhZW$%}% zbKUNQXpG}-8&H!YA3IjgouPRZKXS(n2KZT(l}Q~=n^0hSdEkG+8I5pX5#4j8PQW#j znRS%7X0X zweEiVbCDXY+v9>Bi9IF@>Ndjzsw<|a0K7tiDMQmRUaZMMMh^;yBdHyI)%!1f;s`fmc)T-W6^&uSqHRD_U#bG?%M4$j zd^b6i+p=l>kPF7`pE-L0bQd$;IZc){vdkNdRvtxhJ!He4tQ!FE1;dR`;XVF8O_YU6jY^co%=)SJpzZ!;xazpWnm^|!c5ZZ^GO0gKZ5eJwi(2!ShFYq(Pq@FD{N}w85_Li_%`CiFRo$Zp)Lrc0=mW-G8 zWPFi!?;nt`>KlNKyXOKurIH~uw5EgpI?eHl&dbf+nx>^=C=;6`WPlWNR;5IjfN-tm z>M0=|oo^(*Axw+Q_C-OREQDud#?;9aBG4B+xQ1Fezs( zd)R^Nc**wV&u1L~3}Bnnzh&b-R$j>~Po!QWVBl@UOG-tO&6S<~6`R;##XJY_R1o`g z7}X@Ll0`WS@DhuCiM-&e#%m=Rcar#xWXwPG65F0B@~p2Zs^#*UP!bsgg*LOcU6g-T zFou_B;YT7WP>Mr4iD3NlH4|3ajoeEPLVk}o{BjVRnx$h8K+=?H6^m4*%(8-*T6Wkx zQM*475?iFGWATR!SMW1{7;pvXQLjgTnhPfTxdPm2FpEQ8A2qCuMmt+bPB-fPzZeQ0eQqI2Z5KF{3fM|a zSdDycQpV-DK5A(R*II-xiQpYCh>~<*J^RAFFDK{UYVdRI3-C}T1YFB>P+!i2a20iR zqfp9S;Eb(%7Z)kp+ZM~spMc5e(NY78&04!>!ieQ;)vInE`(QstX(JuMZN&x2$% zNdY$Jt7M$Kz()}v&%!FFc?v*1&tpvQU*asZ26cYmyxw>q)QB#|gKftgF1(*s%2znqH5Q*J3i8s6mGdJbU99NDDsPKi7#!_8EmJ#?1?_tC*n@sFJ$L zX^SdBpu%?@rtiOb@9z63nCHDlH6p>_bNX9woa6iY+p9NMuc6HEBU~LlXWwyjI08a- zvN**3#sd;4GJfF5FE#oM(h1eH_gELEZ!P1C_z7A%Y8LZ-6x;3j0;yO!^7vp!^`7Jr zxLhFtg3wjRyK|A@r@^iOk`L^8o&xS#r1wWd5+%@MubY3YLJLA2{!fshva-eI5?Zg? zOE@!9LR56?d-pvnqw+4$#l-s8hRFiI0@$g5=8|c$mGp7xQuQjnS{sXZ&o0$eVwFM} zT#c+w<4CI_Lr%hIISHrUGvwyJ6jrSIhwqLV^A3kCB0Sg)e*0h9m-hKRtFo@^m~w-`;P* zB!)=0-h9Ok%3$YJ-gc0Cele6%_H7KtChFg)N1MoQAuKGqizRXYqTP7xbG!MPgFdHd zXOsuC++|8%bIrb0?~2Z~P$8Rdq^Fixb0vGNL#_AK{g|7Yq>Eo}b~cMhm4-2On4e>X z&WGl_G1qi7anS%VZ{!R3!|4z(QW_Z;c;3h@0)cGrpQ0b*m7*ByH@D-vca{i5SEe*n zrIzAj1a-nGF4@PD&SVitpgj#R&jZOa>_k8Dnf_R-)~}uCB!4}rMsNoG57UOlaL+qz zELttD^lEtOExPbr5s01t&xxT%%<@z}F zv@OBMp^%-uT0|Kq8=)Ehp+m#cU|~$<{#En;hELxnIGmIVa&Wnyq^RNwESVzHiH2&; zcc!2HeQ$$AqvQ_w$IAI?k8uR?M>bp+tXb+*n8N zZN#>1Rz#_NeH`x)@kBMPCMk81q<17T=Orzdn#r1;LE|jW_{7~zu#pQ**)_#mZrKp} z3>QcwpgbkYe-G{;w|bKqrVMvr+bEj>akVPd#4#nBLEXM@%iV++^gF<849Plzar5)- zF?_!ch!hg1QK%31%38bx9n{YkHIdq8s*xE`d=Y%>(GDA_;_z8lBpYG+F@wYHO*UyZ ztcFL&Ikx%_dR$jP@!2%$h=$v zT}}q0FLGaUHhV}iEOAF0AAD;zOh8N5$;^&1jrvO}|1yK0!qxaqO_&kc^4FFe{3SWV z$e;A~XvU1#d&86|fFEHbD*ylI0&H~hmrh$ITj)`Ki994M z9HC(%kat1z*ZxBcu7u<9u)(P<#7prB*JyUR4~Br3a%`6)(~88VOQzsV%`EnlXc7n? zCkr79C!_1bq!FX+_u?y}RQYN-*R0c2jG2+Z7CTgwYu?6V35n-{rQR5=Lc2F1ppH;L zF9MV>w9FP|+SlrRyhl7*wmF8X-o3uGZx)I12{5I~ZZFs+D9#}A8Bovq-3>jzJX4B;O%3&bh@giVhz!xG;NmVLduni@R`e8|~)QW+dVUcYxwY@=f;WL4G>H?1N7y2^w?<1pJUmU2>(#$5aXqWdn zH5nkzZ!?ca8yZ**tDJly*x9Ltw#MpmU(>zM&U-gNqN()LkSzMp;C+LUNrQ>KX6459 zb@rK81dg3?3hR7q6jOq-?I70kaWC08YfBadEA&^c8G$y6${)r3AtXrl(XEFh%_S$l zj~b&N4^_Gz|B1+dx2XY*KC|YUY$3%cA4spKCeg;;v0c*o#sRB0&{Sii&B-&14&gr^ zI|%#CXDv$Y?Bx~anOjI{R#VKrKX0@{bkM&4=q+0`w4Fn?Hsc|(6VBk9VwbM2qNWCm zWy7ucT={I#mB-QYpEp%|ZjgXDGs%aD*2S(G z3@k$PKQb3YjkTXzszS?(3u+BxD|iivj7!XI+Fy~2e&F%^)2<4_t1qdg0S3g$BPoUD z(g8W#_Z}eLUAylnL#OY-17~M^%1XcXB<}kqP7liRfWxA=nwlE$6e%gW)@lcB84dXw z*m+<6BU1)jHRzwC$6-iTR^qyXocu0iX+oa2I#E;ktSCEFHrv!$&s9VJjn zU8oEBNy(cWMb=z-U_n0)a|NcNFE%E~x@h<5t~3jJygN=hTxy!c0v~}WEO5+X1#Zl} zW5~p2`~QC0f09!m;JW#MTvxXk3y<18k06w|Pn@s<&X*O^2pg7-0pK*-dIb%*v)@D5 zrb!&MhZeU6sjpJ-Leo`j+ zaeMoxUkhnn;ZTw7nK0|A+!8-OVAb-my=|{9;EDtq`1J5Qf#lZ~>*^X>WTciN^HqKA zVT!g#%L@Kg+EF0s!Mn<8Q<)pq^_Bjn*t-cKd|>cxv(YdG0s0LPY489bmQ5aE@orIj zmHb;`ZW*qGw6Guh+$0U2NM<9{MlBbg^IPa*;|htK;R|+?C-zR$@ID*P59CJ9{dqi; zgm?7W;EPV5eAMXb@RKW`)z#I|-!v=*0cSZF5XU(ZeDhaPtn#kls!IVG>Awi8`979) z=3hwIR+Zn$b2+b}KzSawFhhc!d*ACsa$^aFUqg_*6YxNlgo~L5q~Q9$+k)R;$>;Mq zIUH*9&Vg_Mv;AR)ngT7|l+8*Sa3=&{K!JBHfn%2Z0DTOPz8pjHeJ`&_?5JXdFzVYF zX|{*5N@c4Cob5Bp8lY`C%XrHwu4=lg{ZD_geLKx*FW_AiFAZNOz!_h!z}Q0x#v z4M+3{YTLj0m!ct{lEstHnLd#?(cK{?vcYk7H6>1tnxyG{EaDu^z$0i+^Dp!Rc?{K% z!Vu}eSKx`EdsVp^y}gYV@Nj6Vl}5j={JGgdmH#$DhGyc9p=0W; zdhW%=!I{@PUEM!fTmo8*HBIL&E3@omYok*d%MHq(KKk%(%#>8y81fC~=H#4>jfCy` zq-sqViTMtGHw}oI%Lh{)+VVdtNf`0&DE=c5U!-s}|6kLQX6a@5L6O^LC{YqPQG{8Q zKE`*__e8u+f>bbo8jZ#AIcKXPNk%mdO0kTbb)GxI&@iQ@uc1hio(lNtRI?E|=6r2V zh$WE{GS=(#1%>_YmKn>QH(-~Dv|Ua9e6-S@ha-HKdzWMI!L>wuvWXM$8uFriz-89; zXj-aISFd;AAlEcjbeA>W=#)RitO2%4=>z89QhIg1>Cx1mo@68#{n#gE4oQ@58(hMK zk!{a>4Gj&|`Nd5BhiH(Z2JtNS_xj)^NAyR!@hcUYN@7B(A+L#P86k?3LTe3u@?PyZ z^Bhpe%q&;m`+<>>s8bDwe*NE-8SmLKMobMB+|%SyfMW(U25ChfFCvC^&>0;PqHf(< zS?N~Ftl{V6l-Q-MeCd)$FqHztGu<+SrU7<{SXALOF-&H#s86_v^{)MR%unL?8>-3f zdtbV^R=cNpu8`~kPA3!hyId#8d3Bn zp3i^KPFLNxuM)MX2M5sYQx-`SZoWdg#X_k+nK=cJYK1Glz|%CqZDgPBD&bVgOl)JM zt{_g_C_#~%YhE=n#WKjRIMmp%X|yoVBLzki3D)#niBqZ&(^fWHi1kf+5$TrS`*CKU zkAq($Ws^Hlg85V>Au#?uZu8Pw*5dZp!|rzo^5K62hax9%rn)KA^#abs>-S&#G?kT3 zR?oslyog`EE_J>*@^Dq=dVybuCh~iFW+Z%4DRpzgD!De{qwP2yThAM*New1kw&8%T z7|Kzk9yCSEc({W&aqg|UZrZz2?ZK+QT+^(R2uptNn%F;a>N~N*6zyyArS@RQv|>tF z`&FkcT@BO%g=W@;;WK!8M0$-15qjs2Oe8O))kql(MUeIuHT>b_#uXrzBD%>SB|A?k zl~fhAz{;Q~_iDQmS3)$yX@>%i|8jJov3heLe0Kx_*RAh@7Maw8;(0n8a<69cHs5px z+{N=;btQJj89|-AA*K3D*6=fO zHr0Vgqu)=_wI@Cqsk6eGJ=2D>QnWIdhQnx!RrG{t=CkMq^okU6g!mOnC3SVZdb}d} zMWYPr^OE+M_Ej&6__wYFxE1K61Qvw^I~AiM3T#Piq^yz$=3PDeXs4{XT%rd! zXvXv!%Njz4^HsWAU|^~65Ho>U#IihxWnCJd_v|`xuS^Oo9VWBaNqc3o%KT#ZWCtx= z@O*s6Ms`jR%+snBy`4-FMWBPxaKZ#^YHN0&jWy}9vcD9%zCyC$ekGb4&a5%%ChSUxXL!> z>KO$NH5+L!! zDxa(tn6>q52R09Y+Fu0*bHLg@2z~!mZ|(}rUoh)zo8jp?Eq@L1`}xB6Pa;IqPppPN z(aO4y#jslUYW>#@lCu40m6Cr<*k?+hTXuD_zFy8vxQjNV|CE>qE5|f*|s+j*KP!d(BN|4zPTzTLN3N7jKFT)dwR1F*9I z#v8Q{Az$>u-B_D+%iqn*E4_o?S5v|H$?{Az@^ zgS%UcqsXH+9tKwxIKF6nIs7o$ce5liq)x!_L>1- z(7Rynjghx-rza>{3cry_?e%|?%*)H@!zwbXVo)h{O`8BS@DwF)Ta-3Xl|@E=lwQUa zZCw+IoU|+j3E`kDVqMMAYxgp}9v^UMAxmuK^g7+3@4o#TNU=AkrGx1dD~~IOzG*B< zBd*VN{{Uq3Z?4rDG)Y;9hK6WqX@3~h{L+V>oNKJ?EMNaw zo#w0aDU$`%gtxK6w>qR`8kE3n5r}FluD8r%JjsDSspdt( z2!}{AqKG~-XKeaG*dUm<#bpQicPH9T-F(O;Q%aV#GScqaU3#B+{f<;x3E*X5Q&Y}< zhVlXq3fI!sATJu?cPx0;faJnW&@(@XO&d*V;0B4z@-T!=t!x(7tLG%5)<5&ZD@u9T z)Dkw<5sge`Mjp?lw2Y+xKH8@LoEc$k%(j=-Gmy^$3$YDQFA;St+*bt;r2ejKH>sO5 zQ4X)t_;>1aNfU+v5n|igE2`%m3G~ZLv>bBZCcJfZE2cC- zqa1|<3oL}k(b6c1J#qWJWK;24eBITAj4Jo-42fQAkV%Y*g*PRSTSNP`4;Y!C)LzOR zSC!k-Hps+n?Zu&Cu3GhPNHL$Ygq#TpvU%$2fmhvVb=}@h6SXngJEJHvU(Xy*3!LD2 zA_vMnE5!Di&WViC%1EM;9_ey-TX%YObr$4b7a54m>F-GBZ@3dp6cEEG$*;y+PKg~7 zJ$*rU74prT^otBuAMXk}nqoAu{W zEp1X_e60okT%pe4!9ZVCcQE6yR*NOq=ofkn6I$v*1+%~ecb}ot@vq}(#0T4am2%!H zwn48(46Jy_1fWYq9A=y|KYv~MW^PKTkE->|o?Svnw)=#yXknE-lLumyl#ASlN z+wdtZas}MtRIsu32b$GthE6_g5l`w&!sQG zg5`^lA-Acq%TM8>3HO~G=Rl9U@lsz8&97-~wH2e!Fl=LIvV=$331&8<3xOV}GT6gi z^?(|WbvbphS+$9enCl$ZnycO3l_O+V_5W%#%!U$wpq}9z{HQOj+tvsA4-K=1dBN~S zh@>S0^D=U+h9-Gz^F{u_7z}dRn=IzHRp&dJOBks8T}7oTU$!D$qD$uU6-c>NNb#A! z>lhDR<6F`azpKpNL$k4kN+D)6saH5+VM>~cwdsG#2oz(23c$GLkX)4Bs6Nuy7^0D$ zIpK@GBf8Bi$K{nTww+twx1QWWQIic+3fT6w7;Lywxuha#gOfOTaedFn{V?09Vo;1p zJ(inQ%@UL=bgq?xq`&hC1wQ{W0uy-ZK%}I;HjgzE%qp?wB#%k_{${e%D{BBeg`uSR z=X3Ll@wrzVGMeeQUrghy&a2@-16@9H_n5Pfal^)FU1vZON%r6$;!VK$mLl3;c%*$h zn*^0s{l(zY8izqNmfhr|ppL$4LgZC6h9jU?b z6xBSM@wscwtw_;%H{U8GL`?dy$1YDgqa>+0txd%sHvWuiO#~&x{2Tl+{XMt5t6z&V zwDj_B|M7JE09Bo#dBu&}CBJsj?EV}&$U|H6>_J+XD_~Zj9`nR^K4CCEWJLr29vp_#(b|C zkxqv%Ba7Va_C%R6FQT)eXla7@6y2&6iu~Aw{fbVQ$U_)IBVb_-yFa`Zl3W%QsB3qY zayKkDWLV;o%4@{__+v{BS|fMMx+rYL4qIL_`>p3Qd}=morU7yxBCeB{|Fk+LdoDy1 zPv^x5A?riQDJMyLUhw*w6atUQhBX7+V-Sbj%BVlEFZ`shvCy6pLyghgL|LO@L&{Xi z9HBI5{i$wf+gUM~)jv9(fITRIsOb6KO;V&Ui)pg(e1RXm#JYo^z`QhSRTjP~U=(le z@bgx+6K`*pO8v2PB${CyUM`DK&zm#*jKvUUQ$uN6RcTo-oNq6_(q<-BM>$mmr3ZWl zO6yWFY{m4|D(dP*u3Dopno_)Spb$KClPLZ#IdX?D57daGz;9@>J(KF_&T2`$8u8vJ zqhn7Z)90yaJ`H`z0nU%f2Vp>bsBs?XC^XKuWV>xS7NfAW3{k|UDwCXV$p6s2ikmkW zBA;(cH0K%@IvWBKWpc8Yo@zb z724lOy>Whg77k6`kH99&cFGG){JBxZq?vhcecxftT`J}!Ni=Sgl zf6%(|R~+R=x+s5jAdN^N76wkt!ewXNN~DCyXi58LU;Ig173*}@=#u958WG_ zdQsFkvV+Q!F75!&R>>>n9QEijPOSNlzqoy%G1x1~dB4N)o5$%G5>PzO~?o zJcq`~Obd3MNdN4F*G8pv0w?7?giJ>y;5kD6*W*$$%bJ1#*O7sGB{b%6%Cr)lV4hYjq)d>u!u@#Kme;nG&dzD&>`}5SM5_hK3VpC#|a{2 z3g%eO2^-StO8EP+#8W2RFVCE8y}h)gf-dj=K>a^`>&oH}fr#y7Z8bIW>wf)bY!-5E z`UxKcT$8#HK(Ig;8`WOlWPL-7mYx=vUBn6&vQ$90;#4K~QP<9Lw*F=zv5BT9^7;_K zF5v8PfdbeUH=b7uWwG$s3uZlx24-4JxQQNn9}^Za$QSVqx|w{N@zp2oNcu^NmRl@W ze}ssqc}6iarXLhA)<97Q3@gvnW`VKRv#&4yySuLai(u$}qEA@&&c3$P(b@J+@@)dP z@j$LbGzXA*zZI9%=?FQt*Jn8mHp-3drn(Y;@3L+B{di7T0>~ciZfzA}nY+zURQ=8i z(#RK(e|9-lj@$yf0g}^3!H&!Q7p1?nZ@NsmYP-?u_?6eNwmOg%r|Re;oeKv@TR48t z9K@!a82|M5GsuQN-Q)&=Bb|E#<^oG07#curZNVakg7RA5p8-A=Jcs?$W>H0Z>*j0g zx?>qmdrs0PAa!)$=@YM&^de%#&EM04KGShjrnqGh4`&ly~Ses&VYU)phiXk zsZ?ZXq>({eY`FaGGpS45_Vj-#3{l1k&8E~kRRv`YQbKO7Egmnc;?NY zA~*e4B+@V1(jX|Jt$UPsE9lD7|6jl0Y6bdWatFwV?j+Q$CObTg~+MENLR(dc$( ziLFPq-rH>Z^jNY%*=^%M?%iB&k@%pX6`--5ot?dr4KOpFKOW>g;Q*G-DZm#w6_`7( z(xcRGUN4FJ<)7tF%&nTHqCftwD=)3{mR6EXr+e;Tli%3@#eY`z4|d-7`!50?s!TQE zpC2FLPr3COXNRUws=Oi6bIrnbn##0_@#+MiQQ+d#u~gJ<_tgC*DisvsnXjx2(>UD$*m8V z5n;JZCVS3qk2)RdejFCauTgqfZ0KLd^n@hOuAdcSqKnPb1k`R__RtlQf!2G6Qn5+vhHKK@_oaA=9mVKwe#4_% znx(h7)Sk9|BEFeG?%06CEcp(G!5;EtiP4#5+WnV0;t)AerqxSyxMigDI0M*r&!^>1hbco5T8;gY z0dL7HyQ+uhPsQSfEWq)?IbCT4YfXVwX;gLFZM*B3tuk05ij#^0L~CjX#NyJChuLCp zWMtzT=u@m0n*YQVe{z9t8$b8TY%Xacw<~DU#KefCxDlPM@2Xx5&biT#Sw{osohH`8 z23yQNr(gRM>~~H+ce&2kmtayJcl)Mrb2FZo^CSpy-Ct|-Bx``XEFbh!rT)SA0VI`b z^+38>y4yQSmF}n}^&R>aDSbK0-#);^GoN*+UYLY;7KQ}uGojdoy(~}S5t;n9Pnxu? zBdIuzx)Xf|@?@c$T<6NobIZ+d4>Q0}qsrz6#qdF+$LkE(zC{@nki`y>>FTra0Lqp2 zPLc&)%Cin+if$BOJk{6GW8FUcdS;V-r7u7}uNvx3jG8`5QUQ?|L0Y-}7#3F|VYmVU zV`?gS)$URW{|e8S=YN{mvtWb+d%OAOYN59scImN0y&@x6M@%o#=^e$D!-vB@eh@Ht zUCE9uc65H@I$uSmI>(_lk8{xKHi2rUbgapd6!`E97)DFMxt>cq}}(Z`K?m; z24^HtJhu!0LLn&;#~z`xNhI%W*Z*?$THq${&u9H#tbOoJ0`zu7 zw>aOor;*zjs;~G&YZ2RplEKyO%l%)RTY9IofZ)>Z+acwo`8p{5h0oZ{A|d7G5YX7S zn-}x4^K3!&IZJQ--Awn%vwwe+CVT+&(Y&Z~QEOMLRg-?bouJolBCiOJ>OaX}zsd@A z+Z(Q9K33VTL;&0rkGJ*c5UkSEsH@98P2c#r*Y` zf1|5@3<&~VY8WtZHFR9F=6}It3&JLl$+3gd__orHD!S8&80W=!z zx$fTw94JU7>qMTn{e0xUxh~#YTxH zk*m>4yHj`_&oT7gG@#ePKTa#HFsu-z#GraDxFxu`9lht;MnIbwr5rCY$MX&4Zz1nQ z0@y~DKu(R%<)zWTXwDkdVsbnB!wq8a@{>d0e-(@pRE!*{t}AiEgU(BS%Rcxs{f&14hR6wb{` zVXxkdAuQh0!>+Q)Oh>m-PYbKDX6GuNsT5`nE8hm@+)B@!iac$U8$uMQCM@~)fIhJo z;o;@~qvf8{#0L zA;>OAHg2_?X}Y?M#1Iq{#_KpZA}%YNUD&lyKBsm{yOYA+@o{$#{~WP^2;%4lj8rNb#!-I^mLO@0_x7o4Q zGaY{JQx8iqI)`{m&qVq>hAO#j-99wXff~U zym;*VEU^A_^D1-ts2lRkxnFgM9`8R1ee_A zbMU~ZD55bly2m87f0EV_A+pn4Y4?c)ee+xY>i1!Kp|g@*<|~etGFNR}kPZVXACfg+ zc);)D>gO(6Qm;=X8oKPuY_)h|f+J z-F)j@3dI8JTdYKgcGJQx+ggVNC#GB!w9|@A^2=>C6kqWq<{d7W!vAU=M$Oqs>ZR_q zK&AIjw1WxojvUzk5O%Y7kLYE9=%zf@o&0-Jox^ke_L567*{wDmNODJP`q`>uBpGE> zkoU*nKyhJ6GS|pH)`Cx5P?Sg9+H=#}1;@MO(@*kf5oq1*AiNEE^MqVct(@(2 zfPH?Qs3((8A1Af_?zRQ)(>XbKfZYSoS;=*DT-q3e8}qF;)%`yKaf^a6>a(PLWahsk0%#FI7sC04-ESE;Qu} zKXB<>RBzKPoB0u6&2_iE?472~YY%?+_5!uft8iPpj4>#7>u~>)y}`2o2qbXvVl3pb zeh1Y3xiWOKqd`!hh*8z$o87Ob+-FV-`P?|u!<&E;T8!i^2XE8JxEZ8kT3+k59ClN| zUCtHo(^~BqeAh>|gSnEK+NBz!tSAkLv=X&r_QP-2N$1tfeAT?N8Vr9yHvU2hp6^k?N<|#w zJI&=S-$Nv)L*+i>>Fb}DQf7bt-iMjiec$a!t1CYDxGvc4N}P@AO=Pq-!hH93Ek&NO zaAI0Tn+5OlKp)|w11JA9_r6gn-c27kJ-f~;W=-)&=_GAA20yVWz13FI!Strn(ExhO z-oX5vRd(V{tIX6eJvF?D1=U^CJa5r2>Ls~LOrEgsjw|qUr2x@M-V;cuZ2O(~ z_%ELqv3@gO@Cc*X!Kzc;sqgX{*{HKKu*v1~nHmWq4H?5B5V~kt$tT*b{GsYEhe71wxeo~*dd?+$k zAvJJWctEc=yoO1DBqVt#YidWVIdpj4@NTIzw!*W>*fJ=j_RtYxfH{q&~QjzecGCX;m#=IOs39=9i)op2z^iGJ&Weu93 z7TTZ6dg9cyR0@?%bzFFB>xvVSslzG2k6X9OE1bPtZnJdX<(TBS9p>@B08*1o1OfbQ zA?<10>Jb&Glx%KW(XGe11~O&zfM;{v)g9>x^I&5lvM%;--hqhOu0+LxLnwRF>Wxr1 zOi-J_@=8W`yVvyDD<1y@E9isF=VeKxc$^Q7w9_7y>K%;GdCC%L>b32y~L%~%FiQneeX5x*k~{YH%vRbxsCdYdr9i0|M|ic{|$#VqbGRKm`&k%uc@zb#*#v8?1DhR2DqQ3TCPqdf*)Obd+T8{O9P>UMjs{haFr`?0Hdt7cH^r3 z=YOq)4mkyVMV~-%yZ86fpPY^XW5VZAM%sCC0fDbv2rY%%LPfp0ZRnTV=PRgKa*<`kXue-JIE{BciPm zNR6iM{`uR+c8v7s^t}_PIelY9oA+pfz2Nr#lv{Qwvx;;#xcZ#g?EVvRTg)7$#9ZrM zk3d%3%TB1LEwP+75uiSo%tif2iseCLH|Z|4H5h}q`;m&cI~;SU?N8Yn1myV<&I%Ab zxA*hKZ2x`a&KD2die+GkfjK4xiv`3|bl*L)<};JGu%16;S5*m!i47AD_V+^rOZ9r% z48xNzlR7Bab8}Odm;UTeiRLMlK}ByoaAfhoe=y(0MzrZP_rXVMy*1A>sl|&Os?Pl{ z)3Cmhv16IkH!?LCeBjfGLsn<5wm_p6GTlnA}z`c%s| zJXQPx-g+5OWi*_9d{Nnn7%^Ec3(X}62 z-}{>n&GQnnTpXFHcq_Tbd;qbuvB1+4xq)8d??ii%MOsu5N_J1Eo&YSN#>nc#w$f{n z!TCxbOT}+k;RZe8exBZYia0?LYqIDkr=T z9xs-TcUAl2m*5ZM*frn)4|$dj1a)?JZk4~nKGc5jx3}S6wP8p#cUZAU_CzS!nTosQ99UGt#yE@!~=0aJ@A4HXT*kdp#cJPVS{s z-mG?@P=X6N21;TkG0+gtwtg;5HNtwpLbr{%QLOu4e$GVOB3wI1zf0N*dr^V$8M zVMYzs--InAP8RR(1?CgVRrqLOelN*E?C<^PpAlE!F{lPPbKd~AnkFsnq1Dx_#q`;1 zHL({U&nqAxc3|Z%wcgBF(B@jl9rDq!oZrBtm5awTOkj_AsM zp~a6N)*mKJy7rRKlDK|%97#oz%Uy}sW!$c9llho(%RP^rD>)&!E)*LOyqM0qRr@x; z)3lruuiLGqCF=*35C)xckaZHDZD6`jNE3{HSLRYiY9{Gm6igengknS03!wPXy9e2lwWGwwu);M*JPuu z9k0I!6I#*5v@K_kxnZL)Pkqib7AG(?$xM(`y|8ApkS*fqbV+B6&7W&rSGcgF9JjQuZy+lXfv>zAUeC7pKLed#ty zFp()uHKgqU;Sb`+|B^22C!HD`DK25nQ(RV!Qe7fs_v(w&NuHx!=V;Wbw!fu_SKo=D z3X9GLc8q*#JA>+Yew^8u5KP>%UL=hWML(vWA8`C^;p&t0e)%ME(xDaX2;_Me-3PsR zOhxhwQ_+ouX%G7m#cEPN9?@zO$KmgM6DwHYQK>&k4)bLKs98W1pqS;uSYTd#Ex6m% zEYO`a@eE8*>`HtLUS2Y4-w!{0lpNT*4u-^q0SRF+2uz=69hcdb9^Xos3mCbuv>tW zFnz!V7o@I7N0;tO9^IGWPm#x1Rb?ht(1eok!I^!hsAl|NstVfhZq2_%&5GhGYxx`F zeVTuLs-*4A04Yb_%<3YVdZAuJZJSovfAP*Nd_pvt)KG`;61ku)O>LUt-R`a-`ZDw}{^LFPK-WkUB8wfx!OJ2gi;1`84P`KYw7 z+mY~GF1mawBx0oqGiBa?7_)~S7kdp;^jxHBr4(By(pT z6|!#4H7%r3DypR|VP&gm(mFd_<*tB3ay>FHhyO5{V-|}f1x@I+v|x4M5``1qieKi2 zG_ySxFoD~d+d+ck+VgPi$Z(Ao-1oc{;q+LX#PQq79frKBYCzY?AxE44D(G%{p|)Bw z%iw_KmwoMEWdOx|dFTON26)I~6qRD4hpun&`pG-(WaAu)i)wA8*E2+cMcFJ4%W}Py zjFQtvs^}j+5`?(W$_pPL95nwx55pwJ^H65~{EYWUDox6Z+OxXM>c#AuF zkC=&m0;9T!`PRcW7+N*+Yl+Jp85Zl%nzTHTcMsa61Q}>do&NB{nKB;~%l4`QB4786KiWN^-3NfkD>;d=^X8Qo*@)b zCC<}#_oEp;{f(A)e*KMg;}iEcp7DMup))d0eP(FwH8=GAi+Md* zf_Z!SQUBN$n8h>6r-xK04;OIjhOZk#Ec)q1Ll62++~1k{iFb7GPd>61Q}w%8J=T#T zU!~OD1R^zb{;VYW`=c;3-*4%SL1G9sdGupo1tXb+vI$2hjwRjD(QLYD1SO>RHQxvh zPrJ?h+1N?U8Dc|<8DuEb)w5wD;VEof z1@B180K=3wA!x%U9`*!W_|-MOTD$z8&|!gbBj&rj(6HC?TV*rp-6g*YCYvhrUVTcU8uBUaaD;wL-gVHZxu|Ka`VW z*rbJ%p0EQ-LL+P4NdM5l`I&o?dTk>6c8n->%T4OhBhN!%@;2y0O5F<2`6o9qbFrPO z&G_;f>{S2jjAj_xy#z=%rI%_4H!C+qj2IWpqm}kiI4wS~J>qX$?{(;nV0|FQi*u5&#@8zB5?(ghC z+12WH#D7o16M|;pn!T($Iy=fPcW7^Kmmm17RSF;?b5`vabKY~a=*u{9QfV@o&F7Tq zHR%@^r(b9*e`BTsuO@}g>4-V`u#`XiSo#(iL?tN%^DZ6A_@-q*325p%s9+KP! zD$JL29!D-uXJ3zKaS4(^zOaXp4Hf-p&t(g)auj3z!IlBJAVYKY=GNWUvzT&_pe{?P z7fz{&^Ygm3DFsqWsD4Mq)p>yDO7Af%6%iDQn|j@|gX!V>e0pf9&E`bpy7$cnf)(WJ z_k+K9iPv>@s99V$HD2sSOsMNN6C+#`E>$%GJ+ATp( zY{eq#tm^})z3NoqHGLrJwR<>`;RXKB=?|=ef~P%9&%L7xF+!9_3|>J3j$&TPLg%01 ze%tdMZhCH;H|o0WKP9~AHvQK?9dqNgn8R%jSgcY3&yHijU5?wkE-9l431;F?VAyhT zaoI3fAjO?tp$rr?+~#S;#G>_EyaNg`>*^hW8OoH0DcU%#b+xh9Zqh0RrHNMmqV!KV zaBfzA#;zk0=>){SnS4LIRA8?pwd(feb_mfjV&{_ojg zk4)Q#dt@-Vo2%FI&dQAV$B4I0G4Ge~3b16K^%4#@(*dl{BQHvH`nTG$x}iaTK8lhg zk?@g?nL}TBLt3uafV{18b-!`fncxBkod8DN4p;qQRG$k#_cw zUH6}PYC%S^O@O^|!m4He)hfOPKn=n_P1EoA-}dS#mKioqGj$U{vCgL>jmvOcFQ|zh zzT6SK-CK(v=8b@%oPge%fY*hB2*XOUQL8xF)5&)1r&xlSPazw97)azHD_pYB8*!ZW zZM^(SH(o1>O_^$d<(o`)2^nNAftMO?B}Af`nm-T+9qWp3PAz{Dsxj*1&-%1x4?vYk z0CdUSi(!HU)HNGB`^)tphMz@}XYVc$bKbw89Yx_SSJz52<0H8%dD=1;%QG`#$)<}~0Kmfk;@^Q#fTOry4nR{O z7xBso4TayoVK}@`u;b5#?Dn;LK9*s*EF&9e*`Cg60mceoHyX~zqQh+5?bYwmb$Gg> z<~)4&xbCR*d(VQ}7Owk`QuD-p1AqIb^JLfKaEpz9JcqVJp3Dz}wAy#<8Jut)hRJ9f z%N10(&^|BC9rGm`Rz!aE zDs*tWo?qGXK?48yHUVxF=9xQdtKQ$)zVuKbJJj+^E%MoC*(E-if)$XQr#q4RtShD; z`YJKs8Iqw0pgOFF_Z&QqceAq$r0EyW7^91w=F$7(h6Xp6yWYUVb8}QB8u9XG%bxv5 z-P8s<#z?{CKPs70KJXhEZ~b0%)-}*%9Xk;|F&0(=)xGiZvB#eEith1v};ndci<6%{qY-wlBOc9Ii@RhvY z*x16B+yM}gb2eH?5X!Llj(0zRcGQF?%(STqw@NMK&n>)sXFcXs^ z1RI~8uIG0YX_2s&x3wE#zUfOPNfo+iKmG%TY3>5B1)XxLv(?OZsv8@LI~)v#w75MH zy0w2`=)|^QHOhr|5WHXyTYnqix>v*MTanlCGhxy%^e*iopidzQLF$bS*Qhaf^h^xh z7wj=Xi}+*4%G3AsHM66$)2zdA&v0mJ3e9Nc=CW-Y_~<}yI*^y3q|Pc&^Iz9GdT*%E zg3)f$iFvvYK(mUj7D+6)7|OMP{o2vnW9IIv!UU)5b4XYcQ32q!Co%w5QHEfT!kEE# z4M5L(d;*F>#VN<2o}kOt^iE;QLw&{Oh5Q z$c-*R5u^97Ah4!%QPemjb_fW(7_dz{2nhGlMgbTwNLL!MEec1+6S=gRbk=w|p_(>8 z5j-m+f;$h3jpYt_>SBKejxTec_=GWwf&G!hj-H;wy|?0P<+wM>rmM;snI6Vdq;Z=iT1~`(5u4Az)U+u$r z6PCUW9UlJo1BS-Nw_Cp8!)7+y0wWWXyH)FgoBO{{-v8zzr7!uP*vmftQGJJk4I)RB z`TpZ`t~#;7w&$O(y0ya7)9eC$okx3b-*BoQS{S|;E5#s zOL0_)!WWB@Ne^?T5_DD>?N^m+%D-u-znR+g(8axznJB5K1+{!!9l-jzW$oZ^J-;`Q zjtO+${&||1-%W9#VAcFX|O*FJ&ciwjh{uowG*t1DI1uHcCY=B@4k z6$)3Ys^UvN6l$Upa@vwPfrwyqN|RN^9aD3)VPjz(4PO1=fDZlZrImt(r=9>~?M!xe zzx|s`46)~=Q#buE=CTT156>sUM61<7E3PajH@DP5VXdGW`wvh*C~V_Ve@l`$tKoMI zNB#oH-x6Y_Kk@cZ}vLi+I(#>;kUECT}zFoTn6X91%#y^4zF0TR=? zKg@Wm^+3VUr`y@y6f0%88#<=eFmPPO*NEAP@95izw`KoI&kh)M_NFdbH@`)vpff{% zBx`F^650mFFTgEScc)RPhRlW=_kF;GZ_d#jMAm)FHHrtRYWDq*n*7m)PF~#; zK52uk#eLLS7@g;D6@j$epg`d9T3G7n7KSXC5dZ{lckx$ zAUGB^Qi>yA{ZsOjk=fq2G;Jl_uF?cC#O5q?bJIu~cpJ#uwy~k&iSpf}(8_LQ&eKa< zeMcKYjymm30FcO*4EaRYm&QP0}K$9#6r3GQa__VgrO#UD)&sKL5{1}yC zVv68Rz@K!IyEG#V8H)Ky))pWT}vaTM>v(~C%#bIDUl+r9?X@oUu;S1}uE zQ}Mt}y~rlzw}Sp#9Rb}802hK>)Cac*q>WH@o(;Iyf#pcuJ%^APt=^b^&YfSz1I&0& zdhnCTQM;oE=JC)Ix${}2i@Q58@9$E)?+04+RAC_lYI$S(?vPFaH#x6>j%BFL%LZ-R zLl0(%5F-do6}0q?=+w(S@u}MWq95}7&;L^((L*JrZFq||Pj1x>2yjcky|}*i9{;rl zhr9(g!K)5*|bLfR#oqUU6{+Sz-}-tO^J*sdmsj2D?o*xXn^0^M-lJWrVQWHV?;qGR#dQK(pGTK7G@w!B+o)>@Y8>nJwv5fo28oLBXI?!Nwux#0@364I ziaF?BGDRMTvvKzKr=Rih!`#YZ)#ZhKp+%M{kQkz%g|@s%2AdY?+l>K0;qh->%D5t^y-AZmmCUC615;qW{AFVp8rHFL0`o;v7Lhh z+D9qPq{^q!9W?zFUZBMVW^^~D&^W9x#;1zjw}7knua9r{x@p~T=EaM*Pk@XgskYHV zD~)kq=VzJOC*pFX$!x}tk#bqRbdHPm(r$R}qI;`NWM}$l8ddEpz%j&`6-R@iCDfx| zd)n!aK$?OD7NZ%YfSY{?5vV|jPG-AX&8?~u6cMp-bWGH;C~k~cx(r!gXFh9JCDx|; zik;Z_(mT%Xv(@bl`)m8(~u zx_=s_!?L#* zl?FW3*B+q^;FrAn2bqyi{v@gXDZ|YHSBu$x7g(@i+p|dUwJSluC8tBbT(o4eNQkcR zW7pEHo0KEw-?Xy2;KbXG8@fmQ11IiTk#SY`H~H@WWQKP9AYqtiWYPJrV2ZPK?+hOR zNA|OWSGTwK_bK8y;C_ve<^)@$vO?@@m%t#Ij}hlX*|9nB*kJ$=!jEtN?KOStgVBne zP@|$$eJ$&)<@pXZR9}bex-G&Lw|dAC4X7fU`Q@PlrbS}0M9c7Azox?NoELaawH(p8 z^Qs6JJACuQxc}aBv)($j_5MTm>v}6mG8z!Ae%kU)Jar?E*UI_ifugM@J96pX*9A_c zD9tUUvSAX6GwsoD>NesmxV+nifML<7XP47+hS1t{tfQU@cQG}?E!pQ&+epuRN^N~m zXsp+SLF+&DS@$6a-R3249E9!*J#GExZDVTd$;8+&)J6wb`X(iL@mXNyMVbx$ZY)2Z zlQa#~?+c=OVV*fZ{_lK?{uRyn`>uy7j@eZ4hH*RIB_}Klv?IO!7TrnpTM|wq*&SiO zunKkh2XB)D6B9`#3G8z9PLR*0A{dLAFs+XB*=GF;3kOGEiMo01G?=mkUqM*6Mf1;$ zEaIJsc()q<)SFSW>M*qdNr*&l^}JBV5g#%wb%=9%P!Un0*W-o1bm2FH*DZ7V@aKfX zDc+P$$!sR(NPXQwQV^(+LnmEp4kBDk%5br& zNOgA1>wD}ITFjdMR$lFO^+bajdT~@ubi{P(4DIP{|@?M|^@|j1PV^X+W3V&!%S}%!%=yw4&Ma zea-CY@$U67;AmZ*_cVGWR$8g~Ql0xWHDYEmG9rgH`3F~W+|cQ?w~XW8?7#7xxn`V9 zT(eTQGqJ<_E*mQ8tEUF{t91I6Txh?%c3qqwMoi#FxJ|Tv9du-F)=TgH>VHgz;G?FO9APg+`TC zz>%!bzFsvfMKwg^9L6|#$gZ%PvyFao6jIG6<<3&&4}vyt{$BI7Y4;lR%l>pud@`kD z5UeQEcMyDNXis96(|Q;R6k1<o zeZMfni}3~?GeQ|1+pc5HQtfdkeXX_R%Ce8^(P{@9R6~}D+$c~G;%HQ{wtW9PYyep5 zgrAW))4*Dj?j~>v`n6Dz$oca2I=Vv2m>3ZiK?D#IXypX$!An}BlG2(Zl&0pa|dnoVADa4ODZaB2tK@aXRDsqATEtEj$9;`!l5+UR)g!lB5BXg7){m=i>qli%=49S_ zlC;sGMkLtatY*$Jx6t*b^76L$1o<`RR$xfWP^)H`1b0E_*rQwxa@m+g3SRY#luKk? zSY?}DcGLCYmn>;rnXE8Bvx@LaOhfM&)RAoHmXeW%D`7OXdY<}+3ZTD|zlucJ zP{~Nx6p{l*cgC*0Qj!snF4O&cmZ*7L|m4<|8TeGxt-_F zCr;P)TYD*vcUo+B6N-B?0&!R&pTPe2uQi!d9?v-xf6=Pbj&#a;ynE zCfHSC64ao#@JQ=KRtMm}+XY4l2fwud_G#`s)vTG8s-8yt^Z^&|@zqr#ccVL?u;`E> z7Xlb;P8J_si7t! zLiCo!w+9aUBgTd6AS!#ig^{b7*$NnuE{xI_&B9Vfkxksfh9-QP-)HW`)7C@kD+xRB zzco7~cd5NU7YkC9w5f+lClltE?-LEDrwaO`(Qoh1GEdA$~YE#1V;=ao6{AbA(f!X&querTrwh)d`w2ZbtFZzVbX9V3vK7 z@?N%!gVqUt+Kku{teGfm|0ux)$4YLNcSLsETj5?}=769iILKl(MCncRF#oA zcYr0FH8ViY`ReaIgWddU4pkKS zs58q2Qd#yJv#!>9>t!x2MAcV?=^>P>ALzb0+ zP`5EP!o-zJMplgPB_bwPUd8kujy&Kd*5n#^58WPEuurHWG?^Om$%>9RI5;3VgGHOc zYAFonA6b8)MzRI44~cD~uE)P0dJvRu!<~PB>f?;4sx#B*M3B&wio$R+s+YB^enD|` za4^$Pa>FmaQRbsC&Oe2$`5*rU6>NKB2!fPf9M?yG{)Jq=FdUBGW`jC?J>&Tf--Hno zYmX2Ak)#=PJrIM7Kyq=innz9kan3;{i1@{yysydPd6AfNao}gsg37>=d;aVG-rydZ zd@A6tQC!SM?8kIVZ{^r}Szhth0|5KXQ z=ZMI!KDsZ@HB&dbp~~<8IYjy>Xf7l`A!4S76IYoB%OH9@d@77P+IKlKUZepTPSp`_ zl;@>Ogg?577SVrHVn%Vrx)pPWFeCv+Kl+4Ge5Ajc;~7}-6ToR6TbZ>Ze2n>#2Jdviz> z1V?Ba8`I1ySYcaiJ=Vm^D33t7s=7y#JmufR`srinAw>yC26*DJFZ&z9p%UV+j+Hk{uXMFsj?Wt=wIP&Bz4cy zb8f1aa04<=U?#=8x1jsrOp&efs&WuYORjy<jP!*?B9!=^t?}zZ&y2huH4HEY_@A71iutxGT*KYKu{VCQ5zGC}_Dw%c`69l& zfHCgFI{9u+;rMLgds^Fbk9C<>-;a?^73R+&73*&QKr0&~)~$g$|9VO5&zN(X`9m8j zp`{6!&T__;-KId{O(7pddktvjcSFD0m)!H>k4aoaI5^1>P|J!pN?H{8WRaMIA~8Pr z#Q~gjIipIBA5piK@Ea+Ky{o!?mn|&E#kmyJMySOR9Z(Ecr*7MDv0y4Vl4Hr2sHTKz zL|#gKO50*rbpd7RExo#0SH6%F&*1a6sa4rNg;#yf@@Lb%g`{VtQGcbkLew&yYe+y| zOKumJH9xJIMfA_mt&vp(n^WOfFqwQTFU@NM^=ane>qeXPM3V;0z|&0swb0(C9+=px z;0g!lX{@WR=YQi6nSFRmvdUiLkFT3_Z-L9kAO?0=q_o#tFtmJd|4$kiDvRodCvxO7 z?K78v9OzLc892qFw}eu(mnM4!#l9J3}u&%=n z466-52PCdo9H*hlwv&&y>b7sEJI3(!*_6yZYU852lAT?RZDTnM>N3-HHB}VvkDWOn z0(K&wqLV0_%`R)k@C`dk8TYf21V_BUP3`xa$eoU!j$NxwyFKXS%vf2R`ikohH~G%O z{e-dAtkXo2Q9Cv)YeAefUA#bPYiSkJ1Jb9IlLAtTg;w|6bAc%XMK`m5bfGGW^tO)p z)|KG@uHLc5Yjv~D>2isxHaUEeXzAxApDgjDgjTRhS4f>RGBW%imq0}gH@SE~cmFKT zPC>YvTRabsjV1#tp6)T=j19@jAvwAe1iWn3)pmf+XdoSS>Nb9Ja}(iYxRSl#&|_>3 zo?EpqSNw*ahOA7#AX08Bwn_;0-x=zWJd}b|+v-8FCq-T6+HBK_cQBJ?{8BtUEi(21 zWJ?wYhX&JljQnx^SK|{Oyy=I6tDA$yRFS>5;4!#dtFi&qE#y-OgcKDO)~ORMYJgt- zq1A(*VvU31(7zQg_461L-j7S`baQ#Z8DK9hhGe}0Z928JCDybWc2hb8K|f}>d(n#L z9LlEMSRiw^JI3cCjJk2{@YDJ&9H0ZCZZ2LMiQjAFY#*8JwB=& z13F3FHNbi7@{-km1&ek^SdAjpBaul76!!NoEKr*m(?PtvMF_0bvbF-R`w=^SrO6l8 zrB%cr0nYJOkZbs1+XJMxg+anjeuTYbMytirF)-1Cr?@Khsv-)7q_73;vJz0EM>x0L zqcQ`cs(vo%ZdA8+lT zK-_W5F)6oeJ8b(2w&haXaUf~#0{emPqApiX`RPo&*1_Z8h=Ee6m~;^MU;Jz!VoR+P z!k3AJC7-dwAy#W^0R z(b3#;CaPKbR}cM^%cjO23Om7=nPm7xUKQF+37-s~qn+0-dZPR#25$KB&atJ$pbxir90l)o(raKh248n(Z?&j8)xRSny9ZH!LBR-Q>d~jQ@h>Yh1sH)S+fUA3d|%{s(E84owWif& zK4iNhy!Ts^5%($QHlWJzzljy4r5IOaf&4k|1capG|gb%%jl3|;&h zkFTj${{;@~Kd!QQ+?e8mmxxuMCk4O5P0!4SRy2>&KF>wQ1H*y>zgva= zT+zEcP9ViJX7SVcy;)U%$@sVf3?cou&ZANXB)D(P|JyN05q(grYB%|fs6uAVG8gQ= zFM`prVNVVKw9TxoBY~|hATdn=wbzO(?jruLsVONb!v3NH0)^*70D}}03qUsRb)IkW z%JxLG?EO75?ZANYC*gQC3bDnwR9oz}u;lrHU3RV8dU^M7{B2zX{=4UPlB0n%HG}8) z!xB8r$2eKuG)>}gq_G9DFw7oHsrv-CWU*~BrQ&z*NqeTVz`DoCUzH#_Z{X^R0bTYB z;S#FM0NADr*y(xZJ8rRXv;s+BfE)R!=c&|fGU6MWHtOpd97RmZv%CDc0rqGR2n4I7^Bg^{^)YZgEi27x_UilEGVk5pegbr&?LD?0A9Y#_>VJPh zpg#-wrmp=FBggXcb1!56F&d^uM0cemC0r~)(68NoDoAAHeZOndiLSy>r9);*{QPBu zmj9RlE1(oYhcvZBY>b?4t*-v}yp3NNtvLI3{emR$J8oUy9s*u&Rj=CvrRMcE0{1rYE^Hb&1 zfM4(6^fdZ#X66C}NTtNdC6dDi_pZF{OvihHPXlt#6EH=zEs^`J20c3PZ9%OCT}19Y z_vgTi_3iCgd`1=(ivy{j&?nekdHX201nlc^#GUZy@h3~|XXsMb#{UK<^wxoWY8X$! zw|1yS1k+EyO0Qx6il(NQNFp)(TH2dGv2Qzt=h$Gg&3f(n?5#A=EWfLr1y4UVqgMX` z!u9jv{eHc4;A3^Z{^=}?2(n+SKbN40zN>V0loau5Gv@KGU2pk} zj;YceC*B|m<^|L|^7lJ;H2>8a{4U1dCyqc?{o_Zu=M$CK#;7@qKOk;1E;3GsZ&fHE zs0t0y{!*wF1Qjd}j?Q&4LBW~) z_dGg|8#dH6%L_KpU&+g{SW|@yt}`oHWSV^8{290xZU5ePGoK?tAYI!MgfK zdq4%|t0lHYrgiK9L96cR>9M8f78G#jp>GxDNY>)o)%{hOp-3FjPzaD(`2n@qil%+Y zb+XwCns)Wkc~rD+&yBSKVT2x=7$(%3079vG3eYZ)WhKCzLynZQ<3C0_5BaT$O*Y+S zdj7Z7?6U)pX0Cb4iNh` z)JY-)_`pV8CwFbrnnFAq8CSoOl{K@!uDaQCFOAFd%_@)j_2=0DZv*&K04tXpugPyM zdrQ?izjkDrrsP^*wp&B`1j~1Ybo7*wSafu1zN}naO$mz3$6O<@e&MVu;sY|VEX;pT zpTr_A>Vfl)ot>L97b@Y#tHxM#c|Ujh2@p57d_6oo%;rj5SfrQ`|7abJe<3yp9jMqk zW)mj(0I0NwCGCT>U=+EwllFEoOHa?~t*zWrC1NQSW~=YDl>6CZQ0Xx|WMpKAOi#e8 zYt^kBue$9uLuBg~)@+>t{T7kIFJ!Q0NlUz|tLr5exC{Ww)SXzb5zC*=RZEd<)Y~lS zeOKJ7`#ZR}4frPVHIr6k=|M-Hs+{1*vK~qsv1!a=`+|lV>Gu}nO@ty+8&V%W!jmV! zVrJTC)zVHSKf1Mfro4O7DK;SmOQvlkAk?WJQSH0arToU6MA+7p&A?HlS5!j zY2yP8$LQ@?{NuC}^$*_8~_0A1(yZt`wPzq9B#mB)+Y4K-qNechn< z8`YK{I`$iXmUVRcxxVN zh2K|af$giZ?!7=zn^(;&-oo5AXUxUBNzOno~)$!hzmSLb}AM|ho3t;gL|B9F=glRGQ&RU$$_Q=q;BbIXzT>5QccaswD zo0FbLPYX%DUY&ko#=LauJOHeR=0=VAx-3r{FIY-_f;!s|OgJ9Q4HPqno-)t^T{`VP zQg#Zmq#v18UkS}VERh#J);4xQAg zZn(5ZvToBwc#&vaXI|9$qTMf6Xki*YuiE)72CQbnutRfy^IreP&H25})sD+7QEQW_g4++V$swU=j zj*u#Guk?!7u+LlMrcHUwoVB>dE>C0Zw1nBgl;Sk)T~gdMe8(Sz6eIgYI?e?qV$*$0 zDez5g?dnN+;_?o?rkivE7Y`JT=ASs2lj`4E^@Fe4#=g^s`9QgKAHlB|u^;!Th05!g z>9s$D+JQ(JNZ3zjTKguDreOhL#0)VASn= z;Fnw9=fAuPmj5%6x88<2qXqU*4Dxi0_ErgO(K{dh!C|b($kL?%4-*>l50jyy^tw8(LbrBYq`Bi6I6InL-WR!j>uW~>~ zLd#Q;eOyL3wv`#t-v&g%Df-sjlc4kQ{#guev;Hc52d0lv zdA(J$ZztUcBZCazGSLK+2-D(L?6>~&Yty|0ia+jGwTx&cw6$iW)Ydxe7#a6&k%hka z5)uPN_i7{Srp#%UCXDME{9pwAcH_5DmoLNxr0S!Kk{qe6O4oC7UZRSnsZc9pUwl&1 zVUC+NN1PyON*v{(xC{7wh8FKw`oFF-{a+6ur$`BeTdbwW|n0%?EL$zsm(3=r6e4Jwwma8wvpSnwD z3gA2KeOQHB_Yi!y)#UHFRjt{@N8pLnXFPkuNb3%T@rXR_FN}Lu`xh4-+n-n%adDo2 z-MoVPi$=kdBjmsdq0eO@&;*Zlbl-zNhlu^JPgHTW5$)M5j(XjHB~9d6nt|ebsYJ|1 zlZ&POk^9%P{=?M0kBsl5%KxMSL`xn7r7HhvIV|sT9;UVa%v6ymD&72&CIg#8 z+V@LQy8kDqT20NQA{B1pfqpG};nIBjwo3Q)-v2>Y+fa%vMisy7<-pCq0d#3P`;G4+uI~$L2n}g?yH=+XKqy@cqtlmQ`AY( z2(t}8nkOyY?S`AX0HPQoFWT-|qq zL=ceJZAzeqPk{qSpMQUFi~>J7{!3Clv(f_YXYk&3|C=!01^&(3x5u;kjdD(c>yS#X zEaA-Ab}S-CXqRI5*fm#O@bI!o2840kzv36WDFKi&0Yx@;t0v36ka0$4%w21v|97F< zf#wMVZl;(qP$upegfF8bJ41@vQ8nSH7WUYOayt3E3sDjxt)3NgmExESNrZlbIjBy0 zUiM8Ei!Uj~4wCRTvkC-|I>u1WvDP22FjHbs%6?>%=u<=$`L<)V%S>@67hRQci>iVk zNPq^7*o&s6*ZE%mJoy|U4m_SOpUF%a2nu$o$~4xmrRF~UAu^|zn&tvZ4!!{gv7Qd} zDmqx@+B2;y&7UzfRD-1Xtg={PuR)NDxQ^NGC~6^7^O8iFkrT>x3RI| zbD?e8S|l*37cd%4_zrqDSqYFKTF6Z5Anom>S{&@CA4(tz3LrMJ%uE2VHQLV3%eBV< zB|ck?{l311CoYoHJ5tEFczn?ngv7iuWdr5Q@QjBQqyaO%&RR zKNwkLHGr$ZySgnmoJbDy&gUlham(Ux&`gPSq z?|;yMZJEI(i*!kgR>vFb9Ws#M=BH%#+((qTQ+}y>r$9|YrlD0Gl`JY?T0KF@NCL_i zMejXGU|u-Zo>$gLH6)TyV{`S^2<0^nU^;1y9R|9EVHQg##eEy~X&fyCyvAh9ekQZV z%3bo{rU!+{0(RDMR${nfaNEddc{ynWl?HD1ZOXCjd*-L~FYOlRTLme@t)!GD^qrYN zv%zn)eh7F29f;{A*M}OlURD`0&jd71v>C@PPh=kX-7$Z)0Kr%o4O1{_dUuQ({{}Ur zpAA>%-3dUPHqQ;XpHHFkgWJJ(Ex|m9SEUWkHB|OWdt>jQcp+~3#RttketP9(bVSRc zieqO(8{0x-kqkz8cu3gs)@MsQmdetgdh5|^*z%WSuO7ScXE=yRPS?AdS# ztgk0pk#`~L!QYp|f>zBlfgl#lbdI>33>Us3-SNMF3H=^;u1-=e>dGB-8yXy8OyXkDkmKYOAKZgxhB@nRxhzpso`-NDD< z4#q`yeW_DU08=Xaga^hJ&PVuIvnY(4qz@c$#m|2sLHGwfJkV+P4L$;ivXFgO?1xkE zgVqTj#K8-GBYt_&gwB#ErDtonBBJuKn0oHD6G4@}*2qQHyALCGKqPXB8cn>kSM{$k z0OT8iOQKi&P(b!o@3loEz`_`Z{G4afoCFt4Y!Lb{U@?USkMmq8gg+fzizj0mZ;pvkyAg|BLBfD9#5>~(6RK((_XxcBr!eB-oymes zDuO5sw^>yl8HI)(LuRYS@Z=p!OFoSue}FQnUEH)EUDRj{@t_s1#lssSFo)PT zCTNK$+>xO8hDCB?Gn*y(WzebLSsuPe=-_=m^@Ce3a|1(!R}q8@F@mfJ7d; zu_K)KU(hdo!?+uJd{L6~>++QA_=JDdxHxFxsSAXcjE}fep{;Q3GQh0Ud;Mb<(vY)$QGuOV+mnOl+z1o}LpN+Wbn5XA7T>FnyN1>?&vT@OH*AVg37 zDqBX`^o0)}Z`ShK{#RHvSbyXHktmoi>lEpwJx*t={ipR zzN4#aiL-)!6g191*mo{mwND)WjJTUX6Rk8RhO(lc!`<2>Tvm4T@R?j4MMUEV63RaI zOReN9$>eubH%YuISa7>b*y;y*tip@t5eWUOs%o*;tu-EHRVOCWR&5il=6BDIkGWaN znAHI)%FBNBD}CC(|65a$EG@T^<*3Llv*Qz7tF6yMEgRHlcr$f&Mg;5~)IjMe48X0y z9)b_TxBp}@Qm!Lzsk0gV>23v%TMrtL*nK(DQ~iJROTrr^0y z@bDhVcYh+$NS(GKs|!T5J@H;`abpw-w{ zej^1WtFqz3Uj5BzK+nT-D1bl0;Wt7IfZ@g-9!(jrUs07Sp|A|f3rTLRCfa(g#))NN zq%8xLFeM&Jiw~k zlenI6acPT&_XAWyN|=x5;6t#Kyij_m=o@v6^4y**CDy$lmQ^{>!GLq1cAM8hDWUz+ z#NFYhA=v@x0Z2IuJ21jTt1kU}pcS+vJk?V{U*x9!2ynXPO4tsh-S<2-+26afwOSunYlXO&zxHXV>>`-}id=_xH0Fy+sY$Z>nv+8tQZ zjcWjTj%k@2Q$GVci7YSyL~DBRvMPVk(si?~Z%P#8;ZUfcWs$dZoL; zf1C1i>j)PYBb?ZqR8bvZt6azww z&l(U>>86otdR)82rAT65B1In@MG5Z@8)FM5kI9Hf!$g~^|p+uDssb3 zVKV`b6Ca<~7^AO5Bjy76jlFF%&fLXU%vg;?w}j{x03Nfocu_Nl;JJ6{HzkzV75mLu z*&>EEkojI4>t=bxBJ>s6zwE#A=pHb@8_B{!bCNw(2zv7#tfgB%JIU6EAfr{JYE^vm zuHQePEqCI++k3;q&Ao3W^sZyrv1vc`x=HbU(*Gfpmv7+e>^$&T_zZ~GD=!52?;V-7 zj(E=L?94+ErJz*UjMY75x39HJ*JFltSDRINm$l7V5*vwYdl3Ri7uccg!|w?1b|MxR zLFP1n>l-{Yet(|f69^uKRuZXd*uex>Chnd6`H1=c_x(k;hWoV~_}0(Eok#j}NQWaN zc)Sbl1`(L+{NgZUa)l4f@I5-B0lGD@D-2&>BkuV>041_NJ31mop8MLcqCMEv8)WvI z!7|r)Q=qL`n`rq_1>F78clv&KOr8~fV+8@lY(QD)TERJZMSksYOn8OkIq$qV?_uHh zE78Ud!E)=@e@sN=>&9}#U1(0-0@ZSUJU0NA<`=|I*r;@clbEUrnW-mKh8P){Z4hpp zG(o-94c}?dX^buki8U9o4COku^ALaZjcNxO-ynv4eqOw zabqFvLw(;L=ICZ&1f*Pu_pm6*B9QAN(|O;KN)GH zK}y>ts@TZfH6)f>FLyfiYm&%tcdK&>26^QuppNjXe`K;mbl1SJ{DuM(JXvdDj6mMD zZ^l#+aqTs%a!x~n+PY~cSbQc})AVsz);}6ttAao)x z!{tdjxw0)(vqGSW$`6{}_t8A=*hAuaPZedQk#m@Gj#}bh9%p!Cq8WCd2EMS3e}XA*W5|#5!93(6bFXcoPFlcQZ#>r!dPLkIlh|W2@3?!R@X)rI{KJj^S=ewtbK z8LcT6x^a^^c<_yH@S^s1OW9T*lfwk23_x?hA`5mj`!wXsCF|a4_Tv# zS^P=Mm_}ipoiX_b)k}&y&7iDRgS{d*Tkmw4GevD&3gmT3@cuf)@NcAj3YpH2ualbB z|LtZ{^<2cx_ILJCFy0HCnj?uo;E;bK_{XNG(gtHiCAqjyEHj3pJkM}F3l75UgTe}p zYT=>4qrLRk>_6OWQ()DTZe@QB|nsH%tcs-|4#=kx6Tb;?wd4CRrWm>A`1V$a(<@oe) z_kXzn0M2R=`05%$6n7G?9>4d##4%0s&RzLuuUgXH1f<`9#HBrcW2@&a?E`J!Fdhw`MRzLo6fsFG2YSMnyPG3b6HJ-AE z7wb;iCtE89!<6OpMZ`Qe^z*;+SL*8?$@kNvqOrOrKUiI|8{0K%U5EB1bKVsbYyl}w zR*6UKnaR(UAw4z;sU&E|{5a@&p&kRz1o;urDpb3F55Inw*xcy)fyfYT@h!_jwHr3F z%QINBo*S1alYrZZMl`|1#s;kw@zZ!?p<~Mxu`c=%*OuWW(B@E(pLyU6-H0It*1=M% zA+b_J@$`s5q`D$aRxsC^wP@ECuc8eKA$nx~rt{#JmMBW0^Cv#BkpUY7;l|Bl7?KbN zHOwCq)%i4A52{jD4QrIxXN$K=6>&QYcy)TmO=cY_(+`D_-2#|u^3_#aOL9OoGTSiBNU^izuiNV{H#%x_i2}0gUSJkW z@KF=+zZ~e^79>n2m%6d^!*5E%S!uO_cHO|{036ACXrPyYFCUcwDNYvrglAz#sqGd# zwif}392s}+b+4KRb**+B$C4=Bb4jW&>J4MO=;;*EYq|^&Cv_27&@vj?9{put8&gdT zN6FXmngR^H z5RmGmFa#lBv82rt5vcn4qV^#L47vBGI(5QoIyt(-2K6lRQe;Ta|FROO*xQ#5Wn@M; z(8OBgcjahSSRv*|Uwtsn)s0msd}MC1tOi$%9r|SuqyyEPK?ikkTruz_{dkP%h`sZG zTE7Ak3j@@zr-iSQ`YYZi>06SJ5SpGgeP0qnuDB|yQ{nNH3n|mLv>e3$xRGM27eOpomWIUemy_cevDn<&FX9UW6pwe@=x?`4Yh3t; z;2)lQPtk#hzR9$OE%`XT&%f!NVB`{O?ec12+lK(fHRCI#s1>$kiT@rS0qD%`QFkkC zW-FZd*lo+1BWS@s4IYbBzx1q7 z%(OFuIAG%v&epcPy3YHNuJvs-2|c%HoFHBjAbXmr_p= z7mhvXY9#d0&Ch@vy~?$_e*Nkzt+Bf;L6xGMgqQ?L`%y}mL}Tuc4n_`Mra3TDm2cj| z3ILAY6o6V&8hu0Nnnytr>O^6Pn|FvoD=A2($y%l0ZwPU;_bh(t4jU)ht#(jXnHVft zD#Lqianl3B%CX>m=xjp*v=l{58%b%xTGWZy!pyO>Yo0yEmzp5Pt|dRDZ)jCTqtsL0 zPsaW=8s|0pTPjE+g*<_D&@@3v%2ZUTNN8?5pqO#?ajE3fh|$qz8`yO!Spk<*lHHJu z=RKMYE65BFn`xiD0<=~-zjuw}4o=@K()x(!W223k1jd5H&Xv($ z6%qL7ABYQqGL>JimR;XR!$EE4ULz+%2-HakFWF$D#J=t4RaI>)VIFU ztIU@lJazS;Rk!WH*twtDb=9-n*cv|@HuqC`p+Y?-Cn{O7N)~f$8mnDMF0LmT@zH67hbbG8UEI%8H$zYrv>dUR$1`kjHlVbDRO#@ z`U^^sJ9~P@xFvK0<@A*+Ec2})8M%IYxr4&|K_77YG1lx>Ou={FBZ~(lMd98aKtkFB zJh?kiULZ{F+YnQ1gC`1<%}UkP0>#RE8U^?Nn@(0y4t|+;^osmr;@VZjB8|uA!nC0s zk)8}Zdrke4AvK0mT2&i;fvgi>TeTI8;)z5a`s8U9XO6pG*m3{uGGlt$4ycWbLM{*-9CZe;EV|n7 ze2?$uLT@MUJO>o+@$5YBb}$VL3l4yUZek})kVqt#v@4@xPP*XB{j8VW%rL7Zmujyy z{go19&}=_W%O@k_B0tVZr(%(8ucOgUu8W}{Lr&o;?UH|xBsM2$3^HTfB-HcCxO4V# zKh9J6>t=MAekDrG^exiY`*~-(a&@p&nl&&Dc~*{JFg{$=n)wJn5yJ9Ldf$1PZa`R;v7Zt|`sbUdLr@B` zMOE&zLe2xE1)jsw@M1y|u9LienF!#Bsl52so0;*-Rz+eVbfYlTqB>*KTkx2&#*V@;b4kkVPlETs#d0(rYxa18uX3ZP8Y1aCUnjF66rBu9CG-Tw%sO@O+BA>FE5fqHt}M1g zy3@|w$1~Y%kMDed?Sq70Hf10-kqc#Hxe{vUey#8>~+UBCI9PH zEwG@YR?gq5I+sDsw6=DNJIC?WLm60PA8VWqfW@0?5(iSp5;5pJ(dBj~YQV>0o}YIydZL`V!pG}VwcXv)5>F@l51)VH{t%7k ziiGtu>BaUUzLfoIOxuyqJ#5e#P?8?7f<}I?MtT(t!|S7NdTd3jgz;DUA$>&M z437)^+@v3Q(uGI8EPsk$t(4{iWD{SbP|6*0D1d4F2vc$nC>wCoGCn1?*wU z$cCmk31y{PpajKXi&<)Rd0kLG*dCOPg4{55@yW>+P2{R8UO{u#goG!nsV6u!A#N53 z@<};XR51lV(-e~IW72ZyB}I8K6_TqbyVR>=(_zsm$HadrnvF@|daHrfU&MtZ*<0Ru zYa$Vx9Z2oYZjC|N)z$)IeRjdevvhc)CJ}ahEUhfLea8jd?+4IDaS~Z26=`)cN*Kz) z>N7PR&Dd%0c2zJ){F>4Tm&wrc#hN;wK_U|gC|YnBFW1u%p#XR3{Mf6s;3iznc*oV@ z+HR{-1O#MJ=F;s!$8Pl3I;R`ae$5pLw}pD=54YR0oSaizj zMM7mrL!zEBb$w@W9VR8DdhyRYCk}-U#KiB*h@Fv3L##b3S z=Scn5A}V6`Cz1~pkUz?bn^42i7)GB$w%gLxH7SQ}IFz0+_sIT^L{Pk5dmRR0yUsF~ z)0*AH-qtRxE+7FL9yu(fG-9iCP-Jz6&$qqp|8!wB(Ji1@z(2X7?w#N^<;-5TwaaDWms4URhnv#nDD=BgfDN zgpvQB!(&AS7P-U!=eD~mD}hl>3P6&PPS9K z=TNOHOGMB*pI*IlCH=t9X6ez_)}%Bb&H#CR**hF|7QwoT2NOdKY?Y ziL?34+_Qg-Poq)b0ekEI6RssD!ru1tVpf<`m8sc4TF>Alql9^Hk6LkQskWSJN>fI? zF?PLuUQcIn$&Mo0_qxpC!&XM4zinjEkzeZx@28Wk9>vGk(IHz$cRlHrYuEqp+bhUB zklV<0;9viFeBBrql*)ia9=&YbRYt;e3oRPL&A*BhBaA_4|& zJKr~@;U6_gf_P2ewP$5+3N7v3`xA-=vg+o^D~+kd<=P)YIc`BdrsXJRFVZ*<)^=o6 zWukGuo%In;4qtjWT`t2o*us&H@$DUZtxJ1*aLT^=s+C^&KjJyALV@w1ulD0 zi4S+-VpAe#hb*K1mZ_bdPQNSW8C=|T zP)K233%inSO)~af72Fv0+>_3x(5M)4VN`&Vc-(jt9Iz@6Jd`sPng+BbW)Vh3>#?@- z)OGBvx5HpaOfD_)16`H$oL+j$xf1f+{2xmTi|Gl*Ce{gNl_fCM_tu;D<}!`>y#%~N z$^(F^h&5qsDME`-=DyAF31s!7-MUvL^QTn(dfyV`TiZhD>~ASXbTM*jo=*l zK}@(fAV%>+Grk_i8Xq&7pMBRw-nsZ-c;}RU(%7?091}CzZ^%Sk`6si2%y2R_B%Xrp z?t4V!PLt0PcUZ2sP&G7r#FfRXg#J#A@G=Ge zLu84+zg-b+F7V`y66;mfX2q9tKyJ~Vyb#~ye;TQ?H#`koX<(WmKL7R$35`5e=|@yG zCO;Pq5g98$+d4yC(PlKzIofQ@D+j=l>UbNfekR@a$b9nMPo8@AnoK6trmsHd@>UY7 z6e9A=G#&J%JCv%Z`mU5MX0PDc^`*9ZJynw%(!wxaHdxB1Ss&{ef+eETmmGa6uCISE zd^Ix0(CW<^<*-E`g+c|8Am}U*tF%Q%LVfjno`cP#HUd9T6lIl*sSMWUj1KJP1)%|PS+cPYhyrl1-Evt9;D?9& zTPy;VTTZktad3IS(zAz;+#z|sR zcL=i;QGef{_gm9OWGTZDX9>n#zq4tu@N4-Sdu&DY>2wbkOqv{EnC@x-%6BK^5){kp zhlUnX1$~!xnZ4ICqVzG`Khj6k9a^1j_0s;Ain~t97{^87@4->-%|UqlFP{%B!Rhhc zZ$0fvkkA(d)YzI>p-JbM2o;D6FzU0KACw0<5GKqJA&Y7I>s$6Q2GK*B{^}tmro}SE zsbMax!U|#tlw%jQR$MbK#LW6m{Iq>&t!;Ni9H?cA zW8!9vrA1h%{Df_Sw5XFw38Jm-MZ+JUursovnj<520%bfX%%-JaWth^JR6$F&{3$GS zlzomMX_G;*L(CgocU|Jctp7HzU{+ZZ44Ci4hh~aGxUfb!<*5dxFBO&Th6FfhDK2!H zmEgP+ACQ<(=TKsk5pshRT&iHNR97YAHjnU#o1)>$2ZNvK85o;8TL+@hAXsNN`&W)$ zl4$_N%G>-M<{IgOxF%$w>p^p!&44AxWzs zj$|<7xCWV*sQpR@i*?uLnyu$;j(cU6w9)%&1#z@wDyZ-z$>2KxB`mnl4g9?`YyQ9=X|k=|o?z z{R7B7W|1ApKO#T76;C0}Oo$W4r~F=CRuUiH1HH2=0}sIeY!)02sLnN)wxo59;+;DU zbuEK?LXpWDIiD<1NRFbIv8pQ^dr1KFW=lR|Nm*ouxFgdC2@y|^Au#xN)7$3IpJ3wc z=8L`MAl)U)ne?q7?u^roZ&Qy_o1IdBYsEe9Pqh}IB38$kru^pQW>S$HX_pcZBd!Z{ zA;0CICb`H|=0h6ZZB&?Tl?-3vsth3$(w8FKOJI0gT@U7QS#7d}*hDHvUh8O(sJ z#2kXiCw#<(mGb=l5>sq{r$pvmiJ!?Oj$JWC1^sbggE%^ufstH0#5(cJI`Xt)9@Sno@+JSWe0xZ%o%N+-i^;4NK(*7sD>~t zSuf1WrZB2aOT|Iv;wMZ-z!s(99gXju-!RsL!Zw?$8H^+^-I7t{0^(S zM5yhUvo|&=tg}BwI5UnDV)1WpA>}wvHEB}XDCEe&BWL-{*gwb9{6gF1>pO?q|G3{@ z4EXu%-9UNVh3KR*vbMZ}Oq~&&ELBkbFG3bn<0F7dwCp#E#R&(=>V-~5*Ed;ba%RSC zjK$7)!_y*R&`Ij*FQsRkKuNTTr?!jD*=E^HscCW>TItzi36z`LPJjhk8YdYgE(K`W zKf%&EQton>z-;ebb3EL2-6EaLaxk`1Y-LRJ-WIqcLklxz?;fTQUX(VqCq!W#lGrvj zyQZc^jR6xE-42o`$_uvxUxN2mn{$YCH*tc|)R`Ca89aW05%<#l^^FslA7multVL)C zuqECeLF0fyS^yEo$da6T`G7Vah!leIAx){G2`-$>W%y{4Nx3*crRM1NUXSN%K@8&u zOo=&Q_w^Pm@KlMunR(mFoPg}g`7*g~{OL;Vqs8b0PzUK3fDlj~At}%K0qI3PwH`;DC zmCW5tNI(){&cK4Yl4iy&ZBy#vSe&UveTw4Jg)uU`Z}@ZG_X-z(?0 zCv_gxXf%i3?(hDwpl6=p12BdFx8xdT0KOHow8}hJDh=&LF&Fa;0| znc&MCJ|$_mj&k zVuKpQM} zBmXN*oSz`2PA(Y}eFvX^M*Y(}COr4E%Q@Kei+<-1*-WRLHWT2^e2qCBdGpd=Xq!q? z`}H5u>G>1S?%e`{&|~4wn0n*LDUXp~-*n^G7KdgdHby7|qrs=a+jb_4J1Q@=$Q*Q6 zng)y#^BdU=natm}m#uvc<9tdmx?P@>+Qu!DB@mptH6m^Bx$$7+qRuCuG-H?5*bug$ z*k_mhY4@WAM)W~2j;hJqxs{OKj6)YFd{Gg~K10g%2c9W+7LEeB52A( z7$WXkhlQARhRCkK4oFH_RD-(LG6>-;>kv`|r^%iOgh$Wamz@EYKW~Fv$}Sz%K{Adm@+UB(ZMO5T=hX zMrDW_394*j$@L=5&qfE5t-r&36hNxu8u?gYVrb;@@FLn2!TMkm^oYiOB_S~Roc{vc zQgX9@qFnIyJqO&JME*DgE!b+A&BWr|G!ai=T_Hj4dk5?VJntPp3%SNn6}%|4O9sTD z_P`C&plW8ID-}bsUt^dRwZ`{@%8JJZx#SRDDw@o|XU##Yv`kobN&DPJzBcsV8>v;f zewJVL+zJH*0ky`)ZgLmUMPv)4F^TkbZs8z_+uTS`eW+&2g=_#u*V_M}7WZjo)&^Aw zAcqoDBcR+VMOcXm6(3IysJMU_!&BRhLd{MgS)$OIm^kOAc;43DAr`;!n80b)V!Cho z;!6urJHaYhziog{A){WysDhHHS{ZjNT;Bj@(v-ajaing^tT43WxG!HpqQ2-~^#m;KLKive~D z*+}_{tc-cKOvKFso`mLiZZ`+qJwK#m33a#2){UyNn0*eh(tFH9(@K^;@Sl;zehI~N zlj0K&s^A3HBGFdHh}e~~eg4}?R^r-vaI%KQg8=MhSmR*cq9Vn51OZr^-(MO8NUKX+ z8R7_IVO2f69_h*~^?l_G~&4*epyk%BzGj2H3ifu$} z5!wV{|I`;VXgp{ol}NL)y6YDg>i#GX)nGF;VQ9CDt#tCsaX#N@>u*{5{$)QI<5Lj` z$>gV=Gp$-`AD$53JvKGpiD!jm7yl7EW=#&Oa&ad(*~x&umxI4WtI7rr{QKbt%hZL* zCm8n~4|c{LU8T{6?24uB{hD3guy<4IB2CWJB%≷nemGJEA?)X5a4}_mh}7)DHU> z4z+oSgM>cdhA%6ERqjZWK)N%Jr;6_=iW^$ZTL-d<(q&_dI2a~PT}kn9qUP`AlI~?a zm`Aifa_A79Zd|u_%5-b^nfQ1DLzFKtxc<|o;#pw2*Kgj<=~)7cZ`$78Ur1?|vH6st zy+vYgCTt=f#@YIk4plfoq*_OCc=($g+t&}UrMN&dU-X;h~Seksu@w3BC#->`d*muT-g2AN%!P+Gp>}4V!Q?M z-?>K|QYoKc2DdGUc6o#_V&u4UvLOqp8&dN@OVTV>5k(`*&!sGs&kCD)7>x@W|Kp2Q zN}LWAX%H3J11$AvxIZynfZ&d-ERrG-D~VJ#d9s)Ezqw<~!RfF~>6dNf1vMfGUDR#@ zv#$Ch;;#!ti&M2?>1g#q94u<^J+Q30bOo6OIIJxGrIt~gYcSM?Q?@sFWL3{;IWGky zK{_}jE%X;hplJ*>QIounq`EQGSZ1Y9bdv|TgIb6p!muOtJh6>qLDWV)Ve)8=lXFqQ z)GCHGaao>xJ+&Y7vHn2;{=tm7QA8#y8b}gkA=SsdqBPo=_cO%VNzsFR67o8mo^3RA zcT_x3q)uAccm*Mew9lk%A4sfp=le04C8D2=&@)4vBEh#4w34lAi$K~OCO#YuAH%Y* zzK78+`@gHPiZZ9|(QW$mCND=rLjh+)+=8x!DYA(2+^Wd*}R&yAAO5`F5N!x zW7}vY($ZA%S}~-EX3}^avPbw=x8%wkIDacx9CHu^B?9i>Y)dWB>^9hEs~}cb|2YDp z)0oa{C(x_3N}`8&1N`{cT5Wv{ow=c?xAA{@F-1BG$)C;nR49U#ldy%T%om^=iCO)C-uone z@rdK?2JqjQv-cK;B4gkK%<=QON6>09Y$w#4ZBZsks|>&iCM8jjHSq~t0BXi<5CJ(j z0Xf0P_LD3VN{1)(HBO`B6Ro~s5S7(y%DQwUysNU?JHU+$GLzjv|l6PaDNkfWwaNeoxv}8vdhEb7~+^Xu?5gNnEY$M?!g8k!q*Oc9QG0 zE_%kRIAf7Kgq&kZGA1eb+*b=sw2vp6!kJPqnRW|_#!M+ye~=t9Sul|&AdTFV$p_mW zahA)nqB$-6DqXykt2sxZsGuIxD|@$2F-h;zYn#%#mepcEJ6@egGY^w-7|}Sk;Z1hz zGzgD~cwMg;Ocga*QP0dI2`)I^Xi0II50J_>xF8-|ZiZqAcbhjl`@LDqGQ}k+m6GS3 zq3$be${sc5zSLzJ3mvok8;6Z^MVKZ=Yoe#A4BJ~+aA@`QSC{(@>$?Bgqk$5OK5t?& zlL=24J-+E4_%mx8nY&a(D84uog3tZrL!A*`(7!`}&b;=)cbW21a!!E5D)DiN2v*~2 zGYxtV+E2EnkY^Q;vWc!}d;IheQLZeb5I;iR=&>rgO z(6a%3Cd=xC{Mdmd=;ZZJ?xJ4k@~dIOl*DvXDR``lV-6KAG3(`?n!@xeB(R9LjY}_P zk5pUdR%U(bF1T)#`frXLysP<_pLl20vdBt5Sqch^aKUVF9mv6QSJ@2C6LZ}k%bV-p z@Q#bUMp!&a%IPONAQbHu{Kj7md!fX_t~x(z3UTsus!Te6#A6G6KrDL&CY5&per}S? z{nDnTj%%@&ZhL0D(cXo26W_*`)l)Q~$Tp?aJT5o|+B=n27fQQbcdPo$5LXx4 z> zH)J&pz7fM{$?uvfnW6T(PjY?=8e+%^W*8x%m?xZHf3C59XXclujq7A!hgxyo+0)?M zf<5;?!+g(%dhPSc`CpPT-OGLN*J5NkLTgr~zi-*XED|f+R^TY;z&G+5khADi|2Ly%Bd4@qrng34iaB%`T@21M&?Tr|^yGF5^OQMTCk(A&84FZ=*| z5AE=t!)qLLmXG|~E4=?7oyV0!EP^M)kjGK1-3QfpR8J{`v6p?3@B33H`SHIrgY7&@ z-u**-OzRQ)%;l$4HKMHfDb<)!A>$bIEzxn9votq}YlX!bF zt`ax~kg>XUoL~IF9EYB~!cYI1oOdm)qJAS9E*@1wDWRIP7paWdai>QizdQ-)wwbnw8!vd7&00Yh0#vBap`H z-S$P}z3MthQ8Z0ZEb+v|krOYM#_RDpc`b7q@1QZUQR}B9&TBNl1loAtG{z)EVny(C z3}lU0#_W&u4=fHaQyD+-m%oEMe_)oG?ka~FVz>72fB%bf{6GKdlhI%{SbC9Dm$<41 zTZrydO=+0nIeF&DjYBd6;>j#n5sY^j*+%V)e9t`{?mzN5wp|bDKFea~Ec^XMdU}O- z?Eil``X?V^=yEa(Q$M!B=<*JK`)_=O&wO$p*4!R}lMqp#jOI$eQLOLtTa`7>gBrMCA+yQqpNN&nB%cP0^~Au}S>^HK19zP71u;#GAkqIx<8y zwpo4b1vb9A4;h8@*Sh4AO#GgF-F$Bnz-Z~4gIlj!C0I!&YjRo}QHs&eLjKYMr^3lVR+_mzpxE0pMw4 zPW>1oA;~^TK(|SCD<>MIFyVB>WAJlDEKQ<>fI4qJgLW$)E3J~xy%2;I@@z(fL)qHH*yNy2l*^^9YRhW7K@*_~B+Ck}A zfeC7(Zp@gCSGC?S24IabuexvbcbgXU1maYU9gKsq%F8R-weU}hM_m~;dZj9%N^ENo zU`>-X{7%5-B*4&AAa*mTwfZcHkg?JTv7O0~w$-;?d{R>EV!Fc^pxGGo=J5Jxuu;cP zjg49d?#eU#B?f$Lib!3xuJQ|#Zj2Q4g@UR-D7%jlq1syb1XXFV!SvJTl< z=JuWC_=(T4;4aZ+7|Ir4Vl-SxAsuNrY{{y@iy@aQ9L|27qYDPl2osfkBSGm(m19$| zz~rn?uGG@|s*J%%E!!n*4h8i|L9fSNt68TSrx5kzSY9z4J+{m+TjAv03t%MH$_?!b zt7w{y!Ct;}cA2l9-pj_5z_Ux}XcOEzh(k2Msg@F7IX))W!)q~^TKdM*tDT$XoEmQ2 z^XboE^kqF|-|^e9D-W}}_W_FDL!5D+Y4a>Yw@GK?KCZ9NM;VmH zxEne002no%5nJLdkl|GD21>DvOb&jE7fx@ncBLRgDP&0B3|Uxtmc0kAv6v}N3S{Kj zR?ChK$>bv(>V1;Z2+lyhV7M-pZ2CGdTlLgyG@7B7hiFtu#-onW2)tKvEG2u^HA%-I z$T0T4g2u=5EIcM0;vrk~`5Nce{tex-!*DdjWQNNdJw~#D$bD7qzN9Tw5I|+9){-@W zw5gmyElX+*q&8%mKXL6E6KmHBLXMY=k>p(Si#Y8vDm)#t!rE{zWq$_x;Q);r_1f|I z-JM#w^36@J##WJu-wjIoNTtWudTapI5(wl1U`mM*&vIvnlif#IlYh^)ZZeRJ4l@xH za2Ro@mzXSIahlO*hD}*uq>Btp2C^2?gpEagM$p~^9}7VUwR4@SO=-`LNA|}fNgI1i zs8gp?-2|isNorkCFMtq18c-mE}>p$Y*EGS z)9bR5nJ^w$(3C-m*C*XNz1O%_m6UN-zn?Vypj#$uM637HNK0);R;S!c!_JK3T*=fJ zbu8(*#JNaowQS5ovWp!^S>Io%U*j2-b6j41C(oQN`SjXhZj^VU%o3udlkJiE(9|o4ZH&%Hjr~dMFV($GbEA{; ze`1cLsrQ5kN>|AWKyr`_#~dSSu+pQH?U3olfMvac$U3DF)?LnK zF~pWRUVFeWln-OlrioTzqxP=GwQD3tGzTg0b{g+b(8=y$VdVjKItRFLY5_mG4vVYk z{DAU;1A7p&+@+W~igu;~C~mhgUdXmCq73QKp~O>+f%{4JzIkLy3zD{Ui_&Y|z)8u7 z400@0nFjBTQEIrrSbbu!p3H0s1h#bdNJyjCwO%500R#4;z%fl zm!a%57`2Z^ZxBkN4$Bb1<20#2$!JR+ofPZW6lBf5G4WpW{ifh<{+?9Knuc%l{TnI4 zob|Ct&FING!GAJoJE=J1%FyoM;_huoN>kIc1;JJ-SY4bT8Pj#TN8OfG$u)Yn-R_3S zjj_0OT7EK~s*lEc+3Z(SiA;B`@1ELg;&+-O7l6=os^|b^L^|6z)z%Hi5m|z#d7B^o z(fjz3pD?V=J<0mMi~Q!l{sjN*=RZ!Te1yU3BNSU*x^G+N-oN-h7B24aAO7ioz;E?q z9nt{1CX=u(GY}OeCx{O5+GnKe7&DCC_QsBsSO8zB6x7g*5~~yHW5N%J5kvTB5Z9y- z>UwEXQe$MCI*^>JtnjFRCtu)Uu4YdF-8zb|y2k{lqZzQtd%jQknZLD&Os&vcJc6<3 z;~^@s@9MEe7+!&o|F56tu}`iux_m$M2cSbzN>Bj1)4KPJ8_zUe%UHWw`evfnB2${z zO*(keVH5@!GIvOL@6W!2@}9#y>!%rIi+pHdmd|V)qL&T0cVWnT>=!x8moPfO#%PaH z!tp-A&!y2|izZ+cXGS5N!d)M>5Ldeh9v2R719AiBM_oR)b3Y&3S!8Rd(7%HCIW$(o z1R6#YjIY&bsA%)=>Pw78!|Zy^%Zy`aFmB zF!B8{=}t8lwOmZ^3R32%J;eF1?C^7c^?Ae=IOoIRNW(=oFB}EUDHFdA#U}{42I)AI zrhL}1Rxs9r-MDw%B1uEx!XYRCT82Aaaf^JC@8c{-IZsB#x!C!&q*@Q6M1& zT0Ny0yki)*+J?Sr0&R zBsaq1khP4XbTZa5CBG$(0% zt2wC=&}&3!j@w;HPWXxU)5vJ`JWsNrlEsiNi?4jsK5S+#Hb&Mr<+N`Ecuf8z3QjPi zHvB}}qf83C*HG7;1+HA)SD8FI}@NgCfg$*n##S2#7Nv4I3F*|kZ5AFr8=qA zr*U_bbovi4Q)>U;P{Vc)V2qP>|$_(rF7#H)mv5_BP zxYx4({ywAWCDzW4(4sb^6JsFg`eNmGJUsL0n?CYfPeKq59 z<2cqac{dssljf^V++*CBozxh2GX`G1t-eykZoGpV``*`2ue`!06|Bi`OpfVpt)-Fj z&{P`@LKgd3uY!1F3o(`kLpm3E#QyykxcmO6*!CaAm}Oqb*ZH(Lf|z$Adyc|^5`B9I z9+{>0YzCbYrHFO!T%!fyCz*e$Iq8%~q)Q=Pj1*+5U?PB{p)k9VW)0ogavdLuX6jOU zQr*vq@zOz#{rzvn5A-~SYL z>i6-i;^K*+P9W7j5*5sFimg)vcAm{ahM*UtQr3uKP{CE6`^o*J6Mwh#%}1|ArreCr zHa=Gc2I$l#dhZp=2cg{Ru%mN4BlqC_Q92o%zw$NQ`Z>O9aghT{1rCQXLox$Ma4Z;s zRNEBd-_1x7X|}wXwiV;hz2J;+VSSE|JbxFDUph&t7ZAUO@grOnIg&uH$q4(VVd8iB z8yYDZd|hk28DY~fhd(v3mjS>%iDlDOBfBatfbuT~;{Dy|}@T^6c~Q^mAviEN)Xm0Y{QXcx|(M)NU085C(W$AQ>7OrbHtI>|34dB}~Q z1xv&b+;Op@wx$?g9}+4WL z4$hqk?Gj7KNQiwK8zN0zZ0IJ9NZcx;PaAz}{-p70+RVG{r!=c|Q6B|VLt?tLXXGZy2?~1XWlAZqm){pa*->~d=*yDAX^1Oo-{W|hj5{U2<14hR+(R! zr!(6{aCEGrV@h((G1?2Tbml2D$MLtH<-q-4q1-yjorhub$~3Fzw&@QYej4=lY24f_ z>arTfuom$h#B@-Uk(AU~Kf7TClfd$=Ni9g)(k)6~&jx-OPtpyHqIrEV+{!XzyPV;w zJIpXU!ZerYvJ;}?#862f$Ow7=dwBj)(f zBiIvCv293iA*GF{s5*@i7?XzHqyc#|;XA2F>;~*L@4ef-CdX+v+Qk6em3ABJ-P(S0 zLH0*7$X{1_wSC^Lt&_rNQdoJEVSKNMe<$T2)z}Fq*Lw^i1tWDhzl!k}$l2yU|Dj{N z{gH1++ax^+^kkEc_f!$_p;Xc?BbTD-TvfL;sC?GsxJx6R_=ms6(_g#{=a)fJ z{ilgBZM>&af)4PyN#O^0cNwIJ#oPsvFvd>7Yfvt%nF40R3C~(GmL@iKILpldn>UBj z@vTc=&-_dp8+E###5!8t&K2&opJq;#ySh20S-_AZV(1qm9{tr1@xT0=N4flG-_7^` z`3KpVKF1z8!y#TGC!D-YJIs{;03ZNKL_t&=4m6`WVP4S*_Md7p$JS^tmb`Wt=oEd| z0Z~5xxgo#%Pe0Ap>Hs!xMLXZTIZ9`c{SI)+%>zsPV~ni zPj-_FlQJzmvjugzgL2d(oH>c$UQ@V_k z4MaR54kI1Z?BnvsuX6d+uTylk2+kkH_+Ciwi)r*qfoeF!Qe2LIK@jFqa;o)SG4n~j zm-^Tk+Z%@dW@Fx*&q)Kf)@wrELkGynWS&yDICd2N{y%;fcinfL(eOH!EMy|PMZ`bC z&;IO}`0d~RGDz&_u2EjE)GlfCHyrh$l!(2~kN?Fx_~HNRc23I-Um6_ZrT)VlKKK~> zSmem#j>rDV2iaO1v9aC3op(Tvy3vjIzoE~&@u*g|d{fgOIg+&b+2k5f8tFLkbI-NS zRet^#ew~$n`vgDz-+vo#{lPAMzRY6x3JWGW)HRk!tQm|89%UUbNuiB{0ta`jwwK{;eB%#H8L{*D|dOgN#S^zg#;f?KALr9CdxxDhwf=#tyiEl!BQH zt=Z`^`olBul?|?Zc#E}i1%KrLvL$#%NKqgxqB@K^by_i6FZW8fZnk+hJ-cC8+)!d} zQfIkYzmv@qdMHu4h{Rwe(WrwhAkyPQA9#*WK6;8ggPxtoC^+v>|0%Yv3;q5+tV9@2 z>wBkC5dr2dDDx4rRB-aIy@!L}^ENugfV+BExW9Xj{dS9v2k|A&;@lH-( zoT2PJ1KdN#G>YQIp<0FrG?Ud$sKA`&3Eg$-{f&Zhx4zu0kCT1f?Yfr}*spXynfUva z=(Rj+Qoz3&!}uFPuU1)mEy`C?ay&vx6Kte6Hd6RK8J;NuXxC@xItYeLLbT-E@)>6K ztReg^op|4q+Clg(9?$+HM*BcXbwV=DO0!UT@}swQPPSRJ!q9`L#UdD^SReH5CJ3rf z1>1yxH>rT0da);8cuJ{H&y;E?LKclu5Wrj;@dAToYGB~09rVj3V!LrzeEncxvNo@% zM;U;Pk+`Ngx+dTQV#qT?MuxTVBuWT%Ptys`(wO^HTd}c!Uw_c0r8l0MtNUg=C^@x; z*y2U*b_FN6%(m@gWs0uP5i(ZG5np}bIX?TvoQvP}UY;+%o6CHPJ4M;UCbQB9U&crV zNGWCF8+#;et{738Yy|NJFC7MEi7jRkW7*ib!sgRkuwEkCLtVyL>gKEFr%hh`dhp+y zjpJ+Ot$&og_D0B)Nf4l(i>mUVngEm&4mb+VEEj5C8UdeyQ9MJ0HP9;*7A|EcP;)OY zc8;+>@1f=ts;BWL7)jP=xJ!z^IEWxiIC!gyIMOl#ugPgt0*(&zpk0bs?4_Z!Fjhyd zshenH4sV#Eo6K2r+Q*hal1G8Zho^^{jA1PoO!ZbddC#NVbKfV}ap%eC(h)(*lN7~m z%r0c{$vL5Rdcloz-vl3T+~3tDYQorQ9@^rrvAFLs4m|Kxp5_itxnaex`Hg?wkOLkai zP1cxV8_|9Mdk})-J06@SKzv`-Gdn%v#GR+f_-%Ijm+5q01darjqf&9H@lC1|t$U^Q zI?mslRfn6Oj`#Jo>i;(aelORCnqKRkd%0_GHgA)3Gp0Am7hpV_qghaD{5v)5*lgc! z_nx$UC;5)YF~Z?vuB8xcj&Sgnsz<9soiymlWgiCHaCL;rkkVbn>X0mE!i6k27XjG1 zVA}YWsH2sW)<4b{(}k%XdNTuHvTrY^OEl~QQkB|JRzNkL`JfhwHEdy)wTs7CyEw~u zHjO6)uFQ;$v8~p209;c%wx>YZLZ`Mkb9cst?^tAhaD{#O8RqTpa8ORsV@Q_~MoYX5 z*k;6Ky~6e7Ip*f}u`Kdk^cIJ6yZAO}57eJ{UvR6;M$`3c7yCly2Zv+3{20F5vS0Of4JCe1_dI zpj{l{RLNjO7(@&+(_Ok*R`GXZLT$Fv7Ys)w!%;9)UjC4!oAqxuMgR2za9*tv@Oskg zVHm$&^m@0UdA}4nTGzC#3k+l!$(fq&(dqUm+>pE@h#z51D9P>oHifKK$vU}aO!*ly zxr?6bBQ8WWYxO^snmT4O8n6b+kz;ecKy68HI-LX^)u=`d@CwcixF#OxZ!4wK7-d&` ziw)50!c;dX-~oV)cZoF;!%5w~IzYK}AUMPemM(@F@FAL~YEbGyr94HY-dONm3?+)I zGI#=HYVpqFoue!SRmb(U0cD|pjo52Lsn9q$=>*Q#1U9wwtw)pK#iSzcuvx~!+zg{) zk)_#L=8P~eJ9KpwtCn0dgbrRymgivZzyW6F58?6^24;?du@vHP>ah}zod}PP&k*Y8 zrgh%1al#%^R15Ec$>$H5_50l;KorodTT-%SR-n*#llj zKo6Vu$c)7oeegr9SW3zmfgBCeCO@2vD60+>d5z;*fkHyX^wS60_#IH2@N@+*cvrB# zc8S%k=Mi%O&B1w~FqDHeN(Yc(RcK1T-RGy-Cexf4L_$Fe8zV_g-o@mzh}mJ}uCu`$ zYYZ4wfR`zIS75?8HKl04XjYB~lVak(#k2OEO1`HKQZRwmg(_XU6t;-DpszEdv#&`_!w-s?3`=GjBwE5%I;O#nr$Y6Oudd_{iX4Oaz}Kq-GS_CHG6H z)Ny_n8XLv=SVeO=j9FbjW$69ujeWIqxt4Rjmi=GpIIp+u8_@@URoyZC{9kFm!+N{l zifZsX{U%j|vwF3CU+FsrV>672_ZVTl_1^c^f73IG`t)Fm0art)142QUGTEo}WPF8e zOmV1`y*GRe5J&w{+B!Bi!ByYa1-?r2GNdnnzHL5iqYs~dneFKjF-(kQSQ{!m#TXEa z(-b8Evl+uiR2+SPG;~$4nji>Xm2S67yY28X*li`yk`Xgh$0oZsLTpGy%iiDF#n;h+ePjHEV2y*7pO zmuTmCWiI?GbMfYv5lA|ck*q3J=VUcSPv!Gq_%AOl@*Dr+SDE_s*ZIMpTg#3I3c9Y1 z6@nAn^A`jkOWg_}_*{+8{@TMVEVU!MONlB4XW}3J?E87(ojYl_ z3yermIs$p__;>%`6a2v+K691vUdy>wqj7J|Me#qMT*(2xn$uIguI2AT$Kvq5AY{E1 z7&5GBFf}>JfBzHrao2r2Xck?ryZ!~#eF|d>azfX6qY;?Y1eH2gGBT4=lY~qH4{o3R z$;2F?z{^u+3zW`(a;}o=;C^g$whBU-)^)p;sZR zY0s}V0%K$FiBAaM`5h85QPcB*rQ}>Jn>R^_PqZA&w;bn}nsj}}>iGw&Ihh7D1;$X# zV>Y*?>@F-~siieuJ=Wx3{;RXRcK8g%@+poT*aoCnTgUk}>SJ@aa^C`j9Ysga*PBm< z^+x%3$o31_Y>w-%+r-cQgAX&et`3v0vSsTZ;=)+1&JX{0ckszzKA`Qb10(omtk<~$s?EA>b#w0Il&M> z`no{r@cmbv2jAZ>Qd!a^M9+Ghj~;{N%;^<={^!5Wu3OIY(?4yv{T6ujuyW!2Ikf!> zi}M?R1S`S8FB?4$uGuWx)TT_z z7?bG?6Ui(Ibxge^r75uS*nK@;HuDk%1{5|$0$CugNHVbvxH~P zHdv=qj7yC~l9&WyFdCZlCOXB0Oi{zq(i}2jX0x)aipzvf9ekpwQzR+-atS#JQyaFk zX3DZ~_7%DpTKIwa81`4+{Ll9YBpt~}R+ZHNQn<46P`oQR_38p=R&w0g8>mTvGEbq) zh%Yee0#GCd^%fCfJWJUw7b(VHPjfP$?Qf>pSpp^zxEt2?!QF6Vemx& zK#dW`Cxmz1zmAIwZN!}G&yx_lO9m&qPy%RVgj1achl=ZXu5}&rvW$`rHd*e?>oB0D zSTl~YnM76)?*eEl9>k!ohPoSR&u`}WM?S;Rmo9;wh1O1>f!DrS(SNimQSO0_BYAVl z)dFkU>)lWrOIUyX6f?V^NEa}T^BB6JTv`Kw*QUEf%8e^!XZPu=TiQDeGnYX_qq1o<|7#k})d;miUYAH8DSHK&^s1M0a zUQiEdS|?BEX-u6&&ZHO_L-EwdQZSdW6Z^U2o?Do?IiP11S` z0;DhkNk=l0t4KAA##EN`)x?21Fk5Nlo0x2Vh^%;x#o`5;-SfESGHb>&rY6R~8=TmX zktVQ>*J#)_3sbx4yyr&VxBg??aSAqd3}Z=HSUc8X#*VY=_Aj$2&){k+0jSczhvL2B zCy!w26S#aM=or^-P_LGyGBU)!aam0P56f!KR{6f%KCGOEBbw#sj*vlG8UhJ0hG#wA zPtxWuIWu;S6O%7seH+pjnUwQbO|TfO#*80h@gyLImTPgTxxiv;iQLEX^d5(2aM&*E zPVee;oA1J;Z^JY`$7lZhSzb8`97Vs@Ivi{qR=yA6_YC{{Cos&g6U zaCUAp>(*~#RJ8Xsen71_qK&&=@9A9P5PY1+qjg`b-- z&<eqPg z`6I0AjFu$?B`|t<^lBBU2D661)@tN!XuY*PsHV(bG8AqnMz(YD#H;-4fBrbxrUg#u z7)wQsY~dBozv6+Mf}+2_f&14CjwAk`nVsMle&Ji0n;WMn9L89X1g~}4)=1IHRYLnC>k5+Nsvoy*mb*fiEZ z@4%Zi;2)#8xWw_(E6h!HsZS@UFXE#aXg12n%xGvl=(PYTQ0d^M1+)?AfM$e7Wg{Es zuZIl#5&ghrzubNpK)u%emXfmN&NaOI6PvK=S(_MM{!)|u`x2xGbUu!Z0!wH?OuR=x z>7sNHEQT6Z!Q$!SL&?09wz)$2OD_}@+;;P3e(Xo@XKH#ZBy?Dz(^Wbh!@@$F-~7!- zIP}WtFxCNmQ`IMM<$$jaedZaTsPS{Z@ZDT@$3two@i$ozhp#0V3C)`l%}KQgO%T=L zMd(U`11v6hP#Q9@i*yY|Z4y&EhLJlce8%idgP-}C2ibMK#nnH_-W&ft4cB2k1>P9M z=Va~@|j_p8p3e1zhVD2=57UB+4(+(5n7{+<(#RZ^4+gWlCMhuCh zcr_Hjl3ByS_6?k0x|K5*8syFpxavaQsOgQgADIprMh4YMTz3v+2QTk?g_oc0gs5)> zFw3E;_8MM>4Aa8n+9{S@C=Ik|64X;2Sc|a2*Y~}|(=RDDu~0S!sMtJ4LK%zEz_HUz z3}hx8sMQDtnYaKRT&DEnd-0$iZCK2f8Cv6Kxwuj=Vaig+grZo3TUo>M(k$K9R(vsu z6duD8q3|>hGc5`%;TS)-SCGal)bZ>E$0d3-I)6eR|ERZ2EA#LuDK$x34eA!HVDbREg2aT+PyI@e^29wsZ6SvcF__y721czy{n z>q3)`9ynU^#Fb@~aeRp-we$i1NC6{d_L?YO4V|3GFXsnO{W35%>^HdACAVGqy&Arl zV*WzGSN`HTr~!>>uohNMLUSU5o4#_l4hI0jJd0S2QJg!$#M(=|^Mm)Xb-Se~a*{;A zCwOP+h;qLE9E-I_sF@>Vx=c-0u#zK5oo+rwJ2wS6unkXh*OKe#e$>KPCCCBH2x;oGR z&3X{naI3MA{Ff4CFdM#qW%{jos-V}ktT9y^$ALM@%+__>c<+rEg;_hn%HbMfLJq&g zqm_U4yBY-kYsgWAEU~0ELDVCnIB}sdq4$UytRy5-LrjfMew-cG9p+mW*{rbd5jw>^!{MA(06R0!^KF<@#L)oT~G(n$0Ht7hS+ioag%cZ{^N=gv1;q zO%`!Za42F0Oo3_##YI2I1YT+lkhBrSIp}u4`&qiWi9$Q5Nyw53W;cxSuJ>=`w!6>L zwNTijDCd~gB+&IKxYC}Zw5}YvBwS!C2mDq}E^X)Fi8-FzH&5%54bN>Np{bg&h^?U} z3DpuVR1!L4Xp>T;HB35=NIk|P``UB0q>?wYj6l+njATHDo!r<#TtY;3&z^03|KGTu zMx#bi#Km1&*u>LmcKPJ*@8i&sdDJ;53fjpA4%Y7BTsFg+NAa*_K5`4*LXF4EF@Jpx) zBG;pC2JdpbXzZ$7mL~^RJf{{DGh=PnLc0MvjVo%g17!(@R1F%~N;l>Jp)NYNlS$vwsbDnb-USo3Fk|s%P{N-bx)BqBBLjM_6r7aSQ8YOT9mtBHO zP$@iTiY0LAS_ChO@isUZr0jdv@$%6ZnSXXCT-t+4HUylr(D2#=+R7kJKLap4^Ok@v z#g4V<5GsN{&?RoACWLY@}DdIa0}>EJb6(xJXGNWyg2bn9ovi3^nQ=tz#ps_`rR; z_^$7|4QnjoGVm4$oUOGvcw@r8>lD){n5IP|{Sxc+KVao7Et}wKhk?BybGS!n$TA`}1{o&2j%$6% zdspr695mfU&;-K+kl&6j)lr#3+&D@aL0Ujd*6p%n6-u{X5vC@l*}ii#xtwS74PS(b zU!k34bnP<6IE*G3ox)1OY;u}uP9WL=^&ykj)X8NN`;G~Zec{WTeLAP>3an(PSiFhP zp|A40j-H{Byb-Aa`vG*%Rj`^yhDcDEdlwDzQ&H5{}d*EiB25w%-5Y`Vec(C)V$RqsA-#o;QFD&q*-@C+3yFh~Z@`IQa0mrf z9L^h#+uQlliMx6H_m;`e?8W4p$+C5z3F5(f!T4GT?1`YR541XCLLia^FLhMvNLeL| z>EA=Wxq0(H+ar*4BqJG+VW&1`IYC<>4^NDZ4P=g%+k<;Rcm z%5lJ?ILVO2GMRcLQ6|uy@eovniQFq8n{bMAWSm2iI?ZH;f)?0wBytf?hk3t|=iL@A zx)&3p?{Q`NuL+FsVrg-$T$FS)sNZ{r>*Rki8t-SE;c@BR4eB4bDpdABb1vD1G zpMm)?Y-b&ziCCGBQ^KP3{_dY$$zwPR#X5?jG>B3{J0*ZlFsgcvvW=>@KzehQ#kTi8 z?lVEw&wjN403ZNKL_t*jMx5IgzAG-?$N+_<3*-}VQ@HkAb+j1p}UUq)2&Sy+< z?JmyKZJpu3@xvT=hY zFmR~>H--9fI^7Nje4X6YxJfQBCoM`NT~sh-;K~H9TlL}RIU35+jP&;014%W)v6A4m z7Dl370`Wyc+i&FYLlb=M(Q%F(-T>V-(5>|{5_;WaODc{Y$R+V?!X2+AAl%FBi}!Y~ zBX=ofx&9~qfv=)kV~Qrze1?R-pp!OP9G|9>T>`EPK#5iYd>T1)eQ=kPWD=ilWXtv) ze9sTu%-Y$D6uyHKOV`(FcP-)#84bECH9q}?mpF1b$56v*d5%QDwUY4@PAHyTRgcDX z7zd|(Zja@>lVtlVLvi5eap~JF5QlDV$jvFXyM_9MJO>OE?YBfduN~l~A zFq%X_Dr9zhNpPCr6+9`P8##J>n$Lai6z+IIx7ZSNm^wt;sOE9J!`VC|8OgOsv`0!F z>Bv4xg(svaU6N)IL@btc)C7kIrns=PR=CGc~**ovqha2dpYTD zpqrcnVrCi|i>lxJnP&g>ND1_nHgK$V($W+8M*2~dYcF68XVvjcrwIxhiWcWPv0R?O zXRAHGGzL~<0M=mf>aev_-1%)azV#zJgMVG_T+2=fV7&y&IxZGrUZU&T7?ZGK zJvT4Wp7(Ad14W@`mqzJM``x~k_@o^ zuy%Kyw)Z5Ol6t5~le#!E>!Xtw=*Cn$LWYs8oIFzFlfV5Kmo6+KICOa%+qQe&^BtSG z{hkGq>=9h{IL2JWtBsc~jKwQqKIvxy3j!`BGrQ;>zm5HW@Dzw8+r0yl5VTgKp|2oi zB_ODY^DBai;uUhK;TZ>Ngo?y|o2~wJe{1NU5lA|ckqpQ%=;VPEYvvHTq>Yml^*_ap zpCosSsI);^7z3@bHl6y@XnHrffhH-oSmXxt5TeR9In9_|M7>go!4t|J69b8AjMy4- zrs%Mqy0-D&gUNxEQ?i$b#=e~wvfJ>cfpW8sG5QOPO`@SD(nY zhzvy<2aLi}`BqC%tJ}a4N+8R;(lYZ(R4~+fO0ehL_4ZRWWQL=j)gw(n{w~Dd2}O>g zEVuS@#P8vve;#S?i;aJS(`dw_odj*J0iD5gr!bo0alMQj(~AX{XCjx4sEp3~=yLW; zYQkBEF2f;U;7KVvp_ZmlfH+gi3{M5TmQiO<-OIeTf!79rq~6~pvZmFs_XB%~kGN@>g(9f; zF(?6EVs^ZT5F{D#DSq>$vewA(Jt%Pr@)$9Ag<)MKm{`_sK*tfLad=wx(>VKij0u@B zDxQYvaF?HFw=80`Mnf#)dXg03v~1&evYD274X7b1SbWTj4zwl4+Zd`+5;KiYcH+$h z&OVE;e;TJ3Y1ta*nd73H0$-!yH(jPHj@h+LWT3liNBMvb7Yo8P?j6g_Nj}c}s2*9F{@}psK`jN3|3Z z@^!tRLiKiNz6))wp!p=YONi#c64sqVWFDo}%gP!(KO=c#QraD5*1xAup_HOzkWa%U zfn*(xj*y8Zmkh*ENSChl%$toY$Y$D!WnP5+b|F zomBi2F`-G1W^t|bs223I;;VM>wOq5x8YBsr9h@>Z(X{W!0J~UAYR;hM>9}@UkQ9#r zX#sf%9+3o}LY6U&mpM1_Cmf!54c9F|0?@9Jdc{QW-I9d+RxV+aOC7 z12T)s981X>&W+8{&cLJ=BVE)5&!j&;ChCO9$K9hnTV)>eb+B?jlFnf50nVh`Ia1q5 z#}`-;8syCCIclPat`MFxA2@y0M0@T|eEV)}dj@GQV`$*=DM-)K%D%`_{YC1@;}~fM zdH@s=-%nGKzMk{F>JUrfC)riZaO3<|v-kRpYiN3J&mis$h*I-#@pUzm}CW2Pl3doxsXZfH73mg#u^$x zVLVH24PS57nbMSvW9L{*W_c~y%l_;gw2M0K;m7dL90h6M3viFGg<>b61hRS#*Se5t z`EMlGELDS|e0A|}Td90p?HcsK_%d^)1W=3^tk~cHs>TlUS5it&1XWk3LY1o#WFq_@@N8#Spv1y()z&}=x@978CU59q}MzKeCWy@ z-&+U@8!&|CQYryr^(A&AB~P1FrX@nkYA~44G^2Mz2ScbFVZU$^dcci^o%iiw!(BUR zi=(E>xfho>^27>BH%HxBiteR8_$nakW5b+izVvXUN));rTj{vJ;pcKB|22yAz{X%~ zE1`VXV1v=`JEY`v<}J_t?qN>dc!s%e-$t={h3)AfW|9@G`u-DF%|IUby9D6FbJN4$ z4d4T4>c!%;!E(Na$Ddf{rK1g=`pRaGJUfXyr9iC`>Zq)0D)h4mq_@H0sE@;4-*q$N zTV`LP2L!juuYFu7dS#@i9x0acwMiQKk zQTR5_?!#w)1g48M;g>a4Hi>7mhTvHuHP9M4<0O)inhen~U=0bAP=b4LEi_V)h^6bg zY~P*m!H;ia$KKPVYyJYM{W*zQAeD@SwPZ{q)Jgqj>QeCCKh)rz@4A68JH;12_Y%)M zF%L35ct+)#TV~P@&r3x31^GZ{5pSqfIyOz|@xT;btQ9pO~# zWzyG{=q&V<4&ThCO(W3tjY!nra)$SRV2*d(zY`ZLrjx|-?7ky>_D>F>Zfgu;!5jAg z<9h05S>Bhh{98v6@wAKM)SkPDFBCET0Bhh-2?1QOlVsT>lWR}&o)2th)2%zW>DHGR zuN}dsaWoOQE9qA(f)NOnaxwU%9%J(mM8?wahJ+Q;$t50qa5HEL@RH{Q68AN$F5G-mhX(gT?ERSE!uKzzTJddgZP05jvYgpYo_ z&c*j0WN zK)OUu!EiGUXQ}r8l7W4dKw!y)(?oDFkJGVy{4|^_TUZ2gbgl5tlzCzrzwdeuVu`Bjt~NLQ zBJ*wcVcvDBz5tdj+%SpY0nPQt_qKKh9bBs7p>9mg&{&ofUr zMAr1Fg38y+RIOBAg}_T!-ka5Xsnp>DWbtzsc;;!cdvB8;{Hb}SW)9-DOKy~Q(#4p0 z#ze>@rRxifq=+OWJ_$NQJ*dS?f;T44wJXA!cvGWY><6)3??t&S+(rI+8U{h)g_xTBPnOulDhzurB5Eo=8` z_W$dx+rxpEYn5;0`_*G!d0e{ce#37}@+u$r_LuoPfA2IM*9P^}lQDkp_m1(GpT9tN zWfP8+?qy@Vn!fDYI-#L~!8~>Xeey7h<6MzKr$%4*=alw)*k2vTMp|Z?sr6sy!5_|f z=l!0PGt{(6$RZtNlNJ(0Q-mTkOs0smC5oDEXzoOcu^HAR6cewq{(Wb8Enne@m3Q(= z=N`76Z*bwrGDluIM{g}vTN!860c8W^G9WEP-I4^~r4aIEkHKP8v8EssC6z9g9Er&; zsR>PEJy7^i0T-H36_I|gVC~kN5B~TxTW&qhtU1G^gsLB}^eB|P566$KpGbTbC}#j~ zJOz%f zAbygQPoLn`r(V0l7|YDhLFogIiZw8~c|FP0bS%v% zqkY46;4H7f&Z{Q1mA@1_hE1kP>XS5PCdjf&te-x`-M7v%K32o)7%TZWPdwM;?7YLP zAu$=L8ZMnX!^*|uyzTAVc-y^mh-n27T3w8!j&tI)^31aDAZvD zQgvkFG19;PG!C|?d;I&l%x`!Rv5py+vGoDV+uB>1Zr6D2K*8t!ce3M-uL+#1r>u+uz4MugSMy0)7>oBA(zR(j2LZM)&6rx z<*%Tl$~A{xCaJ_Pg@l2?9qJKGl5)r0?_h52Jv@5yVHOXZ1~b@9ssGHD2MYV|(`tmH z=N-qBpLqff?5EHUC+sUc+xi0g51hiw%@I(|D(7DTUss*0>SxvU^h$E2b$c}(H@xjy zL*Rs#*{wh~TV`hBs8Vv#q;ZtD{91Xka>-c^%Ac?uvRMcA)uEKXEX@3D4;Y3~_Ri^w=agZ}*$oX@GfTiJZ; zO|;r8Y@?E-4*QgQv@)PV&?%7rC_TNtxxyg$uxj7&MCt zM=C*yRd1j8VK2)x-robym;uHSQwMvBTko;F{k|I!yTsnR&ycP85`OGClpHHv8q$jA zU&ClZC^>eK-L!un1m3qe$9@cJZ{q1E*YfBWPjK+bB`DVRM(J^2vKaJUWbj$)U-QBD zCAfPnw%ADCIwAwMNC>{i<~^d(mMK^L2@al{<_j-+=GIKGZM_9)A_y4{D^08v+^|*o z(Z98q{K9*fKem_8{PAHHmo?sngOn=Om4?a|8Q9YQen04b`Dd$DEe*=me38|_&0$^h zde2RDop__q*I(s%d_A2ud`|uCswrRn>OQcKQfM0mtW9|Ki8_V5h0tuM+)tGfXV_1? z(y=8pg=~Z8B75(u^Nt6uBO?NYCPyVlO%cnwE%*t9olwtcY-+G&*O#d!7Z}$CGR+A# zO_@kk`XCmO6p;d>O+-9SQwl7(hUQSHq22a8_0oBkyDfI!oG~+fk-21n3tpK^H}m0- zPIB+Ack<{XC)xMZ(Rdo=xtHfvnRC(J$HF4@sTJP;(LHS3`*!wh%vmGnQ0b70lF=rm zi6!A{k97F@6HS~K?zpSQyT2vF`y^Dt5xU%qIIv4}vqN-hFM*!L(v6;cY{n%2?G^A?<03hfs-a`xiUamGLl-gB+jBDbWO@v zm$vh%)}5rCn=t?9V-X}Bz6R1e@*t^pY3_vYx>}8V_w~q@9T+DFHN3OX>|&SN$mzq- z>Vz)x0-{|)d1NSEk!V2m%ZI^f!R6O)cs_=BeN<4^Q0R?FZ7bQ1Nha1l$KE}U^S6Iw znf05-Sp0Um~N+TEEN`EmDChhn)y?aa>4V;)3mx8%UFkwfE1m z=IuL}!n2WQV91@ z;O!LD!WY=_wj+8PNz#YBY>RQ1!9&Ok>rWhW|j>+@J)@!Z9p)bV98-W|9~9 z`2CjFt(G%iI>iATLV{9ek(c8upL9d$hHE3Zrj%LNZhnqq|92D8z>|8)jq|X(5Axd~ zFAZy3aX^OWhsx`ffX?CXUkN0-k{%gepH|y;CFgRraSd-9mf>@Fz3~kH?)9AL{(U8) zc-7F@D}EmDvdSnb;3wfSn8?*Rtm}g_R_dlEmYlCYzQn$L4O(pBdp_|J?|*QNhN{B|bYGP2=0=F?}G1ZqYQa=gTr zdm=cW1m{jRa?X65|L{_SL&pjxO`YQ>p9e0{TW?Dss66{C>Zx+w4z6f_9)wVFPzTl{ z+JNjy?)ktO{_fA!Ft)&R3bn6MNYIfX1d(FBU^GG0U`Qi(caBOICyEmrt0WX-5{z9> zjgPSJk&XQF|FVd&t`bm;z?FLX8Cb*3Gpb{Ly=P@4Z*8f7JSwE|-Y7IuDQRrtBNpst z9=mWWCl4y`-{aW0@hBPX@SJPVM};cecP9M!&rDG_DK9>n@s)=zaA|p*jImg|VB=j` z>Jw905&P8Jh{w!&TGVkj=y`C>e(EsQ`yf+*x- z$+bqCN!m=HW{T5phTnR`aqiL{erjWbyQZFGT)xJg$q6Rb%rNu)8>xTKhxuRsk!9ag z$KqOB)dgkZL#ZfB8{eUvKqmL`vA_2rZo6%qG5-RYZ=*hdzlz678*9e-!slE3n}6Pg zuJVIF)8*aoS%)LTQm0Tur`<($g}j}B1LKoGdtd^8ciFHBFR^iFY|0sVN|A01ge!?S zB+bdmX>C&MEe30*$cv~uN;^zU^jkDuN&!uJ`cqK~cXy!LXA zkfDAK+>PL7`T9d$y6z}<+|lNN`zCSPj!F2zIdR0YXB3fwwR(cJ<}?XP-G?OqNtwra z#i`*>brIMOv_Tv6G9${YHQ;i^8=TyJPS9!!xBT6e9NJ-HV3@y)-tj{|Nch`G68Tkz zk5%qzkUYHq-dDCuW$fhT@&L z&0W$7xM}?vCgvW)kAv6iF>K(L`)_0N`VpDiYIT|0e2&_>Cvf9m1zkX-gYlQJ+9VMlxs3Y8LS2PT-m_5^G(jae z<4+%&U|cWo{QkXIn^3sm=;D2daF>gK`iil|(BslCv0nWd8_AnThS#uuR!zyZD-!sn z(6aGSLE7(lZ;r*7^Vc7Am zmWK}OozlTv{kT>8q<<8R*WL6u%gST)HC|7S8!U35_unLA`>WW!Lp}?t9=?k~9GPMxq@NJNY68RmF(VZYhua|>CiRYfVNLn;` z;^A8mnIcIHPKeKRw3Cb=k|2zM%%U{W;u6rI526m==l$&9k!~4DkSgF)t_(;(Z&Uq4zfieUy5NIO`oE*kWhkO!dZ`^>(HqkscPu^O_tKc-G0R)Sw z=&iFduFIXrUa!acY(M8}>JJ zXj^%#e$!Qt$IA+mK7$=QjLotL@PSBym}NxTh}ICzLQ_AnA>fCy?6$J+rJR$e<`F5l zZqF3kHajc}q((6snxmrNNP0Q1fm^eN>KKkXHk;<=J8om4c{^(+USfh}ru7KOYeXmF}3MYYRN^`k|9Z%{{iF7Dd&aiy`Faa!$RkUw%8G)oD8A-W>#7K%%GA#tdbI%@S|AAL2@_8Qk zuyF6&=dd#;C<@=x69#2@A?J5~;}Va2wuaF?Xt9^VPoX5>cJRa>w)xs0Uf>h|V44Ts zF-?;$9f8Cb!P$_Ikt3p5A4;}WgX+sgC4iNuqd{Mu4Cbe{cKOM-0X$_#%`;m?VIeUfZN&`*_C#lic;u zF2=zOD{N+&PyNRhzp?*%S~7{a9HEG>LkSF&eUHj2fJqVj{hV|Lvbn^2{@bF($)%1s2(R^96q9=U!!M!&hj@Jd&JZJSnJ| zHs0ja^;I^G{|-O&Z8woqr{thYRj4^7(oW3Z&5T+B}L^s9A#?f0i?w1-U zxOzQe=4}j4sf2E^hS&_jC}@h&8U};VMe!68^pR-HmLzb9UG8WP9kXXkP-#$C>d&f^ zTj~!R8&i~F!SZ`1?y+BmfY9%_zN(bPlZwMc4eF8DWU@a@+q=I?t}~;agaVJHz=Gr` zizLkQ{F4vx%+sgo=}8kB5K$Ct-JNpNEw{2}-P7d$Jn2N2ANWy&|HMg}^Sk)Pzdyx+ zS3>h6HG-rblX`G2_-9f>wT3H}Nq|Ix9pN!pvz5-mck;=9{W$v`Ie^U^Dj7|3Os*tZ zgXo&#BnvFO#Zlh&&J}*~mu5&BA-kt$97Y`~8nSdqaNbZ$GL|l^;b(txiQ`9S5wkgf zCN`&bmtpgLv#i^ZA#^FrgL`3gRg6)L`tbaS>4iSUC`ic+o?tYMrAQn3@}JG{8^5v{ zQ%quAhiu%CNZ=6ejIL_k&P z4sb&bEL7kUx<@_jv1L{^DP65cpx#7=d>A#OS*4u50~3lYu#2$@hGmtw0iz4z)_GIef?uV3t*YS#zn((S$9%c{#!BHf|K@=rRq0HDCJhWv= ziS1solepcTj-B*}c2?WVaodTz9Xs8z*6PV|;?*mIJDs#G%W+$_Wm(i{%_1q1GDQ*q zNq_(z@bG{)-l?k2+5O?1s#_0)WU0Sdd1n!P_uY4I4X4hq_kaKQe+S#Wj5dyL($|=jCz;8HWa>$=81ZNfKqY{YA)@OfjDQVhvJL*$ zTO1?*DsBG?soM+%i8RM(s0c3*3K(H9HTW!yr3ZqZyEO(e2JhCHJAQ#5{Mql|o_kI* zBTvv$kGEY4EfE}nmmOG}PWwFej{Q9LSLefCo6ezn4Uqv}p5)ZMIY0fnWsE8=*f-NLwmam*S#BYA^0M~~n8I~pZ3?xBp8u5+V zdaiUjmH{6MZyzVeOZ<=e0AfuwtFuT>_m zR)8KLVe1b2OdBok2A4wqGVN@Rc6ymI2@8C+WlT?4Qj@{(B=8;J=i?G$L1&QBoxm|% z`87(vLvA{V8ZsG@G6)8NO1+?21Y-4U7Z-O)db2#)J&86NmL!qmGOqRDax;rcFxk8_!ybrL5zuhdKkH>tdiP~fqlIB z)WUPu1g#itF`TL~NyuuB*wfhLbU0RJh&MW1L@`tqFvls+Rmx;Ye-3VdNQ#jOisWuK z?1QL2Lf4)}^@W&q)0DQTjMnO*ek+dYo)i1+)tbN=>|QUc-*-QAi4{wY-(jIV$CA8? z^P9K`lo=|=vI6>|!Rs}qTE(!C+PJ*>$d)sR`Us3EAJ7VytcDAa7;{fehEF&LSNKl6Ia~jtt z%6OV_0I&uqYY=O9UmJX2dBnZXXjK@($16@^PC(_XYh39Gkp91~Zu@M#~|nDup64!;SGu~hGwsP7!vWkiOuj_?dA z{REV6B|P&%=zAu>On}evgFbn=%urtl>EybDB%ef*7m-$hmkcn739KUT9HXMZlzp7b zL%(Ya=LeV=oU;|&=;tuyUm;&R41?3S!GPfOJA4etmRb_h(yPANps-&dnY@7QdYtBg z$wV1!A5BnAL2b~?h;ET?ncBW|*XL&c@HirG+1jG;Wj8PiFD$<>$38l8vAzTSH=LZs9?m0 zfDyzs(S~aGJ`{s2O^Mf%LR#$jhq=)IUM}Po8Le`~tx~jq2i2D-StpY`5@-s%&rvCZ zAeaKuqa{NuhE%SSaE8Ko`ehqs0*wTnoE-H9sf=&eR{LKZc|MYdl#(K7A^{up-Iv)+ zbB5&>`;zq-9!`Q5Dka_*sBxeMF$E?)joKIEi6s7)BgrdB`f^=l(-6dos__=$mNBQN zekQRG5$upxRyW4R`E8hWMqlpH10)}%iMUrYBU0;m2Vt>Hi*>yROwp- zX-cY!O%m!4NVFlo&D$PGy4Us^)m|ZSt&qsr8%J0J6Hd6kKIBh7dXcHQ9m;Z8vm%YP z^mY=~*Gn)3zKm?On(ZefS%zs%U|R;KIZBDaU{pyYM6=X{B`6^{aG?r#NIUcDdHR`x zYu6wj6})=Rg-XdjI6J{N_2E7$w`f-}r?AlrX}s&|eZ8?K*llFMcvBR3&G!MxBFdM< zqc~cvE=LY7Gu7=f7?xbPyvojCE2g$24e{u3T(7me7%Qt z8ZM*Sp$yKU#LtXf;IX5r)P;AN>CvJD$G_^g$}kx#CxuO|I#cz0tFaO)tc&D$a=-Z>wd0NAFAKO`Ms}pZ$UNT*x>`b?a_n_7dLt7rK@0)@XTXxA&yQb;r3I9ne0xG z2p}Uo9+&mel z`%WQ=!TAhjp7|wVX7)N>Q;;@Fi&`i`6epgM_Z&aDpEtebUa~9=V&U!(_uacgVpmWN z6)35{DRsJJlZ{z%@kE22qLoxc!xpXjUR8qOAkA$p{wXk~#`RSj?@E-Y(BN>o0`()L z%rVAe3{m7ienUc(zcQSS590kk7V!~p5NQDtF|ac1QR3qH0yn=b2i$)53EuMPG_Rgl z&YxRH$YSO~iE0nfkXBqf&_a_@bMt$?;k}^25r1vWo#ym`xI%~ZGU#V%P-0ZeU3VN~ zd1;COBzexhvc|;=YjNR}xbI|RpG_G%e)Z3=miWf}4Fz^2z6MAmL@Jad1kLfl9Ie0r zt<(8$e4ej;Ul?yK@o6!3Xq$!cn#Zcvy()D+ysy>%5cj^O(rC3ijUD&E%n8AtgbF$h z%u#`8vsf*u;9#d|sJbpf5i>;$hJ}TBmKPU6m9(RDCkjj~IJv&zc;Utl7`a(HWpX}22N~^d7Azb|Ae|tW0;eOa7N`gBbF3;4Jh04c*V9gO zj4ANmGZ=Wh6I!XzX&W3Fg*wV?ojdQ_!J8487FZQf8`w9o=R%UAMkxxz{jYl+vT-M( z2N@)u!SpQV!D)`3I?3|BB}97l-AM#hBo6 zr)7NvISKuu7WER3)7V>T_FW2^#yMC(41`dR<0c5yWVP+Jy$0h--PJnPU=-GiRj`-* z&JLr?Yq+g-GCXY@rUH&Mq=Jk1kV~d8lcn5wVwPdjMf5h3^+mSVh5jhP*p$ncud}wc zfl)yzcCA~{Q+dtmd1L<8H&?i+=~GnxNHrI#jGq=@5wT2k+uU={G9r%Cr!TX$RpLs6 z^NNuYRf}iL9>w4?#xp-bLt~T-UULW=r;3x5f(#KQBM_1* zKQxS&YJ3p=m9Z^X$sQ3gh~TjYu^eq=Vfre&1%n~s{P}_x&#iL$#WgZ(NfR5TEx`h+0!^#!BGUqpmID-Qn@o2 z?*q$4z^TPai@a#@{$D%8r#{lhq~QC(@OKWz^!LhGkNlHjgs~U=_iL!5bgh zdM-EvfV%2FT)o*;plR4*f`(5>l4v@hm2t#a!V9Ri>}mixI?z%=Ecj48y%6)%x);Kc zBNL~#M?y4F#DSD(#agMYqh_~ieIShn>X=DfokS_M;L&%S;E}hyjo>-E@v zhq;}@%xKE*fA9%@`Imo>BF|CXWbx24|M;Ih%F^;Q!`ua6!3;^~KSkkkBuQeFl>m^U zkT`~eHQw?4Z{fSX`{X#y2*tKv!A$;#$j+kvo0oXsO-4iWQAsr}qhZ?EoX70%7}->b zxJ)#?wSGm25?25Y_^AI@vGTxUNkjU+c#12R*#7hen>!<9G(uf9mTm;Vn!kT5hQqhN zk@25qyAeeHI^#l249ZCW;gS}Z3~PkUc#ItbA9aAoj#oU5%xA4Col9I7oS@$0G_Dmw z?a&miMCtP*f8$a9_J96X-v29q!f*bI$5AHY)dn_t#VM@zzc7iL&Qs&{Ygz+1tR3?k z!P4sB)mbVzlnR^_l$;;>@dtVPyY6F@4{@dN8~?}0`R#xEsklai(85R(n76*Uel*Xc z^*R7xHKavX&~ezmJQ^81b>Ie1m9QRw$3}|f4Q_oCq}r`tYHs*@#jKBjTHWha-h#$+ zHyrNzZ$5t0G`>|`iLcL962R^XpsTYdH0+;L&Y)`KMhR#}$D}RDG9h=CS633&cMSXHl|zdqhLWKZ zeD@^DoM4m3Q9lf}l(8`rA>6lU#S{)f#-I9o-v@v55k`e!%fQNvlCycw+6fy*6%@VOa<3Z(O&>j*MG*71o|ZAG=J)DjgiCP05m98N;h<7Lz#s@VEYuwU1u`vbgHGhD|nR6hPzp~El!!l(G^Gdm2_Q~E7bHvxws!N%1z zct&GC$5Mr{Ok*9cW@iGyQi6NTMo5K+L9BpJq@W%Fifzi8DDsLMB!k#qx`SGv_Ze;`I%o?=FW%POc=+q z^`y86b$iqXAJ+LwLMQryPMMrJ#9jB^&pmfe^Vi?IM7F%i#hF_uWt<5IhTRmNKVD5MFXR*y66Cy3TFp^|3;8Jjo?Ml6p%zRmmJ{}P?$15Dh} zCb2^931F~uBo$-SR70TxwIkI>Oax68jD+BDe3}MGO-TB;(UKtYzm*`8^zGjEK+?Uo z*KX3Pv~R_uDj2b#`_SQCmZ>?ct zqZinR^#`5=yB0@WIlIZ$^%12H;8c@gBVt4KU0`~?&4GinBqki+5I6HkD=cyo zZ2-Y}&+6I^TiZhf*uONv%v2{{rjVv!6OABg(4XDf+Tp^54T{o%FXH{Aj4Lu1(J`(J zvm5a{sdu)}yCz(}HF)Ro&V!MdTJoANzox4z!*3k$_YBiBY|K8*D4k~J$Se;%d<%?5 zSWR&vfx)69_MKc{^LWPAv28NH$)eq0)?Q>jJx{lDntjO&%xMo)=*SSOIVSrGi}Je^ z-BXOFXW4Rxki`}g^9!VjFt>P}Q}@0^`@ly@7c!(M5n5mdkbMs15~9O+&0#DAK2r~} zKSO5wq<()5R2mAzo`>`q)bvm(sGU8nfQg$h)#@Pe2 z(Rl1=!*@x@U56)M7_n}ll?xs5i1k6oQE6ldNaOfEn6i!sf;{YgacY{rHu=Sy4#=1KJo8v7+C6zLTqdKz%3L;(VIcrB@lH3hfRfXR{MRhat&bmB5br;zw%nZaS%xo3_8SC;8t9Q%ADkt* z+M?g{Wto{ux!xaeVdWa7ckG_&rtY^2=u~ysBtwyq0a>#_n-T>YY6%!aS(b=N zP@gyUYC?d<`&tJ*7$G5hQ7{}lIK$#%C;D)qhug-GCmT#1gH_}3?p5XzkCUJ&o~n?l zLCNSb$FuSXPjyewaaTBMF49fTa=iUGlFTwx;pk$EGl$>Jg^6Q)xO0%{-WR#$+{c(M z`m~LqWd)0+pG@)M=meiT*JY#$<)(7+`qQxO`PAvR^3^G2(VXG-WQ7hnrOT1Q3tU+{ z3?^ZD|11ZWr*OUu8EtBrI=Dn~`vm=y30sR7*}wP&7CWD(uxIJg!#mGNO~?n0tW7Z< zD;`xJGwZ5;tH#B6jP3^2$3G2KHbLB@6wpfNTJYWlP}74k^Js5^@=BW`dx$(gf-@n* z!CHgZY7A)fcVZb)t-#t~Lx@)IS9V$$*+vZ3DC&alwlU!zMcwYP_ifzvK+?Uo*KX3P z$e+{;l>wbb{OiHp3RIg_(63QSR7Y{O>o6{6F=lKQElb%+>9yJnk`7i=3N^HiV6CTA zgH;QX#Mq@LCuK;79i~XkDSqO=_#33}ohFnbFyLFL#+16Kv!)tApiXy^Pkihp{^8I4 zK4qE2>hdEF9-QOnf8l!> ztACaG#WsCka(d44wdIuc)+RIF^8*jRp1W7>;$Qy!AM^MhuK<&X*ywXtYzU8YAqD%s z`%d!XKlK<>iz%7O$xIpLZVUt0;@lNsI8u^C7;G1O@ZWuvFMa+3HWl9TJ+I@TM~~wZ z#TrrJkSRj0tG?i$^_{HNe~8*J_E_0qdq|-jT^BiR88(7 zW)!~{!4V(t-jo5IF^!(7brR#aY^3jMG+6^lDzb^i$3Vf29UPvM$Asg1LctarDr^$j zLB^zf>JvSF^Vgqd>*6vxT8`J(1W3M-Ce~itYk~PEF_mrXKNiqcp(s>n(c3^91G+;;B_Klcl_a^$c_eGx&gWDEpq0(J{ppJAu8 z-1}YM&&=_^MPe+U{>U?Y;9q?lb=CS;jrS1H2o>d_VtS6R=j*I!6__g3HJkBwZfKSO zD^5&w_`84q?VP&j0Bh+Q?$)oeHuD@7rB&X|o!@ge`)|90R&MySKmIZw{@st`MT*!^wp2UTD%0N6eT zT5kND5{fN)t$=_gvotcNs*3K_xzttlZ6S^$tqU(zAZsW{GAOD6001BWNklE;^=KoT3jN> zvcXXAqzkqq9tM+n4sBSde6`os1Ns^n81ut^Tq;W^oE{5*GgE!@S{b z_www&_&8trlPgfBjX;|r5oxTCLg(_ivSD`-lIGa!E z&xY$LL*`ZA!C;8e=gHr{fIj&}PQ3d8-u2-K5RolN}y)U#Wh4tEy!Wra zl^_1$dl}{Zz)Vy~6#Cf%Y#;nHT<5cR*(5guoR+A8)C*RHQW6F-%_X^=bM3dWzyCw}6s^anX&6H2vg zWhtwZZS3@Q{LII2t>2?-S5O(DUg?#=mNH_n>d6uz5r=3IiUU?_cx~@U^J&$5pIvnm zLXXEs5VPLuteucxj|g5JX=2FCET)`Bx8DGx??E|;w^hA`5Xf+`cvi)1_Eo};Xbp;r z1ed7Foe3ndDD4w0aAwH*Hk`A&m}d<=nKvXHYvVf>uQ& zYAws=rc{A7N--MZcXBRYh38+Hz!kGhcP%FlTc*u+SX@y`fuW>?YI#a3JIv?`iTN@! zhcns-4@JPq*T%U>8Nea0cunvwVWNF2OV2B5s`zpWD-(DvX=h6uJ~qM7y+AhkMPLEs zNF9ZIZG3BYzl@#d7GqtSOQf9_Ief?cEG{d9azLxAOsAerDKRLACR-eublh^sQ=B;4 z<@%Kl8=L*Oi3FBwlBT3df>)SWXpx<;$l*TS^fJ@-Dpoy?39joMoVm8dMh=;QnKjSc z9mhC+eG;1{bnZCJtFNDCy&Z^$C#OA!re9*YcoCzHjDsAzbd!UggrIvy4U~ z5G6~4Q8UUt;%yx%HjRGKUB-{WQ?fAIVrFKJefwrGNrp+=R4J0CE>JS=*_&YnyD+|B;i&2aqAXE}cROH3`CW~7&}W{8N#6ULdS!HY$x#%V0A zr5dAL6R75h_@7@!zi4kC@;EA5n)EMFJ$h$QD zrRZRpt(OjfEkR-tnwtfyZloa8nw)KL%3}8x%=TkQ@f93r<6#s`OtY3C(SdQSw=Q$` zsN==CIaJ{4`W*Y7U7)irw7o?%)NAz#jD|UvE^Xi(fg$0ec2&cO4~tyW>Tk@|U3zJ+ z1$HXNy(AekN2loA<(aVODJPx-d6mo*^o+7{>;x;bN01S$Ja5p>0E)OjS9;E>j8m1z z4n~RzaIZS@Lme)>ewr%=N*iM{9+n-9o=PdD#8?Zi3aq&BA+0hgBG7FtNs@42{~VoG z64;_Bn;QfA{TyS2(I_X+OUCJ*<7;cRGNz}eNHa^f9bsH813>OzWo4VeFekAoXi1tH zlJ+F3mWfHr)P#-C*C09up^XYgEk=b>a~4i6uyfxcS5Hl|pF}B*XhQU7KTD*C~@LEa({~^)i?eE9Yp>uhE%0O4oGIwH@-)C%C${h&2{tp-d0* ze7DPfF?{FZGaPKsFpXoOyTVrM83uX z6S7Sr8;FA`@yv8?VWM-G)LcURWm2wU4Tz6HZm}pSBbi`RCfT$WZ=fYPGt#5ud#JeJ z(2|2KYVBE(pbIY&6=J1f&sFnRf-_s`UQ3(@!5K9elTsEVR<4ZLyf&oYpCw6dMazA0 ze#beWfK`mGGGya^78BjaVD%mb zn->AtIrSiE{}ev^Q`BCqL6j6FVE_~)GDO7TbdzDXq-O*p!uF9aug-MIAD(63l_e(f z4h%h+wQOz-qIPy2u-s(^R>pn^lG+gQz^MZ3 zpwAQZg>$BD!i?X?v595+rzUxMYn~n%R=S+OBVq3T8IsW=r|vqyU~_KwN!kFnmhYif zNo|XR^Iu_Zc8)`IIA*Sq$YrhyY#u(}%yzp?jv->5UjB6Rhei!?I1gZE2@3fqepR&XZ`5Qd72N znvGKY_9pAYMJ5+-L%IhjMR3-kF{@8Cj1#SjGpU@hiZfq)3Sahl@U18L@&D!yrtDd~3^4>H8YiKIgry{-N0)7^*~Fx0C~1MjqCl~B zdtmgH(I-uDu0@%?37_1JO%+?rl9*|VLO_;KyM?A7M_bQ=JV3Q+?$)2V5&Wr)j!Ks; z77S1YhG^%D6fL1>Z{mt==74FR;!Wte#49!__|gCR5#IZr_wZ}~!}EOXPcM^Zvv>#2 zDbsVaEFU}wQZjjHiF5V>&OXJ-?sJHJor;<_!5@fM7sw5DGsA8Qj>8|au$mrilLQsFpPja5Hv|3?vbJX zijP$iA(H{q?h+$+f#Y{5Klb-eaCG4dbZ7qn2iQh9)kQ|=xJSnQR=v0(#Wl{%z}U6B`nhR#RN#bz1EtzeiJ5q zd4No3@n#rAJ|wI=_?v;G@fd1AJHS4W1#nFZZk)mI@(JDAZ$G8P7bs$}jz+4{`l^KR9YaFyiZiA2*o` z)x6dldtnTY0vJh1lQv~OK-IEsa;{FCVat7jCAq+)Tqo0QN||C~<^mTdC-IuFd0-7~ zZ@~8S7@UogD&uHV_}vn!GAk|wR1SEq-CFRHA2Bjv{b;F>x{Q1-6owF26+KD_jEf=^ zb(6?pHy-C5)6*^f+n;_X_r3lWoGU0@!XJJ3GEY3YN-Ilw`Rq%)dhT4tHHHOoRB(;K^Tg%IVC)EoAS)$7Tc;!(`O%_p_Jdlu@Z`B;3z~chTXgk z(|73P(>T3`Nrgm&q$*5`3zPsah$)zBk2v1yhnzT7@+sxyPu|WCz3(Ki+e~Qnp_8@w z;0K=O*Z=va5g*u=V^6EHk#8<`b@SE?7F1)uA~RI!_C08Sfg*F1$wkCpMbb@5_hpO( zi7u~0O4rB95~aNxo%sxy7H~VrB%%hvp{5EFj)APuj}Zw|1@ACX`Pqu1x`{Bv;joF} zhraJo-uv$F;?hyW;|n`vk0reMp+%-k!`a!A%bhLWGCRXNZhIGLUKQqzfzK)cX@p^3 z^4lLc&zZAIl332X@ElhzuEhOI$NO}nFV&YI!o<`J2M!$un~-K1op#ER!x`^;&rz24 zwJ6Jwk*6;BAI2)P2hP#ww~)>=fl+KcB_5SN9o?kkw=p;{pFylcu-*)UbWk2(N? zC?*lS4K71gWH(sY*P4bJRUVMy`PHmZg3JS9-3=G++WHFMwv*P zcNhv1DKRRcTB`eS7H(N%;_yXS{1U3G6y<%W6QD~k+0XUP2}IyZGRF%^ z!Z2NCDtVqobCpcD$z+p5`Z?ZcO8PQ`5zE1Bnv=KBGF^1=7}~9EMy-pSFg-*Kb8?A! z{W4ZBV8o%xSDD=RNtTx$V|9CmVR@8MzJP6K^xOL>U5}Al1>MF;m7eWu<4vP}-WV+N z%q+CHC|sd7Ax;ALhVfi>dT9#;g%)OefLA z3lYTt8cTdFG0N!cV~63=1Vkd^SxOXxmymwETfjUT24Z$$8_mdTNZFU#03DmdQDTBn zV9W0^s;euII>kiQMW|DP>;M^vGQ@DDHP5EGpVcgh_pbHb7rTHRX}sQRd+o-yi#x!L zpdj^M9W~ojGrY@CKNAOb4Ea|MSF_blm=GBKv%nPK(7a9QI*brTQqnRWTT7sZ`C2VR z6RdKZ{WO!w3SNczw&C`L7Pkx%W=lxD!K))_&9m80Fl>ZVYZg{MX`x2(-Z8F_8@+(n z6nVOF{)~TDHI%LjC<XiQaQ8b@L8LvBIIW0KaewJl@nHfs#*17$nE3-|0{*3ZsjY|2J9q|g=cBXAKICa8}0=Pj$ZD#wqU=G47? zx>HInjx0@>SQ(N|e*sv)7hRlp_|81Nxg+%T3A(qgas1&S#udTFho|LQwN0**q z&SyC7P>Sb(-D1OBVxN7UNxg{bI!J;zhu{z~q=X=w7{TJ0)E=ckre%P&V<9giKBfbL z$AeLfjMy*d5U)(j79Hu~#Zts!;4!%9oO>zg=q5oIkl_4kjyD1tssV>oLxOV+jWl{; z>~uEfvsPe*AZlZAk{CJ@hZ;o%%F!e%r>D8_y65hAEPgx%~-u?wjQ3piNo|?c^|XpU+VlpxSNh zn!ESQZ(jSbIqsYDAz0Zy$~yV7hi4VBz2GmI0U|vxG55=c=|957or z2Ao*#aALMi<|DzNVhF~$o*1P+C`mtak@c%@pu-%we~zH@95TMFk*GcCW41%w-?U^{ z8b+N1jM51-F-%SmIJEd8$L`KKe5}LB=KqG3n{RFvf;gd4zo69(u*R1rk>ssRcsIDRIn<{bdi*f8CQJU1(58D&NT}z&FEy0Fgf)D z_>t$3-A}i_gUo&bBbQM|&9w`s30?wRWAG%DL5WO5bS{9KLg2_)tPZeRQj+6zfV8@F zW~Q*MMUqU(3rn^zNzWJxtsLeER>jKTQB8|+Tx;9{7#4IW0~1jYN#jB*IQ2NSh_uIx zEkx}s1IE(hW!AC}kRExCxdR8uOp5q6n$A-0KS;5B2qPT^a|svQLNB|EJ2`{;770Bp zBaZ8{9PwvylHetPwMh%|EJWZIOv#&N2$5l9DM+=C@j>6sm@6>xTR1(BbbplDeJ2@u zA)U#vi(N{;$^6lCuyvj7txd`z4WMAOg|cpotlc5+If`L{h^MsI8KfVEWy`=_zNZ7kP!Dp_tNNGkKqj8l;5TEx7YLZ}dhyhKB^$F|as}1ALOE6fCNHjc+LnoI|;>W5Uts#8viH~i+_2KH&CijVDXVP z)MJ8|`Ug1OKgP?w9+;Pa%Y+2Wf2VXjYq7u)-mKw2aR53n$t#kg(Il%ii!^h2?S!Q2jKm(Fl<_CpjC&oP=9 z(8H10gnnDFvoF(XzXNq)-Lz8^6id_OW|h(ON7zmcSu#SjpfovXNeiKnq-K`}MziNO z94A!~^>O7JkZPY&g5#=^fGR2+c;9GM+)GGUXPVz*(tIRj42W`s z67NS?Mx=~_^9ZPonK>d@sbp-Fgq#_!$8qB@l0?_nQ}dr=YJyq=TC%9;SuiUkD5(^b zRr;T#RM`y<#cIwpYfN!H4ilwPRjchNPZVa;2$Y6%R0M|P^i)`mk~V-@(9*_4=$O7mIgg+H9-Xf!5NKe5mGy}YO1u_aBimtFjh-?+FtwSTNpu(gmt{EQ>tT-x43d`nQk|sGdqKq9{3=sg!l+R2D^2R^E}8k zR9jKp$m4NA>Pm$oO&O(-^AMwS2}$~BJ`q1RP9d+37np~YhW$5c&GFy-y^@*2G?L2KR(seuFLl%OkK*R;`G1e~#SkZ1@DcIW4FN&}IF3~O! z6-u+pPWzKgWS``XGQ_LLYPjB8;vq8&d0QwN4AlUVhV!SUq*R6F{fzcMgdKI5-k)In zB>kO?Vb297J|Wno*5JJ*X#mow_|7ptZhv;XHz7Da*W3>!S zeiZ0~-HbL%@b8Q!sDL*H6_5C^mMcY&?vWtQ5IoFa|2s6+2?}Z9YFeO5<{aJ#BS|T| z!Ml_Ve}$Foqohu86O$Y|1jB&=YeVc&GK>$JnPLnjaDAgsF)D&-KuMyI(4v$c-5HOa zpQ1C>!AX#)nP5o93Z9_VY6yWk=-?tQ-nBhCI*i1kI8von^TfxRBzglddE@F_%I;Nq z40}t+*iaYtY1Jrgkx-&Iw@Ak8NwRw=&G)cs<`}f9z15(`jO{NIgPyx|?Zd{pmKtIbi0RCgyX>pPXC24P zkf2xMrG?i7BLfDqLvlxlhkoW^M(G4I%K>cdOlLfGWSzmvBK=mEkiRVimPN%V^;Akg zL}$a)_ZW5xji8o|pD}Sk4<><&c#=jkQ~>2rA!VB>Ugk%C{1AWbT@TZ8$C1)f(q_90 zqt11#Cb+4R3(G^Uwk|WpIZ_{3ucauK9WvRbs`{rCh;=9~26O{#Y_QZ-{p#xxRB|wv zDg2kX<*sA=!(V-ve%^s>fN!r;&?n8O8D2Zgum96O=fy9yfDyK^_f>}DgmGFI5TmL9O6{ZvFjwla zQ&|V$9;;f=;~7&mA01SUno^#qgG&Txqa9MQa%&i>I=(ilPW#B)iz$*J6)1qdt#XFb zAG*YU{Jjs;f9WWirx*#$+~5FI{a&4A&l%lo-)d{_3vu?2CsD-qs?bOEe+g`t8;;?L ztZ`C=E}kj=Kla`<*s|-o@B6L2&$+{!-|HDYH_$+1Y7hVk5CjBqG9`wCNUCC4Dk^p? zCsI5lPAV#YNTu@Kjw?x}%2ia#kxPmqIhJM3q)ibdK~e%iK$u9(Koe;6JiYndd(Sz0 z<-^+hoO53{K!B25GWd3(@$PW$8TVepf35XjAQUXH5~e7_ZhW?zj+{qyP_tp8YMFQe zpd^zOT+ECSN<>CvQsPx{!Q@rJkb}4F;D7$#Z(?n5i1liYmGkrb%YXJYUVLE@FCA+% zRF@>D3zOCbj=6`e&lF{39a}|MTUq5d{^`HP|Jn;k_c`wW2Os9v_f2xF`y4wa2Mk@# z&~+(XpEA#ht(NV6IoHbIk+H)Bm6RumL+LVPQZFHL7UP`G={Zj)yFxBIql{@cS+Wkr zJN7N`v%maty88-tb}zD^C&(wSaQN7>1UX6G>oMDTl#hRSn)ltc2j@EYwaZLw%#v3* zPCQS4cZEOr(hQ5E?d*TwOMLvj&vD1X1@hi$d~5s<)Bpe=07*naR9?_mL0m~^Dre8_ z+c-bGi_6b@iVLUsu?IZ&|NI8)nzMI1h@L=PiI)QJ3eW?y0;6O_+wRLDPc(_OTd-ZJe9_NB4tZkW{re6f1ShtmqZ4( z7=?^F#JE8rf$bWDR0g*zUWRxbMIgqtf(&4;d=)DoA}^p+_1S5#`J%xgk+V(Wp0B2k z*i@TP>sr$%UV}lE&auH1XV}YWnWS_%gZuz1Q$5_&dm%rBln)7Nh2e*9cUCr;PSq;H8&O@qhk{MGn7r z51;*;2brCJf*_|X8!j4Q5{=r-RdjU~C#!e`=L{rODsUCza{?KjE4X}$roRKU0n)|` zO7PL!9dRAE_Eifr%-+p&A4^O zXJ@})X6Nga*(xSqB1w>{$$g?c)ez;X;v#*J+4)l2*(sSv<6gvB!imrT(kM78JOy4Q z#;ff5mSmO-?g%U0c}mwMuU_SSAKk@mhYvt$S^JjJ?8!8zsxnr?ByXJe{OUjZ6HdKQ z0t+afia=n6O25L#KD)-pf9@8xAAXjBo+T9xdOR+;TE?3SwdVj9V61h-RUB$9qoWN0 zq?hS+8(L^hTMIgXSC12qQv>BkA`F8kh%m@IbdMZn;REkw*x$#-gfj9<6=~6I+NT3Y zy-7THy&R%`cC^-()YDj1DD8m*fzmlbKcmb9-|JJkJW|TNyT=wtx;3`OTaB8OyRB@c z`EJa4g{uwI=DpAQRIIS`=$~@@V`m9^nx!J++oNet`n}wYXPOmqS;I=;lfj%^jPd>1 z88u**h$mRCs@n%{0;*O7DL4|xmYEcG z4oR&y5h;giUYiyY1PwkK^;IMAHOXuPOgn5auLawWI=JyE0xx3>T^Wm^%SP3~OUBYh zMY-yjE^~HGpQ0lr3Y5_(GhmPCG#L+T70W(6SV^0UPF-wjm9(*n@x7>=V`k@Xarbp! zA&57pk#4SBDp?j#h>%<|$Ygwajs0NrtcxH^RJu|t%JKQCH94pm8JqWM zMqmTmTe1Q)C;IvJ8=iSFDwBYh~{>7b>?V$ zjl|WRWJ~Q#wnG{vDgh^ss;qeJnGJYmJIvh1+JE*D-Z-N4<}cIfEpckC$Av+kk)Pti z`UO;$anAHr5Cia}c3h;Eu^MS%63s|Zr3{`*e01_WtLvU(amf1WFiJb)sstg+J+3>! z)PZeGePkztBQLX%y~J%iPFGJEqh}CA3nu(`IKJtnLv?`nFnMS@+28<^>udD=1#YK?I zG3edNPku5mGj|5jv#1z#hN-dyh=Jl`pO|3PPbr9@Pz)XGMGr4MHU@d5qiTaSn?cUd zT9ZF$v=?eyCRq?pRVb^BOBV|yFQ}>!-b?%rQqq7XIpBoBhV93I$;2n_8vkfarx8C* zQq9GECu!6K*;O5@D?=`xAJLh~>BYuci7 z*Q~}tt}zKlFc~KGbyv}MY*!jWYWyRKT(dT%tqM@0KFP!qY+UMjq2R=GVQq#-SC24o z3+#}~l;I@~E~Y*aaCt3CKLyV?G`XIVV6jbi8+jjTyuK2g${ z`W{E_ewllJd>2DDC_?}#31YrRI&Tf8LsJ!8s(@?eSA6#MOC6hm?Ma(dSBvpzY);qe zDY%&66Yr@A!!W^>b!B5%Feryy%!dpPDC_OUxorokHog3q9&Vp9V9HapwT;wzNJStQ z2twrrGC^{O^t+HxjQd*e(y;}SZjG(+mgB9|a$EAWw~dM{Dcz{>CwCvg@0r2vdzLHu zELy!v$fnuZJ%Bo8nkzURL_y5B6jh=_lOl-Y;;Egn8E_PuQ@CkXUp&ck|Lc3uRB22uCVsv0#vhjm*G2}Vz^<7$+_BbH~t!$VvAnZ-lU&OB2()as3767QV_Seo4tceFtTz*t36$QeKJKE*c#% zGlW!G1hg(6Ow%}-bQ(R% zl#MB4^E^$^P0m@{-;MV@KqOU9*V$ai81yLZJ-0GhrJ03eoTbwIy(UGDNNrFmW)qBX ztjjE?^eE3PPjh8m>8;Ik;>szg){$x&Wn}9rnjluZ6KZqtYO7;wY>hM$?9`@)*bHEp z!JQ^^gn@q zO)XYi_e)DGAI~8&hqyUZw{ia0USRzz&vW3v7V`U#^YCvz$s=EU43!C%-f)D`0gwrV ztR)-babx>f0i3t{7(z*fuu=$@s!2Ao1yn1h!zX%22z&Jas3VZ_@)0U zV|g@U=kzqbyT(X2$VI8tnm)jYPG9)kXZLdNvZwp`UCgd$96tO8q4)-1x<*_TIm&5%{12_qqRp!nFvr<9uH%>g z;j47|LxLuKYgJ~c!F!#lDawf#C&BMTs~(BsqOnFTp#=vT)Uwi%TD=Lhbh*~Qfk0Wp zZ~po>_|ijP=kx!~4nFzQeTwh`ZmiK#Q#n=duywtf)LbZVdX7#wMF>hIU4qQ<+0TEF z`#*FHYxWzn=VhKyZf9=CSw`7c3E_KW#OeVcPkIcK20GH)f6^SwwkIF9Q7mn}?|I1yReeNcH=L=8p{3BQJGZP&D`~w_+U@y1c{s#=g zbJnCWHh&VFC5r@U%$aoerO9b-+hgNHTK~U#v{miclT1E;%H|gHpS6N4+eR4N&ToI= zNgjUaIb433>C}5561i zly~>o0!g>V*7z$KChVMZgb+Y-irKx4_H1Kg`ZB|8fRmg|D)z`5Ebs=CvQ9UwqKO1M zST>`9tpRnh%t2CdTpWR>i=I}LL0P4X^K-ipkhL|MX10qO{9(Z-4iPRMb7p9gut z?I3eG_xqQ*j(@{Emq?{Nu9Zod%7RoqPOO~Oa%@T@ShvoK3YV80yX^{k+t+bCidV-- zMy#-m(~8;SQ}mB}R7yfvrP7Ni9Yl&~K&DL2@hnUY)Ey5cDW+Dx5k+xgo!CW<6H~64 zx%}3n-deA%)Y~vdDyJL+VO5RSG~T0eS63Sa>=Z(2pE+~16UAF<&Ryq?wN4<}1qoNV z*40VOv@tUA#Ou_CQK;$bCGd@8NarGKXWSdI(=W zg(Far#bZ^}y*UNYj6lZK<&9foYowtK(3#4~>Y!OW+p=kpS9h&V5NKy7@(B`mQQr zP0;ULX8EOyy!yF2*;##%*T384`+o$44)_URJLp8@|4PmES}#~yz?f{O8T+YyO zC4>adWvG;hl*WbavUpxyw#^3aoBbjqzQtvPCEYS*F~&|0Ry{t8~ek zVt|$_l)8$SK;cTNc+COh2hSqai*c#7ojh&kVgx_l+MWC1#9Uwp@^q6Dr;`OZm=`mKGT!v1Eyfcr_tYXKD zP--A}zXqfXbm&tK3*Z%=ntb_jb_f3>dDQvacE_gDt(ZHQw1s#!`AM zShE^HDzsQ9443gs6HFC-@~U9u0-7a%#Tox$J^vJftDA9ZW&DT)IDZ))f8jWT!Dkqp ztsuOJIODtYYK8bE8pG1yq93AHo%6M>A%#c+*2o8-T_H8cVEF?)^NmY!`@-~b zeE{hp>_C|$k$Kd~7g5h^S`)qawA(QJU#65bonj690vf9t z4T|=<7eDv}Cm%b+^IzHl6Fny1dn@^lZ4CSn3odl9CZ6%kvB?jg^^}zU+7#3-Uktu?3QDjjcgk>nUSW-~P%^r54xvMcS7WA^40c zpCEWgfupDj@({oWI=V`iiXH`7>UNwWacyB2)8A8>axI*rV;~Y3g@S;i#7g#h(noXx ziYXIxDtPHq#S$(nrK^lDs4SXmYL$k!6@xjy)=(j6FoVE(s2m~du`ZJg-2|m(R1!N4 zibi29HK^t>qr%1S99;s_4BSBmom*JfK4n+|4&$o>xN;hiEOJT;K|a>!4~R@TqF9em?EFk+8+|9NYFO(b))}`&oW_VPXEu=G@YC4zraVm*#9QSe1)HN9P7|fBP{1vf5RSW+}_mZgi zNvAiqCgWb>XBO!eN^(|oj`R5eE=^71Gbp+{P5NG7D(FCG=nPY0!mfu2&KZaj!(du3Wa7A>Z5^d%`+@} zJVb|}AZTebKJPK`yIJx3S(6Kl6e=z7!Aj~x0+~Rj13EgYGf(P~)_w#=HTkNkOi`dI z$tMZrbb~NsztsRSI3R;C&p@`ZqB{tBJ-Ah*%F(j5@QM6rSFO!-$0Tx=8ds%?r*IPt zrH>M*!UDohU=5dLgsNx(w?ZYtWhuFk6>Q5(Mq05Ujun|=mcE@w)X}2maN1R5rUS&X zO1+ebE&>-3x>W3=kVzoNlOdEOMnKg7dJZoaK`V+-;v^@y37a2M0E*KL=Te|A&YPH} zEUkNN^4I2(Lz{+w+T5x1-khbjLq9%`Tlr$|XlUzi8}`s^eEZh>kffn30D;h8pr&lp zCH*6{&aDe!w7suu9Id5<8jYxJAGFpxWh^_*B*T$0%>>j zgLo&z9OT;k6q680I&#C@r~*MdjC6u-$fJFctkUs5+WBR)qXUWdPfI^ijHsF zrfyITR3R8`PL-j>PI3*vGG2P*?hr5;eY9xzgsQ&B$p%fgSjKc@bi%Z)fyd9DSd}`S zg{r8F&&EYQ_;>l(0!g>V)?icC&pXLBQ0m`}NAROTp>W-G*Dfj{`YC-~;q zp0%t81T?E1nuAA=@aa$73)v!r8@|iz^b+2IhKdkN07J0OcrIoQi8^}044xnXCC7(J zyv(y}ewO!irWlH6V&-O!?3?3#{SFfoFQB1};Fc-tiXq-5zR!ZWyw5f!5Ma_7Kb!rh zbrn%^s3e%8w=$L-<0p+qL*y$>tV3R;Hqd-*O*M+{N=9Cv1NAdY{7EhuX zOC!|TkK?X=azo3Of%takX3HB)=T$>8%{~llN$j`U(vb1{sIY6Nn@u{iK8`dO)dKMo zgb`X_ht?$sHBO6a3p8eI6;V?TNaQ3H>MiRkF|~x&ro^B6s#60g7c)w&*_lw5L&ER< zCgJf{Sd>}H$A^SYpRm!vvIwdO+2m*f-6H{hbA+w2H8zhQlt~Kp{Ecfem5FO>-Hsd0 zZKpGRTS4lyi$f^sRDrwJi3K!`nyp-fx(9waNmk2@zR8+wNWKME&*P%m3rU9oL zhz=S+henE^jVu`FbW~jCxa+PvxcS%(WDd@qzsSiqF0#0Ig_9>=k6Aa(Vin1(qM$06 znC|n7zxW}J9NJDfvio*!c8#<5R800~`P5H8z^9MiLI=x`NM~j=S~|8OYq}dXkW(@t z7scb)b94IX!gZJIW?*Hy6Pe1btU;oBa+s7eUdbj3i8mTb_H zK!r7JlBAqcZM~gPtj<7#We$sAU84I0?JyPyzUBqA-*1h-R%7#|{f{;_uPe2MBC#or zkzJBx0AjkL^p27DATb$0!x$i{F|Z`KxJD~fO3F|f|EFXezwK`R*7grEDt9n_c7};F z+sVrj-H!6&^Jn>$FMNa1u)=t(-;Qi~vu)D6ALloPDpu^->&8|#&&wgPk)VNQ_IXp) zwRw0aRH5YHfnEI6r|)HIqKBq(ZNNF<%JK%k|A&uq^5ofQ&j*}`pZ=S7bKm_paOC!a zvivSto|+#i;x_RNr_8@3^CIBr6>>F#sDUpm^HCkprETW&d~ z1g%gPVpsJFmDv7H9UhO-zE!AJ(Pxc3=kdO%`e=`*W_;9{{54%%0v{u|>!SV$Vj08$ zKF+IL1RoSCXHCE;P%S743?VLcy1R7}GVVjwCs9{jwDqHH zsG(wFex3vGe}L=f7q5Md@1n5na*h%82Q#0CKbf8nhph`|A+j!%J0T2D!v+TKj ziO>I|dl)RN;U0YnsxJM7Z5;jRZLEY1c>G!X+AN1ZaGc5G(-fn19=Kt^;T|+3lWNZ=T}N>Jmf$5@lG%`4VF0t8*F^O2Kwc@!sqi4siuR zxt9VR0e_oPNkX5++uxtch6vyDkMas`@yJgm^8gMt9*H&P6CV zf>xbU*){Y`edi6r|MwW{*)~|;31J8ArZVXcgt7NySMYWo$=3Lh8b2tLG;NcN*g(p* zG@Vk#@3ZKmM#&R{5b7W`_d|26)XK^R#ZNM%!@zCBxjCF(!bgKXs3Sx`60LAz;EiBq zksShuFbkR_fYyN!@2%9b3;}h4%z+ja7v=k0aIfQJ38y6?TSDHmo&7s@ za9Y>U?>t8D=qx*a>JEGkG7sg#5_kF6nBX+Ce4lMxVoEPF#Q={GG-(X$)9bJ@`$_|) zIz%$cSUg(Ad)3te&IR&NVz9T#8jZmxP0q4ffG{AnED}wff^8m!8pumDByIA6NZz2- zTcu`JNvWB6;R$M$D5)=$%P^#b{ z+sDPhZXSN}EazXIU}cn{KC8jcs(uDaC7|MBA!@WuqAnBH=(f~^%>N0@4ZHY|)9=mk@SpVf zzy9y9Q4M2IAxamQ=CMSI#I#NTRi74htO`p;WbEipUSGRqe8!a*ZQ7cTKS@drc<VO6UO#vyQ@7c7Hjo)j!uddb=p`Kf=uEH|fE{U0|Cig>#8pIh8 zYcZjUm60$EQ>;h zg*~0uIXL0yRR-QWv3*w9{v^bJr_`FXSv?74)HGMxYpT7kOu?3QDjjd4&v&O-CC!;aib3k!A!uVP;a6Qg1 z7F?94Sy_LL-~yC?N+GMLSczOEi7473bPV{6gy=#nX^@IcQyE_be@Q?qeE*JM7`I5SlJBZ z1T{`JE0wqGiGm6zC67I_$k)Dhnxpr=&Rq{4BF{Q>DrK@LS@UbS&Uw7Mh|?iX1HlOu z(J+$0L4B4vE*Vc3!UQX9<6JCDONN%zkxX%dlH)ZgGXc$FIgOA?jS@6U-{xqiSGK*%&7j_!*va*X&ag!%vT@ZxJUUWD_8wTf3#0=>4@Haw#2aV%-PTB@IqP@$JhsM<*x0O7 z?A@lBALUANJgkeX^En^?o+O`F0NcBwqj1(uI&r+E#)Wq1sMplEZ=IL8)`{R~^Ex=C^bwc{SoT;57HscK)8BD~?u=(+ z@dWEj=cAJAf_CHG*aAtn#^yD)*?wuQyJX_T&o!jCo?@t+J9nA&`86gMlu2>qswib_ zHj{ubC963t9L^{ES|Pl~Wcb&F@J)hKmO6#;^_GX3*?%v;_}_nsPaEzb7@DrUL1l)@mQle~>4*~4q2egCAlo;~>xYzQ76Mnqe6&u0 zIfR?~%BTPCoqXzJN600kstU-I8*cMlDE>9t{~9ho!6=s2n_kw4Sp^)S)&(XTVj;f3 z$O&Z)40qB~v-?gg-6mDHSpdw%?2HT|_~i^-6JPr=74e=#(>eugtO;xub%REMCNz{f zQtO@y1vMu0nx|Eq>A4gX#(pEg<3fg@ltH;r^f{O9=R#)+{5mtU+t{;ff%WVRqw+<* z_{XQoGGRH(cvTiyT;E1j7WBIXAAImAH!KX84VO7IA^hBDAK<}b$JyAq#N;jKx!#?j zqsvq}qEBf7%+R-aAr(PO1LISMY-{C=0iT=1Y7>@>HehsY6thJ%HdYcX%(qty(xsr7 z^*bg`5OpVW3uXh(g_5_x@XpyP~`0Ai% zO)CK2Q8Q4OwkO&V0?x7K;SCAQ)lH+`y<-a`-5OhClTdqe#OPWh6^bPUC;@Clp_H+4 zX&IJYzzsap6Ht~X(NG$pxd_2EQMQnpU1$IoODUsfv}BP;q#l)LlXGFwUUkB#5N^8V zAcu~}NnSGxXKUQw(?<(s3j9>>4s!IK_2(ib>AX(KSlvQSWfli6T3Kj}l3} zqak2Wf_626^pwdPyED{NA_18eKW~7L^m>e`L0kkB+obSm z14k;!HzP#e!qNO8=4Enn6;xx!S)Hyb4a}u<@;pjk$k49?D5|#?fz_oQGu}o28HjlW9j5)&S2oL}EmwDok zz6ROffO0P>yQKh^5#qNM&aLs`PaWVRpE$~> z*dWiWq|5f`YDNpufG-^`2*E)aGvEhKd8L1z^KynyC_Kbz9{6 zicYL`L2oJ%Gy;ps-l#h<*BLz)(5f+3XS%LE1=D`osAA&JZc5@e9ER2~quE{7Br!5s*yP)-Tj_c3ys*R*qHmk7&_$C^c^np3*@yn=qLY+yK zbe+`tqKa3UKm@BU$skxpojQlh93AQ6*oly-5R_o;(gaV%B;DyfOw1@(h8J01Jm1ps?Y~5ukk&xLEP)i={s z$w;=fI2^)>l}WnA5q7(R>*Oqxx*X?h%p??BZ4rXBeW<}rK|$O)lkPc`XK`BEs#Z@Z zUuD6rV3Icsh03<+sf&^G(MBI=9EN#S7UWpI!4egh2|7N8HAEWKgUwGgEbvO zxj}zs7juVirPC=nJGj8V`Qul~UCw%Ul9RHXur?3F0lk@Z?zwY6z4ZiDZtDFA8bKc0+1cIZYvRWUkLGYg zg=jMm;#{%-Yt#JF9<@ZuChGl+ykj+k;g5j-vjviFjji#Qwb1Kuo9$Bo4V6VRb-?$& z@d~9|;)c7FJMP&|8B4(hC2M>ZL{h1CwC38Sp_`nBPgyJ=(+$qlINBHWK9Zo!+ar(6! zoN;SGVZt_ZP&j7QbF6%wefmWv!{c*@f(cdUaUqYY zp`fRSm>OM=uQu=lVX%}@_J^E$t>CFgSJ}1G@%{&A=uT&pbPzH`3p_*P#7Rz0G#(`0 zNrN7OHAxZKF)u| zy4+?_mIZvUterqb5No8T;+V>pIKp|ntS}`jD3*PLVzNd&s#dBMLNwwvQ3OyM-Ny4< zneHK@aDZ&k=T&^R%CP$!8fFMS@Z?mZz^*;hOmAOgC3}R@KT0OAk%d*uw-;BJ5vHt*wlEnBTWD*= zwz$MJmHBDo0EE`k-o{Dpt$vTH{07_Uk~zn*a=<=cQAtM5hy`9JV;I3UX=uCRy&6B8 zbThSfmJDb%Svf{sQah6-^)&t_sissBkhVy3D1A4Ucv{;MwI;j9%xudtZO&bij*!Ow zusX{c>`P7`q>{<@{(jI%z+c+8Hiy`BhK)|SmJHr}P2&|n=KM=tLNBdrP{lGjTQmWt zTN)6eZjdQZh*F@adV=I+p+l}7Ei33LXU-1!=2tHA` zfb!Ar_ol7!Fd9E zZkcD-{d-wd5IlXSOyB+l7kghs@-@5)UOR|ns02zWxXCFy!iW(iK}(zjawp7?<2rqo zFwm*%l$;?hyNJ(DTE$Y5`7QyHW`##-V6+BM>m6byt4s7Ku|_&^d}{O~QwMs{Mk3TA zsg`{SHf`$zL4(nv2pA7_t$SnHc&!Ar{!Q|y5*TGSS;1E1V*44kAC@e9{t91{M0|Zf#dJpL#5VR&*N||H^r73TEw3x{Ufz9b4}`d z$~uWoRsxB{4=CO9ATKbdFdc#cNe(InG%)QlW)Vskpd&aZ%sa=Z8lu4y+#Q^Fc%4Un z{dMHRK`eW-sGABnpA*VCGM!!2)A0FHlFf(|iuG^dqD@R%eMuP{1{r z+qE;RDSIoz&UIFU-QSKlmacey^9z?a@zfb8`pEJ}ac&yIT77@6eQ(-xVe@BOV{5$A z(Kw+AmUq!ehJfaal=+iX-2sI=h0A?(W+J0=%rdZSc%nm6qJ*eF9KB4~0ic-`>Zzl2 zW`L8jMKrI22cfAcsdC0;edt50kks zvm<6|c-9%XX|mqkNaucz-hCq$dxEj-n>)ioPr|#TAoNxkH>|r-{u*m%3aD-&+w~yQwT3A5sYe~wLa;3mC_>^J zPCVk&07vU`9npTG=9JY+DJlq>lWC7Y55(ii@!}|J&_j5;&u44Ao5!0;$;~6pnekA0 zS}&K+UFMPh_a$b|&Y}BnVmP&f8?sBxP0x~Nm6Z{@lBP3usO_?LQ{0rCV95gB>^@mT zv*!r@c~pe$hv)gbzx+4IH*P@OD~!5drp&%aAp<-adENyFAN{G%@}ZBukN@qTuJhc} zZy;{cWJ|TqZSUF3fBR2JO0ijS!_pp0bGKXU}Gz`Q6#i>KQA}&z+ip(j&Ls^xm zWT;DEm)(D<FS{Xf%oFXA0n%XqHCDN12;sxrxV=Eqb;0LjuyY@jr>b zy=rcasSBz9YHO4Bi~9JQ?zvDoM@0^~Rr~c29BUl9|0WI|zZ2b<;(V5~*4a(vcAH;Y z*^ZoAg@bnjy3WkhL-b^YT!;4D{Y%h$i5|`ZuUZ;xALYNv)x-@i^)(THU2^)8503% z3n4K6P)dXmlyii^eQ1%>8O$-^78r2>uxtPckq1P|x{*OLZ0l6|;H+z5%$gjlLXO)S zEEJ+s02zTiDqZ`=xEWOfC7{llUMRu4GE{Iz!EH|`0t#d0+SgQkKgfuz zi|RKy-*2Tv+pc+Y{B%C5soXC?uYWm?%(eM--`O$R28WsotzBG)c7PC85#|@SfdppI4aV1iH%AjMLsQI$g=55yb<6_z{>=xv&h;qEbhk1 z?TF6c#8c6YbPO(@dDwIf*BV<6=hpaPMtj~E?Z_B^6eXesS?Y znPW$h*3s-`OZL|(`O^Buwa)YHTumbb%@>kdU|Sa9RUy2;@JJka$(~51os98{zV%rr z=*9MCAaST6UHiP*I!1TLbP2p2y<#AxJ=@R*NTXg+r&OsFk;uQ-h9sg>>tdyfh*Bt2 zu3+TN7RqIcY%~j39IXC0Ox#21o9B@BWlkov`TJ5yvOTvls!-cD(J!PaBamoQ&BoJU zy3#o`gMy5aLPAN$Os;CpPV4cw&Sq-Ws&`zj8M?i&2hLg;y=R%1xGO7><=w-C`EkgbpjuLfe zEvwO$1T9bp+Ix~J3k3fFg^W<0M~B;i0yxV?DB0+~il2Rg;4V;wA)!)Swwq$&2!rx6 zssjif%jnJ_Oi+#H>A9Reoj;|oPas~&xy+=0hAuwli&&OrMPZc!K!xe6+UJV4s7QsQ z#OI(?jHn`WSTHVEA}{5b#FnvtS6lQAjM@hF8ZdgZ@1bLRZg0{4wEn*d(%4MyFW*;* z5PA*Pb#%b2E-_05I-n$H;Lg*LQ)vG&=*}|fx^!HI3z@kFdAxrSFm&SR$OfJ4Svs7@ zsZynYre@@>#D$?XM-rn<32HJGF^k`1buJ6-6R_TLox{*`#RnQ(CDa(eJir z?h(!Kc!UlE-N}i;Exe*1WW(QshDn+d8Q)YJcqK?(<3XZr2@2|**?Jj_m%IRxI~ZvI z(F*$R)^F4bg z`Y)4X(JiG*r?Z*2`Mv1w^QQs5f)LffIe8ofwPuo-w#|00!Or7}?~g^HO)j+Qb{POW`b zXZj$m_mLYf0;Db;*Er*H)~Dr5buy6H6RorEz<~U ziD)XZiBU}h;t__3SSFid!5bIXpGLr@F24$xA+I^=LR~s$Jie#NvQu_`1UnvCRDh^1tW&58Elxi_%NSnjBzF4zR)& ztHagG9a;ix@*vH++O~jP3zqF9Rg;ZD1Q5VtT}qNz1hVeFk%KPMfhG!r0mpdJXf27} zyJ+*X*YCC8pMSrmu|%0)wQFh5$GXuNlo6@6jHNv;y!o9zW_9M7(A*@h@w{D$`#S7O zTQcw9x5QM~y{TS$uHt2@PSdLD8AJh!BK7a$-y?~2I#%Na77>P0D6-7?^YEP))_LxG zAE#UTgXDuh$FT1xEM?;lMXX%W&qh-WOyZ#r!{(<}&=l1Ykqsu^#TyISMcuCf&1U0B ziM~wODl6oJ_pyHvy410~d6|u?7YyugV3&m~WOp+E+_{tl>}UE$;+BK4*P*0jr^(;MG#8A&_6xYW|3cU^>$pEgDjk7s27`f1ZmMA0?-|P}!ic#AkjA%7JgQz3*Rxyu(noDfDcmyV-xwSNYnX zx|cUz+RroJJ;m-zB9~J9 z*0u?BKvk0E!xWH7FvWjxWdV{dWFfaC;Q~i#upv5;(O4+f(VhZj9b}pB{py6Lzjc9O z3P1NJ9_I6(`Wcq?e}}?JprOrASJOr7toxjb`|0kIr`x9T`U;gl6e*5Gn7}7qjJoN^{H_!0MmmcO9 z{@i{J-1Q>sM}M28v_>YQdW8oL{U(3*55CGIy~*EdgDCzrr z<&P}$$*&&g{Qh@XUs!fmF`l0BN}6cnE2tZiz1|nC`w^WSM^jeB7%;6FSAcUj3ijVyX`zRipKIo! zhJcKb-|XkD^A*JXkqI5ZOd?ress`vpmQuj0EuUN+hi8-y0SGv-Q@|HK1(hW(Oz-2D zUwedCUVDOzTTcN~O1XqE7II9ci53LKbqnqy?0Eb8>;A9m%r@hON)=kN?gx z>F*}GgG>D7U;HsX{`gro_-72m1yahWEP+fs_$*AN7@uJtK&c>KAwlYxFd;|w3uWwH zu8?%A-Xn|a)!Q!to0~0NXE>UFSU@RWsPDmn5WB?uLbg%$LGeV(AMn&jTCY1~& zF(J{bAd*<6XQf=BV_->zteK2udi2tHqd>D$l?xP_xxCSHIuDEL%qO8`Qe@kyWl9K; zONWvffWaGAiCAagy#!Ek=_{*9qvpqK6}L4pMnm$NQ;Q%@{VL9unHMoVS_3jhdvjYw zsio+mR+S>V44A8~r__LMJ~%g-2f^pB^K5y3B7#qR0WP*^n)-z!AjZQhsbK~81-G$G zGQMY-)Kf7#XHS%}Ecf!(TZj1H|IftPQ$J0A-xtZp?+4A4Z1!HnI!7l}dJ%@2N$Tei zS*7CVQ#>e*Zc_=T0-FHCj0(6YCltefUNG>i_iPyz$NAG2nB*h;nLqal{=gqO!RzTed|xtM z{v40X%N*hyNj52L(>n||(T=RP;8#S+T1dq-+*I(GWS}d;lHy#Hky$!8%>b_IcAyQR zS+uJj@hs?NHYNP;uuS9YYF8S%vGFRmu}Um>zIU;TRG-_DdK5K#D@)B8D}#fIou||n zDNQD$pxUF}j51*jehq{!Se<}T5^Zaymldm`WT^440hm^W7TK+K=B>{*KWFvAjlace z(p9ZmK^?GE#@MDNdwAw)5}`{IE^Hm+AAkQaPrv;sE=)fKll`a;b|&K04wa@Rl7KwR zvktKZw&S|a44x>xH$ZgoTP5sKtRmX62)h)1QfCYDT0r-&+}g$e5s(E)x{!t3vV_y? zt1iBh8u=2oYbwc_CW(+mtJ4wsQbfqbK_-DRd7WYWTK))!k9~rzw4a9$D32aE#z#J~%<@AoAcuaHZJwpD;bGDS`_fY!Uiuw0_4G0z zObozOA*BerT~8xOKEcwV(;QRbm`;tGRR<&`eJ`56hDhOwReiM{wvQ@U&nKajUmlBX*o39k>h5=4!Exn8qjJ+S{PD-1v6*lu) ze_=j|odqFUu(*ERgMV8Du(>FxJBz+m6X+v&CeX-~!wT|EYJ0W0+y!}G`^3Wmsb-0!DrvXCEjY3?NnyI}9zy_{jVkLmfxf%}bQJ0@x$+)W$o++%gY^4 ze*RwWzIT~^D3%rKTx`~X-GLcKm8hx=qNHMreU>q!9uyWtGetXxzq}^cvt}xvsfT)l zWKIt1^--@Dj)4u@@mS!buhQsc5it}BL z&5w4cC+7(OX1_as-P$tyd7Cl@skTKKpChNSvDa4Ss1li^$?i=rHyka1l_siFOAN6< zC&oisN{4}yaB&?jZXDu;Q=j4N<;S_S{uSsBBP*6bnpGLRd$Fi321-)zE*%TIv5-E_ zOvN9X-{vA16-|53MnfvKE;N*s*c$dj-p4RZQMTy2cYtLBk09(aw2*GexJ!^2?;vHI6*E%1{6N zaUOW+K91bApJN}n#Ma?|#b!Fm#^kds$uZEkh;H$N<+}pVX(nqzidynsQH!M#-e}1{ z%MM{eLUC#V4Xs!F|41AdYpzVoCt@*aTv8hCLzHYIqs^6>YZcr21(=IxY`>$fjcSYc zE>>v?aDvM<8$|&zhl+Yk7cFiJM#p1!j77AO9a^gt+~AroQxNSLB++XJSPg?U{|#U{ z_}*h|V{iM26Joy9`; zd-!pb`@Bit;P*bDxrtxn;_c#kw2O0iHfTJ@8t38r(1@sfm&rf(&x#lqe#tPMeDH0` z0wi6?LT*`HTj}_>wx1ON$!6eXVw^X0Acg0?{~9m+;v3MtL0>NM=qDcGD}V8;oV~l} z$k7-1V}~wtcRmgDuFI^^MI0$skQ7Fq%Tx^GlL)Fhdhci~s$@~57@w!4?5kTDO~$>Y zVvRjiw^-$6zH-;E^W^cD7+7NR=n@Bh`XH+e$kOvD&$FuM=-95A3MxH4y=QM&@GRBP zO}ymOO|e?JG_s9obb7{1=L$Ngmr8h`p|(b7+-OapSQ)HA2UF3F%RtH#Vbeo z#>ObhNZcwFRX)zWv`>X#XV{ZaXnKm4`*4u@7w&vUwo3GznkrJh4bk(UKlQrmX~-e zpJ0^@4$FB|wkbs^bVNfVP_LE)8Qh8|gEl)~crjv|=#OB>AN<`|_>%VV_qmQmB`~if%NFT+og>^%f; z84oOTa_boX>Ie7p?Ab4KYVG3)$K6)-kcA$g!t!C@)v*8>eYa*tXP)1>BHLsE$NejL z1VKfiFUDovKK{w~DS+BSdC48q{Qiko@02V+(uFMKmZf#zujBBm5Wr|{aH9idnkZY3 za`5P9dH9L@xaWxnSU&a>aQqx{C-WSss?(tl*I#(78F)9%JFr3W7$8eqqVV0Rs<^ zFs+kumO@Xv(~wfO^H4Wz#mDV7K>bUW@HDys3f@q|vU}7C_>2?DdA#bDaa{FM)p)

tCGW%D!_pQ< zti&vu&h)yEX+n^_z_8W)@4}Y}dLk~}!Tdg8&4k}Sgs|TTi zm!{P5Y&C+GM%!$u&>FksAWm0{J7_EwwpU3IrFG)Tk= zU|-f$kv^c)3Mp-9`E5EndRb){R#}&$988J(c%1`WCIx@J z2vTe@G9|ZHeri_f;67{7=)+cZTLF@&)2Mk8g=ozdua#8IJcq8Neli=&j2bfR_k3Iv zTSRJly>QKO95nnri&aM36*JY^$AFVZOHMPYIKPZ>tXsZm!0#iZ+l6~#fU92@)kw{W zSW;b0&sK}XaY~fVd)fckAwKRobvhaICpyHqqsauNkFv^@jb%<>SYu*aL4d7%hVoTEcB~YuCL}rAjHEgqY4xd$@73MnSvn<5H5Dw27(sP}JX_}> z3}}$UD+x&kw$>n+$mCH6+RU8J7gdbc?`8~um-RV7Dm8d_E}a?}#_@ML?)yX981BX+ zyTSbVEg38OHZxkmPx0)4=n7d>#>O;}Rioo7x}px)IM*BQG)qD?8;_hWar&hxfA7D0 zfs@Z1r@#Cd$O=szCfCmtZeM@!oq&bBmm+h&=cP2id!V-p0Gaa3|KwYI;~UR2to)E; zKle%Q{o2R)(i7+SLr-31l}*3{&**HP3M;bCy@v`9{=|ow-1jy1Z#~36{iR>x^659} zmW1u$0)OEbAK}mcCvQk-rEqP|$xd^-6YpXhIMV2m`2#oQdLAHDI8VeIUj?h?-Z@DteZgq1 z$H0F^Z#KGT?f`A*CI=bNj90vskWs-RyYR1b6OqNR-x# z?c0D-4_m_t07X%3nRm-JgT) z;R-@xa8N3V-M^w^x$%rqaj-GCOkMF-ptNd9Q7EN?pw;e#*&=jqV=;6r!xk+h9XzXW zY8~oHWO@#F143d+29|Y=EWM2>8K1E>Gog5fdieC7VILTiJ?o>=cjhtIOIDR3h*NRI zNQ0$w9DTdIRP~|E#u_y?gK?X=Yj>?pv2A0i?Y)jw;tX)>6{$d@1|7%H%yK=y(IQy! zeaw^Bs}Ys~=1yH`XA-|4{$6}f>m1qMVwPoQW~z_j_i0gOs)L8V0xVHvi6n*tZ18cu zcmC7-^WQklxhvajbdPYMe1z>`6?Edh(m=iGXH1}@mSYAIqqh{&*vYUd?E>A*vqp0a zFX|>qA@n~L4b|lD>^$~UOZ<{_%S^rSt)FWp( zn*J>h%dc@xif@3p)Af=XLYIPRWkJ|)_-r-Kwx=o^`mNMv^ z-kmWuew=#NUQS7XU)6R*U_1hv*Up^G@S8j;eNuWfifzCU}PydTT$=jFyDYw!QLt%X`zi)t-Vsq+&n{WXKsgV@L*bw8j) zNiLBkr%uIgtH(t%$b{4hnH6OF02?Ph%J!+xAnZq^H$e7=PDPA;{(Kg)klP{e7GTKS zwp*z7h-|R6k=fjM0^~9JOFzZBevA*xzhf%j1J07X%&ZXLQK2iB*v|#h(v%DPGgCg! z<+DG}`pL(UyoBn%W$SVVJxtMcJGw8HrC8k3Z4e6@XCSVoL`zg_DO!6P_5`VKLolK+ z`~U3O&p&ys)*PMw>&f+=*)iz4Uch9(8_>^fPTg9@^Vusn80T>v4av23XJ;AndfM%F zwkvnmrdS|-tD$lWn(mxQI)6P|yCQRT#Q^LIVc6TAG3u`?ZHrXSIF(Ey8!=Gv#vqdD zNfeGU;n(RY9}8wVq5nXyHMX%R>VSy~Y!U4UWASgyH{h1`sc0Gc{rG(L|B)sC|H zX)c}q2`=l0+1hvo)e{t5qgJwcm0D7%6$F+L5fY0YN@P$MRbOr1`xF%z(q=7~9{v^Nc!hS;Pp5#xC?3WyLBrWr;O;g4g>$#k1?M)(=1jL+3Y< zdj3X}9op#p%FC|FGk%&IFMv*MMr)wJ_<6h+IU+Onr;L*%iJ&2vjiFQgvyXqjV2kMrRVA7f>?V<~l(kgvrz%XP&ylWIn!6sf>x z99!Kmt8@9((h!0=Jc1GbhL)ye-}b8>?8Y{#qb?m~2hG?z_wLx&qgAwYhv2k%T{B|w zctPg3+=av#JODA?v7I)Y559ID(ap=8QJFcW%)P$e%={?H4cs&j6jh_lNX@{DTWY`7 z+5qgT5yayBq*9xm7}mBU< zd=|2ho0oUfEp6wP3@ia1T9UtBfdqNIpr_6<+;_=MjfJfuk-KgSL?_imiLZOL+vsQSf}k}RFnan3 zDHkWe)PEMTkeihj!YU{ODcNsha_HzLOWb?^0hS(kfTfi)4B`!VRLCiLsj?!Tah+>c zwc|;?P+(L{T5+N%jjz-e4!VMPoS-vfyrCxbReFnc@Jwu}VVjhJoCeD%*MKO)U!}%W z)X{jQn3&y7PAgzZ-(k1}k|o6iuXSyXSh==sZqnSS+Z2wSeLe&m5i~Uu$v80 zPUS~cGmfQTP11m5+27T!MHPeq68`E3R~8`YLKbpcq%|=*``ZX`APtzKnlZ0J_~Ms7 z%76V|{b9Ph_wm{h<$|uWk_M7yM7t)C%huh#$wFoBXjKQ+>;#$poM!Py>VFV^Ja}fS zbD(%>^lt2->C&;d!OCNX5GsRw_lkludiDow zzV*+!@@FrR{=j{Rz|a>`_JB?cDJ3Q%96fk|Kl+Eh%on%6z}8#$@b`bEaOtHjlEOew zN><^}rzu$`N9JUEOo)7X65Vv<__HwpN{5zF8IB6uKSaPTrkGa0BQjCK0$o(@h!yJo32r&QDdQ1{7b_KWXEXaFKXQ`lQ< zv10;ChfF43hrAP|!9o_YTWO!G0!%5g1kULwlLM?CU*^yJg+qM!vp>Vp2T!x5FQ92+ zpSN1b8#1L>^{zpQ7|;}WPx$ds>Wg}2xWzz@F*-gpugUC#Yu{}EKk-Myxs4SeiDj2& z?NJeWCdT$z`H!)xy&@xpOi@ovY4-1+Qp957pltZWpq^+h1k3bn33q!Q*VDDS!#1}= zW(|w57w+k6toW{uw$ssXPIhZs#`7D`wq=05HmaZbX=BtesK)Oik_tt7N|`d0gvtuJ zJHYFwPw_8*>)-M6=1a!JE6+uU=u&G<~EM3Ycu zcU#uvbk=2DLw$Q07)0JkXsfH5UXm9Od#is0ypBz zMEbpnaNxiyk34Y@Iedti&_rQ3R+bbZKkiTbMfSUrYq|lI+_@!y>$~#!ccm)?E#@|yvBb0 z9!qJHoX-N=46+Kc#FdS0PG4E$%GNe3OUlYpMw2kG*aRk9tw%ZJd$U%+pcfLe# zcREF8zI}5+?aUk+ia-f^8Ny!A8qXPMIIfqpP{GZNA{gxE4EC<1&6XZ*_FjYP$ZUxc z+5oU)TsFgPd3^(vdZ3sTgaIuBSJwwN22jatmIG+|1h2jQc}|}A5L;{a!4*KaV6q>U zmeD=})UIZTjq$9Ix>WrS6@iQaxt^US4w6>dB~lX;i&xY5`Kkk?ZK*vDCV5s}5wV2s zu(?^#TuA%yjH87tMize)6BzU#u_V z9u;!-mRHRpUQ6uI55=28`My)GK&d!jDhC9!=<1lp||FL^tEh86a*_1+*hK$aI z&^F^R+|z@T6b2k3`v`QHdqh!u0j3%9A)fj5m-t(+ zKgVZ&azFpYFMfxR1C(vx|K178K5dx;F}V z-(4bnt<9x8XfJVXDpGgtS$O2btyrYWr>D^u=|-G*JMAFsv-s4t^S8S_3D&_rC4my9 zxB-fWJrts`Q>i?Feh;aFWQs%I=gzP3Yu|jEm*3c=NapJHGM6{*=bh948EY3mL)l#Q zu@@MUp_>tiMhUGnz=>GqP4E~N!9h|lxkbkc$Cg7bf>@uPXg*y0wTOCYuq{TaXKqJ! zTVxHXfR+N20agm+wrS|i!YB**{VlUP?&F_)fWP!tzRHm!huPj12F>($oniGOzs<1p zZ8~||`8z#c39nlVDoQC}RdLjQ1VR8gmYF$Qb2MuiQ(auJ=SE|U7RWSX9v`u)asZsa zS5k13sz0lVK_~PwK`2agn=GYyM0G}8nU5RI)EHx`prnKm_zK%5Zrkd!tPZr|_Hou` z%=!YepJ}trUM*WYQ>}+v{CIKQN^_KVm%Z!qk@_T#v6n@&uxF*lIAhcH8;y88THHJ1 zb@1ekO6%Y=tg$$y4uC3}#2X^}eJa8L4AN1GlC>js2YLC#C4TL>^Sre63!KTHp~zuW zI#RC)#V94Z9>WN{sacT`^o&u&{T!jx^E8_A(ipJYrD$~wGH~}n=00ymGOm+`nZ8Y9 zX!aMT^Y)sOk;P3#$rPeN*X#+0^U#2jdkl@^J26`_^Ueq@&w!>ilT>}h93$r!wQj;* zR*whzMXiiukj$X=xk#cE=!c$^5-BCNHV1}jVHi3#`U%tSAzplQh38-RFsJ|h8~otk z{1CQRfk%L4Khu7kmx>lQgy?&ig`MHzg)HPw%Gh%je8s=6h#ckOi341G^;K4vGne05 zqFdQub8C}sx#P;lHm{yL%nK)v^4wFu!fo(^DK^ZK^h--G6KQ+w92p^ER(Y>qz$s zSB-(JjOJOf>wXPN zEyOQP6HD`n)H0%FAZY}(iM2A}&8vra`ND_z<|{{d^_fB^`|11rT;2R6^moIs&l_rF zBr8$st66Il%){&3>9X@)4%wmb`MQ+jk5U9iOA3o`sr5-=e58ohoIp ziX#~Yx=A80Wu_Ezbnl)_SUzx^rImeqn&X8mWG4~#^A8+a=E*PL%Ypl0V{45`8dzI7 z!<+IuY+QXFnGVngFqzN-2M#W?vYM?rPBLg_pa&^XET&0l@2 zJooCwd*f@P{S9EtW0$CwlaT~Kg6~uz+7o6S5GmfwcJMWk(bKKA$>SXn9V_VOT*g?e zi5N;EHLqs%hpuS%AEM3AJa{m#{D9PbC4(?QD!ONSM*luL=NFe9?iLHSM>y zg~-977Zs*i$Z3q%i|@-q|1p+No-`Uwkx64_>IYdCAn8IDa?8?M#P)A<*vHbc0i*}n zw%igf~um3kM^Z1XS=1>0B2UxvF7*xG^(uAxlh!!tMEfd$hwO5-ABe z8AoHEdj^4`%Sg&(HtBTR=tfKO?D_~)#_}&K=T?ws0oXl;}f~2?NTwHGyqkZ11v#|U9gK;{Eb13Z`oF{L5G>wNV3a@KFXij%93zGnubBlW~sra>ZLG<))y8g)C$j zG7s^^?_xheiGn~m4Dw|pALF%WpW|=-wckRzDWw#o6Q*Tgtv|w=9%JLoR}m?6AhfAAA*_ET0LTH)%4_HlOqC05h7*smv8>aH>sF7` zt8eq%Yai$0$^V$m%}}QbukfsP-z5W5v+K)xe8o?-3z|$~JTZk@V6%)lD zZ^gl*2_XU?7F!izoY=Zq)26iAcI zANw<(;LAUAFVlVlmJ%s1xosF+uVl+!qabQ@Oeu+FMF)`M3m<53Bu1QNKOzIcYnuF7 zwaREEsnL_*K&%}{;$b8fIXW503`kK#dQ{2`=kTblOy{NmNpGah=Uwxe4J(>D`?~(! z+LY_-*}cXb^B%Fze4^KEv$N;hZjqSHSl_+O#$kK2&h>iu0#=zxPMVi!g4x<=k7_*S z*uc=__eL5iT7W^6sX{MGAp_Zgcw45N4g;^gagJBsxC+`altY|KALp6%pXFSBf}%&r zS`Y^3vNc^VK%U{=1xrwxO;4eSCoZd1@Prwaxhocn1(_x(MVh;4ta1=&Vs#wsrvk$% zu8u(h7PpN~zz149y@P*U;nua?*hzz?v7H^;b{gAuW1Ed_r;Tmfwr!g`$qwF}?>y)G z6V_V4d9OL=eT^~xua24R__a!^Jm_piomc(wLhkJ<9X_JnRubR@x}Ts}b%nSFX{-UI zbpYK)V;^JA45%S8m5$wGT;ZN@Dy{tP9UYnS7)P0J@aQP%HD9H~QL zLq^4hyn8Ar*mMd?MUvvup>cF4st$U81LLUs;j6nn;Qhr0bhlZ=-|*Qw>1$4e0dUF3H<`kKhN=#awW@s)GHaaMxDV+c%xw;Q!?3HGN z7e0!zRUT}F15J3DzZGaFIfjfzm{eL{958B?xJa#CiAbCiQD(ujsV_+0Q-ce%mAcvU#ePOk@>i-0i-Q;SKWb05z^yLDSq|{3$=~ zWMnN~6$u~>t%g(|2} z%?^{U93qRwT&q`gxe#S+?u{<0o6RTi*9~<8t>v!YBVIS8Qar5BdUbtp>|JYP?|UP5 z;xd6~IirL0joX**`Bh}yab2v)F{yS`V38J6VVi1jT~*J))8d3E3ieL1m<#Rwo2#pC zceE=7mUD~Kp$$jC1&1$*w(bHd35 z>lik=q-&$|5>!zw5IKS|OP4antyx@R!akxS8R`+)-kJxRSs;d8pQpnxO(#c22?22q z5^v^Z`pXho%2W0g2rj|>;7%Tb^$-^~S;d${?ClJM!K3zYwI*(>j1ct@aXS0e`kq$H zjDQ*IRrKQHRlui|DaB2jPfQSW^Yp$>-HeWhgniFJXOA;ZP|c;UZ&dLs?hVw=BRye^ zD>u!}aGzel6Ol@WxltQ!F6v-TmM{A~JxXU=HhPjW{#V@NF)G(L zQ^LYwWhe}7_K;Pc0Jj&=rpZ>T7Gyd?tFq&-hlLJ8G=l^PnRntD2BN#P`4;!0U&82Mo`pJMyMGZfhF{fIO#`-cHWPIbQ0rrka=wRD3DSH;txZ7}vc? zv*3%E*EC{mPqx2g)C46%rKZc%M{efJaA(JqEHQ2tPPgP4*15f?jtgc2GgGDqzvrTE zj!Zv5m6zM2Fc!qKFE{r`LumfyGhrIcD)n}&FD-^45`CF`1b#3qj`QaBEQhZSf-sya zq%0gZ3QZHgCN0A6Hbu<>t;`qbO<3{$clp&`Vd75x!jgs+Qf64$?8(Bp6ct+&hg+M{ zR*zZ3&F`fz7b+EG2rd=F{n>g9L6r&bEFeY2n|&-s9Bf{zfKn5LL#PSq3}gjp=q8~e z#8GDv;##_N8LrxFH1&2^ASS!b7i6kwPdJ$*w6d}yzErI9E9BDK-w8MOQ2LX_rW&89 z+9$K)iTfbtA26;sH}GD+sQV4m^9Dd;r?k+vL5mM+ASHDc8_~kTnqgH)P^Wxhv_Yls zkr%RJ3xvo6i+efl?JUWeVG0y@;>v-dXAUgN*R%S_xv!K!VZnSmx)^KcGvaC8U#`^e z;$z?6H2I)v2PW9rfLs~qMB72e5}hNBIrDG6u1($fU#$*rl&4lc_Z$r)f_S|VLK1#b zOaT;rlJM}KtwEkwMZMFHZ|aBn1%$yjy3tj-9#Q4w{7viEuadL+pDu z9m*L{gX37Bu&-RVUpP(DLung5ibxV91c2NGNpdCVED#R?M6*~yRMG!;Z}x@zJMsyB z0h3Xx)Pf*L&!3bzxi>O?@5|I~d@wIiPYx-ChLNKNSb?oo zH{_dUs#Ecg;QFtv?Js9vQ+-mCWI=`{r~l8k@w8}EHk}o#G8dMoW_Ys6E5fmi;q=fmyBOBk6DX?su?yp|3U5jEU|QMIU+*dnx@gl zA>UxW!;F`x`_Q6& z36Ad*mirw`8l?@1o4l(qy1(Hbdt>ZJZfEG%mY9c>qfKDli-*{m3LmkY3i!glrBOun zoDdWc4?&8Os*XL zo~>T|1zGPHn!Zx^;1_rRhVvS_ zQY&E=QL2eCN5aDUc%55s3f&Hrms?w=v7U?dqwsnW1gaQ%Dg3aq*~d5oZXP&MlC7x&LVr|fo+H*tA*g)%aIa=C6~Rb$sTG1ARp~yat%CkC!@}5Ii&6H?J6eNY|RKWuYl?dpk^Q8HTh8woytY2K+P^ZbM9lY{z=%I*tnlH(`3m-*1ya_sbOIhaTHOAHh*^@(}eXxD)6`fUw->CBX>pAQbicp zRL+RbDW<5Jxyhpwf(ip^Y9vJC3DJq7$z)owc!i6`J%ys*Z9}r+5AD4?B>YT7OUa$? z2h$9SX297hov=xEk)ZAEk?8YSK&z)a*CLm+5WL3vqPnFHI9CdFlRH?XY zt9sdGY;5gnJ)SV;)tiuj@$o@4hJR$g7cHkpuajQKV(X4vyJ16cA%Penz-f|7*Rh=r zDs4DG<=r@G9 z#ajDbk31ri1Z=u-l2#J~@kki(@>V@)<}UMqjBAKiw#~l^KWD{zdLXJY_>AV*;a+ye zB$xAoR0&H`(@C+08=Y-Nga4r?$Vv7nVEmCig@XQzc=XBG6W0)!F2%C?6EmV`r^A`e z^HKcQQQr&Sc|a-3bk9Y}-7hT}paeaM!@w}ayqp1=(78suGRcXly`N(EpKMpe>3_en z9XODuK(wo`m}V+V>)>vdZ7U7$V6J8?rE6@ra5;`OZ)x%mG3Jp@akzkhR&Z95 zRPA8bSbEEN{jAysH}}E@k9wHTaYQ6c@p^_p%dk4wN-JGX!dM;YBp{2I;AW~9OW_XAagGsQ-Tf5}5tW&-mo31QfipR`+u z(&d+qYwam(f9XF4eFwPw`3#ZcuD>HFZQZtz>BxN*c%Thyw%L zEJ{RTz}39FV+>kWK}XzQDLmL% zt)SEJXDN1_s08R%0-sEA5_*G_jIVF)DBt@%ReyhB{pSglO)mfFQ+iHnm($M^Lnqb~ zY!u9mQm}lJEDv+v0~cFY!R%_crb!_9Syxtv(#Zc2h7XtQWC>j zgDr=FpJj`gXRAoz@jnoORi7XJU{Td*M0Hd;4|CyHSqi`+JZ#6 zI@8rFQ~7uH57txAhz!xmT6JfXu#|Bcr&{$`Qm_BArrI6k;eQf}nK3wdOAO+8d(0Q) ziPI*d^D&*Eskg=^W&$0L-uTDT15*8fP$oA@qY0YY=N|WyA{e@5!;BrurQ|oYZ!Qs+VSKfBPlyojvSl@qxqqxdp|lr=4o>VzDbyC+Vgq-&=uR5WbB z_;MtUU0Bz6i7zvwoLau_&o%qa`2AEQtn!(^>&T@u561u#xs(L;~aIPh)T;jrYrB6y`&uoM$2w5as{T7 zQMLsbSTM~8!ZGji0UTZa?NBpfK?}p)6e_a?$whxl>aw4l%${N8yR%!`*bc`QX%9|= zg$NH`WODbVf#gjcUY*bNN>&$`(kqvt|E&cFI5E`?k4v5EUwl|uL;&M-P6&fB zEDOOZ!ECd37^_9aoH_;12E6^pYoCPW?sq)(kNF9Pw__CI7sQatHi`3xGvZ1ZJl7sk zl2{~oGEJudqkvR=E)g8WZwN#vVRPf`8eJ||&6_ff_)gcC4V!OnPX%Xuw$_Yo_%TGH zQb8rNSb5|I-w>SVG&HObLah#ea&y9Y->ufm<&v7pvNXe!6wXmkMD>l+*%&IFvvn?Z z=%F&PH+)<65p^}k_BT@O5Ki)i7yOsBvkoVhHQ>K#tjsKPM_lxtyTh~H)`ybAHBBa; z&JWV%yoEkt!n%Uu{%14T^VeVsJJQj-@^j)ObK1>m@i;3Dex;xl_{GNng^wE4&n9>2 z&}Yb_itTazb#~_vquR`F(B2%l%0*n@6t+B+TW{i^u4H6u ze``cwE%dl{mAX(r_Fel04vGI*Egrw`9sM3kk8q2!3|z!?ubR||_>JqU zW}jnL%pGAfdqAH4Z;NUSVk7YPHhG0q#XI0$JqQtw&~v+*ACY=a*T%6@`AwZw2IVt?*17?GjD6|j*M5J!L9IhIAvsHeAH>wKLBEeRo!L+nprmHw*u<+@T;LXs7JB|JvUD%c zy_WF2cjTJz|BKkZUesxd-=4ZBbKxn$PUV>}ozzgXJEa}8ltpBv6Kf?I_K@>S@$-1> z*J;aYaWo6MMEYwi5VRr20Fx)%X|xG@RW$lsL!FMjmcn`*IpLqmJl7%0WvH7!^9Q^L zOwLkpD#Lj`%gGxBvi}3t+V?D1CT9bYCxqNv*{L``?_|_ zW$zssK%0bdFl|dDIb~hMR^I2_%motHyPWz%dxKGEK6hulR<_}#`pkzCs~fB2X?7cx zY0tGWgxd6kqi^6^?Na;8erMsHAjsKEL21k+{rhtLH?0oVP5c&5U!yn^ram0BscN z)QejNPcr&~Gfc!RsA}0VU}6?yl2!cr>dN1I-=YRbC1C$e% zH)tUfK~p$D0U=FHNy!$51=kMklb)b7Oy+`|h{GqZTTvdi?^Q9JF|ITdaT>j>EP+cx zcb$RVNCMsQQ}AnRb9#oq=OjKRxHRGD8Fxu5e|KhQ`qbGdU7ZW=@JSvZE2tDuwX(lo zc&ny}Zk&WFTIw6exkH^p4c};5i-e)1vJV?(9xd))*5z}^`*;R}q9C@I&jKvqt}M3O zZ2b*JQheZ)lvTb^9wTaXB>%KDPX28zWK?S;$COf^rf$qX!vn^JSZGLIkqHNueKS_Z z#3QZ%C84OV2W-oCm-=IC`;8vxU3ZgQ%{Ou%wvkR zA+ukc${sV68Ic>4ep6k@fJ`d7UGuvBPJaMwZfM(v6QN}|-B~}NC^jm&PQ{L6-QP50 z?5she(pI0Yb9p4G&RN-8)aL@Tgm)Z>AqVd#N9J|SVEBLmaeDIBixDSkCctS1d9*96 z2%AQn_)8kz*t`xXa7pq6#2g?&F>61Vz{{+Wwu#c9tH6sDm0-dcMLUX{EFou9A-%@C zc|F;=5iMU)I{hYEU-1JQ6QmZ=wLp_HIgYgXnHLBSGwAZ0_{D`bV*?XdA}dwqoPkQg z4!zy=)rOLLrGy786QEJF`?0o3jJv<_&_}l|ev^8Sz6p{&$9d++wJiHGcOZg_H^M+- z>z}Kec}nhkw@inb0ysS4s<+ljmPj*E^8XQea{O)=VErpwGFt^@d$@5FZJ* zovcDK_%E9rWFrxX=FbWLG5ygZrMPuOd>oXZr6hOkY?79+!m2@jk}}kWRzbc$s*k<>8}GL|rtgM6-a+D#%fQ2^RnBRE}6aVl{M8@_3_idtz4dl=`nJJZJ? zc>gSk3SSkP)T&O2tB!_YnMtpF))a_E(RjQQcPK)L%!Psny-xKSjzq2IAhL0?6ixbZ z#8i$`hF|f#Or2ZlzaliOXUurD02Dcvj1KwdSPu13?D>ZSRhc1t;TrAXt%)3ea3a+2 zUl2u)O22Un;(S}jWbzF7rbn8Ah8lZ)0g}4Vlza8<`e_&YUuj~@xVHkk{#7x-#8tsX zI>;CiDA_8{ecEC^5! zp%g@ot7wJM#_p*zq*}`Z;Aur^M@j~=3YW6Oz5yp{NoOjc2QtvoZ@~uq6$a|^9nEdm z8W5eWYFcS5nEUxyg)|{+_iK5-&p9CPRbxtueNmLTTVha!;l+QY4P}EurUb?egJ=r$dF@z+}NSjfQF0a=|N12<#kK-s6m;f4qdI(Xair(#{i9GxS=$n{I zMLuz>uIncgc4Kcckb-#5QFiVaPi@Pst=jN0+eKlNkPIYIS=^k3y!Ac#ttq=Iic(S% zTB41hI|Yug+++%o$#m5xoMh=_Gub-=4^BUuI=Uvy$PyE0w;MpSY!^q!uDfZDLfM$V6Iyl`b2>`}n zkAdl*tO7sm$WI7|KqATSkl%MW17NTu_XHX7)`cL+{fUR-O=OyiR#If8vWm^>DP8M} z%g)NwRqfhAeL?f2X%JzUV;1>Q=%`}%+<)>feqyAim+>=(GaLO1Q zs$43%WIC6+CD6~%!rIJTA@pu=MS@ln(IX;0J{q{MD9ijTaOqjxtM-R3{BFohI}2^e z(CJ7xq^WvR>fj>%ApYD-CfY6ti&{@4vzE_I8uf31g+mK==51$;%N}yy)Cx}05EM2ocs-(SNxg`{3+idCH5Oh-8A|C%q)pY;3b z(=Rf8}r#nCAb-v2=m2s zegc0a1J2f^4Z(fc%0xc#J0hsLgp3r7Q)=)sj{)nVC9<)Gzxi}=O>ApR8-Xh0%&Mqm z5+;eMZBgwVA9-)Fw^di7aizKI2Aq#P-uqJ^li%Gbs@hTsd)uqTH z9`I-YKVeRU(@W|G6Uvggq^0^y&LQhB@o8NwevbXMIqBJA?>-woUX~9uc+1z15|^>~ zJ)FlWm}ujc8%92#B$~>Tdag1{W}J?d7JW_tQ6Uf-3EZv)792#Gi2u7J)Eu9dTZrO z3GU}@Tn)27bWn;e(#8n0y`4FI{8sMwu6or~#d~)HHI>5`jxjznZ@~V8G`s_nmqe

c_~kX>9=yJ;=PVwj7_1M^_NBMu^KadzB2BSvBvIKMCgFJ9zxGcw$1SKyGHkr zN1}+Cua}Q=_&=eX0@2bC2H#T(dH$_LbSliZ3aeyjsiT9eQoao*{b3ki6JeFyg=$|XpG7h*V;hB@taj0mZr= zR$}w+h$NZuMFRG)IoDVhgHvu>_loh28Qy(u6If{J*Ky);()p!2DwriTnn&aLXsSwR z2CG95y&OP044~YlLURm6Hhwp@3)2E3n3lR1`5iz^|u#0fYQfn4i>n>QJU9%Bx^i{qkDh+~{L#Ss>S4q9R2XHkf^BPK4>te6_+E zmSPKXCi2J{4ZORz$6^n&PpOn~1R@q^Z&+Go#-X0-gX-v`64R(xhiY&0hs_k!d|La# z?2y@yo;RxHGg~Rys(L!<@heR1r-i^EQu)E(F;-U5kmZ>T9H5oBg3MZMftuTFyzu>z zIUXOk_xd@K;!$naupeXEw#*EF(-N~7p-J14wiobl%rko!@D_!Z3(Gn}F zR5TVD3L_7yoH`E=G#I0R!n)<@)y>=*H|GeQ`osbm%r%x-zAeux`%kzHi@}#D>OOUx zx~JutjRP-&$pp_+4>lI9#df{+7B^LhO3Q?mT}XMqM@+x_Zr_O5&sLE84Ft;l1B?2L z*JuB7%j+KAsq4(k&v@%;1v}rQ0c69ROYeF37Y7}#_c#u(W5@Mx%gnESkDE-rtl*PX zv}D{i#AYrm?E5f0UGtqBzMq`_kJ3#?$m~P-R)&4O(aK-N`HX2!u(DtMb{Ojb44F{W zrz#}EXe+3SrwVh%+)}trFkF^c6uu@ORn1pv%TJ84q$ya-Uknpa-Bx2Js!;8i-NA~A z4xclQ`DF8v)1Pco5C2lyTK!@B-2$J(mErB9S`HwhElc-%i`6?y{bBqkURLvyldfz!{4K`_qv({>-{EJOp;6XYOhPt*A17om&ynu z*`11-cW)sl?mO|38=uQtGTc7k zExl@P{#Jh%)?nu)5jl*l1u8gV-yOQV&~`!0t)Hh z-5<5L^L1^LQUJnTwkt6e0am(amm9QPaPk6OJGaBO4vt>E>K{8{j{6wXewQTOFXK0T z&4!;LkqhO;#G6R>k@oHaNst&3-*Uh%1086KJLSA%sg>5UYxxz=KF7zD>(6{DcwXO6 z&cTwF!xuQZ^J}o}mTt2H0fDEZE?rZ(c?7L_+( ze-MMUB&lcBPa@;_Er_KK?frTQeQ$ByFO{AYE3mx zPDbCiF6Q#cU(a$udA4-(3?55F7LP|#Rs(kPBtO_(AZo4Sblj9ic<-iA>Oi+Fvhztl z>8Cwz3!&Wf(;TLCS;#b%D@;o}_W9iEi`|^4{Jvc{(QMvDO^AXoqj8|wn-J(PIEF+JTQ~|h2t;VX<%O;0DbaS)sOw*}zRjUVdjDY%crtHwy+@OX1STl`Ns^_M`;%o< zzr2^`LSzI(&55ll+4fseuukSogW3!!fh}Z+KB%ig{~YXM$(4{2EMayzfv!YDx6bTa zy?SMOB%6vXXO9L2AtpJncrUDqBY zGvVr#3k_{u)TBB$oyJM-OO5Z3ozd5WRUJ9v``M3EPWEpeXD1-Hk12Zu;L`x7nRlbK#Nl5=0@3C94Igz<2Gt=dz2NOBxWxmSd7*iH#%pyh zZ4Y7`cwsK;!rDcaSg?oe-By>*q*hJHQ_h#bCtw5s5@Twfe$p;|vZ zAj{=gO18GV_qbEF`_?Ap9{m~)4fWbyIPllf=b4PeZ4J}LU-xYnGW z*2!&sSg#k%qtIc!(dt;7rEPN{%8}gb{HOnf)YUFa_dTn?=Q081HSGJAl*xy0*W(Mz z+ne9Lrb_b17>twzA@o$9?AlOcvQjDbZ3@8;2^a73%3TZnQ?hIgY}7+;PapS`Jtw9> zs%RyHPoMnTCTzQB2g(FL4RyeAF*v%$m&-YK^a(vWAJi!(8!${3m6;}di;WZsUBj5G zLFv0FjV`lNjTL#~iPH4AI?7AC9|+r4NB2hHoq_Oh4g^2$h%krdQY69Fh$v%?SVd~k z^l>rF-KWq>F{jnxQ++lOZ~3wrSJ5P{<$D(J`x(oMF`lt^|~^fWa|>jlAY zH}Q=p_t`D}(C2MTpu4yFW3Bm10$Xv|^aUTrimmi=_+ZIQBEyLI&&-?4_COo zi=gk9uK#JS-cs8!dicV_mF9<+T)CSyP&KG9YLUkTtAu55#|ndPssBK0i6(+{06H$$ zfV=h&P);<*ro<8(_Cj4IlvlgY*DTFpDs$LW|5k|z!?7h7;RT!VE5gFc#jng*B*Avb znsLZ?-XZ3`%m?*LJ~-!5Xg-SgH(x~2Gh6ZK`Y%0!xQ63OYxoRSsVm!y`m9FgMM4CyF0BX|986jgLNJ=>`)ypCZovE%m6^8kI+Z|dy4%c%Jf!~euAxRhRs zUk`q2!wnBMkB({DA7aO$RzXe5feXDD`C+#4?<9%_UlrkAi<2&tH%-r|YF)+cnF7E$ z9GSJ>n(Tuj*S8`W8{@|c*3UaHI%aAbXpB1yw&TF{dg23f{jT)9mLJ;T>;aZIfwoLs z$ti}?_&X_5E zGl%o9;Inr8Y2Dm;ryh~(_MVV-c}Ban$n?EmXafNalEkzf-urRIIW5AvfK{W2i4gPL zmeECX8q@2`By9oYLq*YUt8Ha5Ws>liup$j~Q>3)boV{u-2Rv(YcCGsEb?WymW~tj9 zg4%fK1^c-w@t$Ac(<@QyRzEi9lCKu_3o8A3XW!&mypFY7Ku0cjpj^Xix^2<3EY0l1 z64?XH;{!N3r$lNQ?#Znd@RaedFj}X?LB-u1ui)%N{KQdAF7qU-f~T>J=?GoyzNpG? zcC5$MHQ=%QB&0J8Cki%mjCt!72g~bpLX~{-d_IZVUPYr?ibq=M#n>?KQPmyK>^VGd zWL}}UJ7J+xFOWu;m3&~sv2A>H=fX@?rN)@`(kBxd>_R+@*G?|GR)*V~cKKP;^X5DYnFfp3f}R@gmZh|k zco891{C&)(*FvJgF6~tNhZl7UxY&NNTj1q~*ZjG_lg8505p>KFT=%uvGfqj6?8qe# z;fL>Idcm-tIgxrO(D*7^ry-cQoFDFJhTpV|+BJ(}72Mr^T%n36W0ZUM<|b|&M*U@J z5`nk3_}TMCQLiF)W?GJ9E?%1H_jwDy1Gnu2;GCt%Syl=MjIATL`2r=4%zI(6jou41u+Y&`y8%`g9&!cz3-G+ygJ4|vqs)PWeAKydUYQFO7cB9wW+US75o%wNAWm+nt$-JjpagV&P$8_O;BlGu-u!t}|z>JXb`s zvD@~EJWOSk0ljCeCnGf$^RCtuBhir&VCVZ;nGONM3O2v#@ddR_8ls` z3YwgTaI_3piIor%3nrX*aeUH6B^1+ArBkbCPM0-l@Dxke5?zEOh$Br)^Mu$cz~^dw zm_6xW^{^-P$F0KC=iNU!Ra=Q;o&AG+H){Yj+Ms0pw@~$$pWQyuwnx{hVqS6m)_A(_ z4kw=?8fquB|0Lp)EIkn-xrH7vl93PME)*TeJ>bHxVJwq8zZaIvZ8Bc(8+UDbqR8b{ z>3sH%;#`3ZO3ogb^IwT~h!cD*XFBLZJNl*{mxp#N-dS$D*dU_Vt-^6j@EjZbg7jZ= z3B{V8R=AgMuRqmucPqia0MH%$MzjbAG)O;j;<7B!Tdjy;Vd@pgE7?MaqY+rH3tr74>Vq|b}u8{lkz?% zfJEi)(dbnH2xMv(xuJ#uHyT-M@j>UBDaH?Jn;`fqUhj?$5mwgNZfu zmrCCps+fMtQ6cWw62X9948hyDFCd<{)30-_LVMGb>~MChZrMH2T%1Rl`X%UtqV4WZ z@|RcF&Q4G<;bQKxAkypno<%MebBjh`6f1Vsr^E%vd*a$R(IHaep(y%ik%P_rUj%Pf z-pOrw@*flh8*z&FFuBQz$r+M|uTupFrLqtfh4>j*zu~NL2+)uv?b*r(L;5$Z6V^;z z#M>Q=u6O<3ULu51X~!1mVQRvyds^EmZhFNxf82im0N%w5Jd#SLzU*DU6El3=Z;Lxx zAuSec4lAeW3y+bL`S|A_BR@ZEKjXbz{4{VC1m>X2US;4&MZBLgll?%>5!hL3etKTW z?aqbyxZ^v>4q1h~2Bjv9yI7o?^FODPzI*fw|5&p3hgKt+kgq_=w}h4Kr4{hd%6_}A zJ1L^$-BQ;s`tvO^D5@#3M|jUVqAgn*$(rf;#dw7Csc=z%w10PdG?Re+kTag@Qct9` zOAo2wuFTavE~{1)=7Xf}WuN6zR^7U{2egOEUidek-S5ftx94dD8;;sAe#QcX6*e79 z)mGYl2qnvy|!af9?K? zMy;K7HF8%|9@cHRDEFgn3rfY%&idP0D2*nlHW=87h}?^Z_2?YMdR$w^hknHA5n~ zsgN4rEBiu(g8C^N?Irfd6&)=FoDxz=iJwfN#P=d>gYYv{O@s01;u1HVB$IE;XGo>A zRFbF>?@0#*!D1+rrP99i$puHeYukfY$vAS#6Z!J~kb;Eq`3b-2JDHa2WLuy1;GPK9 z!TElB{;TtMhCI~M$hj}5Li7-)3m5w#YOZp5A8f=&Ji4@$FZT?f#TH6X6W1}D&XQ4cyTE|ZpCQepSScah+8a{ z;NWH*A#Qx3o`s@aU`(xTgqbhGUR2_7QIQ&Btj_bZ_#R-}6^T2&-QOEcjW@NMK5XCt zflN<)eD&A$cxAgwblRinkh_$AG$LS81$T$pNBaDgUXK5f4FW$z#E~W?n;!pfB=`5q zeZbntT7`*)CaqW{wXR8M7#WP9xJf5YR88FwXNlZwjrjw271w5r0@4jR<&oB-sFwc~ z^SN(qyPSMW91Zsiv!-p$WCH!56^#PR;J9LbT)X3+%@6szgDcf8@B4L|Ut8m|2i$}U z5<)=gQVErG3v)2_Qn_zWzLa5)B?|RotM%Pw8hI)iW+k3A3qnR&DXfy)b**LFPG`HD z#N#C-D)89xUaQ(4kn;MzIm0=feWTgv3sOd_aN`Y=!c)rUUMC@H!BK6$%)jGZC#B;tVksU0L5Bw(#PfzR(+DYb zSWr)4Zm6u=Mj2)=nn5z|`BZC#hk!|mwTVp)hAx@7ejUlN{@(?-T^JL%3T@2Dja5a$ zT2xzk^=WY1mkKJ^gK(m$rHgaaxZ5u>_3G7U#+uBtfTBQd!p0RrWoMwUxz6Q?mxI20 zWcO;EjJo5YlHh4eocoRQ(IE3`C;Q}$Am(-WbUup)z3zc%^+2;hFi=#y2KfZDb$mhV zRN3U#OR5O4S!<7`Z1C*@g2^;S)^;ba^B8(qFr1|EUrr;_L{dX;P~E`@99mYeDuZT= zuGgH6OCKvsp=S4p3Cq;fZ!Cg}BSea8On(P#h-j#V zc;QSI`?eQD9NR28SS5YHm%`kAyH39##CWrM_FDoR>bSg>-&f4SO$UbHiDgCcr^hVQY$wY$}^8LLB zkIdyJn2#JTQ--G|h{nuH;c7msfDq^t6?_J*3+gg5!W?Waz4KF>bRhXZfASg$`T0E?n!ZqD@!@; zDYQvU5~A{}UNxW$GYP>F17=&SSz{!W)8kqsiw8uaKAm$AQps>%<@}`y*0i`I+6sm< z(AH2I2r51^DS{9(0au-|K?43uA?KpD1f#T6_3C{Qi|>laQzar-smJGtpKQFLWj58D za_scZ>b#UmLf|_b!1Mwo2Zd;8wwb6Dm&k_p6ln-5H2!&c^k|r1pI`;X`@+^G(pgWDmrzx6Z0e5IyS|Ph|@H?wUlx99j_DpmF2*iFuc9 z`-&o6w+;MsAlPfWvEN239o_`EWE>Cy>7<>{O(JM#of;}23WygH4}DnPFHQ@=ekS=Y^c>8h7K zHJYeld9b=)kY8KGNPC)YMg7aZ-W*KvKfkpQZRH$J&os)rVGn7)upDJQq*K>|NwCY7 zeEk3`vUNmjuPg}`P*?OKWDe(Y3+LJud3$pQr5GvC?@uuUi?ee$QHN_P=Y&x0LS)&1 zXRzqs&WX%e=vB17Mp^#rm+P?S9NYi@VI!_w_vCp()h0AFPJqKH{h*HA`jV+H)D8#J zdUGM*o4^XfQ_{b&iHtgdoDDW9l=C8ZOOL&Yk@wD``~b?|KUe!^Cl%x2=LF@4&K`Qq zP&exBm3aB{cLz-bR(b}>!Rw}Ky$GoZSqYsd(5Dk?QJ5;ix5|CL=FTKn{$VAZBh|K4 z`U7vp9kUps4w{*_pJAjEQgW=JWYuD5$)fScPX@eJDlkh8PpBDaPBlG}`kUbQscQAq{j% zxmrg1@h~r5J{S*a71D^DYf|?^{q-Tk#{&$P4)2JO$Diy$Y~NeEPx{Ykh7W?uN?Rl& zM}!9B87%z69jl4L;9;f_%m!K(3eI8Ds;wQJs0SDe^rfd-xrUhQ2x69%rwuUWnH!|HnW{k;H?*7>+wc+(@| z^SS$zD)+hGyoJ**hFao*x;`mK8bvEjQX(1dzKzJZx4!TR7C!?3+Pt#|(B@Y`OgMAm?CI%?Iz} z`<84dkf89y<#R^+HrUO$|HTjFc&FT-GP#;;S2f8Y#d)Pj(RMEweJW8f{cR!$EV5Kv z=xN2*vHXVPSf5T3N8VZx+pBH8a(++_Dak>!lBnoeM}b_@(NJjfxx%;c_;&!){`m#! z@Jm6u{^gR=8`JM^Vw;{1{V%9S5nV@uJa&wHpPhqN)u(+e%;j?-?e+(G@d7iS2n++f zNcq5F?X`N;!vt3tRv`sGxxGXY9TID^(PGN!P#k_R==;A*yo?1=xdJ%xJ=-tNK!3O` zd$tkiFW!Z?>RQY|Hr2u6@Isc=1~lBdD{YQ1t0Tn^?RJaaem&REr>C)p+<>(G7RvfZ znn#0dERmt7ewhg0|KTY`O*>%>53~5Wf4gg9x%haeOOlKDUxYQLETLwev62cHV z_k2Tu^Bw04W7hB_?mF}SdNp$IaK)LaOByztZabkH=|998s0AgePLNmlwy`6@NW6G% z!ap7hvN`-9*8jJUtu_HH#V@Y3MB$~rfM+uhxg;gEzU*nv5DrdQdUunuh^5UvEBt=*)gk!8 z%J)K)4h<{ZPHT{vYtucRb$?CNn*e$M(a1}oM?tG~Z1(jtxVt!2GgoeFbdTBew|MJ? z&+ryN%L3{VU0Q&c?2dh*cTUjQ&`gKOgu{c(?(Uqv#4@{}OUl^`C+Ma^(K$*Xr%WPQ zkj(4cEu%EK33ZF-wk*J{^-QtzEZRYuQTo$7e|5=Y{kM3kdka@i@35_KxN``z41IU| z6)_{~%f4%+qXy7bhtBVar;b5XdIX-fa>HtbL0X&86_OO!HywFj8YF|0Af73z=+Fad z1fuOGRLdxha}kE$;~EAz9XGS6OV?Dl(@wAWJuX?1EJ)titIha+kK^r36h1fN2q?v} zFH;h#D9ed*ZM*W~xsGXfhF&V?G;`|3j_yKl8PFWE*nb+z0`tKD79b0#OPDW_xuDE3 zNhAfF%u1G>Ip599cRv8Uhe=mi_Rmt!yuhPR-_5ct**SlcX)*DAE%#kXO;s-hYdaSReyqlG_09@QHSX*}C4yETG7JxjF& z85Ob0EiIH38IE3k7R+p5BgF$^;uQ{tSyYGpA5W4FmtLG?)yP?C#%EXq1+jz~&5b~9 z$*RpAANw1xj(lsYr-nU>YZFaiYn#&)b0$imqt_i4%(z*Vqs0L%JD#3D$d}3|xtxBC zKA%PrassMQq=FP+;^&_lHd+~?Xrg7Fwxkf3CTKbaV>!8))v;7Tbvu;^_H#Jzup5$_ zUBSuDFl!bl3+(5f+sJ0w2W#7R*sh>HYq1KJkxYc-^61>l5WOkyrIXK>>0zj z+oNzoGA^wuiEV@vD_gLUP$p2fxbf-7c=R{EMS1=v$R#?RA$_7yQ0ak=Z+!6y{>PvF zUHaMQIr+dL@Bfc}f^=$1Ssrll)MY;Kj>@Iem5C@PCr51Q6{Idalfp7}L@TN3lH~>r zlUSk1DvAtnVmha*l^|wdL_u?+H+FIL>+4fC+U&~fBjdI9=k1>(93U%UuP8;KYB34D zG?2P0#;9dX#?_Lw!?9PRagmkrn}ZXdw}v0?aKsd#t}W~H5sndF)`L)sb!)F~$ct;i zH7ADvs+gmwcK@hGMBSp^ecfX&h3nkQlgn-Pjyewd8E_h8h9SDhMzb7Y|25K-tmk)&Ei+ZeqK?qmefx_<4$14#bu*!~RI#vE_U(H_d}H=uJf-i%|_rr20t zAjdVBt>t7UT!`+OK?tr@#2C98S(r>zCoBGxT$TRM9&36)sBQ6R-_= z8|s7n*57)Z&;G*G{LFv$c0T#%?`64ofy~nL;U`GV6ctjQGL-67(|@i@B!VjfRBn?3C#q(T_Z zNZabjfX@#R4qHtAxPdq_&AF?jLr zE&hwY`eEMs?r&4;5|U7=(dQ|dZ9!akX0+ahuAXYP_f;w0QCb`*cX~h9U;a`4kH7gW zUw-0C+8No^fDdUN-j4HELW-^T+8q`|CzK+W%qk1MtPi#Agf&I`ZC9b3U9IBov zWp9|&js|8oALQ_?@b+K~&(uO;krMkT2Ph>e^RlGAZNjC$bRQ>ae6(6MnI=J83$jRRb$)}{h(+1g zK(Ho4GV~lUb!VrVT`MEjG_6oZ+M6PY%r?FDNb2aMqw11gdrFORZ?87<>oRz;c6}Ow zR_mJke7libSxMB^yO8c;g=W*yexO%NXCHI5sWq%JE1WdqYTw0r6>Fk|y^B-~m*R08 zQAs3kN~|*DfD>Gick-EQ=Xvzox9C#l+T!i(&)!FobD-9=OGO}?ESwF?;;j-E7bhis z-+91Jar-A>$F{!!HjGtDmfQTuiUl{xz$OORp-3uH=j7U1Y+;khsF03YV1gY)cO{b@?sK^Hf8Yxx{<>nZL| zH`z*+`?e3cn2*?DpH85Lh_|bziApnIQI2MUY-?v5r6KMhgh6RD;StIj&WYS^)JIc> zPtnTj7HA8dFIkBaw-0Klh1x!gcw-36Sl5J=>x=;vqYP62%}VKy(<_SqGeL2NffaY+ ztaQV_pIqzC9n<9W0C;(XI#?uQCG+M`REd%tZRHmdC7L*;C>E7Ba@0r&(-+DVPP5P3 zdG7EXl)WvE<^r4qJ!#*TBcNx99%}=Ss~OKhl7?$&DKl0Q8D;W!B1!AuT*#X7ZjMHf zq-%tau@{6p8KosA0>2F`K@YL0acbpb$CE~zu^DgVF}|ncIeVphU7RAdQokvXsPybp zB5R|Zx5g?n4iMip!79*!|i|aPoe*coNDIFfCGYun+3lE`v>JxiRfr$M>%N zVVa}?uR(umrRxwdFB@V*(;>oLnghVEa|m4W+@0g(R4QI(X4?{B9o{Tdg&o8fdxecsawe2 zBi#D(d2XKEr7pHnT^ji+kwp)t=V`um!ZkjL5@mJFp>6FF;<@w2b#6ThN(p=t!8f!$ zkJdm)TPc0SIs(H%`0w^+tTm2+5J@CDvUc>PXSp=lt&|d)W)}Pca!ZA(lU6X zu@;(1I;Ey9_UcKV;r)De@d-XV@90vY))|scVsSCUMFmhXIzD;#t180kS^Do@;ixE@ z)z@eBW!X`sSSm});tYH;CNi}#s;r2@#lr86k&*Fba9pn=d*&puCS6JVG&>xZZWQ?S z_nN)Y*k>G<8JqEj9;@tLp~dtX$+rsp#2txY`ByyJsv})5#7nq* z0aVxBi7lyV04@olPzeP6;s3;Y)(r?N<2=#4!#wqr+NtT#I7hN_wv{41B+GkiDLhGR8JgJ``|x&4s8YqK)- zPjr5-yLQitbGR9s@n#yYOo*q05C}EAH*{vW8 z6-J*qh@=x1QifVkFOe)!{i{Eff=L)3X8r;4T?onGbieP3a} z9#Yf9zMt&Ai0d>QkFEP*a|gX`K_$C38i*toC9~8iyK<5f@4bg^>mKT zXk=qE=)=Ud>m?Tc8fQ9@M$I^!eXJgC9)N5amD{%)74JGpv+Se&RwtvIuBfB$A=)E zf*{R=)~AvXsosfPkZS93jl}R2)d?VxVPDPHjmmGwx0H;n}=g0r_A@6?Q1(xAoYe!UVkFS!t&#ytmCI@2SX3KCSE8lD{hw*g0 z*eciTvx;jnw`7yfX3H1cz^Zs+hAnrokH8$aU*dnRLLy#G&l7E zFVFAi(W~e9!tNy=Tb`iii!8hXz?Nad0hXO=+9*}TAhAl5i-~=Qm`_S#RfIBNb%2?NbB}T@GRG653B$`Mc?+wg4dv-_YTh zM+sAJ*0CW;H)Av2@I!{5?tj!8BFh7rWJ|Jl9ukYFKOMtHPO=> z7||e^oNCnxXb0El~m5fSqQZ!r%TJ}c;s#G+(+mB{q9IX}1X{bW03YS&~5|Ky)LZQ(^ zJCcz*=*GONP_zJvj%1CaG&%4ZmDI2C5Yil(0n8dfXxUE@`C%`?sMX>I?jVMM* z9vQ~-Ni9g}hEKg2R1NzY&ZQ9+Hs!uIb*D-S(d{xwUp$j^qBHJ3ypR03>%8zg&-*rZ zP?ls8GvEG_h{h*Ir#QNYZznH@j9a0QM^3<)C>@hF@wbe&t;1`LBprW#^{U#|a@)J* z$8|$i7Gt0t``e7ocry)I`+3~!@mwW@&ckhjQKd!@8AXu6s9$sC=z2fcI!-TDTd+yaiMnpk?Xo$5|}hk;}5JCbIzRmn=3E1h-st=82%vOQXI zgs-R7wXmZ?!Ll-Fu^ee7bE}#EuXd;dumDR2d;*lkJ{(9zDSBJg1B?nJCo=0uR;Mj_ zzGyqa=2WlQmNwmmL?tuue4+)_Op%FY&8U^ln~gT2ROA`X-v3Kndh01f3tfUDJ&StC z&BYbw=>QQAkZHnd^6XxzEx1>k9STF-GO}v&Yiif0wcJ4jg>JH(dZ}7ICc!Bfhu2Sp5Gd;~NMW6S`{!=Y(A8?G~$tS{q z3B+Zw#PCdWag$-L>O`b8AKKSE1yVFKO1?CB@_|p0C9_nj6k2(;ubn2hB4mYmg{Pl> zfG>RZr#XA}OMLi4{|XhM$M8s^gPPYe?PHCJy=W|dgL!Y+@!ITD^0mkGu?J}s%fua| z0Su2>R=kKww@|Uy1Ol0fXX6^-ixbIprFu`qh-AY+LuRHOm)pvu^mwMRhpa=Xn>;bsyz(^SATW>m5gVisS(@anWoxsS7hmGJ0F+l zYBnX-eLtSS4`GzsdOxx+VSmQZ17Rw>l7;iMg?9Rn7f^@3GHo*QCg__+~Iv`m2c4|L`30jQIs#36A zl^G(HX}85x?nZQrz5>$INp4`N!@*NE$D@)VneccPGsGI$2pyascRVy4l+i*Sx-8M) zsKNU9yheHX;1u2kyiKrBMQcZ|vsuog;hD<%l3R=vV%LFjprDZ=S z)k>OlEX7LjRf_B6q*ex*bkM4)HPdTm(JwvXn#iiiVIr4{Fu7s*H%oW+sPvxw*<=+~ zh?lX&K0d=UT09M(RR-rH{?^epSo!`cNh+hyH7{`VGe~MDjxqYCm9)Aew|=FD6R zLM0^!Wfi1mBpWf8nYiAieWov!q7{*jEZKk$Jyng`wJcIQ4ru@*vLGD>HBv7?hpaAP zy87#Qmg1FS>8(t3N!DtLGSV5iR^ypJXWW46r30Jk;vd6s@d1 zs!MDeMQmS#K#yhGSjJHyNl(&BUzUI{NkU(5GOt%S(2CZcE+tA?P^%){4k9O{)uzPh}uIX8-b`9b=-Hgq6El2pT<9oCzauR-3%9Y$PWIeYcBJ;Ku z2n$tM^icO87t*%UZ6zi;Au*xWN?(d=GBPEkefJARX2Z$EO4w;Zav-RGjK{7(F zmbqV(1;+}|FM9yG)OnLC=eYHdPFvN10=ZRhH0wMHe0u$csZhygD0PWci{fhS&@{EuJ3TVP9lKX`;3tq%3$R5gWH?$0rBic8;`IiV zBGc4?agyQOa*Aj!o_T3!IdOQ|Dg{}^1q#Wz0pF{o##c>-Mry~z*E znZ$)T=KhnlpW{0>O5ewl5z&}wounL-q+=5FxP7qpz4#dpeZjJnG9#1F9}$?O4fSC}t-zTXY=g4(0hP6n&C> zbHPluDCv-#EbDVoj_8*?U7j*aTLxg$k|c?&Tcm0L&!k2i+|@!~g-K3Gs#q8ID4q0- zmcSxTpqV@hc8sofW?FmV_SV*jAIy%Gmh5$jUaGs z10ffb!5TYl#%8>xBW~KbaqH-xHw$&lAlVwGWpO>uq*OI>#u}<+^3FD=-+31o&sN@c z=Er#O`8lVSf@Gmz7JlW^pW}(go^y}ipT(pU?J=1ZUy!NnobC9~N6&D1He=_(he)$s zmMN3#1n9}N_n_0zyfetRLLzHIv{F-#B=gaO{Irb2p?^VjBGk0~BT+(#6oITmph~MH zT_o*^>OE`xG%*ZAL0ORKNuJSfw5uZY$ue?9EjU(5EUN`rl9~l7LDss>N2bm8#oAOcjAE}BdhP9VYGKLT zvhS5#VIq~KD7^^1xaH|QaV2ANU0Pkov{H0QElRE(NTtt9G+WrMS4Cx;Wz9VQ{L>sB z+(dFmt<`K#n(%yH@VLyltPiq#^DdAJt*Kq{YpTgJ`?WeR*|#ZcQzu6JHeaYMz4i$3WGhK9U&1%-IVvNcR1x_at%+K**~5`!fVho~;6VZ;c{GfhN?5id zo?#!|7sp$VzujOYv8;$X&|F%DgCphIex^>gnC2x_msEAlEETfLijiRH4V_X>6jgFH z$E8T27t3^PU5mq=aU&xd#Gj ziX^&D$T<_bnIZ{Na<|a3CmUXKarYskiUxSCA|eu-dFz(&+21?h z(Jy3pW)9bG!TcGRe*o$w0*NXMCrJh!(KV5RWA4Rp0EW-qnN%IWKK?g;P4DoT7!pRRaupo7`>-!{#Uq?(?v!*>{i8=@JYiD~J?Z#MLusBvCbVr=4uY zG%9V4??5{PiU>%xra&6AU7Kwg$~nC}uAH@-RLf?{N|!sTB#so2LZ)wxuBtlqAWE$TFniROLZNbb7yjUL zTfBJfB1baeNH1{E_w-ts&5Zm_B9xRyeI0eQ3^$bMK8Rh%aT)&jZf#zXv~QCWE;Zm+ z)PbvkOD8@WAja+q&lYMVX&RBBZuhkv%gAGL!n9^a=U|&mBR#;-vW>Fe@LMe72?y9R zoKM&<4*+az)n>f*!-5X$ewIj-YDYCz_RKtn=!9oqk}J{NO}1yqeOq*wVEdhC+1ZEf zLzpHwbqHs^@D$xsFEN`;DJ8QgP|L!z=ZZ;YS!o#4lT*$=yu;qCa{8WaWK=a(n3{Zx zCKj^IL<$oz)jDQ~0B=i+(DTuG98UZ4WOg`~vJOSCNw{S@;%&AX0ZmN_) zGZw(AO&Z2Z$lGexstkM)W@k3xgCCyqu1EHmO3zN0>8m2igMO)a<2-Clped}{v1#%i z2}&^TI5T<+U(rifwVtWkVbApt^z8NBn0Q2~x zW^&*B_GCknZpLQ(u^8(P^7?{1yk-l&G{@WCsg_|w7>708ua$iy&<@m`fkI~g<`JL% zg@3|tfA;sGdyXzI&{`aDSoVqtoVci*yj$qA^3c1^@Zk^N$JXQoNir&xWm>Y71*vvS zy=!rR)Ip;Li#U24tMvp5_41JH-?sBpj{uu~&i=uY-~5+PbNTuqQ%!7DSSq}H8TM}~ zXYQ_?J`W%J$US`EkxOJZW11>OOqtL;+&H= z->Yg8kVFcsep&IW-}}8g<;|P-4BtHGdkl0?i@QpU+UN8B1pptPm%s{iH158ZR{Z1}3A?syk8i@9O4+B`n{<2jnP<6l z?L`WS#WFK2q8>!z{>__w|GVF{D3gu%*koE|;)FGo35rlpj`)B7*Vp;>Yl4m^PA8&_ z6;4T{VZksKzVelG{LR1p0uyTrXG~HVOXmJjVI0@oy?esn|NBS0_h6r2`uD!X*FL*q z$;iYZs);OX5@Q43#C2gf{~`;7p%XtL&oP~8?q26a(eBMCQVN;T9Q2eJF)*<LipWIO6H1w&WEN?`?b{P?y>-lT1s5(=4i5IXe(egf6mG3g`PLua=H6|K###(Q z9fUI!in6E`sRkU9Ei$VnMN_3FWh{kKAu(|8-ZR`f`s%SH zPUi-;+MPx-4tRzWE|$%a91tY{@Oe(P=?QH+v7p)@6!BD6c5T=Glv{77&5())U4;&y zM)@QG9-@$JQD;8ffx)EQSLI}-d@zjs?y{0DFFB~0&)=#18~^@S`PnbO#9kR#uM5BS z>;H^D_~)i+L@CA- zOy2u<8^eQU|EY zB({KdrfZIlZnG?jYX_HD4hgBL(FVj~QSwDTC`{#uv(u3WrSjnPl%#784^|*+q$XsV zSRbFTMkowkKrnozYKuapGEO6s6Yt&_`QY7=r(ald>BWQ;ILAJzCPqedsNB9Y^7`v1 z><#eJi~F!V#~ohe+tV-c+Un<++Q$A0bE_rmNQ~#vY7*hzY&ah9K zjt(%hR|?_J(Dv=EqLx12ZEwsg?GifcCuL({&1?@pQEyko!d(q22s=;9Y)CruW(SY0 zh%K^Wi>h^U0=}S)NJ7p&FFdWG7Hxd)K1^nhd;)aJ4kX>RUHe3|#{p0JG5gL(w9kIH zxK}Yp3_Yf4fK{Mk6C3V--UnjJs565D2!h342jjtPjT^cS6NHp=Z;?Bb6(|VnlcHJ6Xe2J)3!96UfR4Kj4O_p_1n&m0NO8Eny- z%!NLFGyt+c&*M_<7RVXzMUubE$v6;40Qb?^ljI6?MZGS$Y*K_MLE23g{NM9 zm7|==`vZ%;fkI`O68icN;LRVvE$^uJ-x1yv>+nX=_23!2S41 zf~*r$T|=6vx}dV8sHM(TsSerBi-P!2h^L)SC{tC=biu@uR2H0#OK!_0?#Lxh>%gd3 z3VZ=-W*VVP6G$af83f9DVtqWZpANb8gA@Mw@4UtGT;lTcOU^wt@Y1>GIlnsO!O;=_ z@LR8O|3+aU**Lj}WPH?9VZnqIXw0N+fUhQH%9SDoC0lfBRo3IDnZ{qB^7EXQB_oAe zy+9#&G)yI_0R<|#shvkvhNl@yMDsX+$*g5m1E8dHE+qn;8kLWBYj1t(VO*ul(|0vv z->FAtrP^CpSh7T~CY!1jRU`omf*tt_>Q4)hBp8G2=^TN*p5A5gi zd+)#>6c4H}qKTXbrjn=?j*D`fDrYjWURTZpR7^(Jx`)c5Em}+{)M^V-$x^-*7*!}q zP+5Xjr~ZH_>W2zN?eB=vFW&W9V3K%kv-vMn0~x(gkt79~NGY+d#jcwLO=g#xB$T;g ze5qs#xlWMZVUd2oA_-D6s#a~?vJeU?wPj2+c_$_SRfSVsa$hd;AYJ7Cl=<-VHrJ+` zTv}9CIZ>+lNXS4@50??IRUk`_Imc}lyj%9UGgSu8I5#dWvk(JW&-9F=lgd;wN^o&c zs1)h$>?$eceTxJ8;7|t zR#-8yS8<9M%l5FvIvWdL^k{Ck(icqB-bnw&gaA(dBHoE}osJthZFlPZH|iVhT()OTLw!T1cLDj!^Vj`wb?Il1(| zlex`mA~ZV6&vEj`9(<_C*-dVL`x^gr?+Rzj6S5`_ zr)L;ne+s$z9H-Zu&z|sIC z2S08$JZ5Dd#04F)9-%*tJ|Q%BZzgPmq&@J-);9Iydq5Rtqa=eCM2^DTc+5F=ZPz{t zt$)7^APtfc+mcxi3+|rVU^3#9y zBCqd#jo+@{;G@MejF$@6e(?rh|G{})(rX-l_;=9ZE}{<+NvxBwNSR1^v+BLZ17kp# zIduV|wy|(7x}+0H*A^-2a!zE{sDe4IZ+!cNfBGB8jJ0xjuJYWAiD5{bo>cai!n4;a znn#9}aQ@O2@}3pID?YyBks!t=CRCZIsw4&nPDd(`q zjPAJBb%mO!6O^fXv{YhMGvl3)IC=dBtLYNu)@5#Jk_cPB4D!eJifz4rQr@%IKhmarCX_JTkmQMp&0RbHk!&uAGS# ze6q5S$?Fv*2Z(i^m9Y+&>>15q{FddSGOGHQo}%Z~-PZIJd6-^QP13p$Yoiki=*^hm8H4RggAf(046^MGByD%EdMvp`O5k+Jn* zpaH*6a@&EVyS8he_|_Xe!OiJHzJ)D_ucQhhUW}ttA2XyR2n&=Y$^^PH=cZQBeRR5l zQVbV!vh&11)d7_~#t$ws-dsUSJp9Z{eE;^uFnou~O@;-e?3EEyW*8QvWU1#`&AAJj z0P)m~oaWWtS}UcN*;SGRIe6IomsWBfxVt{#-dmOW?Q5LMvmnaJv|u$A$eHQA%S^W( z@|&;!Gk$A$3q6HffBTDE`io!XZazh250wF}YpSlDD{gjPBIR#lNzDfi?%K9eO-YrS zxxwf8cK#CYE?+fAZSvL0Ds2@oWg+d|Cx7Z9=gWBxA0Be^oo{n`Phhx==I`;*ul_C{ z{rW>F6P#R!2QR?sd6<-Y-#y{p2X|m8paYz);NH`4{0itjko)Fs^CG+r@aF_R1$b+_FjMQ67zfLGW|weM$B%+PHYS33Jd+2q0M4U67jr`z80Ah+iK z_P(_HwVzX3*io}`Wb63;+B?T|*Pf)-&-ZwL0vruK&P+}V^4>nv!2!p63my!G^+bo zy1Lc);qoBl!Q@Bdd~?S@k}!C+c5sZVg^L<{TzYZEt3Ur7k`uRYJ!ExW_=&GxBQ0Ur&%FHkPqDY!XVgj&)3f`4gdfk07*naR3r|W)+cc59^Ajdhwpvl9@ilpzl88SQj&3*>XIQ@RIn9h zQjn$VI$PD$Dz@+xj$#%f|1hb6lR;fz=ke$rNyddICWFN*yEk9ar>aVAX|k3+*esj| zKAJw38CmtnPpjbU4(MY<_*|p|km8PNZO4nubEqxgcGpK7pwMKCsZ#8IB05RCVl;|J zT7}-zc0O_5RE=YsYSadr>K~Upv1_~bL$}^m+I}g*9x|J14yp*ssf_A?vOw!#5%U9< zfFxqsN4*UuYJh)L&_dEeR;4geQ{}EKIL?V-Igk&9<3sq1fAzDx{BxgWuUG(vB;mcc zC-e>B?3>@_o&WRiQPaB|;blYaeA4>6__p;ZXXV_NuTVw!WC^^X9t_ymY()@|Q}27X%6DgWGD5iy;j74TvoQQf{(D0Dzt%`R!c zZH$8?v)y=*{CeIVzb|C4l?b;{4$;R)9Xheh0(}b%!z$CgvSo)sUW|ou$9H4q= zOI3|}x==Y{&23-}&aYXBbc0Iblv+n96-uR?T;hYpPxJ1%i#*ha% zhV^CO=g@Qy%EW`|uk!ngf0u6^JfzBC#g*zA!g`~!?(6`8vZTtw#=sqG@#V(~9LW{# zrRz4<2{fe{SQIlLD^O&h>>cvq;RP;^D@tAf4@g?5M+2OF7E)o5J!D!^#-&B1%3%Gu zeE{hISee7Seh6}gq!GcYHcuV+i7X5(*E1FrPaRE`9+I$CcAp>BQ$TAR%e>n9=p5|1 zKASt~`_9J`TapK*Wq0{7B&rnEv7zJH-`_dr?b5*Gh9 zDgTTYf`GcJqy@j?DA>YY!+ z?Pqv!e#slhUqP#N=C3kQ&uhBfieZWYW$=V zMIq|}i{X%ha5Tb0E^*2MsHLbE&v#W%XSWRTYFc|xsvII`FT?3mNLe9^!JOKM1^6_` ziylR}gmM9qeXpjQfq`5>OQN!BynYM?O>6fL_n=t86u=@~uyLybS%(R=MxOwJ)j=2AzUN|o$`z{sG#5g6UVrklMui)fb z;qQ@X_6bFZ=MQ=G_UMi!{9`QGBQyf5b&a$?fVRI|&+O39<&^B$uda$NQ~u7{lIMY8Ns z@*Y#E&Up#wk~9`LxkOqYP{(sHDaZt}b~rs-igzrEQDDsQ;8~+%7zRv9C#V^f#JDUl zcwwgjT+9zn#A-KUcDaA%U7C@qRpt;)&Vi+18Vj&C@r>VR)EA*cn!V%yAjO5Zt~CRd zq$A6xuX6sS=g^`Yyn3CRtE;@Zc!v8jLK3EBHKhj(lE^7-Dj}j$Z9&AU8#gYP9I5s0 zPgJi)8Fwy9EtPUysYkb2r{_qVqUAQoVRL$^qZw*?4)kYCDU~(r@h|ai`f2_s-zTcc zrnF{|(u~D``({qpfudfd3FixPP_6Pu;-}XOGNO!&Nk+riQcW zRWPiGNMUOCGx)uAd}$l=Z@Wb`MJs=$ZJ$2+bNd{r+a8mm-*-FRzQ1nmwkey%pJD}h ziRc1l0Zh!bgtsl9&HLE3U3)Ux$GofA=rVFT;Oez!*}r%hdFmPu1x~46lw$xfQ0GL1 zV~HH*1ZhC7Tx9PnU*O`kYt?v~lj$6nLJU<%)hf2{AD=^x6YIMdxqssV zluxrx*LY|74Niv()M`$U2;5mJxA!Zg6;i+8T$w_pq6_tidUGUF!?|2)%Sc4i_scx- z=4aQ6R>@u3;#gI4JcI#c!SZu2^74Q5S2(D3FIEiu zg6t_We8`$3##E_fM3&BLHhBbyFXE_yb8D?kwX%|dr7Tc{(fgcOnqOAc3y@e}qYATB z<3=Sb$^d7F$avm-Qh>SyEId<51Ia4)f*69c$3&4ik955Ay z0jmrhAf%e}nlvFbA|!3pg-8gAXXMp*)j;kV;AEl$tz8FKC93_-2*1qYKK_n~Riyce ztvYuLCh~W~QyR%}T3_Idv`3FzvPe+lB;0UfdwXWv+3p?ZNZX9#wp5!8J$Ra#3ycysk`E03xEHThjRuXLox6yTU5CPnp%-MNg;pj z-7F{%lki}n4jlPARWtHJVt*+dF0b+_zRtms7|jbN#Y@fzg{*}ll{yS8uD(b){}Sc! zfbn2r8cbdd%LhDs9=^qSrooDms#en;GTZneXO^0I`f$bSD_`c~wKJ|=`336j2S!&` zY_aX;2WK4JOg!`Sf`hA-31yK%bPweP&Q^(gKYNECT)1wc*Mli$vr`b+L)f>>JO}*> zlMO4$xJcEq@IsCe0JbJ8#Le_H@8s(s3xrISY~(spnV3*b2rE<; zOrmH}vRb}JtxJm2o#1sJ$Ro%_v>br$x!f-HJ(;W-#)*kyvNTm-fN}sjSkOy#ovc=z z(87Qxqzt5D#g}Tv?Gm@rMSYE`2M%L#YNQF!YUfYRw>e{i+M+HI7va7Twdu`-f^a>s z9W5$!Af?XV&99E@r2v+@^KH009dOw|Xn$|;YlP1lI-^mPNe9Z#QKTB@CWUJ6K!C2l ziAL-4r298JkaX8}?GxX6khD`Eo+@Lmlt&5@5g#7j-$nN&$*AWq2oo0T<0)(5HE<4q z$_ZYVwyA59lE3gNhQIL*$V*P1T`(Rj7*R^WiffEkotK0cBJgxgcc?_1vsA(uaAzi* zA$M|6CFNwRi{8hHLdkG)20HD*v`;A+>Ynv7B0j(sl+39iWklDO`l3uERWg+ zVo6&W#jZWp$zi>L7N@BJjKW;B$SPg-%(Tq|Yqqg*8I5*_Y^Jft)Ae&91h78G?e<3Z zhF98sRzFwl*QaFlo!K_tKhA)UbBCKO-O<~9*p9k!UN|{K^bF((7~QytXA{6`54Jwp zM#QdtlA15{1V>~`RnDO2S)^yV{>s;pFFwcntHOhYG9~p0pbR-P31+7dW{CoULK6ay$qNGNc7r)-5hyW8uoLqwV=9gAAl>BQ^QgDa9R) zObFyeR*T{+MW`vksHi)qB?$~_h5MF;l)a!88BK#nbB%yfq`1hd%{fz1rU8qt?4!iQ zqJqtN%Poqk0Vd(N0fsaN+GyLgiD`=fOYX2)1Wfl_L_jlM;i==n#?P$gz=yN!mv8JU z%?2{iB_&0xkQ@w2L7$Vu4w4|}hAb8>=BbSV_KK%|TINggb1|pNGcPzRoBV;10*XhD z3N+`}c-BEgNy%V<WkU5Kr&EP# z$$G7SY*FaBE(r2U$x+&e#V z;V)&F4%jb0!Lo|;n_4i+ga7XX9{$FX%Rl=J=f0kJI4BqQ*Cf`|DxBs--MhrJI>idQ z$!xiXxMZ|NzSa*b1Q;4BlI8+f^J@|Ik=IZNKs4-w zHeDjT#q?S8Q)AIERZEvowF5)xeh0`ZwCeS}&(u}|Qwv&|kM$1{`*zpZe$8|3z}c=7 z0#=Nx@T9|tPxjsI+OF-|57A`f_bg8%deHb7wWXMe3F#VXbz+4dBsV1!rc#9#z+fyn zdsrmS8Nu~pK9v2X~B7Unkzr~0>vGl+8ifOIZxR$BaDC4l&-Dn62NFE zt#DTSU($@+E37}dOP!QjE0Y%LdP3hhgSQLZIRIJE2!u2uLNO(jJyy`c2;$sH+IICXaftXHg|PUzscOwt5E<=|nX^IIB`7g>|xisrYjXMo^Cq za;sz3gYjMS7THv|+xu;AkDAmze=?E%1k+%+E8hyHgMu(S!yz8qiZyaBEd&p1RI+sTp(uhkLL( z57PsXl{woUfdqKeUqrB~rE^R5=s$DxMd$kz=k$_fE?`oNY8MUY%FhEXkMTl6A@gTx zYk;Zgg!OXd`^)25l6ilG1v*|}nlfoMBEy=J5;@r-q-bioZjP51FD7N( zdE#L;9ikDf6BTnSKn@r#v^v^waMXzzkW&0B;dHL}#a8_jI9ceiFZ%5b!T4>#^bTGZfX%Cp~B z6DiU~^~EhG5*DnHWTeI-T;qH6`U0XnT%2&c9QjZpf!i0hT*l?k3d7lo_g_vNKb5$< znmD(3$iPFCj9M6li&ODy)37kRWZkgDp%Y&+`(U(lbo)u27dzd*Q>ytQ-q)liwzUK; zfq-VC++rZAu%V^H}yeNqlgvs}a559Tz&F;{wI+ zK{PbD{U5eMjp)uE$aS3%$G5!xJ^{`Sradsk?VWxi^oqLwv)6g;WPV)Shi^~fqM-7m zw;f2jYrFP|Z@p0TNJ|`KlT1_}mjFsNn>Qt?ZL?HL|2ra1B|BKxM-3WRj9qm$MzRW& zO#Q>}qu+W1YUbQ8f1OJ|eVsd(_t2%MiX@p8hle4VBkjPKrwxYQ3ni;co`%_9NJvZrg)OzxrMH-qFJz0rK`2b5rDY$~Z@v%zZ}t(9*SCjQ%4h14e2xao8a7+p5of)mq;3!1~}x5R41}7nB1>Y zwP?((k?Q2xMoz$MWJN`j+OB=#TL@5-fR<7$pk5%NrPO=WXcsXG zUWHHsJhlCV>|8Z7sAX$&Lw6o=9qC+YDx@=^xN=xMsGMKBgIwmrX6qyrM0Mx8a~MKL zxz)0fY9_YOc7Ab=@tMyu9VBFJ`<1)LJUq+PyQ8Nm+y%8&P%HE_P!pX0^mWcZdxe}U z!>Tf!opJdmo@PvyL9Fyr3P3>pR0^7A_s5j20|g3*6$ha=6q?h`Z2XDXcqfH>58(G- zLtncO4+at!sT^QnbnlSE3<>^8b79js*@ScZ&+&J3P#$~yqe}TtzGj@$W66B>q}c#@ z00UB$+(Zy)bM#(oJ{qU<3YAo7r^r>GV-ueW_)Prf0sYoC79Q=XET?~=UWmFvNX$PIcMi+Xh$7YFAo z)1mrvOP;oBa&3PEdF><4K6;1@1H4z^=o;zt3JVU9Y(QNBq*RhtQi2kh58Gl+*-9Gd zb(aqi+8sB`&*rNUi=Dc$Yp8zkdyBx}WY=ijhzAgBXR7w>H&jPFBsU6LH+;-gXgsSM z^F=oAAtj?TaMUHD#lR!qJd)Y~cRwy7w<2=YImtIBkAt(?M>{np7fXw6ix82LytR%P z+>g3FVRvoUe&iPOU$?%qA18)D$n0IXN?I*QtHh=2&#=1uD#tHf=8v8d{^$}sSO%YD zYID6w`s)9#3AFg<)?RY42)(3I-%p8amT{MnENIU z^vMQT+x4aiEk8W@@|c6SXX%t%%QJ+;sVJ4gfS?S{{|Q;FfS`qGY{r7h*6;1_AKkX~ zR}6u4Y5ZIJ*;upj*k^xW4w^9VSS;c`{Fe~e4bb!XlOQ7SC8AX|QCk#g$l0zdeN?YR z|AoP6a!#vLF_g-n!c^3X6GjG#sAr;di&=diky(Cv=EX*fg)Zs(*gx|C6H}k2&V1h~ zoWU3d?Eq|ldm{62!>8zkIe5SPy@_;@jj7ksU-WZ0&e86-e~;DmRE%|BB$qjZC;9Qw zhbO%4K+;{?wNHH8_Hq)Qch^AA`NxfYjR@0-Hr?LO(nQ>pAX2{PO5qS`XbGiIDTo*N z$WVj$7b}mOmKyHN=W3QL~HxPS`SQ>5ORzxtmz`OX0MUxKtEr6sj4+NfJZmsimE z*ykU=x938?bxu{>hEaP%`SAc{>h|3}vv$9G&pPfPKBuki{qYSc=?3p{eXzn<0lq$J zT0XALcP%VQ9Fo%+MOVN>Ho3WaCt~N6?%I>qY<_F+#E_Uu;?{fj$+z$D?1if=o?UUK z3(n*`HBVMqN4$!#Ky^S%6|2rI1^{YG4J@oJy2oW=6;F@u^i<JZaiGmrp^$;PUzJMqa^f^JESK z4~FPOd4OuOwWy9=8bE0EdTe_QKsBZLJtss!7m?Q@Kj*$`+Xt!&TD{{N(Wn711+dg_ zk1PQ^+TSw1+G>r=*NIniW5_(!I+7v^%8ARcNoR_)DvC<&_?jQJDYvcQe>uo1I@;UM zKWyv9rUywk!hr(}_l3$KK^j0HRb@~t5W)-DHo#6C7LH7mY<^RdrC2e)Tm&Y8GLW)g zLS{^qRJ@zciP8t5r0#i(nw^le(_5~0E6oqvUI`Uf@{%lQ$5PRC-Y>L8w(E$36xVrM zk0I=XT9fOh@P*T*Ih<3b>wbJaDd3tYKCh@bKvv2)X_o0JQ0N0~!-ERky?%J;H z+LPbHfr2^Gu8$racmyDgZQAV@(WDNLMtc4xv=)Vj#EpeHNnzHhZUDJrN~)xyR>{7? zIynH^9K%@2G_E^a)pg|-O1kM0Q_>|>?(CiMa1Yk$j5TM}Va0UeCTIDZP%`R8rW9J? zpi(NxG4Ecv&)paAaDIQ};4o9jOaiBPYNQBOHPX8gI;eVFWS6F427p-AUiGM;SYeDu z6X5B*%n6#vQ>NTJfSZ>Qx#+8ZKpon_H40>Pj`?f@>DKS<&zmzu9@)D6?KU_Wf7izx z-G7#?@9exYSwkcM_0h@wb>acXJY{P;eioaTaqexSv%jP5Zz@V+iBJ&T12U@H*YD>! zkDO`OcJ0qkd;A-}`L5cWR|Odpxh~l|&7iPM!Z-<4vl-VJP;GStG`SJ(sdL6-W=?}P z@3KSO#2m;C$J(WXRp$jwmD>j+X95@B-=n_w99(!nUau%57#5@fYAqxQp6dXl{F)lT zsNY_7(9Qijqe1C1GJSlanz}TwG&J7~5JpiaJd2>mzv6PXy&}~kDO2b4M4ElXi-r>h zqp|=1AOJ~3K~!3B<*7X{rzqkPCbib)sCjQ&FO$O4$HLK#=imp2Xqq^8{TcGUpp9<;{qbFje&aD;3Nx)x%&{1+024Ya z!8}_u768Pal`YZ+2r8TB6TdHy@KJ(NqU&pdjfu8vKj!U+0jYZ1<6mzJ$&ylHstRe3 zd+9P0*O5ALZ8=b{CBAo28TTzO%W$UP=Iq`>Hldql+lzS?6+xzb|UM`NX?uZMR(_8zG4Y#MXcPvgc2`?Lg99+qGR|Q$Y3rX&<5IpQA{@ z256e*-&mS{6zK>zApln)HNjKESi&MaYmM}S(D?3{iA9^D!cfK2*L&eT`wla1WtK`P zZ$v%YO{h{?=aErCm=LW-k+WQJ{c|sH_2H6pdJY+tu}-X|pk$7Y;iLUbxpY!SjWv!!u60$Jc zt{q@SKdg8~oMSeQ<_OKl&4;-?YP$De<@PbMwS9QZKK;Ir_90?@EY;rAMDfbn8`p^I z=SR-b_hCNAeB8E)^Jov_O3BZ$0#=9&z9|6Uys`g}lM}ORyY{0u+4}u)O@R?*VpQc= zVHzuIAT9h|NSJfuj;6L0X+K^92_Pp^3vlkx3f&3J)nPF-$sO+SIt|pFBNJ=q>upe$MF^s!QnT}~ z&7rnBAP%6)maJ1dM`A&$x$~#Ad8v(Rj5J4Eb*C|&I6Ge~F@d)J(}2^2deOxyi9v;z zUO3O{3j#|eUq8pqV$Veh2NBn&RslK%Na#+M;67t$^xz)o(YlbgeZ}2=iV1USc{{Y1 zt)Bia^SI6sO`sFv`?Ue=99chiONI1(o1GGNhmU8|!7)FCMm#7z46e*;x1DAZ^>lrm z&l8A4{L=12k~Z&bu^{?0JLsEfs4>Q!u5plMBO68N#$eZeyjl-4{irs>pY=1<_IrM{ zliRs~BradLK-s&(`%wRIQ6L7xl+5% za$X7LHGlRoXqrl5;m;SmI^Rj7m(_w?8Z`+@L0II(u-c<61@;m}66q0Mzi#Q@3x83y@w&bRd{zmlX)}Z$syAfgBS}(6@Ho!c?Y`kYRG-p1{MU-MZY@5U! zZBeiRWzShMHRk$8cl{al&vT>IM#lqm0U@yfD)aa~!EFbU?%J+>;+qTRMFkt*7pH}Mte zh)^=hve{};PeW8yCb4R;OI4PbQ@Xf%ji3K7{!@PGM&{~h(Vb&~F@sj+cYpgnzjEho z?!J1R!}I4^=qbV}$(>0Xi9{8p>dX-y#OG!NNEay@Q8Tpkpm3}Nb@~DA!g4GvRR)jf z$&qqesnZ&*%QhaS{(E9_PTvn-ftN zYc!oQ%EZ|^F;*e(59A6Zq6T5p%L|7goY{!Jn8N_OeJz5hMpaiL&D#s=rN!((6ga$; zdF2;B!*}W-H~#LgpbuVy=Pok*=l?O~E1yGCM2d7B>Qb1iS}LX186eY$RD2{mZRVD4 zevwDZZ1^zn7&#oL@WM=*P+g!c62->Xj*lz}>xWUdgzg9_r;R61Bi-I3UQ|7OTx~H< zNmLc4h478Pb(KrsxXd`fZ@!iIf8Hx(@q#3SST;nZJ*%o7H5))_@X>Y8CQ|?B@ulf% z`<%M53UI@9T8lR7Q`CXZIkx%X%CSAlPX3A*@R%YM*1zi`U?TO=pOYZA7VOVjQnhE% z)QWDZs-8Nb@0R+!?9<}gSj4?_uTcP`ts`+ln-}vm?Z+52Qtt&#$pI zITL;h#PK*#ofzi%_i-#!$N2N zNYkOu(u&y^a@fWo#z}j_k>vtF+F7tV2dD;g&NViY?PIDwF-F=1} z?)6#!Kq4bx!-kTrKj(MbKxf+DEpoN9nY26o{8+VJzfp_z5wAU3zhT=wa@XFEuovQ* zw$Qy%MeGS}JCJnOcI^}2ww>V-lYR@|9ttCX&;jEt?f6C8cKc45m^mb8?ifq+8(6bM z$P`a$PzGim9zcb&5gy#TPkpdradAbJil#(K+4$51v_>j|AUUHcQK@7KNcA=D-k6*X zATy?lrQ4{5UDPGK|H=h^|LMfx2vlK`!k8-u$C;a_OSpMPek#Lo%vcj5%h};oyJGE( zv|23^vWfwfD#=qAtRM&2ih9vPQ7cen+&p=9=vvxgYK5(gyKO)gPa(^zR@uJ#v(W`m zKt}J^mIwFPIZz(+y>DyEd;6Gp{(U5IwElYY^MBO1*FR?aW6j);xrYs}aO=DNJexpp z7!fo1!)%ampTpdP!J@)MP%`Kq{k&?9^sc)7uKl@g+j=2>g7QL`tFb1M9Fx*ptcGi_ z_Z&ybT%BQQ??9<|)TS+4r93;=svbF6)5dkIxoi+DJ-LBK;keEmZ}z$=Md9`V;}IvfCRS;mvx?KiRIgYaGP>A(L>hl{7^BCoSDQ#Tpj=y2 zrGN}b%FX$2(JC?@OepYb6b-&E=Q|QNg+j zl*UizkyOk)tab_KO?05b^uBsJV(qdn1L$z)HBvssvO**xtRuy-0jv>0N8?O&x;PtV z2aO{Am$Wgn=DEFVKW0sMGy|ofN*{Af50w5{f~52HOe)R&4j51t=h%Ps)0{kikq^GO z;NIuqM3p-U14$Q9lW@8`fEJfV1HIkK1!wVqZId%iglX z?M^g;F?4=!LI!Eu3B>w@)TU=_0WEA+Pf4!QMQ^(t5XI^Tg!vt*<@h)%H7S!;GSzHK zu>h3RIwakg_jYYO3$sk2*A+i}Gff-p%=0&~I3=NL)l&U~Ec*#cb=tOhbJJrnH@kW9$l_M>8CnN`>Y_gu1p2;2 zKoCSW!yIwzr%_wL3QFyfO?NtVh_L8bDY z)yNMPnOqlWO-ypcIz8n2(Pf_hsdGG6pX1$U?{ZQfAhG~i(To<)xoI4v*h+Uzi6WU= zGc|dFk~&a|rTPcITH`DA73iqI8C*S4(KipakFNL7@dB`Lw2a z^YJV4;t^B{l?AYeSz!glKxuIU{?E>N*|lB!(`fy>(}zwfGlwIX9EPg*kosK?moKn? z?m13Z2_2Mafb1M{5x0^Ak~<0}-h`sVoUZK-qC_N%s}c+T2+l>JRjpP3EVj^7GJLeE zJj^2(*K4?c0JknN>>cp@!+|qNJWLaF)Q8NsDmdY2L~@9Or0O84P*Wi_N2XAz#*0dI zN8ck(=UcIR2r=5mbk<5H4mZ>AH{6~InuO%hoZ)C!kygkAmpzu*fKvp3)>zaT?8iJ@ zgp3N@IE42Pw9&n--+V~T6H7T@;VxCxN-e=38v3quYe4~AhJy?<80kQ=RJ(wvJx6if z-TcGO5%fq|I(h=TO`A(j!Nv?E_~+C<9y*q9FP&%au z{_OFt^F8&xpr@n@iCT@@N=-tkXD;hWR8OYrK%Q%gs2tWOHTPx)xP&(>;0j)FTaaT z=@j?gIib?;B^A}=3u`o|QBYEy)BTg{z~*39;~lM`Q`GcItH>>{#D^L%5q(y9w@EI|4A1vO5xd0{#^QBewo;O10Oa?Tdr z6aX+DXVwO+8pXhd%$5y+LI#U?ib$R6K#$EccPt&itkiZ~Q+FHBboPy{=#x|LBq2*g zso6bS6sYN~h&)vzSf?gWISpUA4?>bT`Ivc%w7WBZJOK91s8dN86Gdj%e(c(|of7tP z4_L*1@aW|GID741b?a>^_X*P6ca?|{c5r}7PDM_DiP`JC-cbs zN-`eis#LYe+3Fy1l0?-?ii`vwvyk5rA5cRN z^gPXkT-@BA2a6_E1hP=m4EzSYmK_`uOS{)DbeR&>7^BX`=Ihn{p%LvZeb+W!mj3TQ zu5E00rGye-=$hf_G#wX<9(C)AvjO(#kUXhv z2a@jEuI(DL@e`JONd9e*G@QSLMUoD%W%@J)i?GRA8WMF6IPd2@1CB5eUqMEKx8<4t zpS^d9wJk}`^S;Pj`<#33qu#G>cC*RuW{aXE%CZbYrU^l|Akl&i1BN}LG_VDDWY0YF z$bex3o*No^VnBec0Rh7n49I|O_$7iQM2Qd|pqlI^`&C`l)m8U-_Ffs`K}2Nc+GpQ- zu-Vnsw|1gV-M#l(D_5?}Tp1C6{t@x~9lrR*ukeR=F8SI&f0y>^W8}-9h27%9td5ns z8`CDi$P6QwR8_{mvs4n)U8qBlNGJp#;m+6)78bq7bv3?q_dPC6ft5uIt-7lM8oS(G z(zuZqv9&{qFlU!!ET70M=muhOH~aubO$v>ISn0jjqW`NHRvN{Em1AL$>SY*?idkbY zfE&r!{gah^rn%o_du(g&zfV2+Cr6*3rb!%wjpM z2mkQ@TOS1-1m8N90Lf>c{-S)gnO^JOJ`?_#(dux)M1F% z!Ql#GP`8yk+d6*On5vTX`gau^s1Ivum#y&Q7*51J{wf?tmSHo6;G;TG{n~a z$RS$L*sCrW$&awu)GpF!5d>+|QUTGiiDV+1B}pXkuuT5v@TqUU#Iw#0?wLR+!&-D1 zkncLVjvb>%NA=_}$(|fX6F^Ots!XS*emY0v?_+`6G2{D3ofF6B54jAnkwY@-2T+<1 zq$YzEFGPIm9E7MpJPOiNLXwDF1Z_I+GHv>&e-5|z4zh|x@<;Q{pIX90!DWzXqm+tP zakg==Vz=*^Or4vHX^v35lV$FkymlMfpv&jpoe5D+3;BmCQ~l8<3ms@%kGHei8U3}) zwPVzlI+XU^>`8`10%RMPjOwy}$>*&%pF`l&u=92XNzdh6&V>yS)OG1(AZDz}SS&kB z@fHI}f&qx8C7i6hGM$(H3xWf8?;$+FsJ)tNq8QH%I;I#`aHyWxoxRAUjL&?vfMo6rWOD|FfKLMGDsVZ_MHPJ0?aIV&ae z{E(yTX9HneH)f^vV-j^pzemDj~c zrYfjL+-UK5(EuXp?oTJ3&ab)H_KiQa%6yn(H;zOMO$jDbSnv6$Zd6$qXT`xi4bKF% zj7KUx2Af#`kc2>j?hf1cNB5ps!>y?r_F?D+>GeSxn1qd1Cu6q^cg6zLsG|y~AXTV~ zb>Pqqa{ByGiKyZ|mYc^koX1_dAsMS~EtHH^C(iIK-Pp}EjxqtMgnag}5heSR0Zvj2 zGX~;wcQC#j^ry4YBmhu%e-B`xNCz}?tV_fiRcz#vifK)}F9c|9=^iS{nspcZo;a%t z8RDl`B@y0r26@jS=@V9t7m+gk4mb6-Fds{DULG9$*!}`aOqYfW%|FIs3O;`(5L~hNGy_Xe-Owsf6te@!5*uf|qoZCO9a_pDgJ7scvcT|M zuqqxiy1zD4C?NC8t(5Nl0?zUmTs|NSVrUN?z-Z5LU(C~qEmS&=r4T*UpHC~3ZPfe0 zj*iU(z$B|tIgrG+7u2^(@TPOvl;fTMpi<`|jasSb_91W){Q4eW?WVI(8O>sdLJm3OWh zZ{1okEi6x-=Z;qHi}~)O1j|D#7#Cho$sJ1utHSzo+7LeTd6QfMH*zY4O5woDD%W5Q zGmU`Q?iQGFUfh*o66~RQ*#eqN???dV^o>$ks;*%%=UT%``3Xg*iyu~APL z5Sj{i7^P)8HXKxfN!A%+vsE0*-r)4&p(708GF(Fa_~?)KQ(DiK>bZQ<%T3b{=<&Uh zfYDjl7V)u4W5v_=S#55lNXitYSfzx^w`T0CFkW?Dr%BhnjzW1I!NTwDOCxJi;tgRh z@U2_MTNfS!PY#tw<%;^?MLzreOWu59eD{`vy4~7~wK|!O$!PQ}yrl!VA9l;>bPwJ< z$JdnOb#J;}(vAy5JLH%H2cGOtV^dFq0qMWFT+v99vSD`$Zp5k~)i}Xs84-c1I?=PV)h%J~ZtFBP@7!8q~%K+3j`n$V;v&IY7 z=f4AYpQ)Z+KzBaMPB!SNAkKV!hAhCSfog z*h`mcnDm|;nypNKN4-9+dEIQ;+()Kq5-=*bMR z?FkmLLqmSos9C0Yo$FlRHOt?!A7Tv*?*RJ0!S?URLl;qtuqH&_39l%B^V`N|n#GuI z7@S9a9czD&NjjS^20b3csom2LRi?^%=())b*^Ee@eyoj5+C-l({!X}a7*tyM{+?A=G?)r3FNY5_04~i@Y|f9 zza--^ek(gDLVfOnJ70Mfd#~~M|M&w`R(QU_U;aG2c-t5564#}T7Cw*pEJLAmp)8ia z#4{UV{AM5cHN}*L#zn+PGj`61A`*8TDJ&u~i7R(=$W#yM`q+{=N*#)yNyLmRn8q$? z^lzbt%As7@!tw_Xc<?GU6_iIpqKVAOJ~3K~&Mv zE|WCclk+pfUN_(9*}yzL9+F^t)W%AbX7e12ET1uLon$CNg3AT7>VRmeG^$^3LJK*g zn({FX)`FDCX`FIK1zPiCtHHj&zIyvqkfxY6XI({ttWJ%bf!8S>YtJ5>jL3t}sZxMi zXvG;~*(=?(69?NZmt+}zH4N(&I>0V|ubzEAyI5oHeqWbx+Sk>JKMI zI1KDy=%VpU;P8xD=%_5+ylJ>rEuqO{v7<( zpJaVWD0ku=FX{yKWRprmthrlvzJ`_z>k&bI0K^vhvuoUQZ%Bm7@a<|3XXVF_!6fL^ zfmmKL!JDY~JF2<)N5{oZjoPWT-bYf$g#|{;nF+AMrZx0^#`V-8$-8BJPdV=?WwbMw za@%&%3|QuG8_UB&3A;k-w&F*)SJn?pxE*ylCytL!c90#(mP)$KN#Ci}9zSRB4~L=EGu@^^hK=3g=mkSDX)I>!Ojx<#x?II3;vSO& z#v1NFVNg#Bh3~RU4_4qTC? zc>25ftbX@YiAOZPxm7mL<)j65mllgQUf|5?*01twu7Eo@L;9N2#>}yH0?)dVaV|fO zrCS!$-vCUzlbHoD1*rvD3S}3rkkaT(kE~0YyHAb<7c@a2wuYhrD4P`BCDxiw z4=fCSOqu1fSjjkhC0J7)ceHUqvl@vtq_anjh|gy_7&97w z5&xy2*c$S_6;IN1SlBgXr-JH%)efGBrGwMc8W#Yc^sMd)0$LcBI7li67sX?E??AgN zCEY+xck%%YPIF;{*QBAG`b8V<=_kd7CFjc)@agksX8w0WIoly)40}6-p4_ju(Yov( zMs&=_{Oc8Huu++Sl6;q}_opA9!W&G+{uT_?@x6oB`FG)c$#NDqpQtkHEcrd>;&w&Y zqAoKi@^Q5jQj5~qjF+C1z`bjD?}CT_%bQ>;l-pnxslw-80{J=NyH}NqTfzb3n#Q3< z7%GjJ(BgV`XYq^cYuGP_Ba*9@mY!DJ+!jg`9Vm8l6@zH^~_XA-@P zL+zh&`^9Y2^T+G=d>0FOki^H7MWbsc9;s}5JH=xz1@kN!cbjDN4aVUIm8qT429Zgp zpEjpFxmNy;%Z@U7U1F`Y+~|ZOIc^b-s=;MpSqtoi!y0`mxfaV<=Q8d~%Fe#dF?CF? z(*woMkUrjoSPN5zW9U&Z~7`)4y~*=Lf0Z$ILY*l=Y}H+mbo z*QSrUelY!Oa7N5+I#pk{ZLOY{VutM%eLTj4$kLhp4b$;jt=Q?YR4wKhMRZ zg~#`v@OZa_YlGt8WHomIRMtqk2DkfB<6xE!Da_*zpLFg)HH z1u3x;t_rfS|Lw1H{XhK<+`mK*Z=$?I`NB)o|KM+7ufBw}V0i{NDOpM-1ad=1%rO;Y z6_&M9-h9CRYsSO>XNUdYPoV9wCk-Cm#R1X`flx79!k%+i%N(CgteM{5vylBL$B$J* zd!OrPr8!Q>58 z_wn0XIHNR_yxzWz2Ew_V%O|tU?{&Tt8m~e_ZAGk5OGWD9_P}bM<(-1n67eQ0RxLtV zrc1p*k2NV>`4-E#Z^Jekpj7Dw>;QlY-J2mnKMNx&+uK1g!%Cyw68QWVxXr8Bt(URG z0*^gDS`R5x8**9TYN014=m`pjtNYe)7lek0hc&STfblRN7J$}}kS^z3=Hy!D|4)-y zI#3Yz4cTPo4zFfH4Ohdam6e6YGMJ=*n7bBQfu^f_zyrFL*rRL|nkN>tg0_Hu(;lqB zsKSk3)#&TVAnit05h&r(-@(VMh%s&^s0!7DqHZ_4deD44catuWF-_Bu?aUa)9O%H| z80&uDG&swAjf}aJo4K2MW}|m%dw(DDx9J`tr)|Z~Zkk@H4S+fI4@_abr5mt0<^vQU zX518_sFaCFJw2bqxa@#s?t>F;J(nLr$%XECLv^NgarFBsJ?n>E=5~w?Y7q(Ie}HTJ!S4uHV574 z+0!W=z6%fI(i6c&D^ngi=BUiNt4;T?=%=o;%7>dDgCbJ8b)-Fs>=Hm-jc_1BQxE;& z=TuOa6{_yxrD|j2O|*NMIM62n`dvT~$}Z;jO30IZ4`QRM1E4Nf#`+)2TOKbG@tDW+ zY6W(NEG0}%oz_3|s4s=+UyoU>HQ@3bn+>yfwsEF)v>%_2*(6Ik2x-%2#`?V3w3~}e ze>1Z@@59k=`91F&|8|gBxG^1iSb&s4vb{x$t`g^F{O@d4b^YR5FK3YST+ZcFU&2`E z3fKWQuw{u1x_E3Mdja7!usfuSw{;+N{>ue)a)a#m3Rc4gyi?%dN)S61y9Fu%*f#2| zf_?E0O$^;#BA3mBga@NzXNrh&u!Fmy*)9x9mu4QnsD*1=C}Y+?g`AL{ol#6ER6OK> zp|VosahEv;tWsT&L}H~P$cx6F!Pbsi;BQJ!R zYVRrq)I2t+Y2nr?ly4RIr;YMk4gF_(SPv0N;5NfT6NcNpO#OWXGW4;KqrX$il}!IW z4Fo;@9A7v0I0i81p+P+jh!L?O2J3xT72c#nTnf?n^#I4x*t$a7FHD=l5!O~OmTFq+4c3@}ilmmL4okPRaWo}q)K)LlzMCL!Y) zC;M`aE!WMn_&ps=eI0RGtKCDv|1~SY!g87Do*D{a*wO@=P*qvjQ>@aoqI*0EMr*#$ zxr1h&Ra&K>8JjfS+tUz^_Vg^cJ!V_{o4{&5lYt&$vl4LwRt{h*EFsG*&Yws$!;qT{ zSTQzWc^aQN0y9Xuxvq?PR&^M?U6k4g6)+pj$&B5InK7@oV#UVwk}_0OGe1f`7ooXaPq7<8|cS!bE`B91=)D9Wr0rK@|s2C2^^ z|Gj~|3%pBVhuV&}e`gQB`-ngH^RII6uYZy6?)Dxw%Ur{jVC|*1lOX;o7#%#N-$5vm z7r{eq)J^XsZj&BrWi#PNuoHih?i0bW`>@2jXF_;AWU-rSC39#DdTR^|fb=LQfOS6t zs#7H5&hrNT?B|v`r1o0U|1SL*v_GwE@AZ^&Jj47h;__P-3{NC008(h?@n_Wt0NZU7 ztRhxp8I}Rg3BkIJxov{jj)I`oK}%7g6hm9YXa?MSfZ>Hu>yZDk#&v*HB+LSvObf%R z!cMRynV9D0W{JL+Oys1|S1Fsq4(RrnZ13HZSHv27%AT6ze)o;DT&D{g9VhMA&8W

jaN%6rz@;2fH(QW|c3Vh0y$S^_vV zP-78?$FRojFMXcZ{_Yo%e*$0om3L?lE}&k3T+w7f>cOjMAXaECTv=3I_G-fp>V0hs ztj2N;^*cNEzYpuTK-zPdhBDEE*UeISc3n@wo4~>ep?uoHn~ojNlMh)o?3}0FC&#{? zI5vyra&*ot=s8h8)3r>;W&l4_Q^{TXoCkB=66X-dj_dQWGQ9)b1s2jJY(TNO>mP1q zlY{@W?yhn!Kh9;mN4H*kiO>DQ&r_}{#gvQt#vlFTZ*c#uCs1}^4}b$mVZ}4cYbg0{ z{J^o_U?xZ~2v@vdadelnxNrkl%}q1<4&KJ~dv1Sf`bODRF23{{w_dyA`o$g1pd2b% z7RTf$-E*Q)XcEZ}!f+{NtOI81EX{Nk#|^J}OC$|pmyww$$O1zQ7twrv)IBytXlb;| zcuY6ghjH!SE26<1mE8OZz*Y^7WP`qG2zGGSz0$xQtk~f|vjb%<*f-w6-g(Gc7v!4? z%ROj<7B^s3(f|(hyQW-8Loqkwf=MG92Jf`aCzZ7+x@Wjqf*ZrhChG2mllBQEwR7ME#iSM4bbBo`Jfo zW7|#|+h$|4v6C;hjmEZZw9yyaYHZuKy|d50);d4p#mwB#4E=_va_noU5rX2CjNNK1 zkI;wCsKt^5#wgIxS@KD=Zfx>kkDeziRAV%({ZMoGg?n^*!uX+=R7(9vzsx}gpOSL0 zwVUhkT}@Z-L50E2H^3{YDnQvtGd85hvozD&GUd?)OB862XlYZ)p`&1>lo1_KUK>V` zt4{)rK{a&b=r0p2ccKqED!n}uj`*k2oEODiCcKe21=KN?+_^PWap}>0t(5n$t+;s| zz1NRD-bMdrTq4@K@md1j9?{<5B%U<&r>V_rnC;FKT4U*Uoo<<4Dbxi7X3=6m0OA*V}5GVF%m*qzgc+3D~T9o1r>Me~DT7M}BWpI|?k$;^DkkPh3Soln}R z<@MtV?f*TDx;XH*fmts)y*6P=;LIHZn#}O(1|~o*TD0idg6VNtYjXKx;EcR!A-*5Z z5NJ{m)yDF97bfkfDHHkws!MNQpq=R zJw%Z%85r$)0rBV@H8%{^<)}rzJil(b zdNFPr?fKw}V1dw8b;v<`$eY1Nt=|*gobLc2GJ1%svaD6ipX!-}D)xJkSdnIzSeP2m zhWBYdJ@4-~d(8Xs+2E`&@dt3QcX9z#3cTIA@HMG3HGReJmZo+xL-au42dl=dT$nX~ zR2n@J6vD4Lx|OEw2Qsq&C44W4u)h|&M?V+5F+#kzG!wQyu#dCi3K;UY21bdEU@CCJ zmPu$5NP1Vwm7mTJ52R2&I?sM1%^khlNy;}^%4bckbzHVSs#)o2`rRU_#6UB_dt-8~ zMlm(u9hu)olA_TUGXE6^C;vv!RZ86=nC0|^syC+ZI7^?jufhxk-JoP2M>~RHdvR~0 z+P|lZh8Pywmy|d%|FlP1J$eUlAe;voA>%(nY$uKl^F3D$?Zhp`TX&(J`m(GpuQ2%1 zQ?{~xO(1f`5w~b@X7P}D^+nzZv(=2Cd-!g#}C@?1QiAl6kqEa`;-nwruYc#tH@>tlWEHtAw50 zoL^=iYd1k*UfLjA`4tAy?CVr{L->?xFK!A$bur9mz-a@~$TM``R7w;}zZ_H+FoND@ z$NB-RWg>OCb|gfb%r6R8D@~X zn=w-2Cr10=<@J3Qq7l*jAd@L+KXQM;A!Kg{9%&1FP52r=zoc$kxZSEsDpVr^*!_j{ z*Cd(l@onzY-+7jvk$FJwA_x&;UDxp4?})OlByXF>dZe3dSJ7PU7(Kh8hMg5qf4*kq zfh9Qozc^0t;lLvyXCo6{ypNE)svSh);9ut^=a-V8ZztzZcBauxn`pSIx0Jb(wK z7pM%))!`036rmu@KFpb4CSQ{uvFN#3!fKpAY?bS)&GPZwe+lHaJ z2tSHWeX;GR#OG;ZhV47=#4kbM`vqFEEvbT~kb>-d^Ooam^IHz?L!$QyurX-WPnpv@ zr;3T5?&cu5@XArY_bKnZ3w;{>?dHb)+2@zPHa%$L{5+oZ@R0p8v3#{1(fRv^HMeIE zHkk{ML$op_E<5bU*|X@vL=$+z%pxC&ug}`0Q%7soZ+WMWRy#J^BLz;aEWveM9d)~p zmRcwk)D%1}n<~Si{mTNe!tQwrHUyy!mAB`QLj(fuj*t$>xFwaB?i5Snh-f zn4)B^3R@%JOVJ(xz4!1-JtxG6{TUgYWpTB89u-LdR|5ODbw#Unq3520i1_ly;`@_! z4#QtZTReNJJ%17N%5sV5mR-5=@m>AI8+7opnB3@!?WO(D@}U;9VL2!pJ7Zobe-Xh4 z&mVwE)A9Kjd|2P}SC@_*q4Xg0qRVXmoQdM1T*2YEQv?uI887-|Zd)_m4ffZK`X5>q zteyiVNr?<5Nu!*#Gh*?iS=r`CxAe*A+v9PSgv=uP&-)m612tfp)&!Z3w(!j~x=I$c zx!7z|NoiNAy4H!-f44-baz^v`S4#RzJ-R)9iSvB!gyRh(vCK$NRr2m! z#}2Rd7=Oi-;gM$z*>des0nh&Q^RL#88l2w;vEukq1%@-AtG-w=sx(D#$0 zoG-;A4?3*iVQUY-SGAOhI>&WD$W^hSQ+0OOcO3YZO~Fb1OGm7zl|!~?OzK(sq)nQW zK8ADdw&yI||0fo{r80GVyDyd|I3YYGL5we$u6{j z9JN;#VsS_%MCgraW9PQ9Z%|?RYU^iOpL3pPh&@J2NTE7S7uUf{92b2jXds-ON3s00 zFD|FFcPV$D9uZ4p?RvTYT`RS<7hJLkAN%?1s%g6JZyFVR)!x<7*W=pyHzq9A$a+t> zWW6Cjcsu35965YT=5;1lVB#!UpXY&2vlF}_gGSVPv@G)!lWV?947mm+UFeKU0S7Xu zp_%4GmqX9owu8gEHeHjti~q@`Q=6p!9hc|z!!Z3j{gb{2E+2cQNK)VHGO?K0Kl)H4 zJeUoX3%NmvGh>3;#L>#L98fV`Y+HJwwCa)@>6YV)pEIa)ixM0P(J8=RrsJ?lwOH+g zL>Go{InUXbUp!oPsTeL|9$vyZEy(F^C78H~5>UxIZ=k7deGBx%>Up!qLTRe5{32fqD#Klgh3 zhtIeC{=FVkK#K?6P-pz%Czf6wSaqGY>xmoKU^#K5fcBy4OnIqstmg_txKW}>)km6p z2ti0yHGX+$e8f?@h`Ay;O+}>3QdFFqqR6%X-L>}G+~vOJKewS@xUuKG^I<+)DwF_A zj>uy+Lo^o)y=js#lo#uGlBIcLfwc*WhHpcQNQanm>SX5@cI6yV|*~l!^of|Mh#3#pZ2|#zEy(gwJI74{K=L1Q2RPs_qlLndE$`HrIcElo1<( zbiF6_fIsMMZ;d-QD=rWLl`~?&Mx6%|MF{YpU^~i2@Tu}Fl|>*Y9;18pAT79Dv^Ql&oQikDQ9#^>-{l>UB;Od37Raun6cP%)^JN# zi4oHczD;ff2}Op+P6{lMgxNB;&qsaB&8AL)j8+Us;`7idI9rJCBQIezW(91fQztxd{ zJ>BG#|f4|>Jbvkq_MYIlj1L0;_=d)k*o)7leC^j!4HoIQ#P{1QBpzu*COagd^}bw8VA zjRN)O$bJOKhGO>#YQ@=Yr)VdDS+|D{djlg=bV&H*Age;f&*cV_NVQt_l0tVHidcuk z&>?6p>+CrZl0Wl%ua7mLsIx|3(W99e$}#655T}CG93Rh4iJ<5QzZTbj@;{gA&`mP} z`;m-x7Wal8gkF7#-iO><-t4=E4)Q!9JFDlR&V;9}`y-WUk${=42o%OBqqQK8z#7$? z0VF~XdM;D>-+`R%8B}{J{FJSj#7yQZNHzZm?72c2_)k8(PN@IpIR(*!`|6VeUP61l z5q_JQqPjOFiA<|8BA&-A6Xj6NBG52fPPlpVRU-fPI_5N z3;JkrpJw9217DqE(vn`E{bG^^FgZ@XP41o=T^r^oom&+PWIhy@QMJp(4qvqzYQGW~ z=z3v%_{68D#0Y8}UL9xFv|(l);QeE_hFyzP$W6`ji+LzRA*5wR)K9lxT%Q+bnX7a6 z>yuK_xcKtZmdnZspJt_$xb*AriVHAfw`P^KrIMLly}1;EcD4;INs)8K(ZigMn*%N= z+fy0U%!8m1jK}Qk2E>GBYZt}p)fcOkvas?n*8UqjEOH7_Tb)=8X*9s!$eo%cJusxr zFOBP5)BOXT%|Et&Wl#GEZ_7QWF7~)!;`hEME1~zQ2Q%_|j6${J>AveW2A+LGgg^((p1U5#-F=uHI_MKYAxI`%3DW7WJXqVIM0!qqJS09ruQ%J#nor8d zYYImH%R7rd4d9g}%25tReUa0N3r>b;GPrx=y8djyzr78Pdrhe{esSE#uH5G|roy@W zMjsCbd)M2bbz;_0M%c~Nu3h#30pJF9&j21m1+ zgBvjn9RUlL;nf!9o<2=#A2?vMJy;qb>N`#xf4jn#*EB!)XBo*TTW9HUOV;$xt3+}P z%%@2jXHT*LruX~0FY$vN_QMp46>sG^R5QAJ_zz1aa3i zf^Z2$EX~RS_3IbB;%uN($g*{L7d9#qetLaPjLeSlyCCn0Z|>f=iMz+R=3XB>LaqJ> zi&+VCvy>kcC<47L#E{OlM%F=G--&nxX6O+N!Rf<@f>6e9x`y#ni4Eq|upM zWpeq++dUN=09$C64QFnC;Y@hC{_=K0?B=WJvjGXICPVsHD1EzQSfD5k`-AzCS?#+y z<#v1+G(6PFWVa~*U$x74& z!L;?=q1kEy<@V7NZg#|UOa$GZ|F8f^(kL-zFEEoBi+1^J2#@cbLS-6CG9IQwENW+BW#sFN ziFT!dnc3Hu?418(k^DRONGJOmi_FhnH9Cl2s=xir+I_hk)ReLl$h#}z=1bF{iMV?$!x9t6RNzg~sRID-_j#9_E*{FYcumnb!t)u1um(8|q*zO^ zyrvAAyNu%Y_ps@?cGZihv*orc$MQig%En^+&wB)1FN#lo2^(hZ7(tKEnKL$)QB!ey zEvh0-mNdH4TyhTFz6|I>Ax|`io=U@o3!6Yf}@@jkb~x zXM4}m?S})3!+A$E@waAdIL>={Dqn9H{=p5lhp+E*IGCll95AHyO({o5d|Y#UKF&LP z`ay!9|5bLSvj^>RNQtylWb6G7`SV|Tz}$TrVHIc@1}j4q5F71GUnVP1Mwa%dtMzF27Rri<4FNeGhrgwICzg;$dA0x-E!;oq1J@tS#7`*C`rXgEzkm_hmb%1c3 zKLa2LR()OkpPZ7~VrPMANb}aTyT_~G>bXzAbj>a@>iFM&-_ zNBBsb{bkn{HtkA+DqS%@p~qY{b3WB zbLDU^tf$FnUBv_{p(b)@(<6*3LIzg~>Q8nM(oGhhS7+5tZKp2{inhAr8VtiSogCdIJ6i%vp!ifR zYR$-T3%Ddd}76H$f41!N=20NcqwB27K zJ2xS~Oa1{_TM}%j8$C4v5xLbYqio9bc-Sr3hbg4Zh^?;neYS|dFh)hSKX6>Rb=Zd& zsAb}WS3wmVe-}y})3!27Zp_vB4+wr!aQL<9#wK!a5n7mEicscOY#&62HcQXB=|N&k zR31CyGsl66A10j_>5o8!`tnDmznr`OSnN4XLO>xP43!613*XqU@_d6HhwH~={ZuVlTL{?{HYMK!n#Va(~ z!Df4(SO2x=2AFg_HMp@5hnC+I=K<^dDx~Zw1To;K0BB{8nl6YkcW0@bZgfkpAYoz)dW7WKIQb3 znCFMm7^qZy#D_4&k0K#w7(u}0+J8Va=ZHiVH#A<=Xu4=VZVTR?X&%eDNB3pkHXBSn z#bs4g{T|Jq_TJ-)D?#*{t1J5*Rwl`(0tPr>KDe9QEVdEEYp$Nz3dQE znTbOL8 zD1h0f0oVked(bKQM`=HSof!Gt?mlZT_p@rB#)t?S?jT>#4 z%)~-{Ko=6z^)V4p8k%zkT%H1pz~SDpu1G=M5kH1Yr$iF#F4~0*2koeCx&v{W&fC^u z2GS6=#hCn7`^f`cLFvKLDVhGC>Z#&djI^?ttDDSx!BNagZt1X9G>eH^7`+t5#yAz* zwLa+k8OQddSg@BH6hggpvZ8dDZbkKKp|zLzm?YtcFE8Ya=hAt0B2+5|t4&+S;{+MoI&*-Ms1 zFoh$HRff_JDHq5&$xlyjtSL8k z-iH^kH6b_Af(mEHjCoSI&IWhckn^Hr3)4;F1^q2re}1h)t~>f%$`*erUqAhTCPk>2 z12P*}xF~Y;$S2p!qGaWxnC}v;A;kcrewj*^iDInR*AO=QhL_2PhojRf3>f1W`Y67cE zleb_W-$#QmQqhpe^u%v74*+%%g128F^Xfq#BZ zspCdiK>f!2U2c-u$B;BH3$-KIWEUOnN~;U@)We9<8RvMhgjuozSE2Mc)!TfT-~EW? zBmPI|jrF3h$b-6 zs#9nE>%-p3;|NYmP|^F=c{;bJIWNe*QWJA^19F@IV}Sw#Qnw%-Tu0U!TrwY82ECV6 zG#@2ZaUiu_{S@>x>&o%Vdg-4A-QuQ0Dowo2I!knc>I%*RVp9Fsc1(kr)ZNPyzYu2P z6FAeBx%NSrQZS!5CBxY#kMQilv7no30U=>h@oMxD5RG>+95TFREiGcIW)cH3@p13h z+(tL2L@fefq4E_W4G&JUymhcQ(+sj69ta`POO3&({K%c6*@}y|^Zf^nt~~(gJ}C-2 z_kVlZ_MWPJTgP9%fS(q1_#(?d+4)^^c!LJ`aA2}M=}|Q=qa-m23>8-X-pnoOo5=hj z%S#RY(P_`hJob{^C6OMaOv$j1_vu~tQ$AnK;A_c{nEp$yqK;h`eJ~Ekv z)mHS6)h$|W+B%HWs&=406pRDn10f!yO|Q)`E#Kphxwf0so-$B%8f_Z99;abdh)Spp z$|*g~N;eHp^dKl#%yC8!7udLJQo$y1wC^FQrhkEpq3V!Y77K<(fm-^RCff4SY$=UN{|AKn=&|dzD zB&~f{M=Bx%riV-dgZFH5QmWWCSjRBYk<|RIV?$$#-!v3r(Z(JkNf5u;_Z5)kRd<_T z^!}YN^hTkRD*QR)BBe-_4_z8XM2`Kon9{^l%r;Jwb2-4Nhuda`wL&jb@KV3BHw~-% zWo(jh;h8$z(kk+NkUR^3saQI~*394(n>V1ic6;P@8HM1yau<`mgR|Dl?{V|+VP`k{ zls0=ExhWeai2^q+SoWRVwgWzmaT9nYnrrk_oiUWpd?qU>eMhP6F%eTcn+d zh>6EEnlqdIH=+9jGjS$pIKaX@$qGvPh}CT_7V6BhX)2<3j3@WOrBG_L{dnxYJUiiT zc?<`CQI0n$j~%CB4eU~VBf;nbm1gu1z9V}2sN2|zplGCxbT24-cWA#)6=qt%TYw7bi zQ}SzY>uBc774br^*uc+}*$QIc!gQ)d6*e=>UVf@|&uFAH(amLTf5i+Ji{CKW3V5=hSYF z=dLABbz3Ok<}^KJNvkLwU*L;RKuIIIuUu-4ltwsF;>57Bq*sbMBT0XJ2=Shq+W!)R zjRwUGv`Haa&!>+jbmcTsLy`#z#yi?qULh^=8%^EC<6__Hz><{wvzYF5y)?2im8F1Z%=&^fvyrY9_X#gmG>ayvW+ z2$1c%lKNp|ga?apXq*H<+;9UtAIk=_ub|e~m}kO}bDkN#qs4uQKwMT_d+=wXExJf> z7S9^xpf!Pe=!rTG75!{km)y)Y`6gI~m%B>VD_w${gJXQ-KA&mT((rs3?~*TLUQZ%f z7Sp&KC%2$|uA&fJk2jQq&ki-l6Q@-Bk6b`E7Ep!(-rybH-r;D=BPC3zqN7=7Weh!2 z;{B^je_$=auy8_d<)R+>$y>;eOu_tki{dBWTq9Mr^a>fR1r2KHV84+~4>|5%wz<0L zEmC;%511sDILRe_GP@$_{vcZdzS*&ate3}hZxQZ0U1M8rahR!$IWB8KF=_dR0WW*B zT%2f}VlgL`r_obnOs<5OY|2GFgIV*B-a*|^p1lAR>(BYyCZ>KK1TuVjVXwSZV-$TwZ)jYzubbA6f zEuLTb?TpDwgUGE(QpeQ1TT?@Ku?4F>4N0=nXgS7qI^*g5p0^NQsbl|vU@afy@x&>s z4W|r~)kC=zNZ57JxkzYk-p=9JnTjEoL-1-~o|G5^;NvBG(8rS(FrKjpHbu5xo#(f@ z$1eOIId89F*Eyfp&z7Bp(KS*ko1_Q~^maxhRm?}zgZV6gjB*<-C(?*2nwh}N>x(pa zdwtc^?tA_z|10=&BzKSNML_QPj+G}->jzZW24rdbNF=IPW#chbLih{m<=-lmd=bmd zr%bzS+Uvuocz5ESM#C$t>aOmx&rN}@rz)nOYd=V<8%g|o-qcu!H*W--7C+hT>XD0dRox73?$TJ0Y;sFHKg?|k5^NN&Kq7~A7^yGqG`qtay_#j20`L$l2t0idN3~7 zy=PWXk3343TJ=z1!Sb^o=_d%5Qf{W)0lhm1&!l>ECAiR|r!U?T?gUqJ>L|+gYFprW z0MS!-?hL>BU+2f;;dvSZ5ea-5G6-eXJsLNSPkz^6Ix;`~>Un*+VQiHkB*VfNzZmEy zHeXRVMzh`MOYYT7r86`NbG-367*T}X^6LcZR%+_`@^BDtn{+w&`jvsX|1!U4M(?d| zAhRn$$%6d+OkM{@U^5&qe2Mc_YuE zU0$klXhu@hftS7mr6rqh9O@_YJ~#u4RwNloJAF-|O=&K*%F)a!r%#gmIE!VvkJd9B zuadb=s%lT}eRQ)H-Aj4mZ52L5Bz&{rdW5y{U4N|2l|IjX(gWyUZzfE9M}wE;{!NI= z^_#mOqkun2p-^)q2YBh8v8nwxQI$y#AQ?16>G@aNht7h!5d8VQ|gO@!8W$&etvM*~L{)TFk4#m*nv` z5S3TVr!Abiy5uZC0F)w1tW9j-;Qdvk&CEi3l4#3;P@>K9r{T!0<1z2k+vmW(U(rwJ zrLp^o!|#pDFKo^KA#$zzou|ux$z%Q6B_erB8hutcga9?RE62nh(D^m zMG|4k&Y`?_6{>uZ%Q5-E5Lj`o;}7xmArx{2|DHnlo@3BshuvLGdp_z>9UHF|9F(zm z(T}8snG|_JyNGwTih^|&yVx<63t}D6Ts_ly-GXTq?&J(w8SXyv;yBYZ<9pa=MA2leNWU`E&e;x_$S-2Uu@X9ZR;z-6|Jg01J2QPDF zY>ZbtR+f*tBEcKP-iw~GTsmMcx?4PoX5>u@^*6k|J9XLOj71tCC=J%=n`>_H%zuW) ze%RIChkvrgqy}zd*s`Vrwt{Za4@_XYfpb*2ijr=s-M%_(^#PNej5Lhj;O0z1jIIrG zIejNq&#;9c39Q6HtCC*((NR|HmSaHI@yyfmfF0dzz*F(%aliAEL1IauB7_CO<89WOroOj~aEIgN z?hO}L0`OO}F4g2@gnTWx5ZN#O^@B>8tQ{fMaLr6-H_1dZ=%)QgPV!G7b2wa*l`xtb z6){>jqj~RU>M%IPU{}474g-{tE;IxIKZ|-G=;#cOql{z7R;CwHxEgRQWJBDD0eJX8 ze#g35!pl^hM1R!=Irp)PJ25mXh&Tqt{T*e?xe_4u&3H;qxdWzWEB2nBjGD)PP&N^A zoKW7G2r>F@PF?vWXV}~#{P&-^e&4o5M;Ekxz&!$~r(Y9=sfShYBoMs#Qk@N_#IkZ# zwMK3zFz}*%G?9dOUHqB;Z;c0^2eb#oZM+q-ruyFXg>3whkvn4d6Hz6f%?8=nB%m5p zJ^0{&uH|oe(}+sX209g}g*HFD;Q&-UbJNCmF;vJ^mseK5?6jTeOGe)A>2*A`&^HZq z7TUOb`F;o&WRxzm?Y0ORpHZk@UK&p1K>oCvBCWT*wiR^6^=uU)^iIR=1G)&m+UB7W z1;&v0=`mX|E3BgNKwxokj_Ls16}6OSgMSWU2O{$xeOv)BraG*hFeVRMCJVfR@j@RE z{?2)_)-J&OZ25j`+Yj-cpL(1YOL9A!f63X*n_QZ_)19@ibGDJ!A>E^S>t1b+P7fy&esh zcISrp8wZ=EB}08ma-1iIerTvVrBC#A$B&ewGdDKYc9S_ixvT*St$)Nij%u0j#pFL3 zi~PO|D*I7%I96M0h>HH#dY57?i>nkQ4Q% z4r{S7L^p#bNx5w!4Zj4g(1McwFC@+B+n*CKVyAk8HAE)o7p%SIbUQM%O>Ck}Bfy>( ztD)(A5=6MltnGZwm{^$S)_U|Bfrhzdrp36LPmb#kGYtb)aKCi}MHRTej(VoFvcUU>j>6r|KYbVU+JY zE0YUu2(Pgcni0EGznJlyfe)Kj2}zoSr(KDjUmj&#FP=F2uKF+~1glF?*JVl75A*_c5l$K8AlB0}d`;hi+FbfE(=imp67ZU? z*wI~1In*=*Rd7o?dlnWPmCp%_hsrPWMBx2<=BtJk$R2tR9R>aGY;-jEA`xi;A)L`g z*NC!vQz~y8P>CQ^KJQPChipGzpS)K;j0<19c2m9L$1_zQGL);Uz%A~JrNq6U{A36A z^h2{HjaW#FCTF{Lqz%Ak5^U$r|35%!8yJFo23rq!q`ii_MsvVKV~$;kC5mborj(Co zM~85!Ac-yzkx_|rnKRx%G=&jv2>}`s{5~r1fjvK9HfH*Xh3#OkH}{z(6v}51RuOoC zHKpXE)KcDYedQl<*8PchrT=d+{*0nBjAK{z(Aa7SJbtt{PTL*vF7TV#%H%Y{^J2>p@l7c4y}`zkT&Z`<{o`b%%Fu@cV%$k}=&= z1rD>|I0WAzwf%`^84Z~G#y|XEIVD6$ym)fI7V)|I{>ffqUA_10A#Gi?wSighFw+Z+ zxfN2a|NM#$0ubb|{c#Wx8s6O-nmjH$Tp!QNeUw{#SVf9wG%YgJWHC31sE9AQ)ZFLT z233QD?mD<=K+tkr*EqU8Pa$@(p<>^c)I!MbB^330jeK44*4;vL0eH+;DWk%-DatFS~Rdx5V9(RlWyROEGU6QNyHFxe?8p zh|`zLIqW^6@Zd9jO19oe$R7TZ(xwGsb%vu1U^z^Q^Q>RO!rD!$|N~M zs@yoi@Hu_X5J`0P3JHSf6lqtcD~V^c0XkWIr#(W=x&>xVm!uSQukbho_FXE)n;)6U zZnoxd(dT#SjEUg>A$@3~Ll!*g@De?~wqkc^UN?i?=?unAO7jbp-UXNSVMo=TRXl8_ zBWG2oRSc*dwn_n3HN659x^3LoRY;yUFw?VH95!UD5p?^_zLtJbzu70nHS}}83`l-T z|0rULx`Qw*5RT2mANqPI9?U#rk}_P6#N-o4XC+xHCg0hFCg*r!H-c0` z8I}C3%iyg#loY$PZqQ!0K!!+qlue>t%87nuViPeak-df!{p8W6Y^U!*J>s+2>r>*N zSTL&7jd`b7*6>}go-)zM84hBSmr&7eaE7o>Qb@3|V*HP#rb23Hkf`k7sf4$jrlmZU za2a%KJS%Pb9&d#|J?GhG{`9rQ2&oGTR*M%^9fYQqXIZpyAW2TXvBNVhtUh^G2t4YTbNBk`duK?t8eUqE0$6B@rFwwGEZjQ+{Z72 zvk1nxRV&OmVIQ|xX zOfk_}4FZGd42>hytsC%(p=4RDVB~Zy{*`vz|L2=!4l1k$vmwy>Px{2a{))}ob#Yjve$GfQvgWN5SD%u}WKC@4>* zR3(#$_zLTQBWChHEWn9!24+WAHQ;3SUJ;tVa z_+;T{E-1s(^|?n|*5EDbzI1M&`p87zz%daaK;|djl_Ys)3r$MKSR%*5!BtyLNvU8) zDb$q7`CFwc4xKdlr+)R#3Q;hGlX;fxc<6*NH;HAh2yBytfh0m)XJ~sV_B!+8CKib< z5=HNr$Gd`V#OWd*yuH6xIoO*i_Ead9%B;x3Y(}+ZI(I()xn9V9Gv@@m>+eCc3`Pg; z9@h{x>Nuw5Dr_P&v6uyZsL}z=m+N3u!63ihMECq2DYs*g;5m}4p-kPfz4c0Sv*^QD zoxXf|a?-uV2Z6Ope>`_BfW%?vAtK#zRtRkMVW2+(+9ZH(#V<5qS$N`w=_=`tF=hmX zQT%9x<8(~NJ%=nLU;ape)d+yXcK9?m@MP0I`Ydqs<0`Sf^2H?eQ)J+&FGhGH`>qIQ zxC$ZZ=5Yr176Mk}=RhxJ)E*xyqq1EYmByb27~x_IbGL7QYP;~PTJU1nS++7_@{=G- z534QxUY;jniFOIPa3~&xa6C#rKOUdPjh7SicXGXE7y@zIUsoRw!A%3t+8a2kp9}4? zqJ9BuNTe(EK?k{GnZ~tZp}Lt@Gu~9IO)oCmUpPxhIlh4vxO6rRWlQ*V-9avn3Jt`S z^)@+%mEjnQb}5XfkTMhU>X16VzE%|F?VLlEY&UybAZ2E~Z*9*v|4mWF~OCE^J96rX_2vn|QqHdu{{{Un39)vcZcm zZ@N(0WOkFmvJef6#<(+v-2R0p*Es8#WpJ828~O~FK(d-l*6aSCmTeV-J?KMv2J;MY zz;1CeEvb-zEvBTiQ#fW{N->3}2Gty3dk9&>E&o0|TuR@Oo!@=p_@*7c&x#=5zs@`5 zqfJ-Tu3mJ!xA0Ljw6wH7ds?W|^#b?pZe4_cmAb`c>)~&28lK&0C#}H9$|j`%VPM;=Psis=^Gb zHi_h-i7N!Vb%>kxxAsg_3?I)3*oQJ&RqZCRQtKH;>5TY)JD~p-7UkhI`Zb}%pW%R64A5VG)7iLqI)aAddt#y9 z17$2{9=1^nlPj@RJRYOXnqD7d(ZdW@U)46$E zOnI@SN?(acBxBYL{2QvX5@Owizn0vK`}2$qLT;AA6e!1+ z*{n0=evA`}G-KCczua@S8;-1|$?3r8&=hb0fo1wHRL{Qp5#m&OVq>Ab?ap(46H&OL zg%02-iyUQt9oSYGw0!Ark9bq8hvrx^7%QS<-$3TLYWrb{e}rnhq!zsir9wTt;2Dns zZ7SHz5KZjHkbLLLuX80?8F!wvVBJBzDDDhit3(;Xj8fi&o5VhUyo`eBhgJBil8Jb8 z8gS%AHAOuj+8xe}xwfrim#&#(Y7#wXi4pG;D%wgV+hP(VKhN`P@voRXW9!pkrmEHl zp@Ou;3Y!}YC37l!{tRAF?+H$JL|p@6(bdmjai~<*o|p_={>>-CoE_f4=YZ&u8^^4| ziN3P*4s&QthW(pz(E-GSH`X+?@au45ybpNM#PWXROcK9LP8z8Jw#GKK&~B<|OEZtg zYgty|;_rneUL`gXq>Nd<&D`a&@Mbd8#j&H#+HP7}CId3EBPL;*PU1=DBIv|&iST@= zzYGbrr7~K&mc8+ve-+w?TtFom$j4i$<+&P4Z8(7fXl~|+H#Sc;?*hA*U$Zv383i8m zOEIqnN31sVC3LiW$KbXiXO}C>n55 z|GX_9F)tb)YL<6TG-eLnuEtYN_7AcMItJDJy^oYCO|os`-eq(at7?rAt%iFkqv-xq zf$js_H0pCX<;0vwG+NMc9>uyr^r1QhR{z8DAHsfNfq=QXce;d5 zOdjPX+!il9y7AUn3fJ3=Sx%Zi%3ZUg!L-chQSl4*W2xJa{~D4tzQe6K(K97gAKk0IF;dgZP{lo?+osOYPgrhI+zJ*VuywkX5`o<*VC`BM>vl%3`qCxPP zDjFq9^kb<1Qb^ehK4fG+?NVM1<&xD~aShRuLy=F`Zp!1&;9^(8RX=}OBt`KWV|0^b zOBbAmWszGM|A^h41eQay(#gdBQceCbQzt1TeJd;0njF&tzod(`-8@(JB z0F)B7Ad!q|4%g)0gCj)7LcR4Ne3SwsrijOk(5#{OS&0c*v0R|zaTNt}WVTruN2P*! z4Bl4QsUspNL@vT$rX%>h@ybVr(}@jO`e*WEh_T)EaAnQG?U4V}Vivf$;{sh)wwPMm zNG^Y*!6yvCt_`RE-lj$#YV-lo%1!A zzseh0MO|+vx*g0+Sh;dQjis?j7clf6As+2i!CF*yuSkp6?+_S^;weZ8gZyMuf67fu zNHrfYKFMR_Hg#Ba%Wh&r;pkVzz)3sP^MV)d$zpRaAzBO(=ke z%a%1ay!D^2r^g?TB5an!E5~Jc;1QH{~?q47sMK!NYHe!*{4Oq zCt-aDf-nLFw4%6$E@Rj3NTJsmZ{9p6nA=H%VM#a;lpLX0kPlCQwn3f>l-28k;0Mw= zUbHx&DK9;J3jHB2b1E^ITskl$7f2TMTuCF1 zw(PH4BnBU*9_~p+K|UNw9``q5hIjwBIBL{<-WfKcbt{VrwdZUgR8N~?C|mGW>cNt1 zF0{21LB@@>Z5jWIpOEb^cL%o23tZu+V!FgE89q3qz9V?&3tSxUH3a`Hjz*2%(RsbY zE3#yM)IzPza&#>JE&b6NThy>iwSymiD*9`8PVM^=gU{iQ=d7^pL!N&u7NWygL|+P- zM4-&eZRrGr6?=Mmgl8>_TT5WJh?e%@+m;eJqIhUJ)IGmY#@)(A2OGNTCu^-u#KTn? z>=>n3BqT6dMR!uw@=4kDO4{LQ;p`N{LCz>mE(iTc5#s0MDrbh-BS+7jk#~9q=gi6% zwJXQ;+i88#S-=TbFrDI-5%9PdQi8wR0soz#R7ICz@@m#Bj~Sl z)Gb0mZ5;2_FIgH0mfD86*;y3c8L65cPe!NfNODJNI+Y!AXNAKa;Rr@0wTzyD(d@bV6r3mGTqG<>qlY&>xR*y3*Z;S0hPV(GB& zMbT)l6D#kb*pfjJ5HfRyB8dF1TJc*0dIwf#2=IAylYhv9mlTyX1leU@*bR;t{zD|n z4fQNFGuLEEP@o}uiG=Btjct7;1yZJ0_+2KO0hYB3ZfFPl1*790#ahC(RcP$Hp(J5P z388|fQ7Ou3bc4Z-R>jb0R(0tURVApPVPqS{tFE6zXG`@n!yuaSig6;)8Zn3e)afu7*!M-gKNKd9_D9O4Z$~aejEbE@EA=fEw_hS{@t;-?xCtJ5lRS3R z-279?1N`uV2_T(7%w0AL3a2`7=20sWsM1PL{`vF^u|O~ulVNJ!h4e-HZi?{-t0~~0 z$DplXUZ{cX2$*_d?o)S&WJ>1zsyY{n*rH$BLacs@A)R&exs&}n%3sl}ZrN*Egk{vG zT1w~K{+_JKhXB>_Ln~us`lh=nKSHNFJk5J?gzIsGr0_ps&aG zzc?UHTl?&o+cXt+l0q-%ZzbKPIvwH6{1!{oXS87ngy%N%asR6AcBKeWp zHf*n$9P$mE#;fAe$|;@1nLdjBuTefux0>i2e<#&)PN)N?!LTn~t@XT0ZI_nEGHul*+G(BQ=lgKBV)_Bc6YhyTLjMt@LU;RIatmGT+fWfM2i0(TrEu&`N)7I#fnp z#)SCj#9PY#kMLAe==ch01@PHjS@pz9I>$Vkr-vRUTg!{ zp}aVy61n>MZiLEu@7+k`-|VtSi^Ytj4_tYKH-F#%#8a=k#$#7bcybZOvuAb?)OK*? zgyW+Vq&Jo(jINg1T(MYV9{xhb+%%0`SpQ<*Owv{Pf;tdgr_m8tbrm}>31NNIu_nn& z%KQn@6kJpyv(`Qv00mDMTefK|;Fzr8h>Q-|C9a zP&l{4IJ6sY$<*%dQK3gn_)c@rjiaR)_& zWekP}lGI}nN*KZg3;Qx?ZWy*{4td3R;1X`3vGxR{4fh-vZqO;?rxE)w)^s$^kLN;^ z@^?jIsu`2pc+~5=Ek3i=6I+S~{ zR6g;1pL?-*!@gjjRC`{}jQ0NBvyVrpEJIkkVGt*SV>mgo{iuGUy5OcwkTHlDkwXnx z8FE>ZC7qrmJeAZ?ivl!ydKHOcd!u+Xi5rpBpRcT8)P9B`Q|!Ch8Lds?9ujh4gL!OA z6{dUhl;6Xp-;(o%F?estlOO2haeMr&8q_YXhFa%kYsKl=P&H&py^+uv z%-IZB;d&=ddrQo?%LKR-R!l))jES0wG9djopGyc#!#mPKbGzHtJl-wEv)+BIn3 z0dflq5PpK8M>oI`jBB9R>>9_2o}e578+dlW(*v$vgKMuuKm8PUz+hqF@*_2#sGlC24b=o9afFX8WjE|NdeuhUvAAx4Fc6mqFlbX{K+DOr zE48g{*y=Twc9n$64m4J8>;)KL*VRe4S$ z>0W(;)iJ^lx-oclDv#H!jYt%FQ!t)nB2#ry;!UbG|M zs>Ykbl{KR41Y#}iBW^S``-FcMwdEMew|wp*mSD_5Zlf-4#5wSrd#}9EIe97OGNhe7 zewLw8Og}Io4JVIoM2!FWzG{zN-lN@3=DZyTm^kLg&xb~#RmDIxu|Li}8fRUqxPJb=rIVN4{9 zh+4+Aj(4rN@TGbQE_h6@pLd?VcY~JaY$SFQF)MpFFvo3QJPG@+s2PpNiVmwEA88&A zF%)HCY0cdHUA7m((LhpOx5k;Quqf=D9!ggd@#`p2i?0>iFy5UgR^*v-;B~Qt`^ufm{%l7zMHQRN>e6Po?B(lh-$Twj`}Hbd-GOS5Q$Xy+_XeJ|Q?`}hH}SRLa8maDKkv6yiT6gx2$4}iaLgtEiZ z{wzLp#b-3f^=^b?7iPk+o&JHPim7={BSH}bGsatvlT7_PkvpN74MR~?*9M{F@MGD1?TxSlzLV zh6~V*bn(|vzC-9}=JKCthD0hfQ?B&{+7$*{B56x%y>};d9m=7+h^5jOcSF;`t?>l^ z?Q37+blGzH#AEQxIehLhcwz^e6R!L({}Fl1HJ)0|IH$p8L&O=~snWGM-%xjd+e0>Z z5)OQy>IfNJGD^o7u0U%Ty-dhg5sy7LF7#ogOnki(A;R|WPn2p)I+Tgt@(nVLl?u}X zV4q$W1*-nEG%_e=5U5lV8>=Khql0dZHzyqp17RS5iXt0u`kDnk+(Xk$;IDM|ayDY| zSR3xrZHGq|Q_kaM4iBZ!=J8$FyLGrhubZ)OCQnkgwhAg8Z5^7JO~t(gq~kG1Jx*&l zD0tm7dSh4zWHrwb?^=C5Bs~sx7pxJPMuR+*wU-z_oSLY*dx1L767Q@^7+Q>frOU4K z?1_Z)#8kmIhx*}NOQ5oLGkU5&vb zVwoNWdPyCWI?DL&@wXJC_uC=$u8T%FljWV>$}(+(Qv0~4SFO;8wVy5nr`MV3h|Nx` z=;7U^Qc$OhzuRQ-uF#~deF-JFl<|_KS$LmB1GA>@8J9K=xhT9-A`qA2!hITN)zPx1 z5{{J~vr>`2Udf@*DIQ39b*f~s8Op%`vZ`O0s!|>4_)VGJx>St_yFN_y@0+A%Pn+t7if!+BH zJTRTN=M2OJHIMgN-IRt4Vw7uE8fIt>@#`{HSwHXpt%~pUbu1ILVsiY^kNLW7~Ts`VarO{k5hfaYqjH;t~ANJ5>`yRHl zO>@mRk`-og+-MoQ)^VF;m_Tto4HpHX@&fUCCBKD zHdjdnJD6~T)(E#}j3(Lh!%0K)!?KI*zmr0Dp~QjQxWld4C;zt!l@Yv1%p#Qr$)HD< zG$}5xqN;>?*yfE2W<4zQ+|e%*2SHJh1%$igeS0*`Ir;F0G@1FMZCqPgG_-jZYEecT zen3PfJOQ!|OYn$hv~NW7LqiK>P4;UJbnyKg@-!Bg&--JzFKSc*zZ!SRbvU(FDRUc0 zxG+c*4c9-Wmw?*AT*HxV^<4q84W8v=qro5j{p!X}GuEWai@I@JQ6g@(CgQlZU$YMy zMwDW$(QI>Rd)ptdLphY^Tjtt}5KgO~+#r^p%Z3z}`viAUmqF8oh9%U&jc0a{3_2PX zn|C0(q!BgHrDp8(<7gd5j|PqiH6q@0XS*y;y*)WnBaE_|d$5v=K#z(O=Fo+t{3^xJ z2_7nHHC9DG3Etoa$3QYBpcGw=?5d6&!)5OpD?6U<{WkA~l@8$7gW4K>9!~ppf-Tytk7; z)@$;{72S84Ar60|etS;P;il?XyW<7W%wTxF7rZBB*mTyP+T%qDWu*e$sZ@364!>uU zsP$Do^8EW~Ple~<{moMjM$$t$ltbAomTgnmkui0Wm>T5{B%QhfBU&kX6(*|Wp@_EW z+OX$-7SB#4qh4e0x=R<{oW|?{PX@2Xf7B zO)Tjvk;VXC;;mD&AqU4@2~$3XX4_ri==?S8 zo_>(s*Io%<9`NPYz*nDTTtDIZ(>K^H@YqRb5vBkw;cT}sBusIGOrGZ&p2%9+YT=sa z^g|=A+0-n-Yawei~n6?9}O~83#u_1PTL3!%?3L zqgg_s!7ksoV}k^zlsHh6$wu}Ou^zkB`YJ9r;K(l<|E2>`GmJ$3?6%r=dt<3{2t_c2 zX7B`uQcjLXD$;?jH3fO{HbR+=^&{YcTIcUR+M|4)YbL%I`9++k5PWM|Hb#Z|E=GE^B%iG-ok6TYI28l}@Lz_;Ode zn&jM^9;mN%i%)Iz-i)ck$wnA6E%t8L;bE7|04JdzI4ZJqlw#4Hfr+14l{EnNCTWsyBy+jfTsQ$^-1Ad&xdACewS-mY>;&IyD;6= z)Q54tC!Ig`$bGH`zkV4@e9rc*R_Yzr)m_wLK%qct-@oNxBt4WvITSBWFrA4>w)O@9 z03ZNKL_t(23yYrnp;tubG3BXkg3w3IpmGu$JWILgP9N7?2&%sukCO6yMRfSXRjG}{ z6;K%2WSpsg(3x?&7U!*@tb@AgGM-LmC6aATcOdZ$!Z}>BVs3G|-UtL$Ab>pXm`(;a zWnB>>UestFKh(3^;(uZhw@UCy144KJC%BXQTJ&5d@s)bS}|*muIpEnSHA9;^9Qz!8yl`X1KaOC zLT)XzE1m5dw>;T}Ws}5UPmyWG&>6@c$yW;Tn9+69d!`a(aTU9vNh5iLD?g^7iF*vl zB$dG@f}X7qC50F_H9A$$c*(@VRUFJ+Ap6F88iO_n6HRr;vOn*kyw+>+xwMHGq^P3w zEjpYZW%g;G@=Lhp8=taY8`6_d+B=Q}-8I^Mqe@d|Sz*WoVdV&M@| zo2t(sQ>G_Te zC%7JN->xT^?jGoxERxgDYZ`?p{`dbl8K3Co&FZFdqiT)$a~BP zEjcd3jeD|cOAOYY=R|E@JSVX65G0X2FTzWSC^810_OXh<|H;H-za_)BQf64B-+#&rmhnIfAF{Pebzj!jM;!uIT|_iLj>5wHixl zkg-^;l6{FFjL4Zci+S8RDu2pG?CTSktl10lMg4c#J^LM8563+vwtkDs!AN>2hjJ)h zT#1rEJ~|RoKw5WY0Sg?n4I1s@#7e<4g;Qx44x@!2&68L*ge z69A&f9y?D^CnHpf3r1lah6bIE@9C}Wrkz$FxJ%ltz7WwJ8 zb)%p~1?Y>lUBg%#NE`3mGWOg)YHXo_Ax*=OdXdp7oh48F>OY}LGh6ItSk~Yos%g5k z+bOlkjLQ^(_Cv4@0Zqln!3B`W7-$zqQ_It*u;S>^;IF zYVV7QR1?_EEi{bQBi(qTUiH{+$@JUo+sa7Vd@W|i(ojm{J|7u1L{wvkD4gjr$2VTf zgV#?v{mQ>``pg--WW9m(dKpL?-}WUeJ6gU^L&wFv*ZrR>j=4wg9AE6-C}EKqNzp_G za`jpC4d*NmFUT+i4|-%?-W~o;;bvPb0es&x@c6c#u55wYB-zdoLmP#`P}LH5s0fW= znQa5z8T7`L+abcDS`+Wim-ebKRON0&qr8Y+ivyCNMb&3KPg9sQBB~8TnJz>Qk>@|P zg?Ft!Q`+F`E@>1#W{^lpyd8PJ&i=)L;OKt#qYi#=>ncUyNLhAv`XnOs^N#Km-3eo% z@Nee}kw_?Q;LamN&A_|?whiN1ploO~OWq}Fta77_Zilp7rmSWOgKu-*B2%2(?`@1f-)MqD7_iaXu9*mkwzp;RT+-*++ms0 zg-F~aE{|_$zy?}FM$iT8qw$r&P6s26UGx9A@iCC3ux1A_UW1M61DDAOCZEHkUl-*F zcMs>X{cHCuG#2d%C|DCKH%1b1R%=w(>6X3|_q7u)kh=M<{a7?*RXC8wjG2=3bMZA{ z-XIGLiyJ=u+{Wp*;Tal7Y$i=jxdGR*1`FqA%#B_IYjb+nu=;2gH@l1VZv_7)P`A$F zB@E4BG!=FtKIe0+@_~@;($l1jki>YK%w&e!IvtZBPk&2T&AA#%T695lvCmVR^uKB$ zi&nbeUa9)aO5Ut<82_q_ROh0Xmvzxm~0Bt4WvITThzQWfMB^fBNn@F2=H zrebD-il!SSg%DSQysQ)!ubh>UKrSK9@kj{v8B<0vw>T-b32RRf?KQ($3ZpOrzw&@| zBbNm7qxq??qi<#`v3h@D5@B@9me(;D&cF(XlsJJO&ZnffcgKii$L#t_I9dx=b1cvO z-$mhQ8bsZ_HBqW29FEZWV_sL!djH+nnC|EZ8b;edeWijn`#oLZ`&0c zMNffKZfzEx?2GNA<^r_ShZQ6{_cF`_3idp+CLIV`Z?`X#<`1XE0D%H=t69eN4OF>~ zboHA?rr4W0&mv^jG5Jck$CthA?~M3mcHKh+1VU5G{Xy$Ob8F@IZ$=4MY*ickXh$pK z8-1$ZD}*rmt8JQJ9ZhS8R4r!R>8-8NMeKdr)r<)%Pr>=Vf=DQd9FcCdA|lhhyzt|bZqEp z;aM=}IqHz9(ur$His=LHWswPA@%Wq0UsM%ZFCGEWiU9wJkJl(*BG-;nT*c_`=^0VgFXrJW@uX{jBOI$!ZfT3ck7P$TbC(_NtmS&-~DFD ztanAo%QZaeXA9iue)#M7Tuun{@>FuAwKd==ls+nBiMCzxdDTU|H7Ka0;B2cGvd!N%`u#GF|Y^sbkgFWI1zF9-YQ8Tp-hC!q zh0VS3tFEnijlAEYCdIs#8giJ*{fPqQ&h>^tqh3$r?#1S`!bR?zO9P_Tk2W9ecv~nQa;B4g|aq`E||e|hwa-@>b+Nr8+`y1$<58J zw?=DXMzbir!)}ik#6d{xjX;l544`=rP>_1*D7Ye#5kEQhl_tH8cxEGFm{fY2T`6-U zVYpWF&xX?WXhhLus(z64u&w)Bhpm3NjE;OGC5>g#n7wug>%X$D6Bmx+Wad6^cKtMr{Mex^uFWD>3`xHk8(wyM)Vfl z<)VhiuE%4y3rI7xr-I4nSi--xTx{(L^tL)!K~&9-TIDaNHA&L(?IB9@+za-W+*TzN zlhCynUNAXgY=2d?gN~K43^Mtv>=;W+zI9PfsItOkrOFR65B~IscLnwd#0o|GRfFD>T+TUILRfL6ZX8DMN z>%7KS8XEH%da^gNc|9i2L;~T;JN-S28G=QdrGt>!#x%~O3`gaPmgkF(nF#9KJmnqJ z&4D$@N%B?3WbS}gEn|E?mv1SObXgXbW#RPnlqa5ef-ijG3w+`epWwqE{xH3Fe)xxf zn0LSX-Ms$wum4syyLDTjb@kIBP$fVz>99HDh*rY(5k9LLmWMNIGwrW&F^x(bRjzIl}x&{GpLKk-GLif@TRy^J>5bAHX5%f8WcVPQZwYVO1$*2YoVl>N&#`g*PF*9R}-daKTO+;g+~ZQ{-&_a=Qg zly8?(WIrH`X}+S##is&tMr$__o`kXE3!nNdH~-IP(Enk>(HkG&te?`m$v}!H>T&rn zP^HowX{w5}rMzBJ#tZG?iMXA<&m2i;8QGWFXPwQM zM8n+5N zT+*j34o)>kB8IN0G&a|`0XDti%7jXUaMLwklsOlQuoLS?(cYNhC&UfHZSVK_4%Lpz zV&TqKdaX`FJ|+`Q+;h}p{JF6(1IEn*19EKD!?EuhNuvbQ?Q>z5HI;m3&+|?+(Az!J z72nV0C3Cl5mW99itH0u}|N5`_u^;;}-uvG7vfXZ9s^)xKmCtdib3J;~3sbvY`ed0le3;+95IVb7gn?{}5y z{a6j0#kkg-lU5ArWM$ozYFC;<0bIES`4cOb{b?98myDkJT^BsN^+%BDU_y+5k{7ZLW|Gmm+d_S0dHvp6x3e`8aS11upjHP)pVj zVLQTEGib-;A^vyOZJ9K(&mZ=YA=8~bewPbwb}vpThKN8FCL-jy*H6T&%P=TmEN0Ts zRF<4>A&u4>T?K9r#t9M1Tjp!6JcDqI3@dR1PV<(R^{@7h%?*)u)^=YdiZoGmpjK;zCp&ZH!EhBPOGPZj6p;?E?kzY93E9#;Z0+$N*C= zkLPT7FoZ=SVyC2 z=p+}9BEaJ14nIg%kvgNyxVuWoF{{<%ymcz``?beS)f>v+AU5ZN&bFO#zenwS$$O`& z{K=pE37`7Zr}&j$`4t{~@WGe5N%w4d>Zzyrz2Eyi{`}AX9988_Z+g>9-K0aguZm#g z?*#NAL?5BGSD~^qPx{sqL8^jhJr1SFh^PtoO1h3+VgpJU9@g>#mt1q^suzBAcl%_% z#Vio?ym?y)G-lD{LN6x7n12DT5g^sTB3T zNxr$d>YkIvQrXQnrTaJYyQ&F^@qB<{G;(sfd$>d<>o6RaDX8-ybLc|v8hd?Dr7jS& zshQ3b|4;y9bix=J0#$uS2%UkJnL-N|e@>O=0>^B(CEt=97Z)6|-C-b@>sJGHP=pR^ zleZC=NuLCK%!d1HYKpAh0>5>~;PyG}c1OT5%Iz|shjQ;1#pcZuywOmOnDKotQ*dIx z%HBUN`5y0BD`GFKRLZk|?QZMcf8J3aX_RwgQEM0XL=!juVEahH40drw#{QIyD^_V!8q-!oQ3!avpxiKNc^H5T+DDbuNzIE^>e?~x zF)!WayhcAnec768Vkl#wcpK!>(C~{iH|QB|rSe-FD@i?Xl2yB}H_#@YXd{vymYWqn zB(zuRFdA)1!Nd;Qlo^lhO z?$tdQrYtgrg-8&hzTOLd)%cM8FO~c?C_Ote6W0q!YrcHd`IH++;<+Mkg)umcsfThX z-&mO&L_!A7>%xrdK3H~V(2jsDdg~hJUwbo0H($%q?kcyh47S|jDvHQL9LN(f=uJTN zEntacW9KEENAjh9e*!5 zq!QeH+xcCdm99?iNE&>(M~TzP{e(uXFb!zsbQg&F%O+;d}qaZuaIHV_NF?_ zpTYYi!j%=L{g8J}<#U>pWM1>Iv#TO9$_z?QH==a+8qhSHy6buva&=hvf+om_7`0lM ze7L!Lo`GuI^U2lbp#{`wZW(TChR~4JVP1+1PRE;@->bWQm}v*LTy|=S!_YY&ekA64 zLPv89>qyFMgUeg{zDluL7TiNm**mlgPl~zT%c}526FT9T!xZZ^zsK5>e6s=_3nS4y z0ptB#Ua*n$$AA3CxpCvh9e*EVu-ol8J3Hg4r=H?#U;7&W@-P3w&6_tbz5jEc`yB6o z|NHs%U;lNkU%&oBn{{88_r33ZeDRB4e5sppDEDYF=P%1e^+Wsx7W`tQ3t@g7yS}G~xzRa4jTV z4@y(xUcay}6Rq35?q@PyVnGkH!SuXac-41md$!uqC^a>Zc1wGl2gb#F+jx#0qnK zbI3d}f(sWmu2ZabQ8338SHiQM8Rw_jc>7prj9)0WZu~bx&&&oL2q$$T> zwrr1XaQ()sIXgY$+1qDjQ0oS{C~zOjOI-wE>uOn4Ap6+c8NG%I*V65=|>R^Lp3;k3EAN|$=<9Jerhd1SUU&}sSq z9P3cnf+{`V-F|WYCeGw8p4C>A;Xx#{Ba8u+{<45)=pEW=O^~hkxEX?X>_8XuAZamf zX{EMtlWxY`g-+W5T^X*ZcMi%fnYk^Zil6&>YI4Jiiia$BbjPidvyPb?=2dw}sJ=ExhTC5Ay2oeKp_l z@DY!x?Q4}CI(8_F*SNGO06?1P-`vKMvVUdbD^jVWhlZG@$SnlCS1Jw!cPQPwva=t)*N;tKXzZGpN7GN#hfLnwb}RZGYqWWNkvMEsLhO%tqiq^6mH17Z zT?)+>tzJOukg5P_evy>NXBz?y_-oc}fKKi_$`{#fDXFl|y5Am0O`Ijju zM)~3wzsLtZ@Bx1HSAUh>`yFa{`Ighu)0eslhjL#RSB~Wv5lb#JWTE#XQ*=7?ZBbgC z0f%kT+yjEfIs5^pb=V9286d*z<40Pp4#nKh!z0hqb z07*0Vlo}sO?EWTmF13tNx)ZkfdEebWWfPfeK^KMQMpMC*`xtA%Pj_8xY7UMTn@w{m z7JsLo4rf2C{t{Qv(bZ={H(3UTrT-r%e)qtl$fDQOR2)pQWz~3Gk~tqOA%JU2Sta^qh}W0Hjb_d za<0g^jm7OV^>1P3d9crOxK381A^u$=&S_cxiOeJpx5|*GOa4?y8#tjue;#}{JyT)< ztMjU<SXaUISk_8f^NGraMECqJE$qdrh+nGiZ*9KGZNq7IUc|I7sgO zTHkDXJ$TE{v2i2rvDX}7Uktry>75KL?k?x~JY>x}J%^$uRWq;-N_@)tJZ&;68F$#D zMxbQ%-27s@{oT8m+WAo{Em}uqXk` zz3(z`qp!DXj<%1n(k0@-l5{(aoGUi9`WC2Xa;_SwdSKz@2=eaNTfTpW!ZAixMuN3$ zS3h5ZU{1ajm)CM);K*MNn#zmrZvXn%zn)+Cg5~s z3&_$>e)5xi@Pi-ZJ@0wXi`}$CIh2=q5#S0dKIIXOyOhF2j*40DeNOZnKac22PzeROeJ- z++_&M&aUUrDF?dvSG_iHqh4Dp$YJmd7BhjYE;!WwW5Pi%Y-<#u211CLh?6cIHqA0* zE(0CstdX2iQ?&rpIo*IpCT_o7Eg^;(1_EWM_Lq0$~~w@D8&y z#cySgCow7Sms)=qS67r}URxPnEA6Os#p<=)xue3xfvO=7B@J-BkSR?C&y>iCGf{7AYlb?^Z0G{RLtGa9x*WPqG-w{Qgxg+4 z;^A!#@+NrvRGhDQ4B9}tH=#K)Qo=P*ZL9>4Ve!aT2|6^|LcXu{mSbHL0A->+DMp8V z-A3I!5p8t77DFy|Da5z{VN@M7b^@a&JJB!{#EZZ+!E}EW{19v-$kq(v#{)Ktuo;8f zH*cZKIkG%!%lSKB$>#crtsxOp8aH;(iug+3!ft~dYNc1H(abJJw+Bnc&5Q9$b9sqf zlZc)ev&lAc8^&Q~{5};;zppdLlHhf25-M9yT}yYCXzQ|*G1*lIIsz$8y424V?`t?^ zg0c>kjK668_qMh9{_&xr)1 z=2_4!e1{kmxze8GSk67OxzWuqKvr;f*Kom9 zmKD8^IMTu}y&?@|Wj8zVTBIT22ETfR8Op*dsvI@uC*#1@wu*T5*AW1M>Qol=FYZ(g zBkOEa@Fx7P{nSkUUX6Nf(O8W?5C*+IO(H~R8 zWC|Ig^rCnqqgImfNO>|8l_fh8ioCZW7?lq~x}P`{O0_w%agI|2jL+7Ej1-*-5H05-n5hF482KcevY* zj5lQWX>0jTb%RA<$;6dnMbV~iC=5x^OLKT?xQ$FJX})&~0ESwSjg6n;Mp{u96ul`8 zdd(`?#D$7s2LV1l8Bb2;>8$!#4MxVwn`;3qL5Lvko*Bxv0?&wWE*p-oq})1;bl+D&>iS8tAuR2U`f~pwy)3anmtgS^><01pD9Mx zxIGa8frN-e773S|1bUTeb+6z3g!3;y#uNX?@4z*IlLz3HSK)tqH@xw`gCUIWYdJK6 z$YSpF$X@A(7zm=C8`TN8xk3i*jdlVu7}{tf6bz$wM&jcTN(vux>gS|n8Z0&4vRAQ? zfru6shQT}(YJweUg~7}Fh$dZ9V>FJukAor*AI}-D)jcqp#aGP{mOz(yOgA@@hLSCX zHiVwt=s8_^_~^@``MpWCeA#74giz=u4EH|I8p^e=VMhfA^2X1`5~06o!UHFRs{(rS zoTvZ(v+TZh6F&VZ&@-<6-2ckpiYc4e-=k|Tq;IzR`vIXGd*TmGx#c8c2E_5!} znyboI&qU(-ILPdVh>v+}51BD*^9IowZr#Up_+aWhHBAvFR*tH|Xcjs^cYE<*)Y|ED zYaxmpkt|+!v^xZw*6a{k22DLhoaW1nlLso++hK-bXrYORd?94mz^Pj?wAR9R z_`%eedO{p%gtvg*-_zEZzB%G9=`(RnRAGZD;d+yiB+3X6Em z7-!faf>ox_HGFJHbzDNL+5HUW8IVOQl6Pu?Juc!(W8Uk3ADkb`*IWHsONB*0H zMRZJKVZ1t!zK#UN-C+hJgQ3rp={SwYkg1zsvdy2VZ7F?>;P7GT@ZVNKmGg|@(d7SoW2hq#S-t%k}cF#*nB}D~|5g8l!Y)5XnH5>N%Me{6g{lBImg3Ae+Oq*w>-OCV<8T-Y6oL2mzIjv zANxpSpNqA_^k7NkOYWN7LqT6%ff3BkhYdmUA>WTW2D_a)Le++Jl;G0U^(_y3@G*$* zP3Wy#Tir!|jFD}i)DUyA>EZ}{r#qo2`N%Bdl&mU^Vq-mm21>ZFN*=l;-4?^4%*@Jj zxYft2jp>qV#sadR!)vCuY_?lx$&*bKTE`CR+$cE&7H<6Jli?G z`WiONEw1zpPj2C~XIFhm7>yfESPFYedBG2jg728+qvhPFTf>{9bi(y-7*|>G>lok* zdR%D-f_p*up_W>L5lsZ}#m$#%#$^%hExlJ%eb=}*fm`Z*otnEa8mLeE-3}$iJZgOX z8Ozt)JQm;8cutFbQ97$-9Y}};{KcJ2;k!I1C!*vZkFx2|5gX5Fwdz{SOa*g! zjBIn3mHnrD(V&B7Avt4^6VDJOu}dJ4tua>aHK!V0E zOToy!xnxd7&~8eGEUsuedoj7f6xd9t;q?!Hr>ZGX!97=Egv_=j*lFsl*^Mx8)&sT? zb~`32DH2MIbWwMs0_16fGQY7rA>s54)Lyv8-R`JD~_gW>L{0DBq>IODj-&g zH|`H1Ld!&HMV3bMo4N1=#5d*g5d?EZwn#2$7+ zRZ*lmu)v=d*X?3E;=Mc29hvw+VY+Jjeo`S}+o>dm5mv}pXn7*DQmgFWP)@kP>%QYH zoILa<{=-{e$G?5|mVbDK@B}*xQ6baCD+y~8(tztt$)p4k`#JVb#F&ijUHE~5yLT2E zC#B2LO?%L3JQ*VzNO#L1$3Y>37X0&l)ibo9gg8xJGTjYzl5TWr zb#+eN*bs+PImi22tTQO}u}cIEB=1u(gQ2u(tj#)tZgx#*l7K@F3oUD=Wd<)5r)il< zUf~p2RC(aWhS&e_8+q+*<@G=EW=_tPPrqu*|0BZgDmHH#!=_0~hqJQEgPV_c&{t`l z#%3CU!@ZO+P$zT*Rm{brI>PAL)*&lguT(EzE=uBEWjk5dl=`@i} z*uaXO?z8M@yBNJP^tbbn@IK2E5QxOG!w*zM)>Vds^dJ%<;h~|J@@*2|eT?X&14?6& zBZhX%?$nF z`4KYI>a9N4p;P4>>gs2J_3OOh4R7GlM<1oN7l(K}pQ5UK_OqYm-~avJdHnIm z+3j{*yLOF-AAXoOzxmA^A0NNeO+1uuc~RgDLy58xzgDjZOzyxL5y`8 z2uB!_oQWeypQsF&3T;U9DvES7u%)oGIB3O{vj7G``Mx+Ui|5jHTUZGw3W>1ME;DgQ z?WLnQEP0dH*Xr+>T``0Liqh-KOmoR$i~-9qfewY%Xw3{C)=x?0JL0E~O!{MeH)Eu; zNatmCkge!2giGJ3;bg>;y^OJ;MmCKTNny>531(c3i3SJ|r1g0cD9vrIEwd5pqO}@i z(_J}pq=1;gQXL{}NkT)=m3cVs$gUx7fKcn8bWh~sLV-WHnup9H3=Fy%KO;sdq_7>D zr=hI8o*0VWeOSWQfLVU)QqS$)J3zef|9xsSCmA<`r=f9v2@P$ z6^!=ZbKZ|xmRqPi27DFt8SlrwQS4CejUtzPzLW5I**|ctlIda>$j;(k9#v#QwmU@> z448ydzUhAmvXu1)A|2%j3)&pW)gXRlpRf8A7wx`tZtzukgw4@|TzmBikH2!mt}m87 zSQ;Xo;fZ#}{^^rw9z;}{X#YYJ^*%}IbKTn;JpSCs?LD#lw#STK3z0Egy5zk8O~qro zNz!sl;AaOoW2n(RZ`;6>U>nzA7PoDovoiVCObF=6bPXPuoNyxcTa2xDFpQ>B<|F1t z#8ID9QL=!nMMas+&=n>};|70h=Bh10kNpmdi_;P*J2M;&Lw0qGt+^nKoucPff7?ui z>rQu;i0M_G-LCWG*l?uqp?O<`2Tw9u&ZBkL_1G>u#&Sns=c0Z#;50eiBfYXf!MU*_)^8$woA%G!*Y9N`%tT;EBb}GTRhg+}piFH)x9x9*1%$&$q;iD!fQ-b>+Us z4wr{oRzF!RhWB!Mgr0ZCa?aS?qRXk(qo=4Wc!YRRlV>BOkwoaCX$qRHk+`-8fbgcy z7{>N*Wqy=GOD-v4#1u7S*=T-vo+lBLD&&E`f6hAcgYEf1wT8DuDmv+h9fzgsI*d+t z7CJ+=tc|G?WvIxE|0?^V^}>q}g~_hC7lh8{uWxE5U*s6A`}3_T`-ZwjQpHG{`d!zf znubXYnX2|7mB9!=z19KJNQ#3bq&$*U#9ci<+4XY3C$_UjvaHFsVz@KEFvcP;(;7k* zsXXDEQTCQ}#-ANrvm;$8207Y{x3&|TO6hky8o{QmF%etv(`o8H9x-~WC9Zr;4fAN;`| z@Uf45Y-RAR<;IO0y#4KO=Uwl57Y{!8;MaZE-~HX+@teQ-n|J*EGoSekKl`&kySnzC z_q>On{K=oZ+wSnxQ%~_nfAmNE^f^S0D^~ ziYrj5{Y(Y6cnc;9X~YYJKoeEv5lF>jpfg9vo?;Qgh8f(3Cy1E8Yq;iRHiec-w1EO0 z$(ra-B@JZ~?iS(7?h2X@3yK|7swLSFvFz!iEg9Z0VzNnLR~A)Iyv6a^nDNZw8O+v% zz{#S;?KaJnR9B`eL`4%BM!JJc3Bd2$L&ON0Xws>iPAB`gFX{>LGv-1BPvqe)w0T6E zFEAu*NJFA5LXI!Z5-DjY=^@|8So_2`2BWpSKAOc8H5;c`+&S@<<&gV&54T}T|9nj+ zhC$8UYapDBElYnGJ$evXo(BCqx;zCu6|0Lwxz|e-p0#{`uDRQ{lC*g}>ZwMYefPlC zy918zF-s%fC_yKkSTx0w-bL~@#gM1Ve0KGYy}r2NZnu4aXC8bl^3V~Ve@J=y+TiwP zphL}dvKxXiTqTQEYPCuzz|nt5i&Vr^4Ei*r3{B8)W$03rGD`pISgzk|f2KhT?3o}T zcx>UC&3xbZl*7{E{=!e%($g+-dTe)_aX9F{qIf2OZc?sEsrYwCL7FSuK z6=2LZXgL_0m8|A#wL7%%l9)EXLpNKK6I63q=kV&BE?YXWNXC3sv{jTv6_F*;y!+^+ zeafTduk~l+NYX<&lowip09O8F*BgOZo2H(tH%@3r$83+U&`++h(^FbIWvjRSVEi1F zUAojydCcm`Se}>i)cw_dkzQ;5UlFEWvVL|SdpX6~=;DHh3X3im(vfUP)-9O(&JQV^ zg{^+5%FKn>=JCl8nS+gi1XlNiSA+5QAtMc@mvFBaR6@L0@53n9@{XLhhQWvH+rL>Y zd5$(RW&4<~RCS(569O?DvdV>#%nCP?PhXG)?V6ypq9@7f_b{c-^%w@zd4xGEltNbT zHB8aM0l%{*cDo&a`?r6~$3OmY-ucdV z@-sj4GxsDK_E5f&5`=xwI7j&Z*?ad`Td%5o_!;wEYwvy9bLr*uf|N_SwA>X$TEGut z@-=(}#76({_amY)sQH2sqY@=CA<=&f67dp}&ye6HVoZnzydY@&B3RIqE`?S#0vSxF-*Lv4{=Y5XLGshV7epGw~6{jKcQ~-yd zIzn`21l*ZOJ625bio}F{10$2Q5>0NX5V`9L8GV2Q4z>{#6IV2|5^Pl`Wt9MGmw{i{ zMoKsKy}BkDF8q<3iio$JMot|saRFs0z-;jD57AXba}^Qzl9okM5>Vh{h17uf>#p$5 zG8vMI64_ahGzx04e0SRAjU>A5&)c(N51NSI?59 zJ)>Yli_<15a2&(({)Pd+NG^LG~mMoCP~tU=ZQXL zr6I5Xw$5o?Iu^mhL&3&na~wW=1RKLaoVxo#Joq)g;d~`1wod0?%9>PjGi-};0$4`M z-)YgwvMQRZeZ(VKQD0uiS;_J;86cWk9GeESLhl9pX<1Wvh2YT+F1YdpuKwQ_;NdGT z#KRW|7F)n@WPr?ubbjTBFU1cjoOmktRR^AW`y@4mykJQ=0lGt*+|JP21mO#~N^b!V z^Nen4MyedhLUB!S3X*1RG5hgR0|H=H>t6L@oQbw&MEJc$gk$6Ay{C8mC zfU;3A@Frgo)Ul$DZSKvz-L0+29&2@l-Rs{NAhUw`Trjg+5K)~^jAf3+FpF4!1%lZK zV4)ay1dHuz7;Ci~trda=)B#NLv=I?kntd1whWUWmTrg}1#@T?82Wuh`B7o$Yig`?> zwCSgn3`5|Ug{)X8Rd09otq~Zr=Bf1+D`?>3^2*yaaeG-i6`J{(0<}sUCK{V*5C=e3 zV|&B^PwxAaAzWu_3IpQ>26EG~@0J9B40?tf>$FaLN!{v&$(puqD;6lK7(}55kK_OP z)z{*x>#xB>r%q#d%7DA)cLU`(W-?+>J9w_DkkX7TptL%788kp61mL4>M`0QGY`efX z5WTD#&F=lJ{JXZjq)xYaK^m3RNfYw#BTv!F>iwW|N=Z4$w}o=Zw;vlw!D&Kr+V2>cyicBx41bm~3Yrz^ zbk3UBqX@$xZc{#YshJ%%C$kgHI~8GyO# zqRxig%Fmc(?J0D22MiDlNwUb_71=e}xInTfWOk?Xs$y0xove{HhRj8lI++yS(E+T) zR0(Qzz-v}m{ksf}&lDK_s&E&^;7|zgjekr2t|`w{`f^LxVtIsMofNbim(hgCEL{2j zP2iKpF{54Zn647mQ6{H(-ePQAb42_M5M*#8o=wI&E|a*F*G;V=k=?K&yjo<-!s{13i7sGfrWO3m5AuKvI{oxmVQU zDxNG0EM^tMAvG)6)7wDVvGu$LNgpRE3zk_;nm+fn6Yj#&vi&5F0E z-v&*V?3S-}^w2iWUv*GmULczVv${b&tHFKpl`>r*%5l#Fbw#z%FwG7z(L^9%ZwlSX}S`PJH(<-1C3jjR$rfz-eq_ zTXvwLm_txxhEXa66{2Q&Ujkr)lm3b-1B$zmx3fsIqBfR5%%JgMBm1_$#i1sKx&lHf zb}`g8=h6i{ie&7f2tY^zGP|ok&k=? zhYlUWjW^!7RQ6?;UDjEe{>#7oOV`gshYsO;zxR8)cdowr>a(`_=9_QEXFl_p?%AP3 zhw%L8KOaYr9t8m0ci(-u`R1GP;DZk?z5lU~eGD&o$xHCkm%j9@b*8J;bJ#04Wu^Aeyl$D4If zP@!~@+Q{~1Gb3K?)B&;nz2v#${Aa0=3M|m?h1RaB1*fHAHjbF-j_otLDoLBobvmC@ zhHkLSUterlf>ofIrccYs?|8mOG_h>4%Fjc}R}hyyNd?p{cG9pQ<@%aht9BY(D_;Qd zn4Kdkj#b4&sLj1wjmi`;pvYoXn>FrxEA_%@w2`dZy`HyzGp4~YOpkyyoKn5^0AV<9LQym+&+s?|V1 zV;2H(D^b}5%BEtrA=sD~)DsmC-+3Hb6kA6RV%QkMXrL-0e2c(iR0hdvciocKNg9R* z($n?NV(e8YvJ#BxsR)WuI!4z!j96 z5}R4^EOYneF?CNdAP&+cX38c^cU)eo-R`o2_+OH22XVn$QrrYtTqI#Gd0 zajk>$2pJ>giqe%3v=Zj0*vm9~Z|m9m!4y)r^yA-L*{K(0hE6@hbM9(M>P#k#J@{@f z>oY8uEa{(K5Biw8Z3H!bw;fiN+Tr*=YIQpyLAs36`dM9mB=|1D6uS{Zn>XOmnu{k| zI&VNy0C>`qp0os#-gD1AyXHS};sk#Cw|{#HAbtANpN==b`OSFdGoQKgy&wPaAICrc z^FQNH{^U<^?AWn*{*|wM1%LR5f4DCz$$Rg;xBGtMjW^;)e&k2G5CKB@8r@F$<9BUBV3wRZS&eHzdygTm zjXW0JyT1MdkoEFoY^0UXmsDYZ=zyUbpddV%mJyJ>dnByWW0kn^`FRR#@cY!VBGUy0 zFrwWqFYsW*_BXVbDFI4rDTqh{Jc$;m0$4y~Ct2H!uy~|9shmu}YWpq&hFQT(0bm1| zA3)LK2UVjh0e%@%ao6agz%ZH%Wf2VGSE7l>Y8D5A>^2LphX7pyPF2&HjMI3JD{0$W zytPIv8laU9>l}~@g_(Pg!%EkBS2B%Pc#O>KO;Bqq4<(dP#3URINazq0NOoa+vng6jH0Hn~e z$kiwO9S?I-MKRM6MHhDdCIza3 z9kDoj(80uq0#q5HIy!%skPS#)3tCLkcK9ZNt!twB;@d`C7Etab=R>@hgE2p2?0o;w z^?tX+F*Ql4LUe&5)maZi1SK~|wRnMckCV8UOtU1id8wX%S!Qv`$hWqEu6s?wKIynD z$E?#j?JIGmE}UZw00!F)ERMmd0j0o8%g;&jO5po*f!9e0`=ysBB! z8I37m1b(;EhG0ac*bG|r8Q-E9CsLh!5g@g;=h%;SAye@KD5T#Tcb{p;hTz2qEe+%Q z$w*B({gi{lTU*@@*T${SXaKScr0(M$F^=IpM*wJbYjJ6XpCz?6_#qr$6?E+gdZY!j zkWX?6(^9D?r1|8y3NX55W!Y;(_mL=ZtsZanfN%qQ|Pp#AA zA@%Hh#OS2iVxr70m}B#zEd%K0K%M(3Te7&387-!=a*;^40`9jLTv=5k?hg{v=y*Z~ ztEQkB-&DG2dz&cXWHX?yISCMB*;8H^F5tjwjl|nhS?4P4WBMMoSLXNj<@y!P9UKyZ zk$U)n1{k+c`B`D>*`>64RAPQuZ3QiQ*@xOOR#-I%U&dMKi&r1J2)Q8X5IM~y$B5c_ zxQU_(x61lcSzSLUspf!48b2=q)%iJG)27c%VWSjsf*F?0RQYGg$ z&oNrQZk<(B5iA@mRTHJS;QW#dLPDszv{s-Egi=wkIJGIbobs%oAPpUz- zfEH6Yv-4PMSN@0gegL!;N1t>Rp7qif;K73x|MQGZoZ8xgj$`aq@iwSik=g|~6u4sCD9jxO)OMzf;kd(7i9ene!o?%(acw~dxVWEm*sDe!%{%r_$<^_u)IHkbG zX2FF|z7RXJ4UDsb5d_R&F)s-bNcA{=?eIq&7>si^(wqc5w0_bq5mBc4OSA|z@EHbf zL)-WV3pNjub`g@7B~$@zwzQ6@vOvWG3mps?4eJ<<^$<2Q-cOb4V6`iGwD3tXfZvm7 zb!RZx2f_ZdHO?>tHhHA;=;*Xm@rwdi?_4HpqnHc5xWyW5Pn2}nDT(KYx|@Mn&PY2c zUI}#Mw#4#1L;Lc3iHok&Iz7T=fhMY;1$`2t>8D1m{iOqeVR{a_m&Pt+(iDe184cCdl z>3dEx`MW%dUYpus63_SZ3qsknYUm+awb@wsK_G9om+*i(dtyJu=_u)YzBOIE4r?3d zIWw8vd)C$plDuCbI%_odQKCvy31+ua8$g*4R(G4Z-P*UhbbHFniZiI+eoZ3+VA(gw zw2&N5fvxUSJLE)kxSMqWRDExX%SAE`A7JhE&9iI2zSGlr1(I%VZZ17ri#M|HgcGTL=#Xt0+58+pSo8SCq z+1)0pm!_qKm+fB-7ZCVL~z9(&<`kxz=R`x_O+`MQKmknDDZS=Bkv(o9*&;7C@49sX)wC zb!9&g>!KT@lIqXx%c(g z(ql|D_0a{v29`>j&#8c=eBAe>IZj=)jguP#FfPpU z9HS{zrJ%~-w80NNQ2Y?UL$?%#xqZ3fAmT3jwsB-IrMbA3Oe0z3Lu3JNIq2b5P&6W5 z#BH#?Z)wRv*KD2vsnbOf^|;I>$Yf!glD9z(;7Z%pPrvJ;23W|xWvI|-tfK=JFsniU zGC&I~6hT!CTZ+xi8Klf`T1K-c@%Q?bfG5a0 z6{EIs2@78S9%@|s&N-rDFYZb^C{VOOWfKeCgos%U7no~3pqTsmv{-6@%7}^)&;pg> zU`7iYVC@G~tJ#@F`yAxZ73wJ;q>p43ytqXpG{LI9i(sh*u(jc9!QdMQTtKT_33XT8 z%Cx#AT@4QxSB6EPl~$!^wqnhz;B2WW-^&(B>$Fb$Pqv!4;x%HEGMP((?5JN+z%WPt zUhpL=#l%YuTAf92by-iHt}1zh5vVu>VQ8*K?-2CA9b&f~-?%5~VcV(E%OskvV((Kf zzL)))lcrB>2l?D`#v~(<|FN}##Cx2M?WY~eGM2^F)|Montg<3a1_15Y$KLD4iSzg^ zAVW#xIiu9oKCkG<()0a{WnLtTOu=PRJE?v%Zpm z8<$;n*`CTcaNxkcE??T%*uane=#S!efA@F0=QrJS)3*&Ief{fSk3)wJ?K%JT*I&N` zl1@V-tkdH;k-cQFsRFWtDyMM@JE&#Ah=NK*II^k>{l$%%Xu(6p(v?*J^b-gIpP73m z;vqHob1CjRX#`yvlqHlw2mFd#?a-C7X?X_f@lqv%3N--|Q8(-5^VHWEt_*0bU}UR! zuuk5gGFIqD>H=jIck%T1{c2tnv3PD`&)RLd252lZc5QzcKh%}UG6;qO41-$Sv|)e_ zHC*k(-H`8Ug)X$sYaOGkW=WdI(G>h)uvk(x+L^{2fD8_H!1`qI0Nq8oC<1ipEK&0s zO?7&?QVMj2upA<&qEL6GZ-O*9yl|^G@elzab+{U>+FPqiL38JVughYw{o3LVfxcM| z({0kgtC=OWs9n@hl1mSgZ~9!C>2qGjs+tvphb*t_#QIw(o}+>_}*08W44`* zCa4y>Xdo2u>gQle@{TeH%3#WJF{$5xM74c476oK%%BJLf=OE%_Oh+om+UhE$G{sXD zRcrbTR05ZLHlvGwg?iWwf_7n%q<|K4trRGV45&hH0L3W40*W$>=KfyMfIFvS2!09( zEx6nlJ*+#?EIT<6aULXQQKJ4JUzExa0o8d^R=A6gO@W|DvGY0yiNzITO}wqWYk+lg z?ojM_oJH+~4Cr@W9!xDVX2jPXaCWhv#2 zmS3Eo`iNn5YCPLOn;I_u>T-%mR%}aCQ{77-@B{}@189fKHasw1TB+xj8XHp&>GCKP zx=!DrDeDM~cj#+X3RDuDQ0CA|Dn+=*tUimo$E$~+uw1pPg@0*XX=0S^{3Y%g1fl;+ z(S5g`bY)E8HJSc?<}&0gd3P^Ex_6h#-~*j}=FieXkepM}n8GHmP8&j5Vg=xw8e+vI zezK~lDDK=^yK7n@8SR=+mS$`Za@M|EbEZ0WU3K2N?DeyUHtfo-&R&1NdDdxFIpz8U$HKRt|53mLkyV^Fwg7 z$FZxQ;<)0`78+Hq6H!a1qGGy zpHYow%N&9cwT^(Mc*CIxdmP1CG2l`FnHQ*EJXcPhM*YMmQSZ7NICuf%Ro@3Z^T~jW zkO4-gWPqxmh+PoGIGHs8bXKq_1|tx(U%3|vL=6M9G)s%1L+oo&gw=Ow%49sv)v|dk zz(A>yTDa}?(cR<2ddAxZG0Q;@R1zSY4(b4#!s1Fw{2qMFfiEqJ5etkMQLzasMN)uK zM{HvUzzia@2C+E+t#H~X3SflRYF3E>P_pY9{THXLMbzBmrG{66g<_?JmenzkCyOb% zc2S2o_-DWdZ?>*Z&s%632UW!{hElImD?bOQ z0c*G<18wnOYm6I3j%M-3_`m{#hiu)oHUX?-S*$qsB#&lc>+~I&G75?KtWF~-s}>!A zVGAfj9GdVTA;=*ut@FJFT|GT$69??bZpe?UC%g6Tk(BxE-eLJLZ@)lkh_gO*Drg~0 zI#8AbmpTc5kfk=P0!hz*_^qG0sZ{lCpVRZ8gmr4^yaGvAS&go`Y5t*y9>O=i@r~}; zGoJB`b3RRZ#xtI=^z4gY{NkQL(wDvLW&5sk7zRA&InTkr|NFnkv-|G558wReH*xvp zm+!m0{iMT(563O`drhm{@^`cHU8l!eq7unVMtmQs0aB$DQ;rGjp}E#Ge|IT_pM}A# zN*m*Z=cmTSsZwoa7+%^fqhSrl4RjIty|=xk#T4Kb&!-6yqfxJ$}YkXxH)yO6)wz5fw(m$=Y6cR=Eg`XBJsJ&cm$f<%Sd_z zJuwW;Rv$77+iiNJ2p}^@ARQzvuKcnLx7v!n%jn81P-_Dz8KM9YE6eQ{c;YH; z4B$XPv;hK?3Po{19swR$d+o2e$lAp!4GgD3VErArhlXksc;P{mqfbG-=QKpV;fnJ* zo!{xP5JaczLMERx=m3wUsKw2NL>k0JpebTa ziUEwgT!Ii6X%4L}ogmr2G9gLYno;gmH2|v z^`7kzjA7ZB=)c-EC1yiez3By7-DrXt9%C;sJiHHT!zdDOUUC;xxHi5gGqm8PTVy_Bi(mtg=N@zJ(U z{;vE@yWhp12_$I6UZuy-*FrCAI$GZj3BAf_R_{(u@SA#u#LJ|>*{QGTd}kf!M43tQcVFEDK(^91~lB2O`#};q8a{GB-|V` zqosvKt%^Fja^bW^v0t(|aV8l2Qb-8NxD9%op^GJWpJSv@%m)1Rlo? zA^gQ?hJxdQi@Ui|j~@mHE4{cyy9_egIixswQe6qFK&c8H3JgQdS7FHi60K zvz0L^YibFI{9PyS>{3Q92W%eQcs*{Ma-9Q0M{_@^Xv!|ZyaHgr19#qu#s7N~PFzud zrwH(>X8{*(V0QRY96dSUuDg%o#GN}BP9MRu9=ZUhcNDkIfm338sno$PE)su6*lE~gORb{f`#T1zN;I&%L9H}SY!bZz#0wK^thx6WH` zxA7ab0b~9yX#t$>20*KTSz}7KLdM02aa>qf6^2oPKy-wl@vtg(^R9VhoF>KaIg;Q( zsufii;Nc5k<5_~nQ^oW5f=7g^3Lach;jL1ji$xp&8rv$)KN~L*71Zrh7MJ$U|3UeW z|A3r4+2W&aY+&)~R|8jE3Dg~+RMaY{x&i0_EM~a)gy6|rPs8xM3$cw6r>;1R`%hnj z2ew9>8b_#{wzevaj-vWx0&#P4JE6lU1Z)z&4)lDqwLA>ghYE;5&&3M2xHP9Y<2= z6iAul;MN9SbHno>PyasDCtre-3{^sXA!H$e-B6#7=Xp?2>6$MHaZL%#8BGFsh)q)n zO!#Q}JmIVAd963DW8`uICToe(VU#2SsCx~FKy;PVHs#ZkHdw*UV8IU$dt^@9`!xB4 zru{7`XET7p;8Ly(m2)d0rbJ50&+&eYIzBv;~1 z4Z7V+^k`gf8Axq?sgZZN^wo`Pr2`5-%$r!>+S()Ftli3pwxb>L)fFw^@}9oi=bKP_ z>M6=Klw^bkVXsb^Nm6%7`50zWL2>o>N)-N&5{Auuk7OiRv*wk6IkGGa4<01Xrr zkCDbOmH9HK(A(gi->wJQDYFS&;_l-F>lph@oT(1l-f8@m0+o7vNmD?EY(eTEpCq1T zn4l}@SpXs+>I|-g0+tx0mq)2Yf)V2!K%H0yI>fjJvSH_7+6kO}ly00ED>p zu&U)>z}(-FfKHA#0RWdW%}c$pUKs>369X=W0vW_(lG-zr;)0Vpv-c{7HUx&d_029!3up`_uofi?@^0OE_FFs3NytZ)s5ov?!@9CTQmQ>8@@+aghh4DF&1 zSxP`j4J`_$VB|p%TNF0|?H_j7_zgsv@E{v)ILos!KtdPwahJ%}s zlZTi_e%z&-Z>GXchJ;NSrq zxaxV>x#YXB*cr_i-aS&F0xT3btvGbqMY!ami*Q zDA$v(6=NL1V}tIGV@NAX@RaL>Wzh;b>Pve#t;gW!)z=iN9XVv#NUK|~`YLjsNH9UU zVi#6?6{@uovP^@(_m&!{O6zO?>mdi8`0DIBed|)@3xqjsB* zcLhFs=oUO&zh*L=Tc?9Ofcr?b*-|*5DnaKd_tQYZd6cwGIyh(-vbq1&EHsi%`ge+( z0t*XLB0nWQmd{?wWH0&{@ExtDYfScQ?D2TNwJ9V6HJQ+KfM(>-m*R(2PDkj?rF=ic zf3G9cy**4T^_9Zmo6=k!=r}VrH6u4N5o{Wu$duYRUsOeL0?1LA_M;=e-B_NDhLKCR zB@&=#yl-PP=h(E zSAZ0-3!kRx9D$B;>x{Ni%A@J3lI`)0*@4eQC1*t!ll5XgU3eoJW_aDGVh%w zLpG;I8j=zS;}FEn@oKTuL?|TWae`Sk2G}-XKEdIV;1EKA#ux%(VFL#5hnGW~q!xQV z3~)EY*7k9`LPtRz6=SWPk`&-96p#_KK|S^>EcWM6fcap`?OY+V5hx40+hr!G1sDe^ z&@Om1Nh7{zFtk~9HbGhk3Sq8TB4lHf!GY4S&VhrjwCu8nfgORdZ>|6IU95f!v-(<* zGVk1f0s*D)JxI(a0d)%EMd%Vq7bdzwTFU;fS)dFjAj1w&&MUUOP5^A-Y@$(-ENHGma?pP3^~OI0fKggq2 zG+ElU@pS6yZtSc}lk=Z`2hMvLycT@b>5PR1^8NNsSKrbW~ z@dNHBx;DE`-@-(`V=}v9ghh}xZ$gzh6bn3faKztUaT@c>9)jW+X1c&!0mbNHrWB|q zk1tUDB0KnMH(C(~3sNoQ3P^{Wg`HW!8?a-C){GNP9^yPD^oYiMqYMBu6^!1ec7(^R z-4643C>NHAO0kl=s*jwCtHB70;Kcd ztLvGf@t)NTkGtI;Jh!o=Y|&)?<&jK0u`9#pk}GGGTowcFMnGnQ<6UjEe}JOGVuY6! z{4Z3dGflJWEhS!%Zr)m%!&3Pj{}Z?@+A1tCd-Bp9%s(;Hd83WpefQlf!Oy2Y^{GqG zz8xUxVzJm$zOAjTbFO1myw$zdyH4x$=p_<&Q}*nd1Oi{9ofeBdRcH8Q?qT^z>l6n( z&BBI2s56jCVMr4rHwDEmyzq-Uz)PK);88sfP|#wzB^Mb%`wVkoEJ?@cbq$LxS$R6T z^t;O>S+$_D%;6FTcdN(rE1LNw+LsJ$kg4vLr2i|Sp4pqU>SS!blE6@xX0)r{`f6>p zNSKwvPMKrjG3YGTCc%~wD&iLy6`D}myb!dAy2OBDwOf$~A;Wiu+*;tn*9#>9H2D7% zFe^@98)_lw0?4l7as2!yV(QV1L93-Yh+M*oH)8eq&=U~v#2Nw*DkcOi&_d80K$7z)nXdDG^!9Rq+(G<%*vt(R_k=0B?m_UoZZrwss))nb#@B(K71(-9sWOY!If8Fwh7D*UTBvAdE8*b{?snei;;25HYyQP zA=SMHq8(^D2&8FoB8`{?n27ccX(7#X#1)~ch>P*6Son^b=(4-z8&Q%}q+9L#c=2F{ z%5v3;c3DLNX;qzQX#*K$Xzli91(@p=r9sDw_?$UF7!6{d(;Vd`rhvIS27v=XLFIZW zZi=6$nQh>@BC#~r5rkFd$b2(wlo_tR>dAP?k6eWV-mJv{9Ge6GdJ!Po3Yl#{D?>81 zcAuV&I6dRD5pgkJY@1nY!zzuLNwx7Pt`l}j;UNH$g*Dd&_gC@1&i8snF%6EY3q!Q* z^>xVnbWxQFsGXY~YsC0z>y7vYiPfbNt`|Q9*dy3sReAmx3i7Bpy4!PE>$Fa*lhZ;} zj7y;}Ml3duqKftqm#wrV{TLYR1n|PzY&+t@<3pDEC{_GVc z>dPX!U1Dp-80}!A?bCSXI!CiYN7QGKAB{QSA!YVHofOS^PBdUz2ica8%d_Vstj!@KUNm_pHr_LVZrf=A8$O zowi^rp$2r>S{I+S$u>(MX*#gALs08zHo;-;63-@dJ5S86B%OSSJRNx;m-DVlF@;$M zNpDbudV;f+^9CgS{O3Qv^z5RGE?OC%b5(rIpZ(dN#VcR=%5O>A&Xjg`cFy_TRaT>q z1aw`ebvn1yvmte71O)~4f;za{rYPuQ*en(rvnK4wcqPXC95^eD83 zz=~`X7I~|2_4d@_3L+K#V7~c#o8jt~OV!)1QcxY#1jH3~A1^IE(_o#>pOiP~ z*`z{><4r7IT~43BSG#2tH>afa943xl7A-INoA>ph4d7E3DZYMzt&r-6ciTm9 z=ceNRK~V<*4^6F{WEIL_c-_QJ=RNPUGwiv%?zz;%#bLs?I2K{SMLsTV+?Vz`$270e zNt3b&ku6%|M}`1MV>yultXa(-sj9A|9=oOBRenIw{<7M$(XDk_r`=NCM}mS42sWXp zcA;ApKo=Mm$8d4I6Eoeyrk;Sv7^IMLlsHXnmW6RNKxq_!pw9d01dYGY`EJ?`~H_JTBZGabUc0m$?q43L?FYC45s)#@x(e7s}U zEPM+j4P(ngqn2R5is`JO>0v$0*@gA;OMBq}G($FIaiF&?Mzo!7^3DczmGY~m7eLfDI3EX^6vJs*xKxPGbkyJD0t%EOLN|Ur2qDB z|F-n(1uuBP%Dk&w-0!{j-bcMndr2owoOo2UHicLYvIm7*j+UlGn*Qg6 zUEo%I)C)@jdjN7@4ObD?BTac_{ty7fX|aIrE5X5QL3Vo&EH7J6WlIug=2mYz-wnRb zc1ijUpfLt{jK7s`eN3TD1HlYDGk`mWl8D!+axO&AB1bAHKhqAE;wXR zR|HiC6B0w%lvV~^Qab<=0nW1x6huW^d!<$3x^Myngv-W0*V5ur1rQ4gg1%;?AKPqU z+Adb{chyeyP2l5i1M+1tW<6wMTIoV11&|reBeuLwk+SNbXUdp<&micu99i*O&QsIp zVNzBWtbs;^ry@TWx^IGjTnLOV&|K`1-j(>*9MdYK4#24m02>g@fkRi~(&t@_+2uzt z8;)bVykL97nmdYe`ywu>OG>DSskcFrxR25ArJiT_=80)wpC>~f2R?j2o@CES!}&eR z4ogoeI?_Jp-+8+QKX)Ld&r`|sn`j=qeFP|j4v8D~YNM-5U>oyl8zW8mxfWKXpF2~pk+oQ%@!ZbAP!Eoo#ZT9sL-WCFjn^V!viMDppVop+7{N6+oiNCwf z=ZeIA)Q9HCWt@#}tJj7IHV6?kS&OuLXp8)kR+O5`%~PKE?mxi z^V?TRAR2jJ;!_UZ6rmkuvloqW0>;WF4lR$sT%N-cG6X;Cp;c!t#THsA$&m4f^f~in ziBW=Ef=W?8FiSGNuuOy9O4dEtQ}=?9>Z6_Ck2X2|Nd4YB5lvh_>n!$Fb$NLgSvsFV?Us+0iNsQ+OoZW!V5-P~d`++2zPb!exuq_ax!G@V0~WnGkn)3$Bf zwr$&}thAk#th8<0wr$(0w5@)B_v+ajyme>yp4ewcd@=60^2mSDY4*EW1`3!b&53qH zEVw9@y~iRUt-BBgdt0D+F}lnw0-9k^%|isMXRTNOj33>#D*Ub<^}F@gR=F2)THpleOO)g`&;BP6IJIrkX?y!wJjHe&u7n1sP7WR645H1AH#cnz_*7h7o_X z96B;_-Zw@pCJik(Ax3XH3(w-T{(uF*{d0occMd%xdY6w0G3~wF?&RZNhP&*Qg;Ue6 zG9dT3o$+G_eP}p5a;1rv65ArGE>lQqDkj=f%KW5K6E2>;2|~dDP{#E@29DdgkiIWW z5Lbqlond$i6x);o23wVbIib%1GW_frDU>c=8yPl>e&c^tjO(`6U|ISk)sS;`o~Jk1 zk8+}XUsLxFuM0!`9wOE*A{t4mMi__Y3)gUPkfM*=P$TGBjL2=Di(-dUVWDOzw7dBS zDLt?Y0KJEp+5|Jgk|9fy&J@o6QHyOQ=iHxE&BY43Rq3?)r)Y;m2jIt&gNb?w-Pj?; zQVp;e7i_9e!#ki)l@0|ulI;wjI0UmI`eMN#i0j`LmDS<(#)nlhG1_dZHCyKT&#cRR z?5d{BT)=Zfr8MON8^H|*4tWm3dT9jQ8cYC$oaj9r*Vo7LXV|~xFXl3$j*bvRq!{P{U2VX+u%hQob6Fd$>P(3*8H7cabKMw6*VOZR8(_sO{X2b;& z2%9qLNPv@DN$-LA`~*6|Hz3x&l3a}FikyYmm`mbXc^i1hJ9i6Lnb-4oulf^8iz<(R zsQB6BK|H&JN)vUIG)&#$;(#tz+={5zLz$uhS9sy~cz*k7tgDX60#p+ZJ*`Y=Lkrp0 za}lE7ZIIFx<>^>F>Ff2)_jU4H?sHQqJ^#l5W{<%Vx(7Nnk18G4%(7W%kNhe6ay_39MP%b-s{gV~IQOKzV+dvh=;B>+PZ<80yqJ z!4LY`nrs66KZ+~4N+yPQF@ii}(0z+|=nhSbl#m7y&9R6owvpZD6=+F{Q1F-H9sf!7}(m40;7m^8p$?nj0PF%zDjG z2RQCZ?JjONzDifNtgwB?%cuF-fXABN;bAGG{iCiR>jg9kZ6;GeSUe1b9a||4 z4MiN+0_G1&x6W^L+o96QKd#cqU791+VFvJ12Gn&Ym*H!gHeusStr`<7eCz6C=fE#p zWqn#k_{{G-6q;yMRM$6N%F|NH zE&K!tmlP0fA+86BmXC^H+#$VWMF`lYYylVZa$QN(kaFe^`{GpzJ7a@AM7-_k88 zt)Md+!Q^a^@{aSbnxp-AN}uEtYhJT&6er=1Em(SuEoQk5e(f!cmhoEk3^%0gO&8w< zDp+T^)!az(j`7I$K2*XaqVj+zc8#to0c9le2!lR0igb@ zRKNT`x_5gzF=N%{&O1DI&8$J5*?4xUnx5-T@K(+o6DVvxtE?GqEQbBIRB@rQ>5Z5h z`Fnan0=Xj))|8Awk<~FE{z|wOdYjJEEO;ROsq$e?_?tHtfNe!u0sjxA8$quCW{{W@(_v-*C-VG7pp{wWJAZU&i!>q!OMFwq?q0Xabigo3{BmK2JY_!C zSD*WY@A3#Z8R9QpIO3htCV9)~vbbrumL)cf?T=wQ>bO1Dsn@R*Tn+w>`;v~?-Xea+ zWRHk8$s_0-0_V6#S;Kb}f$zImM*iOYP+Yg>8K3*a+$exU;c%_q^zQNxBtaj2>sH_? zz|ZhuHwd^@q3-(Fz8L|e^ z@7e9Fqs)!E@(WWBOlXYTpQPAHI2@#v>P=w-lIJ#9Gc3^;X=uc7wrRr zOe{)Z0;pWNJX`v@7*_Yw}7@Xr9MGffp7=*@93Qva^+*5N-adWF~^BFBE|J1>!j z`q^ZLn6WRBT2(YQIdZ+dL>2g=G?k4Bk_{Xcm0#Y#adcoC)f-mH#j2N7v8FUpgJfD( z{SJ>Rdbjr%4o73YTBQ%nXGe^6bkml{zZr?jYdi!`1t+Hq<*Rk)bGCMVOUoQ^2S!|D zhqx4jmwRA?R-`uH>W;TU!aD)?G5!@Tm;`sMtS0nh!>O>fKVc@xHZg2^?sYVc?-@ms z(HjoJmO;fHM>St^WO)e|Hpv zaBYAcNN@@&0KnK&DIm9SfCL*MVWiN<;HnN1=oY>d(ZEQzm$)`;3h=5Dm*2>Km-IkL zwHCfMwTh7>{Q+^a)()VphF=bRDnPrNHF=Tu*|G9Ol_a;C$RZKZ9kU#(m_;mlh6u}gcj8Ry)6Ix0BCB%9@qe+qQ_G0QYZ!)unGxO z%+8>XO68|VeYwXYZV;iXiUb*E%rv);{Mn&H)P+B9;?o;ho?L!CzZn#mmvM&iaE&Td ztV+D&#P*`zBxWhSH_|V{#%YuYNU8Jq}YuYJ3g`_w4MHx*fS!t zw$!c&G!;($pfVl6IeZWc9yfQGGG|G7{>G|`uvHabB-J-iGD1n93tKLj4+%!E{+NID zng|?F+bO7GDbOF_S&!6~yzjnB=34&4&i|5QcjJnF4c^b1{!f~xUq&3FzQa-u1^SXnzr!n__)jIn*hXRlK!56s`*!Olfz1pGk_OglbtC z3fX3$j=1l)ka&m;v?k`%=Pu9~5miw0EQ2P4-L{DcAnFmaSI~x}3(6*U$mmJ$V6e#Z zm&-okUN!#k9op7oy*Z)pdVE?bX1B_CE4idaPW3;>SHB1sF_idxMhd%hsIZZZ->tjth)tn6;~Ao`N!yek~p#ER8=CopO_A z7t%JVHu~E*;2F!k{wEz{gE^iws{5w6VNl*`~(@) zmj$b!LhV4Ve#8>gY31$xkt=mkbl31`c8ezVn;EWJDxXy1!`vy8QaVVf1oIBUQ}`JW zVA#KGN0|#((?9n3@4Kz$^oJ9QIe%~_RtAK`xsL`>wV9o`eILHyt@Ct~j&9Vd@3vaX zS8KqcYz-f-{5bgFu*X;Zv_N*pkEUSbu6aLYWkQg+-y_#Z>JOMP@y{zar}dwASOi`$!y)GgXPMH$k(Yof(t?r79Llz zW6a*{kE!@VsUP@S8pTitb6$7@O8G2^&Zaqcqh7jB`8{s?AyfT6{_9G^16awUZh8SP zoIZ%O;6wWC9%}9@*nh=^{wec?=y`AL{0d0UCQ9wc4 zerlknwUHK8X*o<`ZMtbeW8I;92PtG(IyyU9&!L?3{`KOwT%yyYkI*MWgi{)308 z>0yu0E?WKh3Mu=6ZA0aP-Ucs3ZknN#a5J?9=qJCwbfX9ZmJ*XkdNGs>5Jt^jDmD`# zz}%$6NHPbLwZj2ylLpL!ON5KAA~6arfeHpg#2PXMj%88Cs*u_S=udqc!@9O50Rdij zu=$f$qLl%|fC#hDA~4mK0%D#y0~0PgfD;hE3I+}v)5?b3EG5{YEeUnJN{A+Gc|XE8 z@WlT5626CWvA&5URKDQ@VA=azv&3!uY5iV5bXos4*}+ze+&<}0I5pmQ?6qUZcjPba z6aQ9lVA-4-C!0+Nn+~^e*IhcZuVq;;Es1LBLhpkHatCQ6j5`d-f~bo=m{>Xce=mRl zgT}YzRZ}IcMOoQe+W`UJ>6I?m^8xMMGA*o|+Mfa>e0nz=>5Pm(oVNVd^1Qr?&R?>X z9J$27G6SHr)hmAYC0xJ9qlP$HUa;tQ2T{UY!uZG^n!@jE7x|8aJ@rb;Nhz!iC>BMt z50P!1<(nK_T|2v5nm(VCOMLB{^qSMEnX0dV)0Q3JopyR{5N$g$z_r;}ch-w(E22}J z5kw)7%>)*o2z$it|LEnc;~c^4b4p-Jyj64urVBCLX1i-P#@Qi#V4)Y!@qJ(f_O`pFL* zKcgD~6|r!lM&U9+YE5H}HEC@+{jb2dDDK=yps|{8u5}?yT;5!}%*3mg-`g}*78*=+ zw6u`WM|SD>q2ts#nnmP<<6SjD8QNMsQOsn7Bo?Dc=^(Iei^*#O+1O@SGSp^(8c&^w zjb*F$o1;*QG-FhR8SIvTgr_K8<^H}{jT9}oBCo?>oag@Bns|T>c&fZ#xU)2D>oY!j zob3%68Z6dHhdi@I^zGoYqMVjuYHiiYjeHhq5`q|ts zh65_8UJ7c8X8umG1ZbJm@-Kp#%{MY;>gM=fg`9_avCrHB^3V~xkQ%H?YIz6-jIlVy zwLgw__*Bk9kiz&QL$`+v^7g{avUTY$GFhhmc_3CEWgOU~8>XJHiXDk|G-XPuc~dm( z(D@5sOvtSR(Qlw$t6ngh*86p!`yB~6$Hp1cX4UyTrtv5xG-X^N3t%BXA(Mjb zsDDstr;~I8Fh76~EOF0AU~s_1L@+gP2a59qUCd3h*!~hGv^!zQBQ?DaE;F7#d}aSx zSi3Q>wl`QDp*+x380DcAqFoV%Fvxsv|3TZ!YdXn+me1IYfgX*2$X=m8qo=ru(?ko+A>N+(B!8OTjR$k$fUURI z#Sx6OOu{!~lMzDFqH@&oC5b3V7>cm={){u)XxR$<^--C0fJvDk@=7qWQFd^bu5p*b zI`0F*n&?10W^*RjWyxskFfjNX=7w$;{1p==*=-U5L2J zUEF$gu5nkc*x48c6rm;Si^Vk3+g@FMM~p_vYrH}DJaAS@E}e*VrzT_cSB8!Pdz!}j zNs2nf7J4CZ(CKYjSN%2s@48HR==Flrnf%z{ACV3a2u8y3m(%v5U8A()v5b5CFQ7aF zL&kss`=0_u6nG`N?zmvsa@(|(1qdWSj>P#+Rq#pG+ivi`c;x4K?Kh1=78mlYLasox zd-sKY+uaE69RR{akeQh&ds9v$a2Kw)_g{W1WyASy81pd9?_b#S7DUO_m2KBU_RSFB ztd-bu7=))NlUw+2w)_v`)b=pL+j*L*=LG#<>+oxpDQ!58_HQ# zWuLubZ67XzxNZ}Puc;4}K%R37q9HGcbUQAlktif_LOqq6>_}4?-rtxt;}s?YKenBj ziI2XsrKFRn5)RYOL@lY$OYt?em0nsnk0#%1^TP?7hn#AWk)q{avAf;GuD>=_g8_V^ zwxI7^8G$1@{f@>%+b5?C3DLsIqr9(C&MIUHgTFByomD^qtL(Y_yv{!2F&Z+470MT9 zp!Ae?u3_e8=4dRPfI?NyM7?9A*+GjJd?F}AA70NYV52cJ2p&4yoE)#PkV$Y}Vhily zoheh{1rwtJO^g(orMO|A*U3DJ5}+ZNzmpjNuzFmpQRFVZUz}7`S6aN~(N3f-G)uC| zXV0%m#O~6P4lD>KgjkevJ$&rJ07?;1T#@+nB(jtu6)jTuEYxvRostf87Z`U?E5gBx z6Jpk0Do`|*ff9z5aZ@bNFHFm=9!2)q2AuzPh@80yhOwTFId~DUSr$Jx@yWMmQE{px z8FTyv;n{}9sgEpZNiC`=*H-$)_TG95qBD4m+*C*#nJZ0M`axWbMG=!sM{DW{ee$A# z!5dDPY3+!&agvG>q)NoV42Lvu=0ZQ>Tww@wAY?%wIPzP!cApv zW2?YGzAbNnYV^L1XBSG^r~_)dLS9?MmE-7oXczeIFelAg#-#+;Sp8eQE5!d{V?9=y zch%_L2no2Zk4aO{Wt|xBwMMp%IT!e_Jnto?`YPOwAU_}`ueqdIVj~?hn~Py3J+geB>(wZ{8s$_oj`1`@w27 zuBhs0G(D`d}Ujar*&5kX$Ypweh1PygM@+xM{d`>9bQO~6R^urq7$VR7e)dpF>+ zKihC?h@-^1*>tz*%?{G58&QK9d(tL*@! z?1k=b2bjb)`_<*;UhL0n?A<=1Kh~oQ|GRy zYWrb;|9)2I`#9Aw1^{FN-0S>7^a1jJ;Pek7m5kW~nC;pCUyNH+!8_E`rEk}F1$nXn zG=3Q-h67vuHYS6aLKk~5l4}znbvn-Fc>hW!a!$7WDzOM!Ds7pG2#`78*rR*kK;Y?V z^|()=g!`loOFTbMDH1`!(&rF$ql=dI4(C29Pjefo^=w2HzdZY2THGXSc0%-^Oq(=+ zR;ML|AlhKNm`~vmHI+VlQf%SMNGmau3aG%TfBm9FpWJ$Ru`p}0(4DCR&pFg^?nBTkR4l2KG646yQQ*rHl|6kNXd={Ul1m9 zUxGqYkL}K#OBx9DdW|3i8nrNg5g!xGX?s7`;2X6>n>TRKk^feqjIN&5D|+(3ZcM5; zr_P=@G?Sm9ZFxMNcIxvAZD<-D>_E`1h&qDX1`Jb8gDH02L;$M~=^@m^BlicKGd!V_ z&x_}OIM`xx-#MTIIvLDm%zh;A ziF@%o-pTpYSg_f4NrbSP+|-T+**^ms%DE9~zGN?^37omRF__$#Zg_~N;oIgQ@=am; zZm$`_m7TrmXvr#<*CzmGRQ|2;*#H76b0JDW7fST@h$Ihk?dT`f!>Hej{&%-ykX`1mzK%yFoG8HbJzaI?^2IIPS_~*&po|7J8e=9q;<5rnIlP0GloMg zl!uLv^N(F#xoX-t zCe_zwQKE5Fyp(Yc>q?=r6zgSO`wW|lIAK#ATT6O8Q&~&d8gzi zXsh0i;p^{}jYDSslh#dpTig8+T>Bx!?>$6@T$oGZ?jv%>{>`0d4!}5i(?6a_*|`hY zM8ss;bwK|YW7eKr-`W~t{2XB1+pwwKcE>e%=~&&j2W;bm#TiETTLqiIC}JKAB6~22=Q`RLM;N2W3Us4&<*h~>DY2Iab5x@B% zn%c5}K&v#7m%!7jLBy3H1ml-FXn`z_H@#hx{u*0s*I?PG{0=f^wu>=pF|Yqi1y@(8 z9-tfmKF3F^PRt4n(fo|jsE~YMM=c=l3*_#uD$US99GvE60hFs^^l$@ijBRlzgngQ% zn#YVe@n@`uU#&^MEXuVwAf|+A!Q2t+lB7Ya1sqCK+4>OAhALSR zRzttZ6%z$-)e;;KtwzB>BO!m)t%kqdzsHpk#s*^rDt(+D{H1WvqKzA{1Yie z5tZ78CsZiHh=|Z}vimP+sGTb%QL(w=Moz+OQu~1V>$r+4*xD}8m63N>N(~d~ zzQPUfEVwPo0}}B8 zmauM}GqHw(9=9=YB)0Ib&Jp*OnquG6#Vut9C#B{;tX7a9HCVcI%G%os>7U1z9J_B7 zuV!reR_I@8IyH@zO)R2L@GEwdwTp+$!!ftB;VCyA%q6f4wLsZE0;$ihoy)-GL6l5A zR;cfI{b$jreM|)y?1jMg0{hgg88t#1suG2OhbK(0k<$Kx{D-nFe)4FTQ3~?XmlPMA zyl3|M9=|xgxIJQ*E+ubCq>49FDngOZrvf8zcBL5hqT0DevQVIV?OX`isggGVqol|d zFA_4h+a*n{r3dw8uLx}8u%l23K$ zRy5KU4HA3>{ja%q>*ZtC@44}AQSfWA?YyFLru;j#_w)EaAkQ6OM8rfC{JhP% z@R`)z38bxQGnswTbKiFLn2$6F{!h(zp0op2g3o$8Jk^QCQ??t@dBYx#``t+=+KS@D zZM{k~FE`JEIw;LaRU(j)k=DnUR@De4;SZP*ALF|t$!0Vp7363U73bQMMe>~uoO2zZ zsQYA{S!FW!MY%9C8~20Bd{7fnz$@};O6;=2$S2y_uRUmvbP9THVp!%7ZDsPK9E!rI zSrs@`%5X2R$L?15=mQfIAwxPwr9(|M(q5LZdkoVT1DnXHi{83pGO%PoM=E8P8I$?) z(x^ft5}7nI$Y_DgcIr5`f!a-XONLC^&dgk%*IkI_OnUmpc0#yJLTjU)+B|8fi4Z)~ z{dIF-81rL{8YDH*@a z7OrRR3`(VlY4SPzULeiN_izL6;;LI!4WLHxA|-Q9f-jTG{VYJPKulo_EyRV}bbMCg z^B~LpQo%8Pp~I8-QyX~@u2x;c&ymqV?;(oC5yQvumDnGI)*C=aAH6^07Z@m4naON_ieYFg-k6N1A;TfZm* zBq3Y|&KJ!PTz~dFLiHrRy-yrjefm#J5>eNb1$2GqXsq>{JbXW_2YIr4sTZ;Cb1$uv zRUui6Z~6*b5%d-oxzWH&Ic`SiF~5E;yY*{}*BuF-m%LuiuHO!nN~l!G(8Z%JgCmH@ zfU}9}Zle021F_P1}NsFl%9yxF=`p$IH zU_SAwH}7;SzHqb3SCm?69zO1Td}&p#X!=%H==g*A+~Vb~#WIcPPc8JbgXX9x8at+q zQ=o@^jY9)nyr(i(wFaxG4^fT>tioyEohM|OC*PpP!cg(_>=v&-z1(5@qDNQSjPO)d z50but@bTY=9vwUfux^YiQA3l};aorwqABXUSl#rboDY5C&4v&@msPoK2B-2$JYY4O zVq;ERZ6q~-2lMG|XEbhQ`peU*l*(Aqk-KYceyR4Rp{2;aa>-6w#e!bzvnlNj)DJoZ zsn4(*ifvp}C(fSwHNBB%2HGQk>NVHfZr;xD-t4V6TD}4(1QGWBADgc;?ma;_zBk^l z0KWf+&c!>RmLS^yd-jJLFgkui{k$9g*nI92eiI9PzaDz$5}NL{0$Aa9h~NE!egCn# zTAV-D_W(RSf$!(t@6A`upL4_g|IXo=E}cI}O@0@xey~5cgx{h*KY%~UJ$*L%KhNHN z03zA1oIfYKM!U0$m7jnuOdz0(_@6UwPVKFE;7o~-Yhr!|N1ZL`AsZ9FlO_&2D(R{d zlVFrqdRQx-p0~Rc1WkwqE-q@xqNx+yly$m2m6OfW*ZxdX*^y}xv)#j5vs-&E9dG)l z@1FVz!qmN9`xr+lt7Xo6`Fj;EYH?hMvby&Pnk6~CKp)hB-5Q5tzXOSa%FtiXC33E# z{23Le?h)gR{??R)*$jC_5y+5iIDBI;yVVChvv_J6#wWC}f5qvTf;Gk28!U1&y}7qjcH zcKBL$Gd9ab7SNj2LatI7?obZhm6WSNbTW(fu~KtBKg2nq>{K!nvNH7TUn}h8;{7gR{{4leo2ins*liyM-_q7| zqM1TmEqUCoo}P!fi5ob_cc-Q4fS&mQn2sg zboTD?Ow|X_Q1rUe+7kjW+_`(68h%guzqOx(1^kBye*FSe5zXq)pzi=GS-d_Kgtvmu zerJXeFZ3}T)Z}|K{=tdn=QT5%-Y(-48e|$Nf8-6_vu}d4Q;FBF@EeRC;deGgxl!Q> z5>CErfV^qrjn*N6kkG=}M~hz_uC@cZYS7x<)=L*%;tfrDuwXM6RJPUSpxL|_?^+D# zi^s|gAx*tCUh;(DI0VmCF-VMk}0G)jB-d&VlO5T?H3drA$`zH{j=B)AZK)IrJT4j7v!@N$N=aYIe-x4)g~DEN$7Sj;HEEo zKXdmR=lkR5?dD+C&t@;S_Zj{3HwjJ!k*oo-S; z)t}z)8bAKZjfeXCQ2fb}hOc0Ph>#ik3nE@q{qi98y56locFdOuiW0X#o)5?QIT4>E zIxyh~+Uv%PvkI<;gGnFmj>~{W15}{shs=orG_!pX9Zb^Qe7!~C_^j;b8Ddrz&u zq~Y=raul1>s0mh;s5Lwf^R|aWeDkxI_PxX26C~2ZkVhax^8zGH7~SxnTObORcy-`^7C4L(k3q>gWqrR-c#7UEeE$O2j{u ziaC4#)pz*SxcUH=qq*z2PcWKXVR0yMJf!L%GgC?)8{~g~9 zHk7}VvKGy$lQ%a1KnqVcuwsa1edfQqP3RqIftmD1Z7C~ZsOX=fOm7{VxFr&WrQ|~g zqC2BlJWL5R@rhgl3K}7-4q_q`mrPSAy+baC;9_iDTuywP1{FPi=|W2Ak&4uzZC+m* zKH6#<-*Ost>M*NZf7iZE#{SzL>IiZR=jgG>3*-m4m*~@yjXi~OaAf?7AAq^m^8`Zp ziMTry`;+K?d+-&`+Z*zxKM!#TbLc||+MaH1+EDC`HA>V$lRBb3f%8#kWu~{OT!~i1 z$e+clI%GyDn3u}&bVqa*Ii0X?4y0)Yu<2UZZdwfUlPj=ztX#pUer2erJ<)2cErD5eZD76)o)kGb~1t&=<>NXw-( zc0PR9ZS#CP-?Ix`hN2Je42;70e?iL6IUAc_2cY@AIfBPtF*a3hn21I%%lA%vfso;) z@@hHDZQN}!Euxz{5*{|uMVf5`=melBOd{oua&S{hSkw;k&Qrn`Rn>~Y`&J7EM%7LB=Ghf;>z7fOGz<}_h&Sy0BeHVcmtjUs* zaWPSjvLkdSRFAULcEkF-&rE|xj{mC>H8pWsJHetfU96Q@;6#M$3#W-~P{LvGK2ORZ zXYRgsU|?iZ$;rX3n^M>_&QDCuv$BmV2Ofnsj!-68A_Vn7Sc6TwF`{D@bKhg#@2i$Ks^d8G z?@&kN7KBm$4&$1dBgB|2#~S9!Qc>gVyHcfTgFNYSTV;CRg*%;Fut|BgeZobeE;&v) zJEjRCrDM6sC3;@Vq^Pp&1~Fa=GmI+~{omt!DWQ7%(;(VL0r&5Mrwq2>_}8vn_vxd1 zKqaYIYqw~9oqb({Er>(FX}AypiT2~5Nf4xG<=mXH%{xQbk%H&5I=rzj`|)3154SYg zWE2sf>1k(c6Qp>b_>6xk z84gqCmFl4v)NxLKC~%H(J+0e;idfJ2Nv|sg>CYgjBws8$3ZYXJix~E+a~|YndT*cf z+}y`Mt5jo$rW{Lz*K`zLR`3cM#8MmibMAei4$jj>f8meQX)R*AX;hO)G!|2w<_Q!k z^Q{eEyyu5G6?2RdtopkdyDsjFbn$(3;r{Bj8LgsXSJxQZfG+h-7VF|v#9TO&TPkqY+jy4ZXLAXjX;G@cSb|5Fi z$y3>{%cKK?xx#vkV=IL;x(8vFz{$pAI`L!Gx76PcF`1ggFg|VXw87xkN@gZfeujz9 zSK*g{@^zgxXiOedftw>_ zTjhSx^hpmpY1JBsqC2Wf`&X(wqckFRVC1ce27>q$Tam`d5;laR*K`MWma+M}>R>8nH5pcKCH`atMWzS=@FlfF^Ve-_w^{+?yxu2A%_1b_=TY)Xmb9K&I zv;q#M#mFUM(u08E@m>aUU6_eUS|okg4&jV=4Am~QUT@-3c{~p*Q$7o~I)8qSPP+Rr zK@RqFS>x>M(_YtgQbIPN1ilq=BR7v;>Q&T{AO$nBHDiGl;@+j!NdWvAG7EPg2^oWv znh0h4N=mU#)N@5J*0$*MjH!>JTWDDzTaOh#lpn=(>_KbRqoIF_JFVR4{ck#`UeIXa zP+;bkW92@Kq264XfCb)-?(*pH6Bb@XX%U!Z3>VZb#x1_FQ1VORNf%#5eCbZ9q%{w3 zl24b6^nGqjDx5H5mL;JTs)@WISj{%}43yImP=uhznCV%-&YM&Ns(2Ird$JE50u%`U z{Hnn+ad5o*4mLgU4q9)tZ4BD-&V(lMuqZ>cm{%z+j=U4Ij0m!1W;DA7HVZ|AJlD&@ zWiERu7oyZAK-L8IQu^z@!`d8kPY`QUlT;6VF_4b_SO=$EJ7w*xQ%4T87|5D*w}^iF zJq<8u>s1LodRvE=Fm|g`W_ih0Ds1;LbJg&)z+IC@cU}j?hPz#A|Anssb!UG;I9?}U zA-@#Kg^XI^gjaXe6zk{;7w$Q|rK3@yonq&?qYtT!e}vI&1L*+5kP&6lbsiO7M4@$1XxV? zD>DpBr)$nl2$`;6rMk(QQ?S?0AQ@zu`xVw9PYgPn$6}Mf3~mVz%Vw#afWTN}8vj-~ z$1@GB*AB%%%|XN2A_2ohsTiR$PI9{Dv-*w1Rm?4 zfq&}NWj0xl07}$P5e(^Uv@`rlC7JlHB=cz2v$gMdn{wH<KxYR2=$tKg~4z1~dWnb|K=`Ri}46xhh2CC z*8H^b3}E!#`jdCN&Y^}ZqBhBGUFZ=mx=cT?N)W*!?++)V6#n|G9P}@{y(n3^ z6QSQUTJZ4u@rjU{Tfvt@rnL>uv!25kvPq$i+c4ZP&t9lXWMX1@AVlTv&-g|B;l;8u zPOs!a(7ZCfbghVOwE{xxhP>A<9jz#`mlVeeiD&UJf0wl>6mUf@jx+8}AJmtil;Gfw z%U@T}S%Z@l#*NuNPGW`k+%wWm>reT2_baGN!CI2(-Nlq`;IX(U=@* zoM8U_nJHulkdu^@@_Hf2i(r5cMRu-rmh;cNJC{t-v+sYv?r&Az*{3zdaBIAOv1V82kO+E?)oH z7>-^685wKcM^8khb*l>uA4JB?oDP(g>$eb%U{^0#xBsgFP53C|trK8U5y+l6&(&G$!26=<%p zN=|aIYJkeQw1H0}JCHWu79#*yfK+T!SC{-UZc(zWTV1onk`X>Fk+=4i6?a$}$U1xe zJYp+cv__M(3+Y*!I20rrK1g`y4{23JgBW#^WTIi>FQ5+~J6(lk+Ae9MtDBx(5Xq25 z_lPCvX=rpiM76f=d?)_f?B%PE<2W2}BGKRAyb59j3$Z{SP`A0jev_xgN(y~;K!V1E zl%KEZhr9gFpX+C;QFkDHLuv7@9XuwGkwivbmOf#nU4& zJdWqE+P?gCcw)yz*>J?VK_%8w9G(%eA`{292@O3j~5t*)E{>wB2?b z2aYDWYh__1E}nupK)&#DHA-Y|8wHlGnR?v8>uKr1SBO z3IEDr0Fzjsj3zj75-}n_Vako~07ok?Eo{Kk#z{{IO0QKw8lrr|!L%(EkZ|u^B2FtQ zcQ5}3V)lr7<9WOG_c=Vq^{pUO#=-i7iA=X+IPOMY;PO`GshW@t#Kl5u8%})Ai%fjG zb}(kBHXHzEIqcuVHeKlj&!X<2(8f6 zz#YL- zHXhb>%`G00C_Z`z_b{AxpHtd=9&sG_vlJ{BqIp5K<9*X3dlw|uhB%v0=loe7_rD@9 zt2$~&vE5j02xSK1d9HCt^{2MI4RY^4MU za6@a$pqC*BXI|!wBcSJ{PLF_*y2tlN>{sfiK$OW3I)9$-3umUHIS(VvJZuDg76&3e zrP6`MDpyv17^~lQR!3Y#s&i3pW^HycX>g^!NL)sP){PMj5M=2?$z18$kXhU#6tl}| zy&p|=0Wu9Lpxy64plj0(?m@IZ`F)7FLgBfEUuPXF|3Z=aV@PUp&WsJ|XD)=P;x)`7 z5^kqBf52i0L0^&g1Y;b$VTROGqdI4eJY*0j@C5{h@pDY4;1$0hU}_QV`9eT-&%I$< zOW9%5Cy$hs9_gZrw!Ie-X2*#5fwt&|UNmzv3?0nujED_W0Ix2uwUm&;-$f@YC(~nOne<`>fKS z!uWFwo2xrHhaZ?he^9!z=FwDfi;K(Liwz5c7CK6+DPc2?1JTl0M7+9-@$?K%rD zJF4~5a@YER`N2a zrA6)9&RhJ3*O8c6tF*IB`HtH!_~Yz`)q|HMI+^O>BDRNL7$9%Ij^2Fz@J?<#eXllz z*}K+?LvP(Q7`B7Ya|wE_4Z+? zKzs&1c3)ki5PM@31wLtV4z)v*W~Dj;sm&MQjB=XS`J{*4(4bIbS>SRbgvsnIwf-zl z_tM&z%wgZDl>*ZxZCNM(s6b3v7X~v+@-gzoPOZZ^$06IHKbLOi^)&UPj2aExzp~Ml zj_*t&Wtuej;A|(xtRk8g#34TWCU?4MgOY&2@oCfr?t+(by5dMNgUW#Ne4Lfg&-zBpfdHstO zyKjjbK*`iAjK{@VzfMo_Y?TZN@7@UyO8sCsJd$Rmgzb_7ADzl(svljT4_b%)NZM@^ zYcJikdMZ3_1C!9~jh}sM2KlD8M7^<7rp1@}wo3qYt_epbLJ4dEN$<+~$Zi$%19|+VWrN0paNt z6OPB>Z8R^H?Ua*4L^75!km7*dt9%V2jx_K|6lpFD;u5ddw*LMkaIB6JB3*6r8ShA9 zsmBX#Zn1YqBbV%#s;dkR!ur5kZ~#w6*!FGc$j&nvt}h>V&YHX@6`TpXtBwf@@Csl;gkysD&GA)D?|nwKo}8O*+c zsyfz9*i0vnxt9!K2zS+%b6F1h;x)DlN5nlgT{jQW%hi9sIHFLdl@Dydu>PlLW^ z3GaS*_iEVPaKoqFTDu)b9x;;BSKq;86gIow*y;ial*jH`Dc56J1SzAQOfS(qhrw`yZap zfxXVC+uBKE?bvRN#*OX9Xl&cIcg)6i8YhjhW81cE^UHhQbH3lOu4m2lj4|f8Go@WZ zPR9gE+Is|BBG@Y=2G*ay>3`kTldI5UrE{@Ju4Z3j8&4JqF+3F}7XKc?f9?1J&J0l! zd5K5sdg7uMjqR=-QU&=^H4|sY63lfl^AsGXUaOFK*7`RVI2@1h5IW*BQ;-sLS=<$# z%NSRHk38}w8i>v>F&dpOE~z6|aHAUan1w0HM^U$NfZyg>aUL^{Nf;TL_$Sde(i$Yv z__($C77$%ut?CUJ*wFdW_8WEd6fBk|(8#LC*fcP>B%nTYmH4z(Foy^+pIU3~gomKX z{~e_Z8O7jn;Y3AeE3h5>3{DQ+orNlUVpwF_bqxH>HB{>rqpNFpqq|1AaiTOaW_UcN zJ7`Rt#`@S~jC)A z08ERA26Xq^^Y*kzdS;Y=I+;yIiQ-|wSOzPMF}QD1MXP~^Tj;zhz_klbUuI-@|T^NGV*8cI?lBX;D&2FmIwxx~_@NDZ#{S4w=u3IC3t)<5wRG;Oa zoNu&GqmW_UhvpOK9ye+n6g zbJKYl;O6y@K`?kdL-I>7jZ<%1eznYM6uhpYp4NSa-hBpGVKT4Wvzd7>lJa9P1##|2 zUwp|NJFtjD*ICWoWm{4zlJBGS%bB}mz26Oc>tQxL7-QJ@*kb_CNMO{o=eg!=yquee zM;@73`;l0^Cz^w#6fZ88)jkWykHVwU4N4sk2SK2y((+7eCqKb|dNv8fsK;nCs4Ae{ zrMTzHjPBH7!mB0OUdHd*^R@q(7*Iw#1vXy=@lGwO#+m<`E(IM{;g(#(uI_fg#MwC- zVsQi8qfG@1QVcA>cxG}>h)|C+Dh*Wsb zFPVDtzzE=H9)X9nd0S`ddOjKc!XYdmU3C6HGhAx{SheEqlP^kg@Pc)M(j)&l0c&TI zoFZ|}ITz$3S8Id)8`GK`eCEBq3@NZ_+Ok4tdLSd7xPG%@q@&?fGa$ zP<>k>3_Yc?6^`!3;v`_f1D3blmOn^1y`|U-ebPA>AzkBpU{azV^iVbzU=f1kmtim0 z>Yd=y-#pq){X~=DKSaS$NyY_;dFHS1diw{A74a8?lTejqyAjBV76j8P=C_IJ2VNOu zh$0^EnWi}T^2Rk&KP98Q_>`aFtC3z{J11DK(?`!tq&eBwE-rTp+N!tSSKT~1NXDbB zl?vU37#>Jp%I(cgZ<~#N5S0}Ot29x>GCkh-qvzD3HR(rtQtgJhg}Pk)uzPX$G}4I& z%nb4La{zc3!3e*pxR(=N%WPqYj^IrbL`|&XY_n<6q-;g?9X9loZeX*=$mH}h-5GUE zqg|?TI|^VOdNW&4*Kjj|g_<#D1ZLgIqYt)zzy<;0&VP*O!{L6*7LLfOOB@r6sC&E| zHu={WG$N7fn%!JdV9hc>G*Y(wyK`}n_S5D`2~mBvJFwANfK5{1iYDQ}{q6+Y*J z66ErbR?{T?PQ))Emmkgd(ajIL^R=z>l_Popv+62ci2M?(WY%d3iFG?Vz{jb} zO`n>;S_EkBStFi7#wChd-p;HWBKHmV&=eKx0PLVX*=p9j&oW_xWHz9OD`4&$x%(46 zK$hzQhaZLnDun4|BZV5Y|S4?f)*zgz=^q2@ljzZFWyOwh*-o>=@vE1uB*6t+;>l!S@DI;a7X4|E&?A$fG~sRagAJTw1HdU(t~f z6Cl*a3Uw8Jm!96(%jZZrg1NWfLSS>;$3KugDX7jOMGz+<@HEe2+H;KWC3M))q_C{X@rm#IKNR9k~UYM#bZ;dPLW z4?iaxR7g?RCsiA2pndiB-k!V7p?&1v&oL3Lh1S50SFmCNDZ?$5Q4@u1wc(=m5?XU(F9O^=aN|A~y9%W~rO z(9e_04_e=sJ&3jUftc$F`5L3aXyhk=e<&*)=&H~ShdosyO70+=+^>9jO--xB$Wb1) z1flNBgQT)<5xDP{XOW78&EoyuU(DX|>>b?`ybF!aVej}=rzb`+7QOwHuzZ@` z)(vDQv_dC`&o%D4gLG02R$<(%V_a~MZ(&xcKwf4)(EZDBAeHF8?%DXAd_x8h`x8 zx3sxyoC}i$YogX+twN5uN$K`~GBMx%kM5)vsD9Dsx)MOuwB!v&=IGO^Er1xNZVXgC zVfjfI@-O%y$Pi5F2Gj5Wuu0|Wrp|HkYnz9GW)Gw`+s<$1( z)nP8apIoWz>V8EGyh)FTWtM^9?vTN!>918IH;){P?usr_1`PDsnW%F+A7X-~$YZ_D zMm%#&C2vEMw!7+^CN9p13m*KB-R1Ik4N9mt*60?Wl|Y5JV^IBAXfBjGPuOk(iIWBI zk^l>*aXNH#e9wNblP7N50fnV04g>P6d2BFB`Y$q!%?e(`fiT|o6os}P{BPI?#=eY2 z)+*?UJHqu9nrzDJy1Wys+q{3&U3GkBRF@G{ z`v!<+n$tHn4o9YH!l5#Re6qT|hT20E9EArv1J767frlr#LS%46S6s6Y{|@F_^2lHD zemBQR?M>pdi4oobnThBz>K_bBXt5{d6a|m%&+^9ML`NXEN6#PyickQYo^m~tvnJ0B zCf{!r9LJ;ROFW>bFVg5c>V}F$XHt0iTIUDv4Zf6im2lF ziE!@qEfaQy__KmUhL{zz3c-kpSDXrQk(SGuOnt3#E4$Kma=uQ*6jVz^lIA}hNYGCR`Th(HJ>Bu)2zwTeaFW?QM{F&S6m-3Bb*O)`ywOO>F{Xk#MH#s^)_c7j8r^`fErRv!i z@FUAgM3(MZ+xgueF8bTaEbWVfi*d(Ev3_>>gUq2rK#Xdu+T>-YBz2a8Q~2&D4!=~8 zG{Jm)EL83|ZdJt9n zFobJ@co|_WA{)oK8l!CP3L4%dBr)Z zp;!^6ichulOO=wSso~SI7%^Abbal5s$?BIu3&>fJ9`99D{f|Gs%0sL4Ntuy_C*WeY zMtx)pldrGdAjgi3j-|=;kjVQ-G5}?wbWbl09_J5^Wt#v+;f2@Bc5RVDeOQsY{)K;P zZFO0|8JCyT(&1v4#qF5Vk3H}ir3$!^V7w+orI9+*CSY^_(EJe@PbU~bQ2V?xV})SQ-3$) zIOdLj1DV2_{%s?=UAk-D3&ATzlM!P)|GX>w1=Km^xg`;M%}OBXT*w4HNg<$eVHJq{ zJ^@3k=FR_73RC#P9_?4M@1h#G^aAzWz5834X%SiMpI}LK&3lj<#U4Vrh-l|^wy_c5 zfAYZgn-QhIbG6xjCb)sCn?BB%-%(#iGK5_ao?7BX5?3+$y=V6sPOB?;mAB^$xn{jm zv;7%S4%&IZ2@7JAF=Sf|gy^MYce571B(A~_372hDj)&!58v?werxKgDTxF4Tmhu02 zj8Wb`H!f-23`z<6%rt@WK)PG+n)MKasgztd8ZF_NMgydZg|$4yz3Tc-%WFlAc9Jmt z!?7)1;azyA)wW!3;jxxUl_lD`nc4#{QrGm=ioSeaESexwyr!QH|C3@_@+hJ5VKh+799ImfkxWu^alCHpR66}^YJsmIl z`p4RS{IG589Ow!*h~?tLlp+?DqCiYZ!J8?s9b7h#k>=GCySQLhFEy{Q$=-h{B(UD= zK0MXZKIvIulF#hPu+5&fB4j(#e@P@7&$GM0++spvZ{L7>+!~X1B=sQHDdEfw!3kL~h5Vp|Nzm`+oz3O%@p&FjGkP+ev%zR^E%GGxqGm z6+7TP-F-aGG_5+jz&w|W#pfNc$oO|(W|A$sj@_lCP(+eY+d5bIEMIRMRo0Ezh6_Ai z*o7QW`L%6CeI(lKsEvy82Q&AF?HRR!tii>Qh^fqvC8#drtEr<-h(j4ArlN2MVCLlW z%`s~h;}3|Qo1}93gv%;`!LU2bFkZ!ZVhC5fc_Udi(z5XI722%Nh{Fx~v zVbz$AwP8Mo)j4{)xNHoAl|4IG&g_UK#!62{IC^!!E_3Woo0XH zv9sK)SZGj{bu?O~iEyP$Y}bg7cP>Xw{>)(R2LlO$lp-LxrKIajkD{8?^xQ&cDnwg; z?vSc|lfqF-W(gl388Kp!Yn)c8@|JM_bWO6(LU`fL(Nn>Ct%=8z5F;FDr&-BxA~SK$ zG8RCaynVKj<<7#xyPKpd0k%~P2JNu!IEd%a{mj=*sC zqs02+QFK&H)>MQ^aY>L3+)$raf{qnBy-rWvzw`YY$B7b9^C(EVZ|t3y^bDcX2B)!~ z40tXP0Q-1@8n}Fe9thp+%93wJqD(=*KDqLH3L;E<um{b%2_1c7uj{)Xy9u_4%hgxnvZx#VTd6x8CAC z>gTKYqx2%>+cb)BV|9Q!i<1E83uH(GtG^ilp z_oJKk9TC(?`c0avXL>f>y5x#QTF0#}9e2+PJqWen2MmQIJW@mq&JPFXoP8=OMhoga zE`G6NXvA593x}i4tAJ?In1g)aHeIdA#usp$IP8(BGbp3v{_t;ez5h{_d70QRA}qYw z7dhYpxnVUzAV8DHc+WwTK*)HsqJxp4XvD3UyaEVfQjEBiDhZ57Z*_LwYzWDTQ*1C^Md-(3J=IiCrV`0F8InJkN*lTg*`t6r zlRNk*}H?Thpp!USZe8Hm# z6_US{he=+mX))NqsA7n9DXtFqRbc2*;SPQ9CPpo}8~qWN~e*n4I|pA_e(%?6r~6MV&+1L>yZR#SOQJu=A%68&hf^;{RP zPI1>QS?}em#;+gwuI*63Y~e}Jz&wtlifd)9u(XK+oVnSGVK*_Q_eA=oQU0)2N6B!F zQvNX_J?p_4LgwW8l1G9cW|Y?E=oHI-4}10S1E8&7+cGhAb_Lw-Xyuy?2ur!qxOCc2 z2))?^tKcT_cXHkEdNojZM>jK;;2|5_3bBSmrY?JA2I>vdDV zu=fngQ~$%b6j!pe0ht1LO{#2=KMp29C@Go7Ky(#3y%yU zrt=l%QY`l^w~hO28NN5;bmQw{gXkKVx|4I`ybw|KfkIqfnQ4o1>TFr0F<n-ojJ!Rv2msEJG`RATcF^Pw^1ALy4avZ` zkbU1=Tgl}lpm?ko0P|{anUQz$*i?!uHIC*r!H$Mv{6+cH&e1Gy0?R%HwyRsi*IGI46g?olBv-By)sVBdHeWX~3%?QpIw&f+e{K|Uu4Y26U5~8YaA%%e%L} z%`sG*b&b2wBPzeXN0ory-+~pqJH7*hY_Ly~cF_Gxi)zL5<+&FJo%Y2%0^jti)3yh$ zUd1HOL<_}`*p9}I8^2Y(hRqd5gR%JtQafF{!BuL5XQp1YwoeW^b#IA5l*u<;r(_=2!JCQTd50j<2yZ}#16V+VRzZO2G5oc>IgwNcR6k^^t)C$&j1IS$2Fmr*Zn4*(6NbQykVO21K7!>Jx}1NI2@} zu@~GW#}%X7_HPNY#5FOJaQZcGQc@R@jhprK|Nry-?HJ1USm2c+>hgn|-*?i!Z5(U* z_>R+=epqQOK3ggeip*^!!5sU#*o%^hql*#>`v42#uX~REh|b_Ef0{H#wnxOsenK-f z1z32yv^0|u;q}^D#U7|M6|$Gz96G)x>A4Bt==z}6a722~?4@2k?JS%xfp7VW&ym67 z!!S2GQt680Ivu4t3y~yiSy#Xe4PPlmnXhg z1=_6Q#pz_t+n9tI8Dbn4MN$Ur-s&AJSQ-y#yMEj<>erY(V+YRVwZ`Lt_gM&xBD@`> z**dV>muUUemPsc7cV?&Kh+(<8;o3BbTGFW^^j24j(IbQd5)opOlUJzZU`j6VpgZh} zKWpg}C4Nhf!_<+_CX2-0M>aMQ&jW8`di8fMe7kRkLF&;L+v*muWd!C2z7_hlo%gpr zM-ik1cNUh!zWoGQBfs?;vzj9&S2nBsl^|=<;=K3^NrqUoab-YV%aUR{mc+~3^I&A5 zI;38~RRo5+%oYtUVUNa&gx z+GtCd)%(nEPJ|R6iu&i?gt`1yfxIpC?0!&vy{CaAi0NE(u%}E1Tdjs2XHCB&3o5_I zD&`S)`n8^^F&CHUIe;t>GM;WmZfT-Dz3R%eYob#P*Tvsu{;eIRuDVrowtJP`nkjP& z2i;$GEt)44pFIQ(*)xfIpQtF2WYQTwl`oTjkqv#>U5qU(JEd02fe=+rK+`xb=n@Pk zHT4HYXuDbv+cXMKLzNfd%2Z^dtW9Rg&;f#-bW7 z_+CZI^!Hdy*xB3kR7HA2VCjwnH^ymOh!P#fMa|8|!DJM4^g$C1<(`9z45T zx-KM~d+J}$o9i+EB!F9zoxWPedl<|n&3w1l(Vm*^buZ$N=YF&S5u^pTI{TR)dhiRRdZ8daAha5QJde}6ni=Uq%H#>DK5g|FgMj-%0K*Xz4nd)KMaamg zr2qyfu)lBVX}lxE@SJoFY6BbQ&cC2`O7V{i8f|>g=GR$?ub&S-Y27%9-~L(sE6n3H zB$g2`b)0F1PJ5$~6Qc*bi&iDj@kEs%TS`z7Zl<-Ht1lY3M4h{Mm?e^YJC8%5=rKd4 z8KLLiMTVRP4zp`Xv?^D zi^ZMW>mA21)<@+8GU$rdZM04Mv{Wyjr6m_Y&L3u4`(MH})>bupsLKea0gms-RgtT6i#Nw7bAyomPDn+|d)sJR|G~4t~dw*(Xc1 z#+%lH3jQ1hX-O9iui#(+UNBPXixPt1I~r@2;0pL6ybtUT>XPd>6Aum*ZH`ACikcdG z%_L@?ek`oS8Lr_^6Y*UX+~YN<0`2<5z01-#si};|ZRqdk{2j^dez}eHHm%$APJyeb zxd#cJ7TUS4KN2X=xz(QvR10Au;TO)Met23+-lfZcG#LWcljfTD$ zAinQmeo({Abolp9b~JP97Ly|B9n4{wTLhFe0W)6GYi}>cF zE^dlRX!02dw9anb82lz!jE8VJXmonF9_aVtuW?w1x@?}tFd8ZMupvdXd@$#jv55W){mY!w`M;Ch8IA|GS=m!jIm3@;>0N!qSIs!;^mOpI$l zhJCnvhNq~69Nt1TwC5Q!sgxV~zL+tn%<;clNrFnhGTZ~gv*67%JcfFXYbDE8H|86X zZxwlkpRsQV*HaP(1@PmjlwkqU?;!(v@c%YWtI~S6=ds^tr};HCg2vJCr@}4DU-` zrdNI7e&57txst`cwpK=MOkw0Jogu!3MkV_Y8I*G9+iiN4)bZlt)J3u-gBU>_5PyYu zP3x@QB?EZw(e^9n*Jf{vp9g$Tdwf0?+`ph->PixOnO|Z&6gvM0pLaV_9@{AGu z6Bc-QJUPwB^Q|x;xO=vCw;p%H;{{Rx0C1K`(b z=dF8=w?(8ffHFplziH72IhE5>iW12;5)wHPgA`GKSK{4;kDwJtWC2Zxi>As z(fL-@9}Y@nMjPw|7}UA#b6L<~WW}L}jJe4J68EtJ9UzxfHR>A|hMdHM339Pjy@-W= zE1*6yA4JH3hEArU0GTk+ES43>FJ|{z^HT>HbHyC}x$o7QSkG`+R$Js7HXhS<(El6W z0s3~OW6MfbRZ@U$u^7(Lw(qk^t?@=Y@L;ZdLGn-9#KGPq0$VSY=}0vC0oZfcCwwr@cF4i;OGc6=f}br$snOKRjgf zsOx_aBnnP(-YmDmP8Tf8#~=jew?hAooedk5Y;vDSSQN{^2tXmiaz&st$Ym0zj=xc9q>| zLEtMAk)3AK``y+~4>IOtGa;893K!c6$T#lW`mVFv@l3bJh$G=|@ zb6lVLIPlC|7+Q<+r^djh>OhhNBBCcH$SU8aakQBy>e;s>bek(@Nx^Z6FqDLy=B;MI zGN|}5_@#e}UzixeEB-@l}X&0Axl~_W0e}v54esxR!sEK$Z{1oy|TO}bWKpya$2h>D7KT!~4 z5^9C6xT%r-i}_bjJF#@S6_g2e8>vX!^onLCPc#K7=S&yLfo0{{#NF%FCp+g6ONKE7&|l ziv#HCC2sQQX^&Ij&|dx62y8MDs5(7^w*$!Nzv=n=5ZX@afAG_;rX7Gw;auE4SXZr> zvD=1m-c!DxQ(+CI}Zq9Dy;j>%7qZ_^TH`eM(+FkLy@t zE;<7SlPblhjRK|>@pf$LtxO_Kd@X1!`xvP@xN)L^xlZ3Dw+TtrWp+s|1<7~Ta6xu9 zY(1sz?%UKdnqW3ffCFxcn$XKRr$Q)q&ClVwq1(guu21-hCxzbGLl)3V-J1Xh+&APj zDSqilT^}1l8dqY62y25F+#7X(7m<^s* zfh~7HQnuQJ6obXZoZ>tH~K?|)b#8)WJWfX&=bR- z!!Vc(ps>yUb`w$V^zW=_a&MHI=Q;Vs<+aWU;NmjRao~tuAo2{VVmcI(+I$rh3=`6nL5g%z zF{-3^$2OC$;n`!6ITldrIKzX(B@jvzB;OoFV=Vz~KQ5A$UmAx_e7EBuickG!fAc+B zC1|^k?MY!ocoTIpOVfX&Rth}V)O|e7TW{AaUQTFxv6D&c2p$>YD+Ug>A+oo-2HpnV zm|U>f_HFyG7%<=GMsQ&*E1uD2Ei*0y$tfrYr>Dc>7QzD2#k0GahY1?`7Lw<1RexfV z%T1;e;$RSrANtMAo;P$GfI6jP<)z~I@_BbtuhnG>zSeyfa}Kj7Qi4{0j8QaW&L+H` zNM*KYZx}vYMu*G|g?kGJk>r0dZ4Yj}-t;Zh7?DPzz$2`pNc|K#zDyzrzIK$;RpsU> zeFblm(3YnaEql^2b6jkeG3g2IjavgJ(yZ$oeQTK0U@JIWJ{48Tf)r4XAiHMc*Twx~x9!ln z(M9aq_Psh~1Oaus7S7nbi;E8%{mYG;VYYQPBidOT;xUw-bkI`XDTJTG_dq$VHy!1) zJd9;WJ1u0Sv3ocabv$q1RJ+>Gu-{scNp3$-y~rGOAez~H?t&`NqLtC@Q?Mw$lX=;b z)UA3nAtJ_?iat|eIM*yh?VwH*aZYWn$6XL|p@ZtX8Lq*!BD9nKl)QxX+$cCp)|Kfs z?Zn^rh(wHdJp3Y1^juSL{1tjzVEyS|G_i~HNG8vvSAFl}qYAfwUGslg0952074N6- z-T&i|c++h0W1e3jCPf)+gUF7_i08F8&vL}ZlO7ni)&m|{>Qbb`aDh*X+kja<|>EYgj>bkqJ@9m0bA%@0#IjA-^W07 zEQhp~p1xpf+AkOvIX#0v#x9SJaY*e3dM~2z$(avbNHAn;*%i|!J$3rJ5tEda;4S?` z-8E-p=%t6hAKABYZXdfSFb}^ufk5g@i)INQAygh~(+uXJllwp2i+<~Gm@Tz@OW8=Iw>{A2&IZniMPAQ^oy6AsIV4(FoCq1W`voS!qTVhE$U&h*_Te2yAEJD#Ea0o!Rb_#J>jqP4d#7mmpn9E>X>wQC9I(jFCxU z(-bT0H^b+u5Te)cZb`EHYem|GTpSeRxQBqU4+-`6yk~TM1;Ao=&xTuf?^O#rc&6nu zJN{uIt%G&WmOD`Q3iH5i9K$fVMwZZDFnZK95nHBKI?oNhNG3mgVY>f#+GnR&2JCRAtQ8XZP-LP}b$5 zVqibP`?t%CtFdQWPUdllR}ll&o@qugPgvrj?{&JIqj*f4S2F-_gsuNcOKo^I(?3;g z;@|z?rX%f586D1neyFwt1#ZyhnqX_cT=)a3q$YbNL}D*-r+%L3`d;3mQE6uU zghq2rMR!_lhPdEm-f;C7$9_x$*x-fp;T8?V3{#uA>eCgem znY+CC)(~Og;*r3ux%xz8D6_Aj74=T-NG&PB(?zhmt*CY&JZFqztE#-bA6jrI9<%5l zrBKi#!Bul2VZ^(`b0?ArFqVr<^)Rw)i=De#5`qI<7NwNC$O-ok6YH8Fa8JlIOV5IIn4&Ta7s)IYnpV ze#~KGH2Ua+&QBlv1DD;GwwWH>++ zuZ-1{h(oq;BaTg8uh7298k(<=R@B6)hJ!D~JG@H}-h8uk-42AnW`W1Z%E2Pa>?OQK z6`z@`UUbP}9`wAD%ZcK|1|=I3wCq~?bi8b5^=@TVl4?JJRJ~2;)ZDr5hT$s?O87Wt za(G?5zg$`Vca^OYd0(K`Cl0%vLCMk@Zsz2l`n+!m>42IuZ}-X|n2DLf%f$57LEV2s z?)jaz>VykaynCXA5h+asG0I=PUh(@8X!5puHr+v;;8U-9j3Z|*dg`x5n<+i{)4ok} z0;8-h;|%S@N>zmcH)}c`bb|wvAj()5!3lbIg82HyuI2;PCQ|l z=>S6*hV@ZCs>O6Lir2-1$B+&|Z-sS(mp5GZ16GsUOl zB_y^H2aQH!QSl_!Hg*3iN;eU4_j1Bdy~yRJm@SE);(F{PKI)N`MK=Q9(1l~E94=&n z#ukb`2l!GRqem3^oRQ#PRiXZv;KazEjFSDJxD!l>BNFyfEfSrVEj7e2aw ze5&DFM4_-b(}S?T6opP@1WC2ZCQd*L5nJ5c?v0Jj@bkw>`i~aviK4ALQGt#WDw@=G z{+lasKo0j>xohXBptVBB=H72IY5Gt^2@DIeU68kmwcrBuwz~+aX zj|V^h&x_9Y$?FZjr=M^AJXFn}7&Tg5J(29}OnX_T4wiJQ+8R>L?9sZ-PBX9-4bbL% zT+Zv*y|i$cinnK>u5RN79_@#@J^Fik+U+69Y~rh{n>sN1vL4k$wEZ-0kF8@ru)n@{4p(koKN zn)mmLA5vVh-h;PKmLQb5Gk$;=Xm?XS7; zyhEA@7*P2YZxl0zjC#*!dAx5X^tS%Yenuk+3@BF$us#)z{f*{V{tk;d`NL+`nxfOn z(Z+is^ZDI!+-`E2KjtPaWULDPNMe`fv~gWdgzDKuOQIWeA^e3sGy41sPyl9y&UhhN zHqlKpku?VfjeNG>lG)jv3`>sA?oV1)zqqkwJ6YsyN`&G%B(02q&se&V-xNKCGp5OD zHu>hbNQ+P7V)PwOTR&XEH3Z0rv_JksoY1{VYv8#5=>kQtQC+(=tsZl7*?&}?h8{0o zw4gyJ@r3lGgdic(n%&O|G1Jl-ym&{{(Khu~JnJcY(#Ko?nIyc0!au8qLjf9Ss@Fa8 zzD@qGQQ3aKh0WgK z;;OSxj^QY!O?*fB6C#O8`UmH8rB=sojMNqbUto@>?wCoTgFlcBPIBA}ZK56mBf)tj z4?U}~+tYzn(PGsYgUB?xlJG$k`CoLwl`Ae1;gB|;(!|rxoA2NTVRV=(1r_L=CPPuS zR~RzqTR&;HlR$(--yp`uhZiLhYyXCt-cdumghz0W!89wOn4c{-HR?{ziXvGIxoo<3 z3iCs3-k3%^G}(ulq=#m*4%B$lwj{roxsg%X5qVOyKQpuUF0mownohRs{IMcO0?FlA zSe?R71Wj7W(A9;Ev{}~KVc`_}`Dfh@z5{9wa9$FKyTC1F5UX9*gIkJmV1QX{@BPp(hCPd^8lwJrvQnOl zp<*)x^}Ytkj`uZxG*e{$a|e+GGeIO_qdMspa|$}wPGa09*(kN;uj$+?-SyWZer3BW z2~A*MCz=8R*8@fbDj1vbk1i5j20)kVTKv!1Ewd2FN2R{1T$R{MRkbxZz4yje^L4d} z=gdLgA&jI1_d$(P)(9SU$VTftC5P^xcc0r6AAH$6CGP*$yX`}n-BLrXLHotdNyNZ{ z@BnZVor{6=3#v_OnF1%4FF>sWVXDE^+=Yx^kZDc*&l;`{PUO=2!k|MEji2_~i;f&b z;fKdwm&!%t1%T~!x*ATqW7Hxu49p`R=6^9aCX4S0%Zy3WUQI8;nM{9|S~$)|N@7j^ z_6J1%9jB0@JdaMmMN_dH1a^w6;%Z<{>mMx;Se7A!eOY^iAA9%>r}^>I37h9QWjRo|JJ?50-{=8cKM_x1>A-WBYl- zSLSq$K`k6QSvf*2(~}b-HR1%xVzJ{E{^Pj1h15a&&hiC~yeoU#R(%4|+|Y=g>aASG zlcrBmEH2c_g{_8C9v-jh%sGFdMTBen;a2T;20b_^fsP-)V!nc0as{DhrWDq%GK?IE zjnSdJ_X=1L{<1`9w13_uNA1QiA4E6;Q;iBkkHr=%=-!Ze$9agiV)9#i14^JbZCl`K zx*G#Z;~p~A{IOO!akKfskAJ(bowXTloTZjvH?KlJI2cwLUG9<3A?Ik*L98P7ZmwV5 zWyW&Bh~fxqAmKo=a@H z7KYes`HN2J4(8AFE}U|dUAFHPg>YZIOKcQ$;H>)sLv*29R5DAanp8f-+&mMK!< z6RB&;6n4Vw!KZ(Zl8}SM@V4Q=FPU7!O3^wVT^k?OD%Gmqd>6+iHj7^EDM4rvo!e#m zAaPo|=JHA3FQ$6)9cA@c0_Oovf70LBCsWNycUq14!8A^ z8`UtnZZHR)PWt)B6OgOKTUlSg-YE-4$Ip>obdgCWrkT^KS~3;p?^rOrr$m`O!IS*`Z7 zmEtWX0*s>*wQ`QZKFxYL)@W11U0AR&4>ye{@vN?0xd?5-bZO7=-?}KvdQuLR>A~ES z_zLFLgNE#r^H%D89{tqX`got=P> zxy6vrs>jHGm4VW(RpONra87Xko*`2}))Zmraj^YGTn&JY4$bM3)K6mKA8n_)cHC=a zKSih_O_akmr@VoDNNz%c3BLe|N?}OqE&00fLjf+q46J5l%;hxYq8s4{WLHgOMn}7v znru}=)rb{L{~7`r?xM5UlB}C&co|aiQ(JWFfJ3Qb3Z$Y-pV7w3&a?HJ8_ome z97&S3pv62l#DnpWfpOH{&9OoHMzUMES$Y7M4ur(vHfJult7(_OIFD1|Bc{IWO`Kp? zFl4U7}r9_&eh*rR^dteuCF zV?~;@`D>>Fc)sk#xeTp8*az_1=_=k0Ym~HLHluazr5q6dJiha^jhJliHoY`hA#??6 zYBbU$teN54uh%URdx1k^<6IOuSbzUq_R1iVt|Q|+3wO6ORk^2HUf-(;E#%6qr5?sI z6Gvehu(rm<@dNut--WX(UHJ}!$av;w)O9t2P>qQ5AQgz+NQ#hbU{M%vHg-%JD*LZ3 zQb#4tV-sChlo!=u!>jJZ^bc!RQhR8{#F*FSqjydi6+bef$8OUZcnkCu7i5lzJ<>rd zJ&KGwy%5)%b!Ft%pFuD0yMvOa<$Y!PNPRQ-Ivp^30p{;y3{dtfbnI`B7$oE|h55Fo zIg>g`6Dd!>++Ru#LruqFAYDZGr*mMH>VXo9Bk{kWy>y!HFWrwZM8OVou!J0cnd$1L zo4-f6?qhCt<`bk9w56~Mpenh0xdA$J&+3=?QO9<~nvr2+>%OZap!^%}s zKGdY)8?F13_G8PR1oVIU08&u+rK>lXzRJ6WUuK>vzfAj;RVhppLY2#u~c&76<%eLgC5Q>LJlZRoc)sEc5o8 z9lzs-QiZPge*m#SPQT|f-hUy{&t#33LrYbVIYwq5y9$v!E;;cO!O*)BSab{BK`c!C z+2}%(K?-#WDsO4MEtzsaKn^45-1E>Et~Qj(ewwuUrjB#v|sj zD;Kjh&TU>kcLz#n5zP^b#oj+3z2+=zTCKSZd|{BdG&2;peKf7Q$ysY>jBdsCjYR^T~`w-)5#tBBf z)y#*iDT-ksSGN^WL|)fl0iJSJlAg=CJos`O_yH<8`wqYxfIWuTg?}#%;B-MUKZn=b zp8-JSrb+knu=HRw#7&Xr8En)LA*RvKWK7M!qct~z`5BymGt}JZ#e--A;uli{Q@_pk z#=w3N${-nvL9!dChBg{dmQf*uk^Jmru{$I;ga33d6$>CFHP;P@F$^#Vlp4cL{!{J= z5eJeXVKH05fts#a!)t;pm77yKf(AxYk1m!W^QmwSK$EVxCZRwK&>Erl{@jRA`e5N~ zE9#q#q1>bF2f3WfZ+d>O^TwE>_3g2n?k05JT@d=HO-u@mSL!j^cr_*hfF0vUpx?%?~`^WF;S zW_q+!0V?S+v%;{K5Y7fSeWL@kT$lm!6u?I?`~`rY!*ByvEj>!%szKruhuom#xkjDD zgr`iVTyeqK^Fex3#+(s6XVE3ix@kC@0sn0!f+s^n3L0Z0&nz$t2D2zwb!<=5!Y=X! z4nX79wTVTXOs&CiN})nQNqX+ldH#jF!pR9mJgo7P)2lEbl#BCDIIWgg)i^8eb>lqt zF1k|kCVFsYAjPSJfGbH|sP*1we$bPrqj-;naXO8f@qIlSjHO2!G&a7CSd|=P@T&W? z56|VEmMvW_zCy)~M+HSB7k?%n;a)7vLoY|$)JRNdvX&S^4rBsEYA5DD^mm;XFcrMo zieVZzc{4>z5f%Dw^NvV(2AAA3;@u=?NfVtyOv^MxBh81CX~8 zr}w9I>9IZ|Gm-%9!G}E87*1UKQi!L$)+7K-GW zs~9RAE@&Yl#f1SOq19ey*)71{y?cPq0elX_6%YcDV22cvKrd2;h84YL{$15Ij&X!o zV}*O!yEl+VF1R@gFV3<6h@8~z;JtdvLGcbSC{!XfKvT+*)G#1(s}vPJ#OVjhtG9gz zSa}_FI(n**2P66L{-$Tf$prs3DV#9B@%kYA`@|ZUnNCobGXbZ}cI$%}Y=nA1ExdoXx&?6JW}ElcHQMu?%fjV9iU`Zi(a{Y+UNraD~Kab?i%irQ+* zK@u1o@&!hu`4M9@Q0GfFRnYNrejCQZbQHi=nP$No;|-a;RmmSDu%f31EB;ucEH21Y z1MX!TXPtSqsZ=K@D|AqU%*_xCotFCq7~+b4T>zOcYw_>l`D+6g zpzXT^Y0Lo`dv5|_f&%p&gK>QPjGMDdv(o0{e7pVqD?wY*a~TTLQ2J;1UkEui8rf^1 zXSx1CTvQ;kgNT(NWkR0;Z*LV0g==yw4tBc50R0d#WC{?-vOq8}egcsfY4JpEgZx)#!EIgywD7>nrx|P=DMFEhFCOY^EcR&A zhLVRizAmHow{JcA{EP>)3(tk+4x9a?I*$F`6fabETB+Owh>+&si-Pb3bR+Ws@l(qw z8o1Lh&>W#0Jl3c5@kXcWM7;x%?^Ei!vaW_a96@h^7;?do?X_!C&jgRuDZ{Gdw^Tfi z_FlC~m0L+A)ps7_h)|(YFO^#DZ7b|shWGN0OwUQv^os~UpZ(}c((Qcm@}EN|i5O=* z>R#@Q9%!;c0{#~Col|i-|1_W+F%FEWR-dI~$fo`SBWw}kfbJL>&FA|^QDg31w$0CN zfBR0@ekU}-Qhv4dB!-Y}2E8YKqAcELOGwv4DAb7P;WIup+;c$Bg?p^uO@#6H+XHnO zXPF?yCF!|5&|;X$*(qg9nD0y3vi(y^AIqezK>?2y0HCT^mN&5I2XRTz zr3=TT+G!QD^q6DVcUlog#1;xrIq@1Zr56OrureH?1Cou9LIngELPLdwlqV{XKaoJ9 z4P7_$CpZ*@ay$SvvDW+kr7!{_6Q9TQV$~4pM8fmQK&64iTBJB6p-c|opz-?{24T+3 zz^cy&#HCvATi90l`v?g`ZP%>9J;=?aTM@) zF&V0HG|x)Xdso7%a}9v*{%heqANiS_iZoSSgwp2*=_tH;Z?7RJE>Nf_unyR2e)kdp z9nWFwXRu2FF5d+7F;c?>05&512tbV!y?16|McW5uz@qPV`U>z2$DZ|LzlI&7#KIwK zjnx!AU5e4uA<4uF0`0q$S-=cVFlG;tw1X(pF4t*1=S7ScE?5dM^$__BimuKR_>w+` zn3aMEDn#^{l=a${jzbLYNqXqjb80nWn{azOb*9K04W_PWk>F`}L2vA~T0j$k_dcFH z5DJd&&C0Ibp%>&2$uIe_^a$jrGYloNc|RtP7+~1;LJ;%wcNaI?bGgTb=Wo8y=!?rd z+rMq|GgN>LPZq541LM~QX#E|}s~Co9(reO56OSyg$YDM2&7!60jXwd#ptykJ5nfT$IS?-*{hpGQ9$&JY>BGq%$4I84l7}7z5duB%q9YrTX>!m!pN4XUh6$ zgGy(Al{}_7bF}qx@>BGgkvZAK&rwB1-9bqMQlY$IJx=vyV%sAtH0b?Ln~ zBbVRyvo*xEFga3(qch&WE;fI!^wfl84(Z;{Y^{kGDHj}R>%c=9-e_L@1UiSj+BiH- zWnj$8#ZEjIigeC_SlG-rhU4~|P|l8{d>gCYvX!b;z*(&}1g<|=UoooJznqn%=kh>H z*H+y1z57;V^YgCnb*Rt--JHbhvS3-BV5jdv7K6zy_z(rYsKbJh0WZo*t7?56Te>oxQHV-0PHdLYXW@&@)AFto=b$@51y?_ zn6qYF@bJr2P~K^88>zkDoE!>Z9uXcJdMqUwm}&sT%ng7e>eza4u`^i1@`h8X` zQZPJJ&%H6zuoPNPFJxg7toF{ACZ*I$C5rzmh05vuVEgH)i4*$}Sje~dfWHuZ);YiHxz11Je5Hovz#wbSN!S&_{%+uyA{ zCs>EUY%SgpSd06Sd)K|9Sp&UB<1$u+Q96~6aT(C0*0BsBb|qjBqOWmFDD*Nqp!Ixv zkK?{@_o2dz=)Ay%Xe(J52_iI7d#0sfQr){%26|~XNG=Mde&-` z0+c7*U}5}UQ>olXQR-i7fA>Nf>U@4=b{{XUaFpPgRJYcYHAYOs;IwyMUTTdv8h*A- z4bs=>FsFIWMR?+xRoZ}xM5KZ=Li;y+Cg)jN>Ym1zZre{&FT+^3jD}ZGb-Z#e3^C6! zQeHNzHHK1>8*aPg)lgyk#9~5k;a3o;tl1eO;KxI{T z3IR%CAS7KwS(*7=_sW_)9|?_syx1TvQ1Q>C6s%j1isYuFp^-l2#hBVlIBiW{vZwOn zBi~0-c$eM+wWMcl@1M_w3+a~DetMIMMtFOUYlKzb!Kr)XhSE|7@+QRI{X~DGKxOyD z605!v+;F|pBR781HHL^l;_r@XbE8RnhILtvIlp6wGs5%J02Rq@K^(Xs08*LpV=R3i z=0@LadbEB{$El&HK4*Cj`WWJOy0-E&w#z@yvg|!9;?dZ#e^VJ4bTBV1=<7(~Ln_dX zTXKXz;vSY>hv@)9`6;4UcEE)Ib(=3#~amh8jzFi*}gJ zi#t@dzCH!I``-ujasZ|V9TFZnuIxmcPadNs7G%0aL(DH}fGcVJA5xgw9<{3VkgoF+ zdWV#_iwLhH-Ev`#DHKMuJwh?SlnBQPN#$R5vFI~XTykAB*N9`ZO(?2W?pl;Gq?5@` z?t6oDv^5|-S{BUyaN1wEmA@8G8OCsOE#0re0 zwQszOZ+`FV_~!3^125ii-XL*t8W4&^aj!{fxW{|o&(KE@$ulJOZT0h*@95Fq1sPbZ zhqP1O<_aMf84fXcHYa{(JLh%s5gisei_5zc@hzWHczOYqYPTo^RZNyE!JODWFMjq( z`$pW;-_LSK8z6{XNad&V#_=*dt%B-sAUD4PMl z#bV^TXv|BYh`G4;dpK=aH}O!hE->ri-7yD2KRul|X`kFWR{BE*_sZWGQP$^)eJ(EF z&)gwzs{I=KA{*mJkUaqmsb&l&WaD2>HR33F}!R%z5f(FNNiaHNvYre4hY6N zaJBvfhJS`}c>(O+gIxk+^)NCht#e3aXz3?|t3-%mlGDuZ*5=Xx8=>%{;6)mo-?c<1j*%dIHx8^+H7|FwjsP6@6`8JsPT=DW0k7hSy_}(;!v8EcHp4lB* zaQT_EcR9~elIFy=`E1KEmEOi}oMuzBIs5P97F5#HXh+rmQP?ztjgd-xi}|(gE+nm= zT|qjndGB-WcXl=5NqGGDFf>yVF!wFDdezC_tBHg8ym$2HTzn4=j3qAp;^isb^Uz{% z(+H!klB2>2;LeXvWCv>MoMr%f8<0gHPvS0H5g6XaBEJdKYwYm|Wj%=YW5LYj*QbNTF%h1Se;2NoAknl~5zudw( z*PwH}^NTZ5*~g-<5p7WKQ@Md0LEXSxr0uA&G(JxuROpEX@S={{FNHMP=80kNxF6DM zx)d+~bIy&hYaM#LbkdvQm8VW*V~Z9Qu|7dg>Vz(<=k<4`ii@$B^LojgLBw$hl3ES5 zM}^AbR2r8-Lcu!kGQe}Wf2C85tv6lYS)HP6OJGzUE%aT~>nSt{7#8vSKK=JL#( zq2vmsAa(jwR(NY|_*^*e923p={+LA`OX;;YS}rus2-0Z;sS0+!1*!Yug~mIoI!j?! z7eH-g5YpC$8`0iZ!x-?8ef6I?Iw4+_;K4R2q;s@pq43u12OA^JcWF?am)%N8EZ44P z*d}$U0a!Q7ZSX50otF=cq={T3&KoD7;fS0!@|F0#dG!}>inWyPA(^wDyhFt=e>z~w z{d}auMyxt)9GvCk zPwjX}a+!zEP|ixyb9tb}+P_ylcirh$X@UuVDBg zu)KkFcZ2-`n5;0Y#c4z1V^~sDGFyB1_N(F?iQ#R&#r_EvA8Ux zDH1IdonrKUVXmWKmPQ7m@LVZf2^UHNGo<1)6dVnDRbP@hO6w;Rcm`vnk`e81f+dEZ zPJkr(y5&s?T(${g;&)}3IhDGtkCWqPiNHBtt{sperk>YSkY2fcKT#s4f;5%LH8y`d zfSj@e5ehhY(s8ah6!v8_uilZ$PuDkE0t%cpeA^r@y0G_dL|k z?+QSk0_zU|`!PJMo>vKlSBNRhc2IS%RnHFxT)cgW7r!C+|33T_AIVQ~1K^2?-@|9l z6J}sci^hsA&~|JcB5tHs=>l&()$5ss|IYE&_}>4X!xo(!ne!d1H=TWq2%*!s;AtD+ zi4r<<32!WE&DKgg;s5eRWQN5u^b&iNms#7r>_Z>x zNo3dZC)cgKIA!AR{X}e$Sw11{d!bj8ZJrKZnK@vqE8I`zwN^?4r%29oRZbe*x!mj0 z4AtBH0bskk=F<0)K|=}1ec}7qJpd8j`kt>>F|a}(@9_CIF7T({`~;64{|MiZ&+wKx zZ*f{D5k9_#lD|6@&}bDjQv`+`-2cBotoN{XFGJb8_oRCqN`v7c7fhVRoiU6lo#LC~ zJE$5XRfXm=4bww{vvms2w*kcMhm$)(B%{l zxA!zt8X?f$#>hG6GYVc1g{jW)yltbM_;~WVC3)XrDK0&KTEx|9t;T++ewx;kSi4PldV%7p5XO{!BdE&w)=95OQO@!V{ zN@5T53z=qTn~~!cAmn52>zWtlTQ%Mf()nH%+5D>s>3`|`Rm_m@HT@Mx;c`}zp34I* zMKoXkvZYdeZ2j|2%=sO~nP56b*gR5bR(*^oPu_(tZ{g~#M_6_j*c&iOd8|()!wMzM zUKCU`FeGPF*$InkQ;^pd1P5us~odn6T> z{U?`oj1!Hd20>pByq?X}8mLRb1^IoB5sY>U3!1tQv^R=$VnnD z6zFa42W-E>Q;puZtA;MX*!g+F9*{l!&@80N3B(DbulFl{^4TZ&?42J&-V!Ww0f=J6 zIm&S9&D=1dg}^XWFtN?#tEUi7(AgNCh(Ij-+M zqGOG4KlHHTqnj?jBL+~I_boT6M9$H=u!}9cvP&;5y^r+0walt=TQ;BkzSV*pfyTaM z-Rz9i&lJcFnHEPvIUHjY1P>+|LZzWNbCuV*q%@sht(C?&xi z5q?|_24;I;ynxCLM1!6RGp)Ba&f|PsKn15^mJwz;IOFEtPT>v86-b_rROI%c z?wMk>u(?hXj}q*|^RPh#$EGRUsf(X_4>&HXmu~Gw$7Xjc6IPJmwVd~Z(QLnKqYOM_ zfqnF#lN?X~{1DINncB>g!uh^-pz}b>SxI^>=W_2$XGZ+He@8;coKrI~q#~zsp;1_K zpPJnw_|A8K3vYk*JNT0)1E0P9PU>_-G$a3gfr|yfoRFtGfyfS0A)B~ zc!1J7nBhzS!V@$g=j35zwbqVo$*nQQaI2=cr&xNK3C~094W6N{m*JXaY&;?a+8Tb8 zycu%>N2qmZ8sl7I<-QL`KkA~X@JjGX4EewT$Lm`JJ6W)V$XG;e<7G{n(+m;P3^TsG zk#YnPwk%=nAs~&Pe*13!FzVgW+Qf4`fEU-mXP*H#A<&K+Km@v60>d!Ijem|6yg`;q z!?iXgo<6_EM}PhqK6&fs*uC{GRF`a5f)<{>MZJ$A282|~J)n0~nEi~)QD;4ciq@s3!*UupJS@_6 z4aY+s?_OReD8BqP6F@YS-nXtvl=g8t{+pEg!m1~)E`5zdfsh7*PFS}!-cq|E_zrT8 zC1UzbU5L{N1$O_ZUxu=9?xP0=NZ3{-Z5e!$TlIi-Am&ry`464_VvZ${eh}*Kq(9LI ziM+j-*bo3mg;cei%j;b3vVPlVdG7q2Q5`~+QMopBdKZ42GO)xA^%rJ%EGsT-)cvLw z?-RqMa*%Z9I8IcCg! zDYBtu>hwvE>F%a6F{HzrI&w_(*sqzMDcUiU_ z!l5N5*u2RZpOove-FJ=t_VKbC$=0j^fZq3)_ci-qk}K}pR1RLv^cDukSh1%jGlPXO z!bae*m+<#Y(IEAw&Fb&&XF`LXo;d%nb2%$X&*fb1edz=?v@HkUQ<=8}yWK3O(`1Il$>!kyIT?DYD@l8n~mqb}1zye5IkmS5UG1gh& zpLiVEkh*YTA>af;gi>m|!L5OjR%jBDW{QHVnR~L>PkQLV?9H2NHw;qhN7|ND^Rrhl@?olznSz#efYt9x(6&m=rRP7n~wXec*->{ z@B$y;#vWq@#SFc(&ong;#BZv-Pj}_vIuuWP3!QAtdt2y2Oyio>n9G2x;lz^SAfU%&AK14go*kfKv$d7le#>>^=OU#9;n~=(3Hx_0uXDKz-PrE(b|_K- z<9Ny9YhfxDAQ_8@Vp$aH8o4Sj6qk=KaUr`lT?`jef@pDZBCcc5-aD~Z}2w*V5V(k^WQC8q_^SoG!DE9 zQ#(j6_oJoJv3#bDlXP>$T*{V;_P(-zccf=+9*%t_aDL+5@HTqlgZXJI25;N1>Wm#Y z2EU@HSs2D6J<`$8o$^SYcuM07`Pnw=@n9Ti-*29g%D$GIt?di))rT&soRy^K@+(xn zfIx9?+NKybD?8_(3c+Ow;xaH=P7<$%ZZ|8Iiyhv5^cB4Qs0f1b_lS1{P>ju*RIle$N{)nb$}K zo*xL|b-M-JKF?rq{aF26cW88?nDHh(N;XTNla>_m8$W=r`8Qb>D zx!j*(0^1pIDVen+?;Q(+NP2~~ttGJsH9fFHP@`9+E|W7|idf;bY^rgggjcA_v+QlH zCa^Ie>ou@G1;#$SNnQYU16!{EFwFh}72Fp^6p#xiVz%PR8#{dM+aKVE?|p!q^<(VT zzrb$y!j(2Q++*d$?djyqFhn8PMS>Tk5PZuU?Wdo6ddsWES<)6VDG09$K*<+UG^LPX z*=GLT2SF!Nu4j0IbQ>4-;EGWK^(I{g04SB#ZB23T)GtfzQI0PdTP?R@JlNOm<~u> zXja}lZ4`~I95<*sjR^LZ#>_k?27)f(k~MSpUan1NZ3gK zM{P*>j|GC&u0kzz0jCj;Ay-?mV#Tto5WB{(YsWe~w^V8wkZyrfzCuAN)5h=+ee-(* zG#mpGeifpJt0;O7Ofpsn!)}D`Myog)BQB;D{vDp)u!*wpJRb95D2-5~k9nYHPgQqD zAq^X?jjDK3G)YKtkuMt-5p<=cMsXL3?sS=}@kh>1;BX0GoK(nAP6_07o!lP~B~~9j z;5g%V$I_jKkVcb1jN|o@_hjTs9|uw{$#m~iA6rK@O4d6St1+-zl315JEXQsUWjN(> z=K8C-LYl$~htj=Cc}X$lh*!{DK0+MhvcvG`nQ8mi1f_U7#*Aqij>+(kUZyMw+@p=BCg-Wu|v6g9xTp@9}P=%Fu1|8aj4ywqk$Ut&x8Z%QOf=x_{ z1=0YSW1H6vew&u$w?5dM@{)h+(}P7!tv&16bB@`fV~nmkV5Wq7i{-B0#4Fm5#4EIWQ7SG3X*GI58wY z53_~RbWuQ`V90wgte%f_e1<~p`{)(<2MuSa^8x@ESYJHD^G`p)v#;!6kFRivYmD_e zQebc{PTQLn^ET5LR?}ySf7cB3@BP;E^1ih$xWqiABGn}4lKjH5X31!T`Qi#H(43p8 zNmEQCg>F*`Z+FA?HUmRBfOmV_t&TNcxKPk8Z`sq7lYE>1<$7%9;uVF8dM6fyCBmO|6yAyXF^PPnBWQ}0B8K~3;-b#p^10l{@+yMyMX^Dr zSAHfOk1xO?Fk7*=J>GruZM^yBW7x9uD|lAJP8Iugj}P8^jCXcdc-ub0Y9C{<>)3*p zc&C7-92tt^MW&F^FzU<1ACa^;?m-7VT&HmuV5(S$!7tRD=S75BmjN2LnRmIz5p;X` z!K`-cSQ3&kOseaZ!~Qhxj&^C z$^x5UH57ktYuJAg%jR3wH7kZC9@e(0Z$nw4Iv;;8R0qou*+FVdM*#J7>Wq@&u)8Gj{Lp- z{1*k5TVe37b@Dw5y1kFAyC*nzuL2hmgHXZ%>;c;YP~6-oK6$#sGkF7Fkp-VTHay>% zJ8eQ!$LM%mLMD(lf&*ycBNa67O7BlzW)uu$gcgC8SStFMKS)imXer@sETDL_SoxWKJ>!tl*lPYEv?@G=r4Gf50{41C4R zq%J2hPF z6mtD0WcMM)9$3c}27U_QGCCAm+~gbks4#NS!5~<%!0^Za+dsvh{MY{&_J@BBU;hWc zhuwvwW8Xl8N&o;L07*naR8Z2H6St-xFM35p+JGj2HBl3sjM?l$GRh|x7&=Fgm@XFr z7$R?^8{yqTPe-Tu%r4p|6Tv5`kPgFJ&Q9@|G(t7^8qSRcKN)RJr@6@S`~oHDk+)g& z{nR3`$z#j9RC-eTB#&iKgK!PoLtTJA*f5s-%|Zb>r?P3Y)amqwCRToI8cL;hO)Q4l zK;H1XQ9=NxtVwV8$nW9@-LL`?in4z>F0D}!eL_gL!Qb@HuNQE z;D}I;lrKri z4QYALKbf2`4*ZM*Na;8iG49c5K%dSwq?z6|UYh^rF_05F@1^Ht=Q~^OW(RfTcjDLR zHIIv_7o?GeH`@CXA-x?Z-*$qE=gjRD4>y+q!x(DDv|N4dSwYZK+w#8F1FqA7oAT{E zr91VC8K5Klbvi$Fe8_t`L?ovpS5w4gvm^L`t6A$^{iIB4;nkZ){TMbI@G-B>_a1mT zD@o7g0TzLWi%?NI0IYa52(k8#Y<~7 z0dq=P)Nq3_euh0h#va$OviEJfk-myH9?l^A_xS%f35@!&mm|C z&Ky;U8p`k(fF6}D?=)^DRFu$TtTV=7RKsGfWuC49NaW2FztU~!Lv zk?Iu-OeYE4OBotK9+sZ0-JpLi_o$dm=^sc5ER@J* zK}TpWFaQ>pu?Z!74u7X?PnCahnQkDEv-$SKjiJ z=Kd86Y|cy9*cMxM3_7&@B8at82}Ffvqt)|ql;Y3LfxsCpjr<*yd7bX@7xY{l3(%{S z6qUxia#Qh$Dc6?<4j?_}^hjUh=p{ePv)_0h+TV${`}gw@>%;B7xV=bwM%$cDVG`Y| zg8+RZwDAWoW@>zkG*=*-b+EZU%C5X8qgT)F$ozN{KZ;keD}d^6YI<1mQ@~tMp%P8PlLZy(&;=Zo5!QHu4di-Q z+>Fi8$;2KAd*5MN8xhPJ)_YX|vcSC`yK-;_m5%!*!M$(0*yW}evbwQk^E&s) zP&X{xEQWPivD3ZhCcIu@*hd2kitmKcOa@>(7#1vYfkhX0s@5m4@fLpl>9_IMKYM~d zexmsNqCEcDjZ;d8+ykSD!S#J9Nr9CqTBPVQ>ky0cmd2l;`N8*`v^!nsw0fFt@!QV3 z(APQrfMKPeHPKRk(jDHdK*Kc7A{pCz*DU_yq}2K4Xyo{=r5nG5hPo4rwRc?qenhGF z^2WjR5fVl_3!duZF;vQ#mtqYGN%3$b|@?& zBO2ZV6&CaIO8Z-;Md8!OjqI$GirAw{XW9JR6xN{`vOlkeUtJUT3CognA|@)8LX?@e zj$Rt*L|@gBbNP}>mo<)I6X1)lU8i{p!vcliA|eQ`#|o1l;RkR0Q~d8=Ss~-6c%+8? za)WEThS-V)H^A}~dwB}AJ$6zCzuPfO;cL=CH{vfCq8Rbh6!^@m{GJtsp z2>jjvKjWJ)brBr9pz2`tr48-YwJKUY*AcU5?a`yv==5DaF1@eEnPdeHwC|_(I#aOe zSny9ms{S7NUaqGl7uoOu$6~{1)IB_d*63-4xNnh7m(#a}bIgA;)~Ww`kN5;obUkz0 zbG)0ym^_R(E!UieLsYEEacsu1YPER+kcur-Ft5jk|U8(5zK6!h;#Nptk*076WrXWv={`0}{)KytR&IXx zrZIY{+5mKc=mJAn-65fX)nxRUW}#~gay!d>9Gevt=#xbtEA@=X{Cq9ew8E)Wr6S5C z6f!=S1_3X2A}9hq23VyqOX>uTbD#Ly6EOQax-A-#7@S_3uyXpgXTCRo;q?aGsB?mrKvAG}OKaqNAkS2X?=ayYRLL+t~rSx;fJOR5rhiH0oO zRMcBf#REOC;+u>XU}^}!@^`}`=1Nj-qc}g^D~x<}TRLiD0E2JE4iJfXjwnf!{SdWD zqN~$p)El%klty}psSQidYORlu-lkU37)(9nhU0ivIKGYtj$zMp`SQzlUADg;BN(Ty zC7&CC)ci9Aao&I}H&`G21UGN|88AM^YBzYHSGbWi+&c_d2c~?;%rf;-B4+tt72@^* zlQnkkm~bnjiZa(};AoCBc_Z9VBZJXjeQJ7t`rK7-O2st7$dAUKiZ2yTj-PQ}iQSS$ z>HMs~96JJmDa%}wT#QX5l<&_J|KmSN@7?Hqu0=OA9j=AXJtiN9+t#UnDVy(Q`)GeR z9Se$52$p4RB+WlyNE}&M3H2q7||hv9RO|s zT(|GoC3$Z}_5)ZQh#U7$7OjkgcO=#)% z_h^G*a7>VwQ}6YQNZdRu&C4))NCl}`c=AdLri0)sEXk>arK#77=sWLI7i8RR#FbXo z+Ds&Zsw?MXDR30eTPRV*1S$*Y<>`4^C`>!c9X4QNC0B*0LgPkiAD?C8KikSqxkenb z(IB8?xR{^O{b+j{;zu#Jw-udA;#bxAv5Wnm9_sO!L`78K1FfBSE<8(YxrV*9VufI} z=fLiB;Q9(;H__xZ5Mh=Q0q2H248ZQ~Z({fL@8f2F0lC~^S+B5uWx=xx#a}O2nPr|YnY~C-^a~DW0%>QS^GYu5Pm|7CewXuXZnR3{9O_us zgN=HUP7X?8vLPq0KBvy3O0mFRez8ckJ~u6_^bUn+XLFs%sV~EZrN9k(vf8|=zCX)Y zFnQ&V;8lZj$#4VIyQu)SjL=B+VJaxxlazDHxFIDL8Y2ymOx+{Bi{Tt2MkRWK2U*%U z)R4C@A=z~bm?F|r*qx>%HC89CBrQK#wqfq^8#y>M@*C$(+EURS&JHa-Myan*2vkO0 zxbg+|%(?tk6t4O{(uiC_<>g$pc=6zj7WxcTH$=#v*%E*9*s49{<_ z@kkZW1GJ^~@6U3Ct8G8a%F^B0Y7iOhvC$ zQ)!S9^r(dXzAMX$jvmf8X_hqF*5|Ux7V&2{R#h8SC6!%C|KqoK^5|+y%n5nm*5jTo zu!DMLE&geny7G4`w)V>_#Nb=GdyBqN`(S##jFJaDDVa3pHE9De!`6XyQ$LbcYREgJ z_k5CncS%}P)<9whKpcnIZIskd#=%j8}mVVmekS} zr-!-U#gmk->bJeq*~boZ2wW#xy?@&*K$;$p{{4dTSS2N1+D{^VgfdVdON2J_MrAFr z*ad!u*+)M}+_m*f8n-fo?p*0vPW5k2w)_8})tALZs|H@uyk<+(DX=Dm1iq_V5?3N5M85}CTEA1dOA!v}@!3Ys&NXb7Qz~xD z2gc&nQ2>GM=8$~C5+8ENKq*m2_ehfjcQy?B5gtyv0Bz=;vX@Z!%kLx<*6F0a^>mE|$_vHleVmH$bGcu|{OrWRmkC^3dS?g_mVOH*=HI?zNXNWuS6s=J9iXe10uF*>e?yWYkZ)QYhb6mG6kt;iEl%$vgCTJM^Ny1 z#52nMS;~imCqPrqwEi^6av&{7YkidMqgjTHE zpOH{BDRjg=*}+FRF7E9)-{HC3zruCt0k+%kZS(KcwVbK3Z=r!T3}p(1uJ7Rg`tSb; zKlo?=2;cipe;2>;@BAMA`Tz1y@JIjSKY{Eo@x9;u9)9l+{|5GN{~2IUeJ@(zmVlfLE`)Nr-gq2uRu`0U_de*IOJ{8 z9ym6gkg}Q3Nuu#3p!zi#Hs+ond+CGAw!U6wZlm7t?n(GZRXOF3AN64rlbX4 zYN`EsTde=p#uHE3+P0fSe?u9Dlyv-A>2=NBBXg2PB6QuNUvQ9V+&ez55}wRMA%x0K zAFByq8tb6+$cmr)0mJI~XcwuuHcKTQWEK)r;gdk5ogvQYfw0LxLyBvlIM-sSznvL} zQfF7*R~m|V0%-y(*vPzt^ip%cZRw%wDFF~Sh@+4a_w*P6kl3fS_73}+@78dA?Wyc! z2o}Tb(bg`Slmh&SXGDo&A2{-O?F#8f?P;fPYn%%OOd+ed1z!zA-K$!=cCQ%^eEUln zpDfN%DR)EwTNYr^+MDpbmr-p)aDhE``;T$`lm8PUFZ`~i^*MkSa0Th(7{fleLuAs@ zM_Bboc=S7ej<^5thqzdu0y41b9(x`5baxHWr`XvI82Sa%JpLyY>pnoP5bC^8;ykH% zzBMF2n87?C5pKWbfk1zwd_ep8X*I@wj>uO|7Qsu`_}U~Tk>DH=H(p(+;L}h5ycCkW zyr%eX?1MX0!Y1oq)pf__H*>RXfe$KNak!cARJi*@7<0~&p|pJ6$nT^Sn(Vjv`6@Er zb_}5!P+PC@FVf;tKF-5Snx9$*DW1pnw(rXq*cYv3qPYBFF4SX4DDR2(2q5OU5Clyj zoQe89=eyjcTj%muUbwkmrX(Hh*)AKrs!YJGwdL8O7hGbw{xy8`zY0G3KR(8j-~JFE z{N3NjkN)pR_@n=31zvm=zxMaPj}QL+@8IcMpW<3Sb>rF4G$@}`0@wO=fkskLN}Vvw z`yHyzb6k1YxlaAQLJpLR^ZXq5$`z}NNDWe#<4kl)+Rx5+2m{@V)rjx0rK9Xu@wR@} zx6jMwZ~wjsSVc+jY0@CdQGzAUxU@QwZ5^_-97~B^Uz{;40XZ1m!F+8d7`29$V=BraIS(@R^Wm1WlJs02U=bkiu%*Ri zo6mErnA#HD{&%OeFY^e!t#oF6TYmv(gk-p#3G|MsGSQ*bFZGkQzV>!>?2H% zLW(toMMwnQW0lB2fDFARch2NI@P4KDYbL{~PIav>HlK^R0)q~_D(+c2dOb(hoXSB& z`xGLlWvHk`+Y|2&1H3V>30c7T9d zpT1o=-|6uQV61T@+FqBwH%hS1>scDQm0m5*+-d(Fsn=`WxtBPh zee_)qn)A&+8p};MHn^v4X2~7*Wqa{⋙}W6MI_C@X}SCmW%UXxyL7)VbB4IIUtOx zxkB|1sL)J{%m9kay(i>tXSQ;Wi{QAkME_ne<(9q!Ek@#Y4eBQVF0d>Lvjw*9A@*x9 zdlP^158uKw`{4{gdW_nUAF*a{K)Dck(LIpDEr8$iIufkZ#cs zlyoZQqWcfb^R=bYcKA$elM%+odUpHU@xOscx5ZI}NB;Ji)ArhNew0xMO*S}S)2KNq zFZf1t3HbAOe~2zP15D9E;#qU!Pd7edn7knQnL~VfUZaDJ~Fugk5LM@v;KO zoNC!9kkVE%zy?|}r&-I-luV}b@mX*nU8KZdVuf&wHF}=WGc+>Kj~Eacm;o-BhZick zuoSss^CnS=`K6+BjlWZxY#q+|mdY`=#d9%FC4IUO2NhS!f)>*Fd{UrGPHE;b1z=+V zBD}ELa&K8)rZq8dmGl_p{A#qZEWXdiI+&w9%+LntlDTDb0r=AhEn;2+d|4V5EXV3= zIcn@i<4xOy(}wi%{bI_KbNNdtNh}6nD@?B8UdB7fxQ0FbSFoRc1U&ja@Xl8O*}>Mx zeH(j_nIvdr$@ASwOt!}})d_SiRaKOqZ7wsKwSJ6^m0rqQDOsmQa`sR%tMaVVywM?TR~>a=6g91 ztd2c&TVZOC`27pia9Db0``T^r%|@=vJj{sz+B>E&9iF1X44(F9+gzZXjLxuDXKRPH zS!z&QJq1go9A}b0T6;-wEI)$vM%0xx&aYl}umt&&2V7^4TQ~cTP&+rJ>xEz-d*<b*>Yr?ajqTr;>lD}Ju${J&9Ex+;Au<4nU z$qW%O()-~uibWa^!%Q`-o@)P{30db$MZa>CL2gPiv{rxCK_d%)P7Jz_=GfcSllj@X z4|LQqMPl{oZ7Psk)7{AH!x9LFKg)hLLz#pV&448hG-+)h9C5lwZ_1$T`UshFfHLn) zynEmJn#K3Y&-=gjs zoMaBuH@On1sTw zbQ=|(4vjIgUX8FK?LAWMYbB>(N`!)p9QtcZD24JAc@gt+WU2tqf4Zhlyd zD!%{#AOJ~3K~$jqLo3ucUELjfxA!4Dg%cpPz0d_fKN<`dq(Ys8>j0RW0C{=0VZ{Dz z-EQE@+mqH;_HRs{tEr4`V7{8(B8)cYRCHx3SoO3LRQPkC5}SglgwN$3mRL^+7#i<~ zY(Q0^Rb45y|3R4u;cBIKcqs z&@^nrKVM!bz=(F?mu(e2?vaucX*;Z}6k_CUC-#KOG~SYY_uz13+7cS$DxBWhzg}y{ zG5$9_e)1wdYtOgKF1q(}9;3EblzS~h@{5hq9+#e4*$whq@&Q-i`&V2S)LBnlcMRM4 zIJh$)7T%u4W6O(7W|=j{>R8C}8t0_eG%Cn`cCWcaPXNMeG$Jax)0Ufx2UI$-IG6iV z`uQmQas0WL$r!I{BdHzy(v<~b3)cOJ)G!0U0_@)auD%QGFY#>L;G^XuTtE6#yoGDn z_yixU*WObx+%+d*H_fDqXM&bxh;t*L=l5n9r8^Pe3)Pu>c{uua}(L8TLs;_;orrJNkb(C*=w4w}KI z)5tkB5uDd3`pi3nvXX=`m;vq6P(o(&h?s`q@@%&BGI^0}+u+H67&Y1%LgU4OFEet$ z`aEzac74K@*Ytk?c1Cy}@jxN2pM+Fo{d)4HCD1i-jVP zLTv()6dAqWWClx6aSN~n0dy(h90pqiep9if0>HZKh@e86#jo_4z|#O$wD8O^N_ZP1 z!cH{7%&a7B9)o68ZN`Z-CT$X4O5y1kb77&#L?06sfdW{Bkfw*EYVfKO2sMD0(xZ`E zhJ6^tNXuPPieH*DbrDx68_+J=@_Hn$2zKkQL58Jb)5oN+2@HhNm^n(rtJfb%(iXbRK3w1m(Vip)hy?_)u%d-f^Ti1QHMt%C}zMYBHyn`tEtuhL9G z&^`NlERXPeOaf|Pdgw4L;=tlMfPcga7V-#*6VO-u$iK#8>~$ z_i>>fSm4!+~6VAR>0J=zOT@%GJ0#h;8z5FsHaZ?Hy? z=Yez*KCH*5q8!*8IXbN)q>;yP%IT$UbPt}?y`2v*)Df#sk1haUl9^xul(M|k6myL^ zb_mp#B&FLOls1ZKuB-%N42TTKSp7Uv!5(bV>!G2&D@khaRerl@B!AAxjKXN&Htd_z zfiM`PrxYR_H};$j2y5u!_S>9qn(AK=d1&HI(T-8ISZ!|2Ns-5fuK>Kk+tMFfM{=* z=dPFRN$|{t4JUCS9ckxyqn#|@SvLYA$3d@kr!{n9aCxZh8w1=BqZw&IuG|^{;QcdT z(uY-#YwUflw@)3?{`OaR99z!C=KXY@iG5+48MRP26T3^bm~f+87wvF9gVOrfK`%S6 z0LXW^Zbi#$m=%dK`=NGuAlk9oXi3kZFjJT;SVc3kE%C-cT|{Ve&Rwp6cY`_tncL>y zDfe_5GV`#-Le@+k)^Xl&#Wne>RZR;7B0KDQ&ejK7&PvjAd7#CWq{ZA=S_l<@8MSVI zZUweuprzMCurL!P{&XhO@AxHIDnFdLSrT+b=GC0g!nQvSq^G|DREWmh_jJsR5Npqo zhZL@rOh*OF;>t6(ppEAB>Hh}NK3vJFB;fIxh+xPFp&jn!nL@NvU)@Hw2|b{q0dsbt z(2y}L_?ISQO~vwv@R=C4E7YVEP!@_{3=f;a>1B&vHuC){Q(v36Z`dMjf)7N`CNl?-7JPmIFHOTOXmUc~MV#9P9G{iNr zt!ob)b-boU=(Q#Wl?8?c_VX*?vlp zxZ%oGj8LxH!8@~$R{8FBwNTY4rL=8*q0(cT%Y2i(&ujK{!&WCS_=%8@#LulNr2Kd+ z`Md8mJA`VmE;D=E>CFm=iRWny*ffAhX%};3Bl-}SDtllQ``Zj`Hcp(&Gi$kzg==;Cl^Qj1SyvtUH&h?{`}Eq}%oQW$hNW|dh`OVN zx{?y90BQhow*{E7P8ZuvGSS6`0NTCihtjWTdW4e6_ZHdnz!9q!ydiX(5f$J%qT zHxjr9PVwl;Ef#2-l+A1mx}@8T;p~b>Gz^0fO`I3VRA=5%5se>GfcSz6((bU+4AJC* z&X3zDC^(xdsx=~qq@_t%g6ruQ#0{@gIV(xeeHptVwj>VdC zkSP$NP*G@`u#jLT0)!&fe5{uMtBp$YOy!q(`(@KJu1(~>dLs}XTbw(g;{C6G3**gqVedSKKK}z;?!N(Bp5gs}?ccyV&wm{sUHmydU-npKV6lNEywFSl z#R^6h3=DXVU^fZ~q&ySicGx)S0L1xAFrPRvh%0N{kQO|l3TcZ5jXSa?LHm*h^Vi%P8CU+-`#H*bnBTF^VZX@n41<$#FI5}KL$_HKworx9d_d#{yIcEZ$n)@8 z7q(;)SWhWKz*Pf1YmSL)xAw#am=35g5`XVzZU1cce?iKCv|$l-^_ZWwyqkHlmdi^a1p;y95Wv8U-Zhup7m2F1g(HFD8gjK>3} z%9O%!`bhb#e^*GbI>I-zW5kdAJ?DsLxz10Z!#Hx`{LwtM>v>5UIY@t5hcpQ?!nlh# zRD?tMu$E%E#!1>ozB>=o=hfU(Unx_~jAg*m2$;j3#>w7z9#|>|Ph}d(=S5N$85<8x z#}!C%cPmwUbLR6D^f;OF!E?Rc)`=|xIbg6a9l-p%O~0P>F6Ti_Qr=2Zzv%}}1cCux z;+Z>K3^qccPUn|-a0ny=<7K#84g17rXZk~4n!JyjO3T~3E|`A!(FtcI>A5`6(!<}k zo}-;8&S3n2!yHgoyXAXqK0iiyi`^bl-gqaKqYSyH7wJ;((<2}iJi&07%PYprkg_@4 z&FhlZ?if19{BQBuB)I|DU~gdA2k; z?!$gr-?_IR(=$Do8O&e^f)oW1)`KD>h3Sy&Fic9KX<4*F4mq@NIKmEZz4FQ%{{h~3 z>xGy0o(pd6kRu!+dqIUA3QGbh5;Oo200|6cx~HG_p7T|Dk@?Has`K6M+XKQJ+&MLK z`<(MVsQ8xgps(8p_jNNZnR^ltcEZ$<|cA?CQx}+{`TBVrbLzb7=}xKRm5$} z5)PvPhsyqIH1^f_36osW9eu)ZeRb#>de)$iv~_ z+-VxZGx2Dlz8z@YmO>&H^xTaTE!`MPc5k=)XuK69jIktrF7#rA=Fz}>k1tCvbAq0% zIo39D-013Sq+85AAZvIqXPsO(3g`~icycPAlA^GAwF~hR%Wj9==RSv9Zvb~Xa0eFI z{^$+hnJNwqkb}Lf=ZhIg>7gCDjC;;W0CsRd(yR>rwov@m+%wg4RpHTx(C_}g(8Heq z>k4{}n$G6$$^tBBz`Doz?KAx5fAK5$rLTV(Kf16L`v!gk_m3l{Tk{B4m*6;e48GmiI4T@x$w|LHG$M>$T#iI=wbPCI24xCFxZLLDJ4Xa?Yp`- zNP{%eM0hBncolRG;z;R(ax2C|@O$y3E>>3c_C+jQKiQ(jsmPS$P8{XaTF3xq>GDM* z_Np>M)jOP@h(};yh2R_u&LCLP>QHrk9`~IRNF;^svnJSRCTYy02Quh|dfb_urCYR!EB>cZM{ITsfm- zOK!yR-Sr9_IHmB&i_w@&^R3fhRY(=whrV>!SrWOCuR}dF##VD$AlwYv!Y7X?c+#xG zW3qj6=VF+BMH$txW~1kNc;wp8~P3S_bcvZgjr&Tx;OQa?B zk2r)lpB?!S%J`(7NIfcqhM2=1bx=Kt1`?ywUm{-UAfp0l3hB+;O@7Q&H8;JSjHIV> z1B<}CXqeXr$WtNb!fVIj=&Wn}oZsCNZnjD)g2~Exr)oh9po@ittAED=Gn(>+Noxwq zsW2nwB?KNS$?)@m5L#cBvs>7mzlGP{_!7>}?n1g^X~5dLE1vG%6Yew4U_}C)A%H{y z9z4+3?%pC~%*Zfp_P69mOD{dY*A&a*Vd72Edq*V1uDh)YL|8Qs9-@*H3A9bffEM9~ z#^_}!BkUqt2vCYuJp8(NXHtObN`;yk?GPdV!M=vBE@n8U=TjHYqM(i^4MS=gKqWkE z*_DU{WmkI#mgc+j?uoVdymBE@-RROAy;9tmBJ^%zK2~}fm#|m$x*WIC(vK{V`dUf%V`j_*VfScE<#{ASW{{T0F(&IHzVR&u8XCj8>r>zJeJMr}-wkaTjb?LZ( z;-YsvX$|eH;rW^3QvHy;$jj^XbTwn9htB4qH}E;Z=mEt168A0@f#)psxwY?25;(oa|j6~qP0lHca^CJ)D+*}&^DG5n-@)J?(Ph2=J^ThZHEkHen4k=px zn<|+GP0D=KB44GWSX0U1)2N93pN!S6`y6=lEi7oba-Rn6Z}e?7>ROf_5+0PnfwkX5EhC}Xwp%9Zz|yeqE^4WFM=6Xo|~ zPtqKF(q>~BGT`l6tt-%sJBOjPsT6s~X}(9LSQ;8Vn&w0g*)LIf-SJ^0q?FIXja-(H z7%T0*NfLrpKHs1*H>xS5!Sd(5>Ph6Ma+Ax7RrjzQ);8N$1JK&`GwQK zC`ED>f0DWoV6wkZMlY){`4f9lmk|>HtkA;S#==Oo$;&f)1g_d+FVDJ)fuw=So5cGe z(a)(3VdT<+O#)C1&$4HSI>mb^^4qQlyu8C)Bv~8KuA!9H?fn%TY z17Q5KRC;5}$w+!CH?Rl^+iwvcOqE}HWV3l=mpZu@eH9Ah=ln7TmA zwb*ey$Ez_t6XM#mYnCsw)AM^($l8Fuvp9dY8;|%B-KKLTi!Duf-t87K%?3ylnWFKs0@sX zVi;Cc{eX(uYsp(vKvc0b^^@U?LNV|J@|vn}6k{LPXlWuy$N=@WgfKLB^uR11=;kW| z4?fr9wrNZo_I&0ht}NNEk=I#PxdNE2Iz4ohqx3=($tE7^cing}LvPh*S2d3tE~;-* zQ0{9MjTAUMgiJN(AC33H|AViTfmL{fMvhIISdUSl^KZXM_EX73h%f$tLZQv`7YEKH z-)ma(*%~0+7*+t0Z~giRI+Yt$>I@V#>|lpBox#@H0>ut{oCAkj*muERRvdJXy&SLz zu&7|y7A$>do5?PJMzqv5pdfj*&8!~b=bV-cY(6jU>CGIJ!+}Ol_;?aJRIo^9v0S{R zrSL1G4eJ0yc=IcBm$C(ZcjpQB-jJ_rLI^;a0`k)wsxKw`)!wBURTLx}e3OayC3>9f^@q zuX{<4Ua1_9J^PkpM2SgfT*PK-l|xnxTd7rVk;-*6+Rs^?k%$Q$Q0LUxbClsYX>-205@~RAJR^*zC`pv)d zU6k)Mi0&{NNgGB(?iLGnIJ6j5_^o+YDERIJHy4T1y9d_!_w{Wm__py0N4_+ zBLup1F$xV?4s&=m`X>`uQd(&RUvA7YyO*CD4h?T2Kas?rlhh~#U|t_nHh8bHT`jpN z-HMyZG!qUQ+|-A*OXV=7|C0QwU|Esxo52l$2xO6Xu=(!$ra^3RgQdbhYbuC_*clfX zUOX(Ep^usSl;WI*;9%c520k{Txhd(-rgtyjLm0l9-;;QjCT_r?aaci**_a$`pVwnZ zYUsNnjY=W;#n@`o0<&Y=jl8zyNiJS}Z8;Vipx6ZCBi1Glcd_ZwplIE;xFFq?mWEYf z>%m+dZ60)W84ic%SeHwD`2FX2@;%^je~w*SaQ?#wc=q5S+M>Ao?(2B{7v92Qd4kq10NDrE zGA?By%1u@W(G<_-ie`%wcCAwsq)8JcXjyJ>Wq>4o6O-A{yT|B}4lIZ7*FujbArJ7U zGF%!3zkJ7d4b`wzGz%O8Fl2CsF<~htHkt1td59>?2bpt#A(taBIbyl~$thSB@@(Vy zy|D)Jh(7Ko4UdslI)R!rA(FRXlOEQ+#RuUj(M^%V>#C1vIEI7{M^FKVnlI9QW2pTN!2&EV$5ugMZI9nk;p>=FMEr1^mqe6pB z@)EMK8c?F*O1LPP9Otu;KkihnDwR?i6{kEbk@vpg-p{;`^Y;`RfzSW|AOJ~3K~&zs zozLIL4$slr1-e`Sx?+)rMH`yzV0o(7NRxC-iMNYwG7<{F4%-8A1*f=1nw``qX-XPC zxmd_oWcru%n$K9P5xAysdRzI#mwza@V#np&k zn?!T&RO37iq^zy<$i}@IPOr;Nj!Vi*6?*^ejw0maM|{4_r>^5U9$Ay*!_n{hX$Jt- zoUJl2do6#M-sK8Yh_u+qXr+zdDY*GOQP~U$sUl8bPV2hT*H5jz!H#Nddv@ zj^-s+cp#D~L$ z7$2MHa(JkS<5bF&bk9)7b37~!SZGz9M4+k-67PiB1sjb+1{Nb& zrLqZu&5dT8GAmP9z=oK9k*R6HzV{Mp9cw7PV8W2fQ17*472s@H(EsEk^zVKj=of%I zgyI2o{Rq$tFx-#xPqDfguHmp>@$iH10QvxU_8i~&7x!?ubsrZOxAFRN59|N-BRu^l ze*#?qsjB|a@m?x}n>N~I_O zDJY;=U9Q~84jl({9DuV+y#H&zi2J|#vv}`oe~kCf{xxpt$GF`uu*eGYHtlZcG?{aW zwSB!+m*y#nxh&=V(3hl|U&hS|(pL$&v3~M-#ELw8KH;UvV^E&3~FThx2Tlsm1xau^Q!*Zvl6?+E{@0nQ1hf+aE|U_HHr?LDek_t!~U%u_O}$5 z=Yqq+{53R)0^usbKN`ZCOdu4tur_j{6js6+*2hM8Ed`TEzQ>wed5PiaxqGY-Gjh6O zO7)t%h~^&ia23}0o9cn=^#?hNo@_QX> zf5!}>Qs9CM0m+=yHM%qaXxIYD7}? zIp67G(k-W(&0pAjuoKo0C$@lVRKbnBU28ZK;ILn@KDz+)5r7~1-!p)b5@FDS&p&!0 zbm;mBz$0LP27LDn>v9i$e+P@)1HSVH6H)9GVD7U9 zLGy#Dn)6JCHd+p2SLRgQ3&D(HO8T)Wlc(=qjm|LCxhd993molrN%J#OV-DGO5?ezi zHEW=}K;_%kdsQS9k-A0&JPa{Ciwge&X-QSS{5j`6st5P-kOIdz)wcY|*$;(zoL9CK z&v0s~IlLd~Rzq!D-)r$cPqa1ZHO-v$l|sKaWh%;MDIry*ZIpI8m~`j3BNky{b5T6n zLt|-Or%-7WH;@QZVFYg@FEnIYKG4Er$d;5oPBbTIKHxdl?clQ>28lqa62<1>)Ig6m z;&5XCV?raRve%J$che)*(le~#<$Wrjl_Jw;nNN#t;zmyN1;E)J&wggX?%%kJXZ=Gw z|K{)G&Kn=#)|&!gMPGI%Z}C7*H=0S6->w0XqPrhjZVt-uOwxwXr>1awuGcO!Lgr$s z1|?4><=|GRgX&otL9S`=99($E6gU!Afk=ximN{kI>(Qgc8hQIr|5TkIBf#TQ750h0tLMy2 z`RZI~0Re_5#NlNc2%R7#=P^2I{ILr+xKio>{2U7ZeASW=%^YhKe~cfvfjguKmo=Q< zG*wIYFpRduMr-hzI=wc93N3ogi=a$sQ%}xK%sPXK$D7VmPDavGxq*d>mKz=Q7K{*_ zJ2S5aN*W|O5P3^00p9ZGn1zlE<4A^BSz#eVkq2icOqGGux@QGLH?GaU3Q1KmH4Cdb zlNB8+_IkjrTW{k1zi=P&=WpYO?I*Jvp|>e|!dQg@ zP2tW!$kYQ821mtU45U~klHQOaWAr)FBgqu@^je~!Zv{P;tdHt`ZH5Dh(-j?sK27L3 ztASAE6sSk;hT+_S@~N)_-u9e0=T0Jbo^NoyNMm!QW$+js>hEWp&VLC>)5V!*| znEc;t^6JyD%rQT_3m(E4VO4^_UCN47kew!!>B}+79Kg((M10kU`F`nZo&Poga4Mg& zBCveIJCY-xw_L+P))bj!*atUa_cUl((33?#qq{W0ve@b4q=8t0)=e?hObAv>??t(o4WRFIt6*bPx*2itwJ?Sn4lY z{o?-!JiuZqlvo6X4hqBkoF6gI-wWEYnpUSp$C^-AONEmgbG%=?Tf)FOXUbb0=b@5A z{91j=?$O9P%S#ERkxW0lMXq{sddYbm{kz1K!mf3TisNQ$YxKyqZgz@(9ljwsbO4ds z09sN_NG@5JL7See?g(XRk2KpF)`g6hDaKeNgravrYtG+64>bitFHhX%vrq~RJt`eI zJO`k-T&dq2fXhAb<^lJ9?k)V@KYk7W$N%{OzW(p;@wflMo7n3EbUG$L(fW$U-0Vu) z_Hu|SE$RNf7Z`Ka)+ZY}dag@RXRjL3Mm)R;py`#~>bxrBo| z!()R$xN*0^mW*$#5bg9O9>&aYC!1mWsTrh^tq*s$OT8O?9qJin1@hD6s|O4o$S^wD zJjX0tHw#yYF75!Lk<*zH$#qNhaotK8An{3^hu*HmH&@hsMa%)EO_jv{qci%DWnP5N zZ8rXbqTuF!Mv9b83z!%7ag@l-D<>oAsocOK7;}5_H>pSsbLaliC2C%qq(b#~pRP>` zT~MH7@@}P2-oiSL|BhJH6?JbFcf$_>UtmhIGhh$R1QfD#=o>pcdAH%g>m7$PamgR4 zV2gjRif2&zO1XjXAc>Q|s|0V1$#V2f%*XRt*05=ly^5eurNIROV-)@lxD!`!)WkVr z;?JsfWn68KcMT(*L&WeOVK_v>9}p`LDF>Jepa_XnmT7QQAdIDnMh`(zK1caR(M3X` zv40yNw$m-O605k(MDf$n6=NyExN&`i*Evzxz~2C2p$x@Jq4B@0`d{CJ}(Lh>#u)H-lGx# z1uj<{zV{J;j@$R{pq)QMyZ-=}e_@Y<3ZDFe;Nh)H^!6Nr1Hy7-yCu+|XB6m*(Coi+ z`jV#ld)`Nld-b{Ue7R0#IJ|MGh#}Dl7;WGwzTwS1RUaNfg_Y$4>FH8Tp2H)yabhw< z4L%F?K{70IANcb=HNsHgsd%WL z)mW_YsKmSDyqhs*B8?`09y+4qr;IyMs8o_`Cs+DA}*fP)(SXwuQNqaM|F{W)bblg2)} zZ)|geG|C=rjggj%lqb|{<-dr3E2U02Os#J#+w;xPLtSM=_tm6MV5RBmWFhY9E%z!}WYRfuZMsi_Ar zZ|CUs;EZ%2W;0=^O2n4hGAV%4kf+y6`8;OEGaIt9wLiuC^n_jgJ9CFF=n(AT!jRX~ zL~wo!IKQiqod9wMbC)XKAoVl68#7|MvOaNd&#;m8;!O&8$c#~Sib|odY9Dj)kvY&P z))+7&9-@$jJ$0|0-gPwKp}BFjxwn&`_w=Yxbq_6u<#+Y)eQ{V2`6}sY8C8=rxlv3e zd{D5U6cd7wxK~tYH1uFZcrwO`^|e7)!qhd~kY&Ko5E~SgRMeE-q?{pcfUf$i!DAue z3^DBvCj^;(mSaKB*Q2mX{|n{LVV=E1p}7vjD>bjvKuixDg|i*Y3m-?A;#rMZ#B zE9DAGl{q$MvlQ3J0r;s%;wSM{$5a!D&5pk48ar0&J(hPAlsAmll3u?`vJ!6o(W8h_ z`{WNVmi>TA^3%JReXxzd*Z_f|aIvAMp`15ZSby6dw_^Y{`ZQd&xhQ2$o;b@*EL9R` z;qSVZ?C-Vvuj9Y`um2AI($~L)kJpc|mrFdo+wp^6ILG1cxA7}~?@iqPn_t1_-gykw z9{{q0zz*iyHOlaA=920|`C+`6wRc=-3 z6;New2yko;lj#rBcLhCYNso{AgRZQDpEEbvUY#XAW2(#VX}zEI)Ga8(R6S~|eluTO z^|UiFpD4E|$GlZFFk7SUpc$oC_k~kxsAKZu$hpVw$M$46L~OlA#wp&PiNA#I;5vxD znkjHzfmgq~E$<}5w$G#J1o%)i12xo!4fe!!m2&~tM|be>EjWD)3B(O&C?_N7socOK zhy-$Bu_M)_A(Yqny@o^-CKzOo&#id57+#1{eAe)O!Dt+9(_f`J6*iQ66~@{wVWr_$ zqTM)F#2?#X!Fdzxc7oPCKMEF;_+1c6K15=eJ90-X-?g(&;}CN&cE>ZBFFkS^(CAsK z2q#C3F$*I(Kw}=3B@~7e^k$1rV)x?#x@LifaNrFoba%x?gqg+@2alWWKiH* z7_y~IK{qt|UmBnbqZai5tUy!0aTOoiX#(^TpQ1jG;L~WBOT{xeWF7X|45RdZL9;L- zb)hE0Ih*J474tFay%AzYVZN-- zYMeF1ILzK`b6>Q?KyxaKz{_mIofg#tcx8mfU>@V5Run$^Q;9u(A$sk z@n7ut@K+C5_TR#5@&ro*4$|>dp96A>6R8txDSe_U*V~tcd`W%pj0fw3&Vd~UR6^zhxcBk zIIW9MUar;1aW9PZ`aDpzaJiuuRrYaOI~Yq7Vm=W{l1{Gzh}_MC(N)U(N&mL7z^ij0 z{&e5l8Re}P6!(O(9M!$BAybMaq9VW9QDYAH0f^YL37~YF$U-P`YL6nq@(7(mBwZuwE`qQ>qx@q zC*}KB=gwPWcy%AB@AJ)kD{YTD*dYT>XHi4s$dxdS9R8(cmLugD--KTyrPIwVCnM>p z+`uA$?2v*v4V+crU&}R;*lM_}phk#_EUB1Xr8r(LI95b#&?g~<@ahJot2gf z6YC)Ht!)$>c*1qn16EP&T{%{17+e^Fk4YMuf-1YRsyg+Ctfwe9A)xr5D+H9Vcz}Ys zVZm+*lXVsAgMvGo#^;*rM<%V=&L5dQ+bGPtY%hkO26~A)P`wQ6!ZLaQF^Ub@28S-z%?e&6EO{mD0mhBYWG!rV<3{VxuV|aC2M2MlnmO$ z@TeWVDWEH8B-K*Ku}o8i!cnY?IpepiieCC;W0%kJy-uVeyj6K$;B#Tp1{LXf3paW~ z%?=PS5NR$1(#WaarnZun!S4@wL1V%tTtdUN&*>cKY?JSVQcjRN6l*S3;-s~Vl0KDB zSMf1r68$(p4HAbL*ogt+WKGTcT?EoQv^C#6g6kuk!(7*#JI%f1Vb{-^89~>B&!+{V zXHW=w?~t}QD-);dq_cHhPJE{uoqVJR+}3Bfi>J7S2ROsQj`focVDV69o2%w!m!6X0 zL=O#R7eIK@)>$mRHd=U6YA%L&&JznuT@YM4?(H3s5tZM$HxSH=G{V#-W!1>4dxogz z0W&0H2z8Wvw!EF5{R}V1tg@0PdjE%%AiPbQGhCd;ss0{I^f-7VMgv8;)}WiUhzk9M ze1A3} zAVPg>m}>NAdU*Jp0I8p21L=i@To*dM&+z_WAxB2qYjr2T4}+yKC-tabr*d=3%O;HJ zJIihdbiuCeu=WEU?0UxoDEe5pe$nd%y(p)a~Zt{L?pbA z2aIzp1nAl^r-FD{shsacoGbb;FmWmf{#%>ra|KEU^RcSxF*~BD{W!IHy6+VQVC|&LYh{Fi#N#0PP;G0i=-$ZtyGhNr$R{8ILIj)+)QA+1bdb^bAqwI?S z^ghmZ)#Z$$go>mAO5E$VIkV>+Ug%*Cq`{T2X@Qmamjoz`tU&Cv)5sNuF3Ec8uthsg zM<|5wkPT62Z0_9r9onC|LQiB0kPUXyF9pY#vo;6Kfy_3aRNdetKHi)gJchi^k&OSd zO7|V;2b=%P9Z0(i=?AR69JDvP^R(tfH7B8YUAhN+JHuJKgQedB^c>4_4(L@FuhNYs7>HD?#P=NN(dpriu87zHd>Wq9fv;e5>@N%Z;cyB$sga+OK@MQD z0r&Fm=tk={jHJ1i6($SFQHwUL?#atsFWf9EJdNL}Vri`x&e^~!5A%{aX}natk$urzm2b| zGDqLGk(9hK?$b+J{Ae%Ljk;@bkGznN;Iaptk0!izGviclTB-9D<+H`-TW`OC|Li~i zckwe{ybo<>c>gPJ;A8y&7Ym?^$+^!PpxUwQfOAo(T%zN`Y3c!8Z{dI)L^>Mw5x#xB z6$dv)ng_RuTp7}wtIGcE0<0=d%SI{&_e3@R(!fGIVn}Ji_@o8wwQzTqkW|ejgU!(NDBbs zW@ZmAj14wIMhY#;W4}ImPSTn8j!!tYs@@QAs%Pf$dDD~sEqq2&Y}AU9T9306X>N{5KKw9ISQN`=VB_s%Bt4ZISSZ|+S*+zdJymEB6=V`+;8;L&HGyASJw0^GdDyl>HXW^ZH2iO5r7r+o8SyKr#FemCkcG$Ou-WqgC zFH(k_nF0#*-Xru~V9HH%EsY+GP)&Uu+!-aVz5feL(ME>Mb62mcLY)~*omM* z;fjs|rf4b+M(T9J=7FkY?kKph+5pP|E$KCH(xk}N#1Z`C`?Kp?=f^blUUSzI7m)^VsTP7i#2iglVzA<-AV_+EIB~$Jsm*-@uGEBwh{9L8y4rLf};QWT3RAb)65D!9; zwK|QTkBJ`A7{gZbIj)!JLwqRa6>%yzsZ`pZ^Kn@k?!I;xkTa~h!`+{|hoAkszlbmW z<@>liD4v{sfQP$}q05R@%#$14*xarGOH*K7p?=WQt^;Ttf&&^>ES!(!@S~R&L9Pjb zum6!eM|ub})64`>KV|or@6yBgGd{y7xd@Xz3>IB`qQ;i9c#qiHPHsg==3n1r+@LmeU zH2UPne+H68RACgIAH!i)yt z^#}9V2u0hKHWfbv#X?#loF;alVTrE=rnV@JuC5{~LZ}#`3PR{f=StN3j%6yv0t7B0 zVh38o+Ua5;j}c)3cG`v3D@2aCZW2KV1*$x8v-DGp*;X&zG$134wE)5pS#?|ZAw_6z z9Oym0snmqoVCmj&GFgpfA>O`9cjm8dc9Wk50DS>?7|^MF%F5!Y8Qg&0doP}pR8#=?<_*K|Bh>`N_v2hxU&K90eIhh9Qr(=6 zX-5;m?Y6@i1kZN2aoJu2(~~qc4^vY0*BulK8V=@tLC*$yySc#z-m-O%bkC&uYEUCX2m@&l zJ%>3WI#T(viuBvdRp^Qr1`+^rlSsXn)>{#bKl2M zoe<2VDUrwRw#B@aE69kXgKrr(_Nlw0^NgkVv8GEGSqWb zAx1bJIi@4;G<4Iae)i$iE4~v?cHKUgGM+8oAPfe_f-YnD|7b`jPr(rsGX2fZY{Rxy z4jVVgiv`T}CQ{~%ytwUw$2YisndXM=o)AjPJhkFuT*GIo9rCqq+`n1n#5Ygn1{N;( zK3%KdtElP%3G`$YXVw!H)5}$Hrh)?i^X@~@f{Ia-im$5YYXL&Fq%l?D_$grCCRE z;fVJUxiLpKMgc5GWg4ZEZ&7G-1uWx8qE2h0r5BXX<0_=_N27O}*eq!5vxn1*b5dyn z4MQj(jS0G4=@J@>tPhs+R2(E4O3Pe!&n{l}IOW8%O`x0yphp-Ylqd|QP&X_gmq6_L zm-P`cj|AK%1QuadbKJ~1%un|0gpqTS<082%*arOIo$B36IJGDeu}obQqz6Kok1^#x z1If^TDhmxhL322yK8P#5rt3|l*YTJu0`z7^%yD2iM68wYuiFjF?c2bux6$^mW4B)* zhfAzDgjx~x3T%D4aWTB3J$hnyzM!?&@#uH{0Q>*z8+iY#U%|a!w}UuZTbyjIZUj>- z(y=tFb6a_tc&q&@U-&eM2co*j27KcHB9$tYHsb^izqnPiLeMr=3Y`jUx7&9&lZJc;`RcD&B#UV3? z9}FmdP@>>C4An@JDa&oJv<^*$$(?+WY>Z>T;bZ22p`SBeFh0N*Da9PIG&ibuxZzI} za|#9WY=)oGo3(B{5!@MfQh?CXmw7ae;-Mz-sA2Ul%L zZ&GUNQBU?zU`DV!>7eI^7oTysslx?99J?9M&fqJ^PvQI@LqD!xhyfhog8d7+<$c{Y zl2R(zYM)GGMOp;ca+hP?$myqg^LO1u-71ymUCsaIGLB8s_~|KiMYozL{H?*9Lq^EL2%T*+#5=EVUUqN((Ft4COnt}BUKB$IK z#b7K|uV0$Gfh-tE9yzgAvRmMa>!A%ze^t4pw`olcP@i3(*a0|T(G|D4;=BXrs-A97 zacFknlqoG9CQqZ62(+(Q*CfR3UXt=oZ3m%Mnmhqj3yI|Zbw`*>f1jcQSTShaDw5Nkw})h+a> z)DA^ypF>}#01YybF~mFiOW{!x|0N!iVH)DbyKovJjA8ur5GUSi0J`TdS{6WBC}0*U zE(wPKDjlmNj@<>p0FeeXQ{n{8JxNi<&ew)}=v6$JVH4vr5Q9M%Ut1pfudTZ$l^J^S zpe_$O3eRIrql-v*f;Nun;8{gH`Jj^)(3nfO{5hsO(CEIuD~cu!(v=|jSP3!@o(rJF z@2PycN^Eq=@Y|-+G)b#?%et<|r zgJOXjUFj7%G*%ZTO1sV-Rnfy>S7EGG91*_Zwn7q(a{M}wp?sqSQvw#^S(&TY*SUIo z^u}X~gsPHgeA070;p9CkevLIwOE?U2BzZC+VxTjX&RazUt8T80-stKcvmFg3DLNTcm*KpF%k6GLozh|hF8be}5E%kb_@_49r;M2>A_M8Nb+F0T|DvBjMvc)u1N zR@XS&=tC`)Z=uNVBb>aq1!q+c@|h8z1I;5bdeKnH@lP|v8pARPUS4g?{nL-If<|AC z`uK!fc-1+Bqwn)I_MA=1 zW>Z_Zloz9Scy~h(xPj$lBt4bSSV_fa6q&1Q+WdTV*O*m^DzsLkC7)%g~*kMvj z0i_a~suUG=97erL)aL%wez8BL{(!Brc~e});%MBc*U=l$-7VC>k_h3V*Mb>afl%ba zcn538y;*{YhT(D8j|J#u2Zec2m3~ARk1KjEq(xpGDt1oSRcjXo47ZP@>imXWHcV9bw*4McRz^EUE=N%EiZ3BS(;A?>K1 z7jeC<-^cZ{RVUzb93Gkuu2uQY{zdLB>42=$eQ(D-)T7UnD4`5@)NL4!$=UOoqQoiv@~B?(O{T;)gmSq(9xQ0W(tK2?Gz}Q zu25OsOAEvLvwcVno@h}FvI(n>ucB5b$UeRr)vd@Vo7EGn6_<55U*1+iZH7|wB!%Os zcFH-dvmb+jX)bKed^Ws(KAWX76w;joaOVlu`#-|P{SWYQ|Ccz|4{+=796NOEAtmO_ zHo#Wh;W_T&c?WLE9(UVw6f>!bHyGE+{Q0WTzKo2daZt;({P&ZRp_i5ybZDmhTcSWM zTAsg}Pi7^pn&z<83Z4!_W0vnFY16&g<0sqOq*A@ss1D z$PL5WRbF{HJXaNpoYOw*E4)3_v~gcIp1qmnWF$S6&uFQnzm>n4b(5^F8~2QuRZ-S1 z3e3NK@y8o1Hz@OiPM)Lz!yv|I+nTNAJ%;6ZTNW(u0y33M8fdElYem?ATF1Ho`yFtx z>sZB&I$>zClbOwkmicT{inIhEU3}n)6&vhiaV=e`61^I3WFoc``WM$hB80ptMxntT zmVga(LJft)^h{Hty7mm~rozy=hjiP)AZAqcnjMb#L9nf(t{?99`t;rGVMx#YYjYJn_+hfpfTU3|F;agvGB)yKXu7f=J3(~2SR(j?|)%n2oYJ}k9N0*a_tBIr`-e>k|vs zJLXCWi|86l=Ach;IQtR4^ZFlP_m<+xi1$#+R1@pXaY7OC**)~9+aY>M&@L7UlhheIC z+g5V!wA}q7aqPOtYf=oCBQQ)iv+Zn7hS#CGqDC7G%AFWJw{Y5-?_^!(y({s(_J8Bv}SW^Vl?h&CW#4#Yh?(!x$UB zdZE6weu*~freBU{7}Y)3wRH6Z5J@9?jM=H&v{HGFx`RWR}q1iHE9WF$S6&p_E)$g_3B z6{I8bGCo7E(fJAWFn0mN!UWI->W4g79?)|@cV-DG-W!pxZcvH}DUPt_a*z7Y4CfGb zK9h2Rd5^B(!4SPE4h>ivutpfE6U9jK?Fv!x1|8S~75}il`n_uK;q?fC?q;;=9eF^J zW>-r6uaZ8Mk;5X;%*^&prem-OJJp$i$V6wJ?0%jU8Iy@^`iNtub^6rX2U~cw_*n z<4T%)#yIZ7;LHxPV?}|K=85G~v7u=y<`5g3p!G~`=#GTu}hiAJ-z#`Z;px4b0Rm2esVw)qG&umr;DsQ<;rQ+PD zU@iF(-tB_eP`OI*KH_=v4ZY$)(o%(OQp`fXue*S&M3j&Q#E;q!){UTRP168an=o?D zv?yg`ukg6RPzx0LNgisXhGZ;R3jZzAiF8YAqS!Ei0@9gZaN5KJc_BB0#By1eu}zAZ ztzMgARZ=PWlS3k^pmVEnGWVV=X#>diNNeq@l*M8%d zfqTGSS2XFke0sn){_*eP!5<0!`mg;e-uvoZpew%dPafgh|NOhS`}H$?>1%hO`n1%& zMPIL=)h{fYD{|x7OvhiPtu3B#6%3!G{`sBjwsYOSZ(YBljk@XjiTZFw30koQ^Q*S= zvcAsWUxv5q;_fQg=lSvfN7-uss^@;vFun*^Gvk`Q0%oRmv&+dydMY=(TqXX_#Gbi4 z=fyAOGnEjTh?t4*JO8%83^(RAs>~6p=N3{---+rq7-4oZoG#o3s5N9B6FqZbT~F9z7;EcuFk>gZr2zOTAAa(!FZ;?%u9ySh=<0XNHp!S2V@hj*VVi+yM}JTy#@^EV7BJ?A>_)9W^qpyv3- zAwMT=_ES}2F4Nc`zASBygm*W`PLa<6KD`uJoi>XkFKA{Q-R;yu?OT~IZb;kp9hTQ$ z$Jw0~=lv4>@ddO$!HPX3A_gXSAyBN)vpcx;?$6_J=N;^S=8Mp`--GO)W7$6jE)Q7G z6nYN#KsWxPl7|x7F$XJnsM@wC=@lpg&5F4d5nhSv|7Zgb=NtKLc?9{$?0`wCka^u? zx?kvp(5rQRpP3(9!WZ>wJg4A+c7<0{43M(4k>ojQQU#CRF}76r7I{jXYF`zRim%d! zj@UQjt9kAoV8-A%%{e(}Yl5Yh5cP6T)p6?)x?Uk1$5Hjempno^II%@7WbwhdvPVh7?lmM@(|f~=B<7~8=HmeCA~;GRO?vQ7l*ve<2EP%X?2j6@Hzw_V!Yy7!??*hN}x8K2X{sEri83eZ> z?Gpd|w||K5{I6fZUwi#;;Ju%_z@5WmJov32;2ZzbL;TWz_XXVktGDp1e~|Q$Z0!pA zdYzIall0mvJ}R>DS84h2-_>nw@D%@j)iZNl+uwWei#gBcxW{$K(2aVSg&?f3@=RcGUZ( z?)330W2)s#tc@#0w5_pBX~HH}8&Mi}#hqtvK0`SfNl)d5mm;0U@A^rVW`Qk-nIeea zKfsKjc1`1*y2DSkVF&U0%#+kUfgR9kBrPy#FHMqg@xl<-Zr{ZZf07k;D&-330l+1~ zuo=(S_X&F*oI~4M9C9;zveh)LQt^q@GKvCYPJQmVATapckibytFeZeNPuzGpc@VZ8 z(%{xIMzpV8KnOOLoMw^Uy0UUsxHdJ;Kf+bT2agx$l_@jH-}WW#1|sW5zz43 zu_ua$BfWS|BzLnwY~fn&5EW z@eF&kx9;K1pZ_xU4?n__2On<3>(gq#9`N|lV?4jO4Q+e;{_i}(2Two37vDeNt#@~5 z{nGZ2R6SysG$oImXiEB2Npztl8*`TGNzDg3n9~MUtQbSt-B`;v#7;zRI@Xa;@f+XC zHN`M^^Q^Q#iSQxA9CK z1IroK#|s{O;~wPUU&F1BzlhuWKf+V(_{!J5hRc8W75vPXzYpl|qcPITY3jI*q(>{} zWraMU8p>pIMeuW6Q@Q%A4xakn0wN&K1Mg0Uw^toyO#o=K^NF|7kXu1*csuEZmC82; z?gMhcdcW46*d5=`lvXsvs>6x#8Q*McdR6L_Ym~wH#qluk#~kOmA2U{FDy8M$R=y9T z;W9vt3>?#|uvJD!D26jHhW5!-a!m7m@nf7iQck!YzAELnUe04W%R?`#Z5xNCuDHCi znd0chwE}f0xyI%-Ft>j^W|q^O@p80}pFb%!bi36Jmxs_ehJ{B&3JeikOC@EpKD>_b_pKPKo)w|scT<4O7+1s#SCCWNVMYU;2}SdB;0>Iq|&OO zQK?wz{CX%NG)ROemX0CkDEC;x=sJ1823M2pQ-E5O-MCl02e;MT*%6kxh*LU zDnsCXmyr1_D=f^}Nw3!mUl`Rin^R9)P!Gi5xY4^tJpA0f92Mf-(!10Zxop_xzS$KsPpgG|`hCgw%sNC^TRrlu2u!=y45AT%p!g)^O35tywL?DaVw#dQat3S7@1v zHEB8BmJXZS?GimwZ=Bh<_7&&{WQ;Tb*#S?U0pI*K@aO}`8+Wmse+>uR2X3EZJ!??X zS3mTvH>anv!&BVF-S@tXH}AZQi$DCAc=F(%VhjPVWe2@n@#K5o2IPCd2MhkiZ@&fo zXA6G)AKt@zUp&WU`w%L&Hf@8&PDkg#WK9H%d&^Qe^iGy`j)i`zduf8)5cUV}dmbfH z-}hC)rF2CbrskSwPo>4#x~WRt^P@@)sgH^*m*;3?ElL9bRa01{uJuwy<=zAPbi9cu z77;gk17TeaIs{xjmKgTRW;RD9vpJ7hW{(?xm`WxM#R5Ho)g%^0*5%8I^1FM|6@QDKl;Ot-}-O= z6|j2%H1eVac=ir%-+l(w2Uz7X9^C$YeEvVZg}?ca-oe}FPjS!>v6F+zV4lvYp%)`* z{r7rMj_Y?^byxRmUiFpRj7Fr&b7(}>4LJEuyOP$1kPG;eweA@P;CSuNu#85(>{$=$ zQJ>(q8iPSPCm2`0IA^;C&3j=uQG$N}03ZNKL_t(vQk`qhL9jXICb z!F7{(e&S^?2KN%<2i)}DS_NCPB@D{$0I*2+R6*o)rqMQ8vBUmaaQ!rwlacgPJ_AL| zACLyp`nSX6_UEM%+cOm3hpGM!^X80w7D$Fu>3>N>(nk4bt2$`T$B=GyPOhUyBgT8MctT2)}BN3Q0uus3f^NgYiR!_&U9b#CGx+s5qR=tlsJ%qveuJ&%Dp+5k~@uvZmG$-by zHAIhIdZRJ*fq=Hku_6@sdd#o30nXgjum(Dw~^WFfiTHwJjH3k_&e51bm*JSr%o3N_QeDzH1nDbJHok>)!O-B6Fhh!pfq zkJ_jvvg$Pvp6hTQbKh7QTOi+Z6~J6pqYbNDUG350$%4%iEJU+6-TP{alW*1x>_i7# z7v@zeF6fbhpMnjWI{sPGLJT~wVu@a)sz*)46f7XjRn1)ST7_iX$>)%oHJBD+UU25s zwv2p>r8Xyz?5tpf?Mg7n($o#DTD*8*IX=5~-%Qhdp>%}4yQJ(TnZ%WF)cZ9UXAnPz zH)o7b-xTgmE4fB|K`>}RHpcQ)Zc5o2RCi=h0PCB;dLJ<{L?P_}UH8EG1=jW)&!Bj? ze2fon|KC{k4EON?RGwgw?hz8)NLk%TDj0Q;mrpD{ncjpQJ!ZO2Pt~_7g&TPaoc7PF zqi+6hg;nRBt0+Y6lX-K`G%r0?6|=uzeS0*N+QLkTI+`2Y(yufzQfnVlI7JWOaylm7 z_A13a1_xYg{F@v;O{B+Eu;N)Jyw1kMkQumO92=1h-4cStsEMOsJCn<=gTN- z)UinT>dbj@p$uSVPw|?pH*LTYdAw~j=W&8LXVNI%0&^9sRqoPF{pBS^sWNr|JCFL~ z&AGDU`5!n^J2Z^=Qz1=g|?lBc+s*M0WPem*w^!3l($6x>Z ze;1Fx{1(3de#etD06S_f%|k>>2sPU}BGy~#fHAJFE8-9!S2)eKP(+p?tR2NTlnRM@ zjx}k`yj^wiCe$PO)s3mJTz*yC8gjXMTRh=BPIhw5gvO64k(?PTQSyiq=NzL^s2HRp zHJD=OU95U_k63ALNOmPPJXo4Qx}VH05_wzWkd5#}r1Ikm;=l|w`q!nKS1J)L0Q3Mm zdA-@m+VwOm;(jnPQXtVXeO-`IdscWq4k1E*Mk(_uaFx$cgw1_aMIVyKjV6%NTL=`p zCg{@bAe!bL!GpJE0>khf_9e!Uo~}baSZcHNuV}V}!VTZ1`FC1J$~%q|h2tN$M7)mBTiNx~P3`ilqzik>JT69Dt8k811h+`abs}Y}>_pS)d)*|Eq5U zKlnr7;pcH^chU7Z1UoQoOA}WGOnZT9$BNZG5@uhTRH0^JUx%lS2U6LnpaxAk;)%q) z294YrmQ>-S{6<_eMKlkaLp(Xb>A5%uPyJGpYjftI0bHq&hP|_}pWy1^;e@K;;bC}i zIYp`hIVm6&J;y&G!`Pst1(2x@qw5NK>ziz#*cgG04px>e)3s}rN(wQ87km;DMm_cU zTRAYGz8|5%nr5%pSz`!&lrOgX zVgGdJnhg!TnF_8gjWgPAzCwE{SFJ=|Z-5F!&y3co;t~xX>O1&&eHZta2Y91B!dvDm(R1Pu3bfD_P8t_yOb{#BL z{-~w3`CEnA+Ne}K=M%?soL4-AuZyjcCa=jwiWH^(vUFo!B(dMToG;{LD1 z_kT*u$w+!CpOGR+PtmPE5{WrC4GHYbfJWifewSQy0|D;SwW_f$Sb zWhUudhth$@)FTTlSG28JX$x@Kap>@@D7S&bEueoNz(YVE0R0TwUxywPx(9UidR-Af zYqtCszzFMV;ZN&14$tpH*4J>D!)TeS%e^xjEQGwP0_!Do?ZC4=1kccR=a6-U=mM1k zL=Gk#2VJo6wvO)f$>;3YAVz+a>wvj8naz$gW2Bp@OeC@^?vHuJ_5juI2?y0s1;V~P zw-MeJx>Z+&W0T4rfjg_*RZ8Hu@!b*Tyf*XT{G8vQ0;c7c&NwUdDBhRxR%Lf{sr}ID z+I7p8B(vF8z%_@W5(sf|MMu_qMSI8XR*$D?K193eKXW{9QQ(@#?rJ!Wx`FH9bCi>2 zNCS%ksPr%zlXz%soS(|gE?e{Pm^N!S`Ak%>wjG|Hy^a0Z7x20EG2YWBxUJ98(9!8T z;Brx#(=vp7i=Ms+IzF9dSCrK~*E92li~HjDk;Ws zKSwz8xk^{;{?^J)FVv(+Bitz)U){g!ml_mb`SSvTiHIPo4hibJe4DtBxA(f0c^T z%d;%ZOZxw@_bxxOX32fnFV2@)Rrk?7-P6PzRb_rBw21gc#QE~8 zx>-Fv&D+&^y6a}<_c-qpuk(vISI9%8mWEg>Ujbm+;OwE`{4pTsz`PMd87K`yE!iY!HkM-2t$0k+A<114EiP^EH42;ZQhCFRq{mPSEmo@lI(+PE|0&Uxay zw%$L+bnSYC7YOK&eW&{gr&HtHL5pQf*(lv;Q;bspT^d?zb_fmc`g37`*XFiO1r65_ zk6)!k@p?hvSPEz;Ztf$hqUHu&MW9&T{<~#(f?SI1*B;kHkdZo{PU)ph9H(c`fh$LG zUYrBxn_wB6NrA0EyFeaKXs@4P!Uk9SbF}sdXXg#l&(I%z73Z%$M1OpSzG-2!7p~jh zeGVxw&vtV4)gIV=0-3KD+=O)2wA%*3qqB2-_cykL z#5CDK-94;{Z|X$80y}_k>GWL6yir`PY9x8f658;~&GqHmx2aBts@rE*#$E2OKXZ5G zZLJsO;Lcs@@ZvsN>&H*ipUW|MQJF8w@6%AtwR)_z=|y>$ZQncBfg}Fu<|lb4%_!YA z2tiTHuM=r@Vk`GN-L#_X44$Fb0qEFci+}a~AK}CQ^DpuKD}Rg!-~AYGy}kF?%=Q}h zme*M{Un>w&GM(XM_>z|)hS{w5hr`w-e zwtcO?ZsNJFhJ5a!`#&vj!OADo+WJ{&f}d(UV_kg81;#pr!<=VY+p(kv_cfi2q^ERG zQzbRk5T%Q2bhn>yNSw_^Yj8A1=d;>F8xL#udwnV*R2l>giOK$PSh+O~Nk8Ohg4u z&A?=C-6bxX$JR;1lPdy5RfeB=8HbAclT^p+4zEJYb={4abkpZQ3k+)-%BstG9JaF< znt*OdqA-d0WM8Q*B6QL^> zSOx+$4_z8QhqhV!(r{k6rdoSx#F+$wX5~^-6OBWl;{Eun^W5qc%w0GN?r`bzREPHw z@3N28$JU|+5RojXab*K3C)s1-quy!w^*E3z9hCXRHbtyDl=!n=PV^t=TQS-W_n1#U z`{fWnzF?`c56-2ZybJvFL!eK6HG;Iab19uO5@CXkt9^v9A&+)TAy1*7+ z!<%nEgl-?;`T46jfAbaStLJ!rp-|~|m>v!HyB+Xs?;%01F)JXKPcUD-gRW0-5Sm5k z(a_Mb!{f)V;1B=t-^aK9&NuMkRmZDe-Qx1C9sc#(e~O=9|1o6Cm~%5GWNgC(q?)^Y z(9nAF&H>*$6!{Ycvy9NSmTsQ+)k!W_NL8;6>B0DJeWt3@6}O_R?~m^-%Q_;x@bP8- zN56QG%jZcsj;Y<<>vT+CJH6z6#p-h}EL)f3T|S5WZ)@pt9sKIjvOUI6+~L(Xrei~q zd<7OwP~=x%zf*cylS#xGer1M2u)FT~U;l^y8SS6^bM&wLIWGR&e+S?BPksygK4aTl z;tP5ACff9A=G6^r`c`^AO1FpfeC^wD^m?66tnrNH{pIJUp}xn|^QL;-#5e9*{>|5p z%XL{d!C}ADF%4(e?DS@ilZOF9`zPwAef%4|FA#0)4F9Cc2;C(~MwW z=ZX)`fsYi}s{(GY6sUzG)dVtjH~uvdw}o}H3;6>|rCQUB)Px47bf;-zv9cyKLnO6_ z@~4rspfUu3j+9pFr11Jn30v9Hwg?0wR*Arbc&E1l1`uFC+;XZn4Z~+3LF>3UBGlTVc@J4NL5n!G(qTsO?q{9S zNZ(-jc|4pr>_n_%l%1;T2M_x?Z{qz_VkZfQBn_Jx3(C--JTbFO-ZX$#6H47$jSvr9 za^44B%RY)PB%!04_XY0{A%@lWGQLbA$QLM8vdopWd4TN%OxQwkfxR}&9@}z;K$~LM zJJ4oazp_DlykY7bc!qwl!S%LdhaGh8&?nDrSel1BnYq~ri&lG2TDIOa*j_a|7lVURNqg@^y3n<-7J$0a&4L|EI^9#~$3xSsJWrJNypiqHG+J|U&ZIT1fn73h=z_%IU_<3NqG~cO|=i}ws0@9iY)poxjI}< zA$?z_H4dGkY3d)W$6fp!q8+XaNjG3kZzI1~a9rel2H@bbsHK--0|?X%C1SNp%8b1L%e4DL4!|0J}g$zrAeJraX5E z;0b_V0P-H7SLMAm!f4Ft`2;*Y1D;PB2Lti&7~z3ENbw<*R!7Q-YkUmwZSL`o;`2A- z8}niuOSibiVKp%0RfGiXf-)u4!nj$|eBO z@W{9Bwu;4urlVeIh^3fTQHmidNHVAj03Aj}B;(K@10@TN7jvD(h0@^uQN|18zhq4|3EpbkfePXcjzwIN?ca*oz&!G%K+00-ZY0 zudzRyF~4<&*EYX_uj~|?X@YDN`>o*eqTvdAXuksXGw|ns4*dK>n-Z5Z&@W(g{~FhF z4Lth=fSs7$tT=^DI8nUVdXOBT6Mmphi;EAN+XLL;rb?jT`Ie7rqq6D#b#64(wEnqb*dc(67_blNPH5*-fFCNf{RUTnz zd>N$O*6Mu_pZ1i#M5)fChFP0$>hFR5E0AY@1K3<*d-WQoZcj1nl(aP4SY&DD#-Leu zq=SIVw1{b)C%f0xN_t*@C+%~oKGte&C07#p!Xd4$>#5SwCGA_I%lQ^RC3@s0#NVNT zbEJ@p9_A-RUlc70xgl8d*Z4QvdWUtcC^Gf(#sC1~iGjf@LCg>YL&ILMoAzc75^b=8m=5AxiScRcU(c#8M zDmP>ZvlropunsqnCW6mgu?2KZ@1Sd^AsvJW5&@dDJOGNW^{P;55N%d&2Y6tU(uG~! z)~8-;*S<7b0Z5Z@tM1Zch@}_tBrJhTXPd`r0|3?QQ(809-cUN`XELaJ5Ifd=7o*W9U2Y z0oVic-gtrvY;)}zn4bdu5)BqDbcUc8y6Qnu@!>0H`2XJq-g$e6{^%*bviTvl^G~tU z53rMKhzPc=VS|Q7Lz8w}>yGqSRpddkR+zhkv#Li*=2H`a<{ot`D7s4Z-1lo(c!&R zN!N{}hw9(*i7KzGrRAGBUhGeC8k%L*cT(0`){!x9RUAXbL-vMhI^UKK#TYLHg4qn z%k?9$NosV-DiQsm_QnLoR)FmZN%|#DoHJ$PcrO4Zh@3;Ocfj+8Y2M>ZE-~vh1Y2yS zL)7#aE(QCZM!Qc_3l+hv4ZX@mSbo>V_c0eO>uI@WNPVX8>RYJ;fJF7(WZqmm+o4{e zeozgXnW_(8TlCe~3ZoVIe#N$mbHAzdH|vqyt;f@MNI~1gWQ+mLD?_Ul7`mZqLwtHP z?k@RKKn#X?6Z#AsQCh`jiufuS;!3^WSHev`axJd$V*h0a{^I&IE^3q zR`yx*4O!Qm#azXCv2gd5vYotGhZ4(LpfFZEku&iK&mj~sJq`w z_wQOX8_DcL_f#{|bT5;qtq(h_UX~ilRMZV}(o;zV0Br2L8nYEqGmv_-mBz6)I}(Ae zmwRJ6j(Th=ZZ9;Y)xnnNnBA>#%DmWr-aS0LNC89k`4eW~bavtfJL?i6TRrBMqdG&m z^2ZedsGungvSi0zF3TVSQN&zIp^5(Me!o$isdZ<+dyVT>>H)$;A_gZs9&6YJ-GH2D zGRg2sTVs>%E_5cubv0#FDnf)tMs`A#Dp)TX7~?+5oKqw!7NMxcu5P2yp*Hox)m$P} zz#v3M*J?270QiQXy7W~!n2Niu&^gzF0Pv6nT4foI;jr5)4lYi^bQ2Rans*hq3}XHA zebyt4w%)d|kmRsOpHd3v62D&gWH^p9*EU%@J z^lo{uj#Q^#WF*CE?p3}S6||dksL$x|tVExqyjSPJq6U-;y7*qOqWQ)qBxgld!#9(c z4N-x%j;6L@O4&lH%;D{m14D=NHK*}Ho*|230zE9r|Et0}uvCrBT-#u+1{1-!DPHj!}A_?FMq)%wHNgRvvye_K&E7@g9WGcDF}^K^4mZYLoH(m}rEBxelIm_>!l5jUSpHP^a;p}!q+-_U9?#Ql zxo{`UP^Vx#P_XtDO8M(_(Au#%K-5->Sg+>RT}Z87LuzykBT&t*mcumAUbdwGOLWN% zj!o19)@qE9pDCZVg_^-9E0=sAapo1>+i70aMNQlYPL^q1J z2~uPWY9JCZ8^bW>LV+2by{%%%C?$b*1w*ts%4rH_LNtZdhpjPjN?M-&ZU>*FViIos zXd}-wi?3a1sc?Xb42RJDx<#FtOU^BUdW7n5Xzy}ut3Z3RSj_6^n+Aw`1H`7H zY3^Wz5neM_ze=x;nK`Kf8A(io+Fg|lE#GSUYbq>YF&Z@o(!1&%gK}?8{X&%JY8=Gl zw6(aSi+3nX_57)}E*g-CQs1Byx<+sli@asPWWi+^8?R(lG?H3DTIx6|?aqH7VCWZU z2aV|2XQlls(BCdVQw!h2NOP1CY_66*k4zWqCKOScKouF;&Uqh3^UW~##6sq@mPS@% z!)f%jO`U#c^z$j*r?i-NZSS&E^SHiSpkF}xIVL@WXfwpOgF%{z(MSM*pf`ndj}5s> zLk<%q{Z7ZNrVv*s(xheihb(q*&16n)mkEkI88pI5;sy>)pmp7(M3@`rH<`1>dgRl& z&1bo-8KNrf?a(QLoLg+=$d7O83k|(b0?E2CIZI-v_~w$=3;CG?RwTRtk4;{# z`btq6?Td<2Zn40J}*=*1OvJvUElK$ z(hDlk>k;n8WWLTM0)grGngp6E(VM(SE8W2LLMebN#-Yv{JhZe2QD^1$Vpph`A-gws z3kNyH$i@ZDo`-~iE?hKdlnP^&AW?~>K46)tBx#dkNHm;=p;(t==I!-*dMEo%shsh#81 z&9CF(?zi!+XRqUx>v!>VW93a~*z|@8ib-}5>EPiL(FR4dPa}Y&S3$+*`cS{5U)c*l zJ)k3aN4*cH&oUq6VP$jan%h5Vp7lm5ChG>jRIo^AMY0`4hStrNflNwLWO^YajXQ3Q zl6x~As-Z=w`h1#{W=dJ)QWdh&grrwPiL!ESS@SAmf*ieQ?g?nZS3<* zN}Zy3(!@pW27bL(@2rEC`C>E7o-qN6K&#G@a?Vi52u;1mnR?m5$Z5Q~$;_!F8JJIqSmJo~=Kmk-04)2k*bA zO}hBJ?fY$cT4z#?eIMwhCfA@eS?@Y7l{Z1z%=_%dA zqzGXEv+bI?dt%+cOJ>CHZSkE(%-qSdyqV8Fzf)-xAdD`IGl~m9F95l~a7Ywmk7}(0 zzt^_#AtGXLB1~HTWgZhI-9T^##TI)^5S)Pr0Z9Y2(a`G#V{WA>AX7u@6U3GJP6L@> za4oY#XuMvGpT~OBLRejB;w08$G)li{@9wH7p|~)Enswn8;#DVkHYnC+*fQlR7;LL!5|#vn^5Q#rDi(8;d!7s#K-V}Gbu^)e7l0XBV#hn` zN~Tw0n!?9K48=+#DHU?4L>YpH;Q*^}_j3l%zTqyUxRB!Gs?xlf3c+N10YKC#4f5{n z7^h*u>KrjUtK#PEaiPybT~>8VYi2V=n>S) zWRShq5c8>v(^G%00hqSU=`66>3j~)yf9CK~0s1D(7(S=5uvjE&^9sPDSI_YW|JiTh z;@|xSrf*&2T0X(1?G0Uk4z%t@+eA+i;A|UT4Nd8iJ|hm=t5bh4+Z@hWPW!MA$>N?O zHu2zyRw4&eF>&Rmao^$=)pXSmR9*2X`a2(h$6Iab#xG8@gY`(_hEx?TP>#p1QTO98 zx6(D&?K>yRIQ;ahKJVyMkii%DPNj{Cf&cQE(2jd~K2@;fI&`(45$b60be31^Dd9x| zg(1^C9F0mMXkziyd5uMXdpS0jiAMGf;?l1~ytYuB$$493Ct@2CZ9s4ykphLqkSg9M z3NRjM5mpfB*y>GG=4-0g)}KUd7YBOV##Y3JrWu%FeA+!H1Y({atY55=le_(wH`R44 z;p%htXoG+FU;NwnxBi3Q#0T5&;WvNhkFl4(K;zCfW<%hE8{_;B4~|1z zQRkaEM=Dfj;~~ytKGnPc+pm};zY7FY%=!DBPDavGx`!#%p+s$Uq>+>)g$T}uAx>%B z<8S^Eg-SH(2IJ}VQmz4JBs~Z80e}a9KJq-^&#+E=mwX%SK&A?w=jZJAD(aM}5;Oa4 zx^shIiw(}vutk?GX6+C>fS`e~_2w{G7DJXB!_2cd`*K1vH~7iaC9PGgTaT*gvR>;* z$*Lih1<2xkW7j>tK<~*d@@3y^;w`j%e)G-tJpYLxC23ih>$9d_#5g7Yws^@ZJZk-W>Dl|Ca<%jpT$wVo&Cf48HQI_SPUXUn;UcOM)om}V}@pZ z=>HP^#raiHs(!s3Ru$w1YGrKz%y$)LPU&+=lOZYt{UNZqFc|A|?RR%Z2oyl`IJq!` zWCyU@0<$Pu1J0jy^tK0Z?FM)5me8xAirM4?`%)$VSo~A84IVyzh_`0O!5TR`V^CNh##bO5;YP=2pCQDBMIPCVRte#^RK8l-$*x0BAe$w=D$rAn8H@wU(-z@&m2 z-*Tv_>tZ1$SM{ZfZFcr%A!#C<&0Ug#ChR1}q;OyqJz*Gz!>GfTA`C!`Mw6;dH6 zhCBPtvI>Q#f-3^)#D4g`VVlBW6+(&vd7`729sJS_e2ii0d#<^4UD^sHBcjWvsv9_( z3xpE<*y0bl%Pn1BLxL${MK$_HS>0_af@!kYI&E)#8a7hyB(`3I}an=YN617hHohS+-85o=daYcoZ}T^CJbiJYu>+f z`(nP6H!iFhiilY&%m?6MP_3CT76wkDYy^oI+AR}ox+CkK8;;msnb)Vi-&U3I# zAVZ?iXbPn8?CSs>ufFjHe(yi}_wnGj-@qro_88CbE@b)<8a_hP84Y_VI_97yEsQMb zK9$blBhR!l2DkiyXQtLbijynb@?_mze{i1SXjTZS(!CV^N4{CB&=DRCrai_z3okmm z>s<3a8g+Y>Vv;mcg;FgtM%!>&8R2Dc7sZDpn6$Jaf{x7O#*B5~p8;kstT;`JK|WLSJ|SR9OZX#$2pF#ZfzU&Dz$4 zxpySm)vlTAAQ`#Xy6kq~BeWbEP!0yKo`4eFCE)+XAzO|5h z()AZEt~g##Vy44y4dC=D&6s3m8&)YIlisqZ9YwN3W$w5qHK1wewqql*QjCzy0iW^H29vuLn(ji@3$LVFW<;djpov!7E zL~Y>7?$x(4+VCq7Pw6*ev1T&_L)Ax`Pp&TXda?Ri;#PFs^i&*HweY2)W2DTc<(oP` zP}Dg*I2tbcBj~PgD3GV5&U1URd8KGg4Lsuo)J-v#87fg}Bgd$9g*J)J;MR|qSBBnF zU}8wJ4z$(-B`ZbmywB-mBt4~jm;}H>Bx)3Z_+dxEV3scR=P;xukV;{7XWNwL9q|&M z1%0ZDh#9H^Gm6qcS`^wSzmhH<%uzLPlsYW$u`R{0$2vJtRq5C@K(K+}95O4mZR@*0 zVkaYabE)2k)yt@F^Bu4_aahdAWN6Gnsd?xPn@0_8DoS&pf4XzK76>6@B;in=Lk0x1 zh5*uxdGkOXJ{3ys#63?jCgr=caP(FveBHO#m`NCc=fZWUO#1nl)R@VrLqG#H6(7oS z&HD^gjNuHEZ5DI0nTbRcSRb_!ab#PQiyq8g^17F@vzXD~8hD%2Opj_Aloik;sY|8&&m#sxT_*0*~LQ z*>+0vZu~NrUdB9XrFfs?luD%KJa3d#n3t6yjV?1~o^g%TCC@$@B44#Bp<@ zPSCTMo5(rGSkDmKxS)ZI3ph|?+{|je548c>IiMRitX$jYNK7!QU#=+l`a64cfv^7V zck%RhU%`7{dxnSY1H7UiVT(%$_Sl4bFvEs;%qrE=6pdxqr9(lNWK#6XgKAuFDW6mz zBxxi@Ws*t-yj!*P_Wr(6v+%>UK*#KPt}7;)Y@`0b%`Pcr;#->`&Y`_ zG;gFjn{7m)yGVW-JSA0MD*FZsGL&S5uu&k9mvb5OEW=oi@Qe{m&HKW6kv(mOQl1xW z^TZCVF8^sq1{uvq?1FiLaazz5=J_Y+n~$L~gD19|V^it@3^Qd1`YC$X z6dRGEn3keK?1Il^RTwJTHWkd9K~Yc?NWrcxey7~c*x+`xu3Yth?Jl?G##N<@_wK%l zAkJI_Y6nmOA?sCfU=jqdgkisuukiq>L&G3zC7AvF7X29XkA*NFy%Pm1bcpAcQx+%v z&t?s*;+JDvEA>zaCLri(;hFGlSp{N_I9#%VBhyGayBu@ao0+OEZsm}ZO3bW2)PY%q zv!Nb#gSu{N;sfV;&aoGE17LH6UJ=39^Ia2{ypIMtpO}m$idm&>%;Ijw^OBm+@$MVP zw(0EKB%k#>cnQ9;*G!g3jX##_`BF| z&e5@f&Wf|w&hg$iF7VMtv7Z#${Lq5pR&QDRj+nSeLFTa3z(jzp$6B1!+(T8|T|mO6 zvc|Nu9IbE329x6uS;-w$YPwpyoK3)zdU%h(Vr4>YCtPb^va4N#Bmz_Y5Uz&O9?y?% zkwg|c!c#n654zXAN{OiTq2br-UO26yV|Ew&9&Ph}5etMcM1u&IaA%smGI*b(;W|0z z@Pv*kz_dKk(LafBX#(&hYd5l6j8hbGR7bhBN`rL{hOxODA|VW#bzYYqQ;Lj0AWpF; zCybG-x8Lx&%Cc2UT}14@VQ_}M)XNWK}O$PSqC z@|jO8bt&y?WhvD;bV@H*64Q3NqibSg#f=iX*$n=Ta|l4+I~qVC+pW=$xdYnKM6o%W zpekrjo?!p|Kg08%{{r*JPYP&Ll3ohR+NtY@8)tlW!uf^Z>)+ks{l7V*zxs1*ung=*fNcL=0Hr?~xY=~5dS}fK?}RziT`WJP z&JxHJLs61Pu@8}ZmxY8LbP9>lnwG=OQK|18rm{`AdUyO<$}W6~eeYWYj+iMlI5q

aMH-+t2_=d#zXvJJ>t#wRcqK59K@%a>qwa^$eS6x0pcU~SGW03Z;bKHO%Y+*#f z<-5zUK5UmM;|voHB~L0?yD%D`(w8%h0$US7*BP_Z@~u3_1)gHB*O;3b`Bi5$nV~xS zhP`j5!E^voL*d`J)PV$}``qpTn)INBCPL9TI+uE`)!n|Q`+R+(zN6*ZA?lx;h5if@ zpLZn4+|+S7G7+A&uDPKx70y>h+75w+e9!h)ib+)Bf;aOiDLrsks}*@<^`s&bNs;;> z$IqOWI4V&Ho>_!&m|)k|#OP(cd~5Fo()4l{vB(oKw^ABO$pmOaoKUXr7TVyh^+gz}Iy#&R(>TEAXk%_brvXWHus<=@j)p5j;RYhfaNI2} z1OUEY7=(dU$=Lnbwp4(9%qD*>EUuN%Yxy*TxY_2MZMtC$P+%&^&?Ofekfq(Y6^EDi z;qKr>GrIDNR#3IhXwCg8t0s*iUTK3CrM)%-g3;A|ArLi+uN)76aW^#%E-GV7lUU;M$;5dU=xO{+Pn%13dnx zGF}+R)z`aB_NN_?4WE(QP#sZ>coz$Yi9+6*=#(MtbReFzDMDN8?a#7@x4Z(-592 zQmuiyt79Yo_BRfDLKnXm#TEJ)Y^$Q~`CZy-9vVDG+~|Yo57wTBeNGB4Q_F+b4Q*P{ zm&YWnUmB3{Mu`{$co>-!1+{JyqzZb_H3!|recv|JQJwyHE=0CjY#B!Z(jEWASH8SS zhwnOdV6WJ#U@wBXDf-mW1em&D7C^DXBs;X;J+^Ib324`(fkiB5Q8Xq&oE6GQ6$G=P zN5%PQ)UnRdbfr#8@1ZSVrz&uECknH!eflWrkazO8Jei?~oBN6^e@l;wSZJs;a+0_D zze00e!*F;kTP9WuJK*%t#XOzJHR^m&2T1fow*Rh4z@8fAZu_Zi@#JSrN^E|3`-F#8 zR%s*s7a}N$pwzdvJ9YHKz6fp}@A0>d9%Y~w^3n;{Z;eu_a8=I3jjJjmq_NhRpsrjwEMlPWMF;_#E;Bs25<@JWvQ#@ z9r3lCDvAJYgVtUHHgDqTgXj3u&5ZZYfNPl%MmM@oLlChO#de2i6b#@e+eAU2d!Ny8 zDKJAoW6Ujg$RzSFG&i`hP)5ZkjG<*nn60=_q;Nq*sVSzClN`ay)>inWDTFD0xHu*1 zf*vpg=gtAMQKLH}6*l7#We7B$T}(i4n}1GhSZQPZ9)0EgR1L!L{-u^AVoFdTZT&QP zp3EM7IQDP2OD%;ksYZkHerRmXjf0b+wc-&9QR3It=XVQt&onLk_uYiIUihjfJj zB0?2V3Sr;)_dxyD{^X?L`MLfSe`COV4_p(o2?9K*Q*eWVM8_q7AE3z(F$tAH1Zv$%F(iP%Hj`Sa zDSl4^X$q$sm3NJGt-njRDfvlg7yxD8a%8{I!O z>4?+pPWNulnF@3uOQTFG7B&XCH${4^Lqv?Kf-k=hiJOF>U|?wLF^SDd1!Y9f#(q-C zRS$BgwLYk&*WLadqsaQ3>W5-z^E$Mw!)iI}h}+uqG>%t(%I|XcK9@)5Y$f_vLvEo7 z#ic-md8KanaRV54L;PevA=ZPa&qYDFy$0J-Sf~c6J++1zU70(BtdZ?4y%>+t#LXCX z0?IrmBZP;!bG4jia8xAo7l z^u{7rxe?UsQu{*7r&DT^v5G9hb0Vzu+!o8RuvCB*EAuQVFgczi{a&_-eGoS}8yi%C zISxwFvIuTZ!}_6~r+JuWeNv)7ax-&iQ&ES^xOsQ#Z}M7;1KOmBq3mBhvTa}FbTX2j zq&(JA001BWNkls zgKnb=n8XdLR9+NnijnWm1^SNN z(G+poG{pvK=)DI{7i2)rLCjq~Rlu;XxiDk8yNhKiz}$m@!I_A~v83{a)cA%eV~lE; zb<4i1T$k?~ED<7U=r!i8@lK$pn)k_|9SgWK8t7;bfe^-1Nmu_-PUC!Vuc!sCFXe#+3(Pje%4N=spS0kNMig zy5A56OT|Lymhy-4nRHZ%s96|ES*D764ji;E>uLTL^t#BMDxys2Ca$&8r6OS_bB1dN zIRU+O7Y!uybESYT{=9A*ih?0zF%FfewH3^RK1}D(Pq)NL^VMjM87qR2#^+&AF4Mqx z#(KtGS$&^}SjB9Ss2E1sN6YnwHMt*Pe+@Laj7H%M*($2icOcCe67E z6%|lV@G%`igCqp0sstv2EICxAnm5(t=9-c1*j9o#FG)^b`Tap36#f-*5 z-@)(y!GDOWN5J+WaQPbW$(w>7o&z(XFXH9IK|!WeG(WJ$>`Vgb9lc3P`7Q{sd8TZW zpi9)lo;NbuTyRiPbnVeQ>OExM;YyANG8h^L)XTOL`XoKlMF2mTDU>Q@9eOBM>|=35 zqZwdb!EmD;ciLD5+BL+VwZlFrthn$M24>rJb?8Vc`PD5xMlr{AV79|_V%~KM&6EAMqu&fVrN#zl0An4B(jqx7e+OlpqE z`I^EG(O^S^Tyml-eCajLUB-osKJ@q5u|pVOHJ5h?#+Xau2x!i6-$00^?#A6fZ1)^z z8t*wBpl-B)d0M*>G*AYC_VscF2*|Ct(PWa7ee`8aVc;iyYCzuuKY17ZU%v;;XTW|2 zWCnhx0goR8=yrIW0(ia$o?HT#JLuIF=8rxGe*6RI)yKH(SHLIFeg2z(PdENiRaxN; z1q;JxyLLRe5`1|181tjA;9O>GbeCkdHf!;R`WefRYdVn{cj~$uz8~|O^oNHT7yyt| zaQvhNDmSc>UukocZ_sx`&d?P)P>cZRjxWwb$eCD&O5<2(EuZ!K&=N--SqPX`V%Qzu zpGs1MMD^;?no!IT42t9eL0S29eJd0%5kr`P-X_bZE0>pLE@MG_T2nSk+KAK`7hS|l zlrfC2a9q-aqKJroRx`4-gV7@|ys`6EQ=HebXgSLDa6-Xh-wthBxn_N1V@`JHk#OQI zvV3vZe#$7^*d+d1N*wT0`m!Y_gxvTphxes?XEc*EUY&+Ym!O4VHQWQ-M3{Q@s;jYl>3pdf;>C>fW6BWR@ynhAe?WrR}){!D|hIN(AOM^ABfgkSO1Ow6*H9c*p!~igA6u)9&_mGW6v`PXAFkEm{-u+V^px&rQjZ5$ zkT!nfvn~i}+^mZ0f!JKWr*Xvu+DeE?g67Oiw}3nXK{P1<) z`XO-rNbt@h#WO#TDh?*vy$3|DpaWIz>R#1z}ry{``VvZGMN^3um(U|o{br3Cumv* z1c*aE!c9|RhfiRLM?=PzIG8alG=kPB+aWn)s^XK=#NQDh4jEE_F6$v)QS%D4NE&g) z6{OxN{90Zy=8j;>m{DGc$I%&}F2eq|^0Wz>8@to3+y$A^HX<}*rG+5vifl8%EDx%( zH|OGxv?fkB$(>B|pf^Mpb!s+8;hyVKZtx*$$~3g5hMC`O(wFb76QA+e#nQ`W!#FmK zGX)XbfapZ9Nuc>Ujjs&a|l-)k8Cq;tKfD zQ$T+R$PU0)C=QII=HjQ(%&HK@s0d1V^#MhM zL<~^V^JmsWhUSd7rsn& zUe)o41HXoeMb>49>BQ!+Ki8lhG~#3={qm(snUZfLI$nxsWMPj;BZ)304K%r)-Y;;` zaCHAZzD~#2{N}e0d6-jx)pG7kE?-bL8nLW9GQ7oN^?DkqX>EhVe_2a=a_RY~B`;F) z^r^_80(WbvEItqG{-WeUBG5R^UpgxS^ATS2Ct4ujyiJLaQk4T~lJb4yjD#_c)ne zQ*`KJ2uleKq-4ZmI2I~EOXk^B>;&sBXid@E?5>lwjzEFEdi+X3plvw|yh5Yfy$ea= z$gps?RYycoSRDmH^*RS;d1}#Dfd~+yk9;g0%@or+`nvvRJG6wq)exf@@;;0d!ns{h zUW?R#IOHP6+W*`I){1pwBZ&Cbtd}4|HfnwsEw2629rem7SJpf=Tk-r_OlCWwz81i_ z=zTu zEnm>6J0_Rtq8&?z{lll1t*gJ9OPlk8ui0PsE2NV3nQ3@(j-WfA=Ryx!NA*dTef@&> zNi$>aar72_r5RDIhWW4cuzu>Uog|L_s3ZWiJA%^sRQgImH@!~wDnM6{j60%WUQm3_ zZb}woFo{yn_`GSQ{Bnu>6x12vGL)p$DZ+3B_dA`8q^EQblORs1rLhCRLiEHTqcmY5 zT)%*#*d)PShww9x+lYpS(9pabx|dU&rzo$eOkxA{GgwSg`Vf0NL;y9sQ9A?n7m8=+ zGcGrR8IvmxI{-6!6Lf4XKl*MpKt(aPjtL!t$&jOc(aIvNhfPpYA=PTkgQEkBp*fAC z{++II{+x!qL!+i5BSk9)1P;sv$g*@}r=KiNV^$dIXb^zaRiha_l*K`;DEzE5ZX^r| zXo`-{g9$N8dCZ|?UwJ-cdwEUMJu-xf`mVEjK3`&G3We1=pV&Qf&OH@F>xwi#ti+Tg zGs5|SED%8aP$IJ8khenX%u2GZ4Q9X<4`Co1KugS5Xq=P8?cQMfoFkR5mqWv-(Zy5} zu8*95jG0BWYE>#(_0EH#DD;GTqGsEsGSJmH5~J#KFXH$jpKZ!+Xav<(BJoUWF@BI%O&fKt(tz5>=s`->LY-sv;c+%ga1P^Pr}zp_E=A{Z3B=aXOa| zDY{s=7P{dJ{2(XNbG9RikF$RDCb>eabO%hVOywUpsX~++Xo!f0$KB5>Id7%$Ky&PC z;%qLIkZ-%#Ai;anNIg7-pqES9>jhADu;JF+wB)m_>jFv2$B1$Z(IVs#>+9wlZX$E! zJ;gZkPk}Z^e;jPWR@SiIo58xA#TJz7;u)0g;QgAnjQPfGuT~m(59`BmktSJ=kV2$V zdrJ2?E%ln4?kT3W!8~^tJ5yd3_XJbt6ZH5onLjBV$)q*_#duOA8l&BTI?vLRzj2!+ zDd{l1NeYl8GsS3=?N#$+`}|BU)}4oC%;QWnKOLGlk69-gjT9o*3va8fHDcwBpx)z8 z)QzaoV>=>q^B4n=%pd4e|auyU;Di*t%lK-$qp;nm&n zCZdIM9f!}ja398=;YkOv>jViD5$iscyedn~!(rxGaoJ})>pNWajS0o#Zi?vX-iryb z(6UW_)U3U>x0rqT4Fs0(vJ!oA73#Hg>)of>`Zu@TM>s6 z(IOr*jV{+7TP2i3J<$9TO~rcDI=LjstxF+jl;Vi1lGT@v^`@Q&7X-op==Gq|7%ui+ z#|8`rG*>bQ!?S=Vf!J*t8%yyjoNvzL{JrXFm|ZLw6vWEZ!!6V6;PZwCO!fSS@f00p z3o=s|%HtD~@3pBI+ySBk_+;c4{pas9CTz?@E8Dun`q{eI*VCY}3KG?d(uQvJX(g0^ znjlETwU+YD@FeDzjgkkAQjl<^kNm<&PvIGfL_MXKD@nr}-~Ki(uWWOr1L*UNr$74{ z_D|mj#0{S+7N1nNhBjAmto05CA?2q4{UIO^%eoUseWsz_X2KepG^m{$tTs?Q0Pp~q zU&Ho##;aF9#q;eu*vm684yE|1#axf}K97k?1EeiaO@3w7EAG6t9zNI65C@X^(&)a{ z8#+`H7n?b#qvq9-t(A*tlEEkdD?JdFh7A6$5|Y#hVly)Pmh;2re|mt#+FNM;Tp6(mpqY=LIZ{wDHsF-*SE@9H zbcL?V)HZB3wl+a!i)ng*StpOap%%*?h7jw%_8Nf%YOYK+vwHA@5EH$`rj$QzI=3?M z>nZbNBuy><7OE&gRZA=BSwyi-QO~NcCRjzTsWCJ_8dArtyJLHra;18BkID~g>ZK9v zlqvd&?Pk``NIkY%%E)`u1KwUrNk6QZmuJb#~ z^YuYbKO}Xrd3*oU$w+!i_b@dmE-;dXw)m}!d$*AhvK~hj0t4APB;jj$IZ07-HR&P1 z)aNId+hjRvfQB6G{f|Pu<7D(ODeC+%W+=F^y36sgQ?nn8zlABk*(r zy1P-#bcx&M3c`q%Sqf)5 zhiy`|D72tyjbxrNLl;VL7=0U-E}E)<%)X23G4VzuMo|E}mcV4oY2Ylox#*zka%)S? zIo!JQRo)kvAPO03bC4H zs)?S4NVCitq}=8TuK^l@gQVgPb$gk*alPe20GmK$zhF1Hc)_vAnO@e_DZM;tv%$kZ z_y*iVp|w0#D24-0KV2XS}jMT3c5;-|jYA$+253 zhZ%nb%gaRa%c4!$0u494PQkv`fh6PBC6W9y(C3i@KP+#Hi=BtB30(u7RtErm%pv+A zQL2jykvD3CsA2c0=mp(UFJI=eY4v%ob@efE7h9ds+}j|P9f3h#TrnSbvIY-ACtY1S z<&y(hA1mgN34%d;|EY(HfJ|swIZzOE*t(fZ{?QUZ6iprB=Jni2+%4|*3T{TFsR1QF z$xNkwPaepS69={68iCCvC=W}_bogFr1o?DXBWZ9b98@ZYz`=cnYvP6=Hy&(+_}?kr z-^BIOAP%Zfr~f>(%kG|`W5#Y)pl|WX_3OCaU7*bqCb0uv6&QOblm>x&| z>aw#Mg=*RAp+~GO>zfq0np+7qLnCUXrzoGxx^VPsd+yFx$d!+MGs|XQi%Aj#{W~tV zp#I{#W6{u*{at11%XwAnRA`}((NRgtJaX5748wC|a&g~6CkTK!_|S{{f(*e8?|Mk@ zBZu&K0jeE=u&VALmF_Y}Z0H@CVoo`K%~_rGXz=*&_dK19q^EQblR&Wz!N9KY-;r5X zCyg6K*>YXVv-Pg#KpwlRN3j`nh_;NPvy2q-C6F{kqiQ>S*kkcZ@K81PGLxtX>KY$2bOM+ z{ydT1g9Kj3u4RF`tSgPfRf=EETaIlJLZ}!7t*Ay4?=zNT=q5w%%=9xO62mPpD)hOR zm;%Im%zW;YUalmHAHVhhmve*YY^umkpbsZo|8oP6yimP{y74m%qOq_xNZJVi`#{i% z(+9gNh{$SgKx&+41Fs_Tl$&VR5ZM9J(VL-0MLVXp2QWi*wppfg7wgNbD0H~ z8lK_Rjx=PIrjY9!HGAInoq{vV!fXHHlM$-GhjCX!0iB-Vb z*a61ni+#yDa!Mns(X~9hDTs^LciD+!H3bT7?zQo`8c4kYF#03f?9^&mZXc5vBR7Vs zH%IVIwOHh(2`N>fjFok$#f0?-)cAC~A2gR_l{CF)#>+%j6GrZy26?BSG(_{@CceWB z*`Z$sxqywK3}Faj&Vivim0yM&a#-cnk@jf|o*wQ{rkfDT;~3?4f%6f@&l7|}hD|Z& zl+Sy4lFdTW>-DBk?_*YVn$-^455xWFFIFgbVWs%Wa1 zoTiJL?}%vRToXt*cU9SxOQ}XQs&&oF#C;-T)C0OAX&A%?UfQu!{|zVnxZ+Hg|^z`^^+wkLJqNsx0)5;QV9DT<1H*Bt4~5`XVMS=A~F! z8Kn$QXS#`+krj+YspeYCS*mo2#1YS>zEu&Hb-!N#?11(R(DwlS0MP59K27YzUG0kh z@1Oh$^#Az_3tu`3Fn^5AfBYSs{r7)}XJ?Zg7Q*dc=^2Ylx__F>NvAjiw8@x_kA)HBV_k^g1vGY8cHTkNiIPd&^>s z$-lfE)aU)83qK~vQJGQK_sxyl-6;6t3bM%B+N$P=VW!Z)*L(J%*EJ75vNrL==9+~# z5>-UQb$guR-dBZ>E%%uzR79PMo6Eq2HOGl8GUs|(LsHts$`pB#Api_T$9@2a*ilHi zHwv{`O&u@9IAps6Mbui%2>@Z_7$9R22SFg1Kv!g&`wRf@Yu^#Cb`Y7rUrz6!{%^xe zBR9-|9M$$Xt%IPKcnGQU_LN?Zq(&=xAj&3~OZ^$pr;y+~=v{=jB_E^}C&bAu&ViZcG zy)EITfbM@w78|b8mGb0!0)cplid4AEnrB(UjRYRsvBbqW|0K^S93NVJGm;Z?{SK^x ze4z|kDqwKMqa}R@M)r-8X|ypMywRN&C<)Bxny56AUYd2IZs#r^&&?wwZFO2^=hyXc z3QY{DJHGnHXa@pul{~$L7YQPMTrHUOQ%-_%J;=2?JV>k^JEYPbP)qkVF;q=sJ+$tqcgZ7o{w+hWd{xUd@Qt|0Ye>5KJ^6;lh6p$EQn9tQ+Z+LZO7|^| zG*z*K0V+s$8-Oj^`5Sort-lL>GzrV-!@xR2=vp+$Xrx46&f^f0N zLedl1!I({4hS%nXl7dC&l3inektYe}4QRQ=l0R4tev@KV6LKtW8yYVYNE|#nR)$Y9 z=T@%Wo}#yDAQCuzNJ?L6sy!y?#hGppS3&dWT0IBibWoRE{Wrb;;-vmOOQ>FWx24M0 zfR65m&6f^E z>R0YWb16G;K2gqCW^&Vfu+-ovQn#^Eiaa)rGbz1*>by){>ga60km+P3J*9h?$i{TI zve4cDP-!Bwxrv}B=@Iax^JQskhEW~fA0x8yx|VCKSIghp0bB#}9Kcmkl572)F<%Pw z@*L1d0JZ=wF#TY{*}wP^F5kXD|K@9EJe`0r5>?|R*|i%`_v+3zfer*{7*RPIC${hGqo(;|Nn?wV`FK%+5&NS63y`K{cKFawBoV=D7K&L%5@KwY+B zpvb-|9xgO20BLULcg%0rC;$K; z07*naRF`c4M8w(rTjuHS0pV<~xCZ1J&^=ThU?(#!MX`rq5*h^^?Y&YjU(JOJY2G0s z4+?6)QtFWWNEb8+$zNiFD~LWqrST0Odv%Fo$yz1a<~FIk_L0PgmUk=lBaH}lSl-SY zeAA`--6kGZt~?p^NiiC@bhssO0^i$e2<~5f^6?at8yGrZ?9nQdENE~O-_#TLTp0af z2Blw6HioxvT%Plophgt9mfwLWMj*PYTmOk69p!tD?q zVt%mE3`N__`0C&KD)8nTm|mUHf8!eaU;95WxBnem{1rs6uz`jf?I@QNqp9sQ7& zwSI9mrtS)=*FxyJjUmzHqe0MHHhN^;-bNxwf#}!ZUco8r9P8P?EStZZ06cY_hValv zSx-k2aoj|#@0wV!Jr5$A&w`UT3bc(mo}kw@MA( zQAAZK08F+lM4KJL(bZiT{g19Y(+08jDoht0c9MAt&Ejr5fwvX0XM{>^3f=bnXCTp> z(yt~>6Smt8`sEJ&XYWCOaRof>fSv>W(nq=?JsX-d@FU&E zrjqD>-h7j$0}w`EvpTDgMk?&!s`9%3%N4YK7W<1+l?Ik3!GqN%foOr1w7riwtXw1aoW!-d2N!V7hDRGERp9%jE7Q;#YQk5!py z`Mq9NXEin^g9l0&jodgcK6gs&YO4t6XdkUA;j&(2p=BK@cvK(IyO3}4=58K65?bx@ zLC%*^UZg~08?nUukpDQ(0k;S~=ec%DpHr&b!sn={g>mp5YQ+^Ez41f*!~gmcZ~e|w z?Dy~E;VVBzYyU5%_H#_wV}hW03{!eT)K#3R(%_Lxp*(-vGLRd-FW;}+^tLooig6?C z=2^e2#c}I{t17)Pcy(Nxyj=I!*NS+Vq`l*Np|+M(|M1RdS#Hhs?j?Ml>9eZUr_U$) z^DYB=N~`H)Bt4~5IyzP7rkXNt4}dt0^ib8+!dA&W#_KJ4L5t!;{`?OLn>B8 z%M`inz;NgX1dS+8N&BboK5MwZk^d0al?QSu+k?+@sMJP!EHV zpQJ1z!6TN>Ryx4E^0&CLSvmV{muNkuEO%8|TP<)w$ zNl7LtiUI^fFlbYTVZ#O_7zQN33v1zx4H&TDjlD3u^uk-i3meeZG7P~6Ntl!giWEt4 z_#SdNqv@IHcXxGFW#+yA2`?hzoH+mevnsQvyQe4TMj`9o`#;VzPP|S;9AHD=LR;{i z>?o0<0SSZt?Bg3ywz8Biu-c zEHCzb9Y)6ZxCP&Z;2gANWy0ZPD$-W)ezKY9w8E#iu)?nkSSwy9sl6-n9_wP%h$o96%FFPf~OiGF1re zgEHlclGz=xmhoRPu5s~0s)C~YpPP5NyZ+qmK3=hQC zFE7*QJ1bV|V=$aRo!eUkiBsQOx&n2%_ArbzLJ+NcS)uEA*akWq2K$3PZ=v9(&yv~| zigQN0_>t#6mn9S3U|cMGQKXIcGBtv#dbp#~jIM#sfjhYoZE1*mP$^1)f@%=-{awb50(=^u5?`k=l$_cEE;vl@<4Vc7uICNPuqSihlSUg=4IgLaj@IlarI&c~#rx0GO%Hc8}0$+(_}EoiFKJKx;U;9+?~u_T(1dnxAoUuEQ&<5S6~mk3$r z+|XD9qlvU%ZzLqmdgk~RMjrgY%Lvb4Da6U}%T~s^RthQ;?U1_zHET_QUVdL6g+xqO z?!_a)2Ymzal9F0^Vc=fyb{jvFS;iWBgh7P*YD>YeQj;pkocKkwDC2s_JJCl^tAf$m zmVIT>7ahjQalb^_d7^_K1pWp8sx3WB?q9stx48T7%QN7u&7=1L@eS&kh^{%Dlx~t4 z%S=%U6e@Ma;2b3!!|iW2WU5s#eh|mg!DUIy-%hx%ftj;?YlnGT~W-J%Fl9 zB(_wX|5e8&-!ywH%}EfnJW^j6)((QFwO0DlZ0s}h1z+?U@>W`h(abJ(*;>x)J|}MJ zwO-zj)vHO)Tk`3_uhJW$N!A|uQj!x|FRnJ8ov%c%9^2weOBs`2699h;{27!`Mu=RPk=rXdFxqLo*AW#_ZF1UF;VfTwDs}0BK>V;zW8=X1mf= zy{r&H_RgF9P!Nrikt@g^%AV%o7|Ozeu~s%zTxC{2NWBPEEC*UCA&{HWTD5j>xl%!A zbdJ#Eq_`}^876B#oVoh@g2--`poym1@AUic^22GAt(Mq3-U#`sC9CFN>u-3>!Q z7?LC0J~jzL%nd`<5k6dC^HxNdPPga_&+_akeCA_!c=7DBJiVKl%G{`MQJ8CGraGS5 zy8p^weu>}y&EMqW?A$!)Veq!^s#_>t!5h+=^Y&yRRhgJLVFq6L>Nohu|NZ~O$xnQp zfBnDyx7mF5)X-UDotffj_DlcQ3`3e6A;SRGyK*2gdmw2N_TZK&db0v3s)*s0vTFj^mjM9WZ~w2y)2H*ZsWsWk(Lyz=5brTva5 znagPR+B_PMl1SyE6)CkDfcp6NwceH0G?b1**`Sr{=?eeaL>%GfftXxo*+m-`NL5ZM zY-HkGPuXi_Vn@-rt>)PLF1~6?5`6n!htW|xU7jQpJsA`z>fX}Hla%~_h+f6TcJ=IF z8S&jwAlAt;4{>~{L>dYi3TULZE$+NyzZlI?^lm*-7j#X}@O3=U_s*46v}cS;?Tm4^ z#0Z!1`o}@nb!(dK>p-~LMB)>@M*W%Ec3RuF`>zV)^Fdt~TuD+884N00mdGK^)w(rx zwR@c_2ckQ_kSo3Z-a$*-;xi*_RR1xr`+tJVc;foVn#|OYd#(K7>KQxo-S3PPE=MEj z5pEy|$Obb`aw%<*0Xn+jL{3dC`Y zQihif>uzY37_;~Q%kuH@f)qIr=DHy0O)JvIH0SIblO?U-b)Qt4p)}7aDc>jI8J5=- zR7yz5!~s}+EW6h)u531gi6e#`#3WFmR`)6%+7LZXOk2S6*?N0ozQaI|zbmP%iuI=i z-g>#sSm5E&*tjiydYe5uglLhz2kb^FJEyBUo`+}`LSaEl#ZIp}!iNWxsT7JT(?*z{ zo;bZ-*p)4B@f44=`>Cj0AhI{3+iXVfDlm(1fAfg?g$d3plnq6dS&dH}nySLs7Wfd# zoMNI|T$>TOKuV!#<>JwfSAYLLclN@`pB8xTA@%MfHrtIy83@X3b~F(auo?IaP(ra{X{KLz4InI7FC?QO(2@^I(&Wf=V8o2n#bG(#BNN?*&-1HU{$ z-&m2gT1pzzfLP7NSEqUV$=dq^N$x*#Yt>7uk`>9C-ZTE?t@VqI!TA^(pFdQc^1#<# zUha>NT^J5RF=Vxj{o(rqpRhTdhU*Y{(u*77J3kBlXcHcKn^f_9ubI8|jmaF$8sYun z=^1sX6vvC+$DYtgdp}$Er1K7+uSmHt;6vjd!4IPB&Njxq#l(MnT*3&VtxbKLZBsGj zW$gvEVeWB1=9yc@r|B)~S8}vV!KlSC-2SFR!d=I4Nji%v+@F=xSvj8zccgH)?3rA$ zuY~8C=?NP^B)m%1;uI1gGg9vueZ>?(&8tm9&Qo`kaQYtdEcBD$7jo@tx7+*C^=R2_ zvgaUUd0WJd!E$(SD67@6tTv8ZvfSg@(ARq-zJ?2#;&uw7{@m=da7d9K2i@UjMQ*<$ zM3OV>K{=o=Pi{lsqAAW3uJeAB67+Fy{i%%9GV_O}uWO3;Sc%GOEe#Kj=G=0b-V>L{ zIgK~+-+N6}JI4?=3}16T#M(W%th9_;%^HVNTSU>NV>X8T0T7g>gpK6}!_i23gc}Hg zXdzBVKag7!cwi%L))<-S@adxF!M0+S_U%KfIH{l6a0a}B@{m1BWy11|D#C^nIpO4F z53*yYx6pFS!tqcyG@61e+@Z)_sx-ftMaTTN>|C(eqw|K3edZbd&Hv;_`28Q8_=9aR zg~W-dqM2J;=7>gDcvQ@B{bsQld z|u@W~<245~n^B&78Towg7nn~BjMlm7HytE-0rX^4_`t3q#gyUJ8x)+eHR^ekz z^qawxvVBSybGrh%7}FBZ(#i^>Ohs+Y2IDRrDVmch*on$D%_Z$I7b+IG7GFYJM0!WF zd{oqo?#*K%D%GJM;X$Q{N1d7CtR;_k>`5^q$3UmITen?fKPYM(js#qRp(fKj&$M2pmIX~RZWpy!U zJ_lm$>}deT;k5rI&}pQhsRnC{9pchx_AuU#@6Ee5m7^d--j9vDM5m#x zhoZHG<_=v6Z!|FZ%~|y*>-Bfqd}NdxF5mDEELIhDXYu(ti2oSpNl$7 zj7zfg0e4g1aEtXXBPmQG;<}Nx%kQy~lWAODnK@Ki7M(NtrBo`B(B?98)jD*uavsUm zfw>eSygnOxuQ;LPspwqcs*pLkaWtE=Fc{~NXsVm6_0D=OtrQ>o<+G|TH|2C;i_%hb zTi%q-R6E?14&PqT_Tk#qMkJg?L`svJIy|`?lTqE)ZMMYrfwP${Vg6RKOJz{D-~l08gv{h>V1AQ2XMPJQu={oj0+{dX76Hq|nS zxk6t>sRhpy>7FNHoD!vn<$2#q>=MEdVxL)^8<@oNc^Oj+;Xj&gQb&ZoNiHtJlm{Kv zLp_`E(-~0F&N&AqO&Pp?!SIl!CmGbj5aL{1Z(IQtoR9@=QL_K;|ar6Fk1 z9uYHzAt@EC_+ez$suBaIb8&$Iujg^T?)lMJU(rUtXD57cU z2k&q^FDpo$muOK28&OtG#M83aAwcn_KjY-G`y2N4BSV{Pj--Y{)z!l~v}74B7=%iD z83$T(YP_n`?_5JPD`){LYdnZg7$(;qR79(L056TkPQSd3Eu1~KQ`HEWA8IHAuB9?$ zY|Ge^n3>}Ku6gWeN@X*S*Zy`NkuX?Sinv$*z*E)LcE|@fM*Wtq#MVa~swIh+2YC;a8L2aq?2%ec zX9?Qf42j|2*X5PNq#{phoOZD>%fX4>hB)8xdW95@Bxhv|tlyE!!pd9F^jxkkA{aDf zLQXu1;Td%nTzz#}R^WKByFWO637Qr3F7;Q_vrAF+aiHGU*s#*%eR(~osm05&dVKx( z8<$STV<5&j`@%+Yx_qs%wU~=bTGIXX&B9(h`k)$aYm9njDH(NH-3ryQv6#W{z{YxlYR8N43Y5NpRpF!#i zNWI;-K-&q`4UtPuWZQO`*1^N=wPH*Aj92fy&ab{u`Px&$JIrV;OjCrIxWTUJ-?ek0 z5@a4%ShXomEkD;3hE97(6TuW$z}s$HNgk8#$)uhNG7gd|ZlF~cnj+^<2r)x!Tb>U9 zi2wj?AwA}q2$AElF4JlH%lHT6~c{PunuUbG1LNt*D{ z9CM=ou#hNIxQBZ9VkvDLHO5rJTP&38)=FPusaKJhD0f6W8&lCflM7GNL&-i#zmmts zjr`vFI2F7J_}+I>+i0*{zU|E};E8$tXjQk%M<3~irrO&X9v^*89pOU*s?252Ts<6H zl>JtbsWLM=ZJOQ7SwK$!%=oApdrs8mmeRuvo55T{wN(#^haPqv_&FJ^^iP$ES!cfQ z^B?0s`VW7GTc;;{`OB~Izy2@3LY0}n_YeL)-}~d=#WQz5%ER-2$?oLK#0J%*W;)pi zjV;m*{!NiJ9NlR3y{5!hy-70`m|dkiYYz`3+9P8L2b?UN%{!^;^eNI)XwZ?!z!oe* zjP;e$H`#)JOV9_xqko_5lU#7_PNH{neo(>qHwLFrzDdY}^x6wR;xDd=?REbsk7~^{07Qv^$$O8yi`)FWQ~o z(C|hbCOt1Q$E&LDNIdl?qhG~SV}xwe2cy+R3!TjE2<%SLG)K6h;B*3${&RdB6jX1s z*XKCXTkL^zeZWO|z$qK1S`qe4oFlrYutjClyd~S7|H3=|-AF1C9aYuJj-1b30&*JT zyvO9am9FN`0Rrdy2DjC-Fm*Lr+-3XRFHLKCtsZG>&9-!U3{f7VK_X0b$na$5hy(k3 z0_f1!X}}nomm=N zo2S6#{@gXkC3KSUJI+qe`T9M0>o&}@<$bIrLYQ6Yq|y#=3NJ(V%227)Vqy0+c}j(H zW?qw_OyP=(&@~nNYX(o!!5v}j3a2O+I=YjtG92)bJtUUQPZgD#ID`GxW^`05M`OHP zWhmiE(*~V5II3xdgwm>wd74qzAFIA&ADk%+!c9r@J^gS(Mw_QC#m0Eh2IHiQcvsRq zA29tW6VK-={aSRpy{)c0mu@f)k4&v*;2DI5Q8ci_IJ}QjGDs_J?6nCVT>U7J| z%}ALrQJ5ng1>v332o1Ke6l!g8%9I6UrHAg$UeAuFJ|TSmmp;esXHO}=w_*AxuX1ws z6hHAZKftGc>P5a*UPkpkMRx3|zWx-cW>kv9lbV4(ZRj9o+#L@rOUoyQK^w_RZSAU0 zSLd=4IZ~TYjN_uwO83P{8&QWVBs?M->q^j#rc0ej(l=ApogZeN8m(;Jl~;ivJTU@e zY0I`ZdKR>JpuNs(-RnbwhMJr2va?TaR?t_W;o)IFYadAe=)TNdiLM9j%xzI9)teX% zjz@(^^AN8O2FAdnwc!?wSGkNKwGdll;dR>ft)nk4Pl*dxLola?k&?v(rM|T;Cj4J% z+VXn;-TkA+a=X0J<|A#|_B~<6au3J$e-8Ex*`yoBqGeamS^xkb07*naRFA>CWx(kp z+)N0`#WwEDykne1+U8ni(#lj$DdmD%#blYlHSt{NYa1+=)OZc*)81Lq{ai|;Bg7d@cP^u5m%q~uS?g>6^19ZZyxuC!gLCbH`cS}foJPDDzst(=8Lo$m z>ti*RFGIQc^RkhagLkgKN|t?pcizEctHw4Ru9551AUtV(+#EO>Nsn+tAur)WB6TS0 zF3I$gO!=R#kq0-j6w_I!jZmgSEfafAsB9?p8ESa}m6<&-s~}pqm?xy1SnjT-JNG;~ zvv^(<-B3JCf2==C_64D&P<3UVD(90jPXbcVBFr8}T&NVCnI*!>Oi-#JfV-enYo$m@ z`QDNUA!%%yKvO)Yo{!za=-0-$fG!m8)$#`qozQ-A=$Q8VVYotieNu-yyCz0AWW>d= zDi-y7O9j^2r|wp%0F!%ZIC^MU3;Y!Jn5t&HYsz5sPkY%YIrMz+Sh`d)uySK8TYg!z z;ZyHd`mQC7rFKJkYp|v<^|myx*d9RG+nQ2Av{U1w?Xi9`zQnltJK+UdJ=iiUh=D5# z&G=bkJSB}?)EDy~W2pYTk8K;)H1BB+;+Ua#G79}hMQxb@DB&^E*#dLOtf zrttQ#oIZ-mjD80sL;tn|F*Wm~*pALFP*IBIQc;Edrr~OL0M$l++H5<{Xtj-%BB7{y zRc`oDr=`6>h&5H!4NP?g-sa8C7x|s1f0yYa@YRp}31`pz4!8A3d3*Z~U%UHTyt@4Y zy8Q<5h*|bj;6ysT%6W=$-qR1%F|VJt@v!8lK{}$l=|(eN5r)#up&}V;CJj#`w_acM zyp$@^LjDsKZMEg!+ zeNx>xD7B{@$m4y`hVkvzfU1=eq1lXv>#<#ii(w+QZ{aD^J?9hiCtO7>0M$bJEELt- zAYs6(Kt=o{`=xl$Y4F&h%!>tEf6YuG+SrMBeU_`!E=s>jq?&+;7D)9EW18g;UAr?# zWW#)D@%}j-Xt+Ccq#3lb@(K|ZlQ$Y-Ev;cu>2FFd`|=q+!iO3993H|NHSsk-WtN>? zQKhhP%$m8)eV!_h*y#mZnJoxrR%)q8fjwJ9PT5Fh6EcoMGq~&F8o3@`b$T_@>&*Z9 zufsL928Ux2BhhK$%4T$XBd@t}U9XM&vW&ylMcFyrKAs#)?R4WYyz2=di*dZXjLSJt zZ+GS)A0!<5z+M*0z25rX?qw+W<^1uo8P;K59=8J5+LOcWA79U9koyvKTz5Wnz^mMk z-nM0ZM_7ZSk@N^R8iGA8p_465D$;mo6+#o#gNsD2C4`45iUX_lPu9Qd)WdO8>;Kx4y&>cqg+Vv4nE!V|AdtW#()3 znq4qLyR%r>I_aLP+Q(Js<6V?yj1ixc@QAC12NAAl9zcDZy4R+c)%uX}BGp-9T)eSu zUg+htu1XrK1@1*^h-S!*arAM`XciuyVKgq7t3u2{k#IUfu#JRJq(!8M6C-v|Q*~Ej z@!b)h^MW!(D2s=H3f4v&scN3LDEXvrtJmqk5k6cn&(#0(SD7!&c%`DS6}a;hoIVds z@YxrbKJhH|U;Y95#lOICyL)h{g1+%KymQ{@szvC#K*lqtDn5kG; zrRD$JdX$1i3A9|p-jsqHC)Ey?h}=~Ngx`NQY9+app6a9fz;#tIs9bCyWg}PH{!@%z zv^=c2;>3tE4IcP&R#m(5)bHeYksOx1lmq{rPNQP3(NZN4xGI?SN z@m%I#fl0|DQ(bE6scM$;Q{tb&uZR57X)N02^f(GnZflZnWKQFg%a4t>Xk!{>5sLG4 z(TW}Lvc!vlA$l5uUU%U2RfqQo9~M~RYlemVH(W2kCawL7u;KjSGyM9mUZ7vyvAMh9 zr+@UjdHw}K3({7ktsXY%vFr*xlP|W za5R!0;YLCj0W+ByA@aYGSbi{ES(GFFFNGtHGP4;GrFeLt3bj~XpIM+3MW(&$HhVKj z)d};uGy&S$SP-2|8P?Q#!4&7go8gdn#+9Oe5`7gms)*;sGc$}UHN`y_)O`?CJfykw zFjA!b>k5;YQ7FctE|t8baHu9vQfQ}hs4$$~8y=v|Gcbx2TKr`wl#+8ly22fbS+SgT zinP$^R!;jJb^83)9MbMD#G^6ZS=rPWgJ`RdMI8J?s#nvvH1PN0TK3iqN5y z4%?~MlKSl)p5bZPKU1~C_ZW*{mU^I^wLZ4K##lrdQ}1iDuuJb-sk9uVn(oKC5z;#V zrJ)P?avHLRV=>OnM!mwoa~XpNa%xL9qC!`Y#qdJI6Sk#`aH`Ub=rL~e`70n4Ka9l9 z2Q3UZ;jDTHaEdF9JVe)xpgqC|0CPou^$X08&duebm9EZ z{uO8c_ix!6sb&}nL!9B?1he!U!m5abpIvO!IL#@05T(?K$_CX_-~k`|;Ya-JKiqP0 z=S|MHdmc?Q@6@lL^94^ozu{B=-iw^hdoJeRV_)7tMc7LLW+rwPe5of?ov@R=9XAu6 z_f3!rvLlc(tLC9N%yCUJ>W<;|o!>G(Aw6eeJGnb~!r7Z!Y%{F$?Z&Gct<$#74i`~Z zd~^}BuW5d?DGp;RA(@$!zR}c3rqT{;5=n8Q_`BA=FwwTnMp$X9kNL74L5Es+xHcoV zHXa&$(kac7Zl`hYM$E&$Hp6Gz2<+o*T_2MujEqLoIGQ(U_rvY}V~xh@VfqxkAPI7U^Uug=H*s1bVrK^=j3oQZ9m=@t5M(+;A67&$hN%rlzXhBpYE^~_Wz@DsvWgAvxvOWVrOU8$mGnAX(#>{E@f#1y) zq0`5-!XLZaw4~R|mW_PtgMeOp_5rnT2x9a?>f-iV6IhZ|C_EGOH<#wGtg>jj6Lt;{GGs2jz-cW+(;-Qe!{dcQ<*07 zkgG0`Ypq1^Qd1OM0f`e4O@Y(I$YVPdHzI~o1c)M15lb}+8*B$w1TD%emEy+3c8F=q zlexz{^CqScx`poLHiMpDu-7xRHg%LkztopiG zk-M8HI?UOcQ*`7XaC0c^W%Tx`*~w}g^&K!%e;E)pYv$* zG8b}z=!{5ZaxB_&pNmN>Ken$2!_=8A$|N9K(Gn*B_mE`shPE~o!mJf1x~u2Kl%_xy zkAAQo_E735p>Jp{#cdr8S>Og^FW9d5J7J1tC@GWk-peR1*VuhPqQCvoY{c%rM(8}Z zZK!5C2sAfzNU2u5e#O&?m|j~LL+)yx5oQ#9XSQ|97861bsFG`5mm+EsjDp{J=#G3b2v>>SCDCKw!DkgJ_ z1}+Ke_hl%x&!Z=EaJ2VLi-SJpC?neU<$k%a5H0ZWE!IbiAXuoP!yE^Wt>fOf#gISa zd0TzOqgT3|Bus?K=m_6_u!aw7p8(=K04$-_OqC6)%AGsP-~PEDDd^2JmPDtf&e8WJ@7}wuCs#`%z<;^t%6E^nDW2SY8c+iUoD( z*Op~u89o2bkm>!BQ@_8^`(Y`KMoM?pHgql-rg5dq-mRvTj&4UNc{MR=f?QO1lqjfiN)4#nvC0Yx{?$V$tNCKK&@%L};y-3YS9lp;~{ z6fM;qE=`Q>UJHsJX^I(0svE(KkX40ghW+^kqGxE`M-Tlol$ebPI_xOy-Bz?iWHuXJ zkwL%-Z_lOxi>tRHR3`I&Lw$_wo&b|NBVBR`0ShN{Xo_EEOg;3nd6c$EAQ{PU<*~SK zCh7V}&c{HTQ2roJp6~T9hAj%oT3F)>nqn)mLYx@I5Gv`y)pOvPQc4+L>+CaWjEy0O z5ZK!wZLX8Z7GdgYW6@_c`eayBaIYy@6D1v=6(sWKMhKDx*SyJlO z4L5+s=9;88)eZHB9?ZEd`S+S|5aY1t020fKHjM2LFKOtxZWp4H&y&Re!Lx=+w2fgr zw;V0QEjN5O<99cbZkUN<;EwR^0&92)-Ds~XpFwL)$EYYOThKF3?|gw@_^JPkPyW~$ z7y6K*_u0so*_4O2k)~!`K`T`*oOjU43J@0z17llvjc8xq8$2Q^OqcmU!1kP&aYE^y zZmo-retBjqmk|$JqHPrN$@c31+s0n8b01_uB~n+6H!Wxni9aR@F~8h50qt5zEo?N> z>8NOIj6Hq~55Rd)Y(*JAJfseXDMOa`17@x|pYIinV<~RdzK*%LL-r*eF~RF-hHeyW zbaNC9qn`L`-Xk!j6hWgB*N08J&=nUYH7LfaONibErKcOvBtgY4d{$8NK|wy=Rows_ z+HO*e4mhFG4qNJ0{KX?eGjObNQtf@RlkIC4q>>_^{iy;X6jq8H4ox4GEcOk;UlgWk z;zY$zKFVtzv3pe24DqG6E8dr?lwv})R`p!DL`*wW6MD^&SC~~P#Sdmtd%o0a##ll* z?YVi9KPV6ZTY<&C^Q>xKIWl+AVTs3S0P|RCM*}}0-5_?pi&tHem)j9OETDXCnt2p7 zyb9bo;q*s7%QMeT+&aHtqZ5;Cc>C4+oV|HYk=rN}qB}Nn!G_B2{EXfGS3xi6c_&Hh zI@Y*-mW}XZKlK?t^H;u~7k>O{{<8itFV}y@`Q|0(D+0xgpGKOD?u5Zn)eKb0GVu>Kh=IZ#u|9-+Bt;BS0;c!k)s!q?0?#yGKH`XZFlcsyQ!l}L|T(NUp2n4%y$hf#mRw!wxIi$DsWk*NPR09?bXq!a9E0B z3inmAxV=ktSQM$%c#{ZH&1*CKL))g+VyZ4La+vAVkMLq1y?MfRpILX{+GU^!Ws!5* zUbi(Pu3TTP5_kD6-VQE?n)hyrjY#QF7qUU%2;UyCBrt}X<}@J9kW#b!ilWT)lL;y( z&)ngKANm|GeC};Fw|;|@`On$t1)Fk;P@1Qx=}F=B+~qL|`I}5xqlTrI!Q*?=5ED1R zYB&88ST9{P7hsdfsF7Kx>&`2*IbU2V{I-_nE0JScHTQ?skEE6ybT9MA@QKfFX3i0_ zmL=pUs`~g&VI;isc&N} zLTo_y)JzjcBk2*2@NEjdJL$$01WK_SoF>>x%h6FJ!EuG@U_Xwy`vKQXju1dkf`I$4SWi@<7QHx)tF-!*)n>*4~M#-7r|hQ?aV! zCrH^KVuph7z-+_PJc3fW%c?KcwCM`FFbLK|zS}e|%c8p%mF9~FAj7jUwn$IB-kH{zUg9uO}|JOPc!@_~inpUGy<+(zmZg$=%4_XZ_EvnbK_rd-nwj z{P2UG+R!gQ$FJQ1BKj)Jp-kg;eYxrg?x)yQ{j^z_|7iS|Wq;FWdS zFGQ<4v(d(1tM`>QPOTAb-u#O!CX#%wS9QP>b2Em`y|@?F=fs#^{^_IUBV4SnA3+1+UgdORl~~2mWcIu5I3~ z7O_IVJ|y&D9LpHb>$h!C-!7{|Tu+c5-O}G$fdxulroJxU>2gAniLL=17kmv~aXeZ( zTN^IHyWIYToRQawCY)LNn<|ePgBt`#Bk2)tAlUAUd4d)bB1%C$;itN$)bl)Iq38;V z8&&r1R$03%Om!otPJVz=AZbWP0!jtQht*`RDtbw4@5a}GIk6-Aqyz5nyH1X6`s#c~iiu^-6m6X14bXr2asujc1d>Cw@J9!5(w~j{%B#3h$=c zp0Ql1j#rL*CipIL-$a|6^24E=^CU0?M5MUaLACsKW2c^2=vAs5OIp5R^BFncnn9+` z?ZP{1`KlUTNf>5gZ8asgvv7q)J+wK?2Gqgu+gum2amFgKU0rn)wCjqF%kV1WBXlDV zp?qjFSX;X#86l4Fp#cGj*gp3ZFJ)p^gf~vN%L& zPOYg0-|Tw5tjf!8T%rCLw6$>!#i{>)-7ZAB0UOF*R-(XMpIKcOv=7soXKdVjY!gwSPyr8K7xq4gI?_fuhX1$AwWYWahQI6}ekD zn*=GvGN;hVLl{_l`HxvrE8nly=0obRET^%GCzSKlv2!tbSl)z z^QE<2*D%g#W7-G>fm8y*bWg}aqR!h+Db|DvBwT1abG;v%r zr!;$4bq{I>b=bpU*ttOGGqky`^#c`pkaQ@bmFGVC0{1@gY2N(IbIf`RRm-YndFdjA zKRgTfPA7|Z#mm%+NcPCN0%#962u14Jd3M48T|>#gp0X7}BOXE;;XPgA>vM0$+%hnh zh^E&tq7IVInu4B`{V)d1cqEdvP?+v?m?cxiJcY|xAan^Ag(Gia_!#!WHIe+jfdqiN_4${N=4qKtUIDWfY-wKNG{R(Qub-o(3>0zzYXUSkmG zbLUD;H@K&^-yC`MM!|L?oD^YpFPP$UxGyk^Fp03O!tHw#ya>|-I!y?|Bv3ZWqgxZN zePc_VPhfX~8BiVP!k`n{t9x$#(HH)N`JcSb=EuIu^Pjs*+9$Xc$7U0$2&%xHvxBiyA!o44d9?%qvu zP(#nr7@LvTW=Xk`*`TmO0Q$Hn%ZDPU@bQ%6Dvi6U>a_NZG>@)p`7I8{66Z_9Os~E0 zeiE~ePq87kH23BftheNGs_&Dj`>2eDJa)A@g4Q=r<+jmxRj!ic7}Vtq9UJD)d3MSx zmV1N`Ck#@me->0D!ff)WIP)d_t{0x>Cx7CTy!DZLeDTlzg585ZW%}t0PwV5kYojbV zq?+TG%UiNW=f;xyy2$uF;^W9SWaa&_NxHbdzHV}e`&!F7ebDsW)z(RF>$q;mb=*@F z^!s`2a(}MA_PuVeTo&KgAq(``su-QzUoCxB^(OscOBB{EwpSDn3o#Un- zVo`uwr<4uoyhkq-_GUblNm{u5=-DY$6%$D3icF@&s)U!S5#=I zig+rlJ+(eS>l?sZz>blG<*>Q9KJ(q5`6QqGxBfc6|KmIEmq?NtIa09D`!N0nu?zc9 zF``_nd)u~}oSi(5UW=P-ljq)5A)+!%JFz{7WM8qIBq+rB%GR+6WlgLu^0|c(wdHn; zN0RX(etYiAIP+qF_MX7tt?AV@FJljx%vtf9p`A3g(gs^mi^%oQ>sr!UTi-?K$9n;q zrot|y(QC;%Q?9m!Ay*th+w0jwYANT0hc4QTvvD|pHsj~QDAXeVW6sq>d=+iEda+ai zNf})leI7puF%HsR>;{`Ix?Sq2e1vZuC~UUE*1fW4uoK2H?@%eqMue%tv!6cY>F>7R zy1_T3U^*$h@t3!F{ZBUV=$`YAcQ`mKAr1hNLaoX#|I^>(SAXxf_=W%M2l@H$`z&*L z1LYhTE^#&7u*57ms`o;uv=XBb$O~d?T?Y z;o);TbabUmelxuo{dV>wjEwO(C51`*lOHtnxGDj_4O@8Q>e zHficgH%NV}%^*kk=3z+_g9f)#Mgfm@)5<4*;3NFQ|K^wYqgUVHzx}WNXC6KGYt(=D z2ap#_6En2f=6g`+?o7advdeYUH+u4WYo?(!u9BkVk{Rfrudx}uSQkp9Q;F-rSxOq2 z+|Kd;UXUgkKhvzMrVFWwH0q$QWZoH+zR%OLok2gYm#QR>X#QJm=fR!F@xH6^#`gk7 z%m~w4&hYxpQ>_CY-u^EMFW$Rz+T*~$z|?nFhP5g5#mKXLof3LaudYWQ&U}7;ZJpnI zu5vVz9^nRpu-PcnB$m{FQuh5+6cY~Y45V(n$)VU`Re$zQ}<`4AnF!76lw;&K==2V^)-+$11|#?jKW0_ zzmeVSK2kXQ{2l5ib}+d?R?P!ed;ruB4l;eT`YCtCjI>&;AI?0QsG@W`+kyOIgt_H> zaYe1=6NLp8UKSv|PCo^HdGh5#HDXE9ho51=N_ja6Pt3?sr(J1oCA*Mm!))znr|S5- z!Nk{g!^sBJM8m(C1p(Lb^m>fn(IWRF`- z*W!pXP5+1B(sz;b^O1rhJs)+qbz<+D7}t}SKN-{ypz(Hw8@hC5+-i|`mBZ)=?=uK+ zs(#3|(Wx0j*-f#7ytY`bw0G{oS$G|{bPC3YcHgz-&gVZ)`N~JQ|E0gA?*0|1f-}Uk5nKtHuuh8>R z#iowuBn{RTUYGrlj4=FU!y|2@%MNdI(~$PEvUy0+wscGfb#Y&fw=C6V{2leMVOtw{ zeUB>C(%ZGSJC1tDPlR_Vey9(g%_Dmk9kymvFuZ(kSMah(ztQ>%v|P`z3DOWJBa!&G z+FCGx^UN{%YPNp)z_#&>t$!<;gt z<;FMhDG`rmKpdr~Ch>-I!62V6*A*<+SYD^ygw%~Vc`Y~Z)}C9bozV%NQcFA6${PZ$ z1>VQQXfy>WP2Re$SE0seG(MQdazSsysM|MG7Q6)x`fydqT&8_LAgHqV)A5ag=C94+ z`v<)xUEU77dapc5b8mtU)+RN)cYSRbAGzCo30*Nb`pQ|g

6`5-JA=JoOK z=CSIV5h+@={r=AIB|RERk8tCl6yfxave}x4&#rlvVN5I=uav$y(hhfU*DNkR5YHo86?x{n(9Lrcfig|ZwZdHCd=C#Fp%>@O z1G{?!@-~#$pnk)?b3xB_c{yRPFIKical+jfPIyrEh*nf4iugHob+&4XdCscrjR@9) z6hAdml{m@1G2qbS)Av#KaN$O1LPJw1iSf-%KUBt~a~JnyT{5xD6q~r^`{M& zw_@`w5{9%aWNG(EaWCK|L^RhyNi7J4(56K^jY7=^Sr2W}R$daM{6HsaDnHAZZR{3f z{l3F;>~o{uU0Lg_+80vfBVF;T8N@n?rK-am$g(_o+HuWuNd8M*a>ID@(em~T`zPuf z9w>1TR_;vh+fqHS`8QmV5C#>}(KQ|d_x=l~N4O>kY@QM}J16%D``IvI3rwm|XLcLm zfhfD8Fu9>#3Y3kN@rkGT)Gz)RPyPN|{L#yAa{ksgoF+CV1VJwqOF43J4|bno^Txl% z{OD=kIQ=q@^c_wn_`^SViT~$+{}sOfM?c2j{rf-9W|O@CwK7qi9tAE7qJB-1G9ux3 zZ=XHSsjn1YJL1nr9Y&hM`0vLhi6T`g#p!CSshV;~CY>ny+tUXx4Waq?fWv?>@n@o( zW^g4@urLlgEtNr;T}<@K6>VRPK7|sW7rgjdR`HXPhvHo&cAmPH?{By;DD~+f38R2E z-Z;>U%oYa*ot|l(F}gFHB;0so$QVnC-M<^nnmc;8<+JQ;_m2=x-22LchSa>D?(QB_eHWw+cy}F zaFf6|kvTLJr+X%^RJq{gM_=L}|M5TN-tF(_um8PY*8|PvYa(d4I&Y$HlFz)jeu!0Uei2MtpC_@52g5 zBk2)t9*Cm1g^S6Q*&WJG)l*zb=i#;U2h(q)pIFU?e)vv>qR44=FR#g--Feuwiv8Xz z@DO+%<~M-*z`0j;7d=0LavN@M+1#FBF37xr6QNXPnjTSj8R5(o(miF`fjq#xD{u4g z(FOathY^OdgOjbohRV#@oyzOa7arcRKAv(xl^J28=!rR0YQ;uq#tsdth*UO;D|&_S zbjvoTP@21t60OnZ84(KgxVf4JTPHF(4lr-KYR1Hpxl0nb6l^DZ4C@QV6bz=ep;4H` zjF2@9aRM@`G{g5*eJO;AB$_m(Sz1oCZs)6MkbGCJ83G~FHAreZet1@!Ru8QgTrm7V z6IMFDE6vc7)w%0I_b@IRUX^ye3+9yt!lbve${t3J#ry47cxCn-RBgtck@*kd$f6Xj zj?#vMkux|%jxb`jtbSQvO`pqv(@=#AW;8179sl}!W~|s#n$mED4-Y826S#0Y$voR8 zh^R2@WF93`MT@edn1gtAgL;sA3%>fL zuk#!K->baz(O1}?yv*%dc=Jy`$KCxWxU+-P`58oCrJ`(@Ijw@ojLOc^L||kv45ya% z1*DiqMF_?nU){GQJZ`G-hXPFEC%t2&v{1|d>)wZzd>tAE&dOTQ zh~~j5^w6_VF-zweq4Xw&wGh02Vv<5_UMfyi8VSiOIKH`AK*d>x@yXl|no@6|*M+WMjTdU-rbXI1pV5f(_zr2Wk|U{)I4=Va_ud7zhNAM?tz)3 zRKD4EWI9Wmt!y~wo31130mFex@iR~kdE1rBl7t7@q2@~M$hagPzjzscTZgPs#d?w9 zeqlplW1&?y8jeQNBiuMp5zaTTpOn3b=l_fxpw0w5?7TSRokLNr&;(;qC|i&jWM?N8 zi`Z}7!TCE-XM0}vz$4%d;2Xeez*`{a&V25{!wJsMQTYfw^&Hc7ODTov_Qc6EC!C6M zD)-HRqKe3d&E_uXGv@KA7ku?E|B(HIbJm3qC`@R92d6XNIIY~@D3i>bYDMb>DjN{f z+Gl2zJw@C|DtkZJ$wls_`;271hW<0!r;^&*4W;FPg@YNE)edL!@`rvL>Xu^}3TDKn zE8mT!WMi3oPh>tg`8(wajHkJ}M9$I>(n5eNZX9q?P$Fcsn;3e$MfA^&fY}LHQhm+K zQF@*2bg4@Q1zbqY$+8PU15;kwnw*tB#5K5tpoYhUe+@%^Om2J6qtb;r68NzIGz z(04VAEMw`>ry{dC_C|=JXsb0FT@4QN)dfD}8nVDq+6at7OT1IrFkPAl?+D*I5FV91 zXHC&jvwc=GlJ49RYWaq3hGp+K7m*7SP%5vT2=df9diNFBK7xy^OhU$2GtJDvLw@&H z{u#gfr(a=y{)@==8|VZ0*bn{3{K(J#BR>AgFR|q}sQa&@o*(rDMRaCnrWW&VpHMd8 zK}4a3(T$NLjfR^7GI@FyHryLHY71=-6Ra5-M;hN&RNIVLdXc)q zD`o&#DuBUkR*$c>*cEH9rqO7dI_?FEZx%_XJ@#a%{SnD< zNT`FS=CsmTIkvHKuGx57f7veCydD_;!g$~w!abRC8m;EFJY)IIM8cYw>@nYs z&8(U3owSC(6GKAh)`!u62^>ZS1gq1>v%Byb7KsBRt*-t~_m&;8BJpHghI?E;f^Rjj z-+gOAoo8g)zN{x-%NV8vW<{3QL-|hA-{E}aERRug=Xl1?jz-d(2+N2vHOW%JRO5P1`kbBf@(tYhQY-ZgsT`qBagBVww1DX(mruNvGkg^T9e z!fqSpaY@p8kkXt26g-N@d4@(Pa%GC|NtO~Xca}{T-P3)7AEA^mY)W2PPX@CmD_V+; zNjt+Kue6XH!z`EAZ|Abv=k!`_SUhjzbXg&5G>$Z9zL}MDst*FJ%{E`^o2=S&h4-!< zBe#C7-D#SM%zlrxamLH+{dRqQ~ehrl`L?7~Au z*rV*tn@1l2Z-9Oo(H}d)oCDTq zFYK8?&bZj@s3&{QrgQG7Qe*m9|IUI*RZ5YT3r19tQv8rENt#63S6<2txXeI!!b)py zZ-ydTJZv=tH+xoVZQe|FB7LY)+R8#=Ufui3^-fjwoO!WB?(b`9&$mWi7n=9eRbEz9 zE$xC7MXI`To)yrmLxj)@^zd89H*egsv5VIDe73t;^yuFsTWB*7xTWB*~9yT)M}$WIeSXa#_JqRSA1PmsjhSv6>58?E1IINuDA3m*^{C> z=PR=-!b=aP`0h%{(woK=xZ?ekGJ6ZM@v18naZPkRB~I`))t(|dp0X3pV>5QCBt{CD z**C2$+G3cs7VQv+HRdux8CJS+bJ0GD_9@8R#`9pT!kB^{@{<-O7@<1*^uFVfx1*?< z9aRqJYmu${QkJLQ&wglAH(O`Jz-YM0bC*3yhmzBCOM?$|X{Rfahukq!_e$=C5MrsV zjj7d{>tB8@%kO<_d_}^u+E$A3G+As|AK}{{4(Wr@ol4p5D6enXz4i_-eD@#nA6z`( z-t-q-%rAla71Q370gH_0(do87D40inY-7X33Nud2ry8UwdZN+- z^|VS;5wsC0i*zzwq_!0t8Quf`muMfdWE?n$^Mh-xk068CVYrG=WU0qwy3u(=8Z5Hs zd2i3vAoI_G6J6SkODJiZb!_JxtQ`quVUoG)zL?EuV31J+h;($;jica!00Bt62-1EEKA13gBZZpBbHLTTd6 z!Ou&27R3yCp=9_D>mf)sPdXDZZUOj@d% z!Ymu&AcU!e7&Eig6I9pCFVSyjEMnd+lb9E&tH-oltGHL7hkaXDwMBVD--F7*aDJfaOVi=8}En)>;GEvnL|B=Ub+NOkW^ zEFvb1p{coEevD1?7$tc`(ZUcT#JZuGL^nK)DEjXTZi%|0PtEHxl+){jjZ)v~ zz6z+X69G%|k2uP_3r|uY48r1`yiz53^j@tGqsSd42ZjdDhBsI4uQsEEwC^MCiJG8m zM(S$#5lZY(=X&D=npehp(9#&%)&sxtwH2eo5x(`12wCJwtAZP5YFnSBg1kMW@2G7E zg(uy#gXsdMbL1B2*WZG(IoVAzrr0{KYJ6d$qRgOB>M7_gCMJqruz#!a=3ji3(?_rK z>K);9I%V2!dEq1X*qput<-F14rUYw8)(DXg?JBEK5h56AAyma!p+DP9kzxi)*JkbX z_gZa_Q46ZRagjaYTOA`DV7@EEMyovwR$3p;h$n!16%x7ZT6tl>8dS+tsV2ry(lbpH zZk|iQF!SMRxwQOd@4#XIWbwQGik%kCs&6+UbYs0C&Y^8RE-Z4~=1-3f=&ZBPdgFtU zW~kMkTb|690tX(egD$=p@0cfI?WpsV(dTB#r7ok0ZR2pD)xn{%_vRw4z^cNyM%|Y< zlgqL1*)Tq~SXaI;`qVtDSE4G~Q)}18k}?koujvRO4x`q0fPkS%9qRRWPf~6ALSBhi8_6y;E_(4~$f}Dh-#=Vwo&WgD>3X!M z_x$SZ(8cHFPaR6mBgo?KvgbZXcyHTrwXu3H%Kvbg4@c*YtBmDRGg;!PJu~9;&4r_p z^awW(ilTR*S=m%zSL}59y(?*2TliknM@q#!dm@BB6w1gwSfRjlx4rw8mDL-*L` zR$-FZ?T6|Za&Z+gB@B5(_`A7f5-{SU<{4Q@yU!YD8Vd@(QMVxkp z!W#ya!w%*4D}|wtrGvV>tP^WhG^#RUdK`nh&hVfhS{(fEI*7&5s-gSdU|euNgD%CvVU`au77q+NSLX?my}60g)--|^D4~O z`!B)xwDI}KeO?HI^hPSvyO14@@Ik=kb34LPUS3}>=6Qdgr+<3GPyBa3%O^f{k5@kW z1tz)R&a`2Yim+pLUeL|+iB7e(n}u)>C3YEUqvO)IM?y|@S{&y*Bxx-SvsJY@s*Eyv z+%L>6+9vL_m@Lpp1+zXn#@bxUH=%uauJ=4&U##(#YGoYbFy;y#VHJ8vu#)lV)Gj@^ zEa8#iPh5uz_IS8M6YS_Md=*G|7>4Y`z79F>dI^`+`M7sSdKcG5j<&3$zo{$VuMUrU zYuV>RPJS75-u5JO>01AuG-pf6V(nM%Ra$*lg1)Uhnn80dms6md1xF+45pEuc>7K>C zE|>)=7Pp}-B%`#d4Lt z4ZMOKwzM}vwcY`qhG_%0l>J7Ti=t(AI#xhW>{*$5jvi<^T12qZ(wkQ+baIsgFR-?2 zLD`^OV4glgtp#C%vZ1gA3RPw%o!QC+y0;7??qOt#u@J`QsHwBkq^P#mxKftm=Q33d z&)Nfa8cLMETfvM}CDHoe)*e<_XQXH=SA6Q4b+wwJ-W;cLdtFeoaK}i>;Gs%Qn6q47 zp=c;(STC9dw~=jXQV1KPQEA?w5t`b@C_@wEa-VVIM1-eb7c?A7td)8Rv& zN)5xId6K;wPtt6emDZ-KhJSQHH4oWJW>FW?&9iS3_0(DlQj(!Tn<28#loe1U4sX&v zUo!e-twB|o3P_cvtdiex!>z5W@BqtVtdE6g_XIk^hX|BxBsD@4VT+C+RoO{lu8*MJ zhn-N)-(jk-KYJ5Be;s%kcpD3M7R*yq8JA>ePiE{0vxx=dZkV}E)fYhTq30Dnf0^m- z7nz>_1M2j3c29pV_wRg!x_yoFdX8Yx1QGsSeSMpu)ajTocua%!M~jnDUwg4xFnCM& zno}w&vqeOd+TV%96_;$PjjHi-D6A0MWKmx!+QJfDo%ZqB1c4(P$)ZeCx%VD?w%j6# z!wDnkS^L{cTf1n_=^cExDE!qxMuOGP~rB-7$U zC0|?m!_5QG4EBXMg6jw$K3H2@%X?!Wxyg=Yh;ni1%vP?;a&lX^{i(a$e({bU z*e6Ufc{I&Tr{cN3_|#Ny!oB1L-X6;^@G|X7Xi-Lc7VQSe{A?3eJ&K@;$@=Qjns_l{ zVcL-oxUU#(wpw*VZKMY1qn)W|T{faS7eqa24GUtt)178jEQ%!Zr!>khiHG>xjdBWY z^9>ZO`WQNQNZs3Y^;XF^)H$7;N*d<`n&i|lJli08>Ub_ZIDugJ-*x(fe6iOSBa-7T8kB4YFAzpNP$f*!a!zlt)Z{2k0tCBk2)t9(ahb z87;e#6%3=h!s}u?05Djdz6Rl_3JRdifo@})~Bf3drY@Mwok$7=V6*D zyEE$9SD>2L59N_@Q0@S?IC<_Cyl|U~O@V3e&k5+({;cr?VJFy>gi$3k74ORs($d2< zs!Z%;!z>d;_Qtfu45z3t=?0Mvg>yEXv(>^`-BCsSEZPth^uT_$B(>HeN#t096A~UH zA1NR^f;nc<&IoR~lcMhI$s}zUXiQL=A;VDE!R2}(d6L+;nq8`f(y`i?K*QkxE_*=dOK2=hdLZjTRI2FmE_G8 z!frFdgQh z!zBMddv6|W*>Tr-etwzf+YIK zKQi;2b6>rZC0n(q>i4sye!TzyAOJ~3K~#yTdhgwPmOOdR$;{t3f4^UP0#y_$Q+{I7 zHb~CFU8nXj=6Gz|iuT>_KHKe^+0^jyuYWcGB%n!{&Za=q1~t`{`ULGvUQP7PXHmbQIq!tE!F4qfqo{5~{CX^l4N>~)-B1Wlwpgw#f+yU{U5;=Unz zoI`9+nr*tZ3N*PX>723clSMmg{HBWRE~=!dcbk-Wb1$Ed=hAV)iYv^bL(ccv=@XJS zY>upG+RR*f?bgNW9QW+x;e@nzsCykb>t9#snEYLvabxR0oy)78{;?ZwpPwJsd4^ZY zpevtm*ZC~I}G)>a{AK#li zP!TjZ>LKVzD0?xtwWOTVPQW$cF}dwZ=gAYg-E*dQSEYTvv}xd1l(uo~SUG{xj^N|4 zFdeCzx;?{Y{sLvDBSHRe7ii;UegE=-iD+lO?^nZA{_Mb5(%ZL2-C z@sr1-Ic{omQvVs9G(u;a$@|j1WlewCu~F&t&7HG%10xz6t%<}@VhS#aRTxvKPfnqB z--6DWCO&D~^_8D>-xQi_&et+oSMA^JeM+^ZoqC__w40;mxVt>r*m>%YyL;X1X~^Xe zR=)=;K8xFSpRC+-bSFS2r|_ERCXXxhxFe_EqP-NF>x@Ti7NC7?VTo^QOe8hVIz(%x z#$(jgEK3hG4i20~k1tKD)L^C%GKHFoQql~pRtP>dp7AWcY1Umb3MOalx?NL+64D^T z3$5p*3Qj%kTB~U#m=nek{FU7jmUO@ z)C^!ma6wXsoJ^%W9+cPt2mzHq&?HTR=)V;ZvX(GKu537sOzgGOC6=hCjtU@{3Ettb=g zGLBo4Xqb&G^~sAN05vL(xC(N5#2R zBbGx|5f{T~gSG?I)+;feI~;!k<1~|vsr(G21}XI+At=b0$_uO+!}*HtsUeI|-v{SY zj?&nMPA=`W;)!Yo;&G@O&sO96V_0_>ojQi-caXY|^H8yib=yZ=e(UWNgG;HX80v^& zT_LW(HQte-Y2#uGUdNOVO_+J;46;-Ese%)q+V0riIq8T`st5t6aZw~E65EKJf?&eR z=nmoA#;Y;z$P*JQ>LMGdxeZV4y;Duba|sk_Fdy50!L`0p68rwxw%25lkj|N!!G6c6 zqzS>!9yO``2%3((;yQAhCyJk#C`zBx)>}4wb+u~^1wt9GkB|}s#0g(78vF2cu>tDYQEZ&niBpm8lW+@fZT4W3ta_YdEGf3b@ugDS6qpD?3jb zXOk^wYN^w>z-JHLWQxQ^t3cH!!>=MF0lQOC6Zfu>Z>7B}d32J8bv4qtUnzzmd;F&{ zl{9@%b2DkiSWWox3Y2CNK=I8n+DYNA=-K|(j+*i(X{^^gH+hvBN$)EJ+={wwdU2YG z!Bo|GGPkXX`2HJb8gazj{+`Cl2(9=&+0H0w0VQ>a7M*84;I)q4=tS|(QGz&XiEW4z zjT85p+wS}Xb;nuhA#&Qxuan9lsdO$4x0{Hw?jEl^rKS9uH5}M&44J z9xGWnjn}NUU1sA!*S6JB1dbcTe#xb4%|52C>0^VWg_k8P zbsYqycF~c+X%wWDwC)7S25Q>KPS?wy{x6Xzhcv5n)3 zq$f+Wy#P(F^iFG@+p*C6*1h9xbc7_kvD-tpS0;#W)roTFSF_F|bYiQc5dJL~T!_=1Zsf#{U zEy*+Ln0?y%lfiINM2eg;+fod`gHpND~^04Ibb%mdD)Lzhjkw&o|HeQI- zo5}eyB@Osh9ZXGumT~x-8keTbK6W534+#{+IXpsDgA|TXr>3!4?4})5L=Xy`_DMrfgc@OpAk--=9ydmHoV;vu z0AB1~iu}llBB2iy@fuuB?8NG3;M2^QJ4u~+NCt1)IkjeYXIPLPiQLKh+%;+*PA7pn zq+|MA*LeVu>OXbB(Hl1A*o6X>ace%S2Z#hhS&4Gz083Tb^KXMb>KfaOOvkx)r zUSuZn0W(_;`amZj~pe0zxgx01-`Z>wrKX7$Z~^ zL{V^zXPA1o_|A>v8!YvNc|}tqNu`j~7sNP#90j0Bv=rZM384FyH>G#oZ`-z{ZL3?+ zl!@bb)b$V@P@;HhMpOie27gJQK=JCR#8FeC>hLM0LQR>(;UStt&q4}(%9{|}INhI` zQiNJOV?17}*zZU|pdU*sRpWCT2x(F<=VMJGP8NVpFwrLlsbP|#`akox$```Aj-TKe|Jo#>RpW>!p$x#Cm?|dU@3Qh2?bncN(e3mjw z=eAs;8JY#BJjs~l443M0av~ttMLMDsILYZ7^7EO_ktWZAWQm|V_G_Q6=3gVmbjKbh zlAb9v>39U34`~9uPV>}Jo^TWtQc!D1twlR!0*Z*oQKsi#5yl8L-g&A};9LRfse_~> zBQ*szDN}zM!KcY%N#5XT{2S8B+_FLgQQCz?9h2QwydcO9D0LR$vM`sdo7jH3G~VjA zzwL8O&OzO@(b72q&BUIQB5fDx4D)E0rwXaQTkrP#jt7LwW!oaZt$AP_$CHYq434QJ zqAk1FZ;Pvvc$Hhonpy&0JuV4gF0~U)Ip|ECr?GWj&0RYaO>KS0Nu;<l@!wiHxC8ahYYFi5)2 zj(FCTR3YcwZ(F%662{uE329O@M>M*|8?%kKX|bk|Jm3PDJHAkAlxCn(x}CHHO7Cd^SQ?O37hk32zA(hJFbLli?B*+1PcI+NSY z@98R#7_ZoBwRwV0;ux%%3{CG?s#_qPUt_=3L^dW{S`{y@jowk>L^&=^I(Q0+_kE&) zI14e6)HrKs!mUEZaPA0G8#duZ8C42niS}qEq-BYl4m|D~jbOx~ML?yP)B#gFD2t$@ zg*X@qKp|+~chX4CA~M?!45Tev(AX&wl1Mr+OB;`0YfWBM3Kc?#zn2Py2t$pzMbl9` z|8kEcXyK^Ep}t59HpOmQ#Ni~wbEM8cdjEi@AW+3^n^~nSkmi9&I+t_`oVLsYWbO_^ zGmjL1ZX@5qlukn@N$PBla=4hV5Lqg@7IJvAk8(!GQ|5Sk~=b*eY=KD zYtY5n?>y}qy=;U)0aQ(K9Fjby(y^m5mL8B+1ZZa3vX+?YsJ$8?xID|)4(*UQ=*gXX z-FOsqO|%K$AheMz)6rA?HX?E!sHOW^=kQxEF)aVmT5;vgY=!GvsBHg%Zqy{6|R&)nvrku*bw=q;Nh&h(5q$#s+k z;8v2z&s{EO`^>~6x29z~fX{!oL!HU@p!Lh>4%NHAO@7}F)6zZ3&%|*`k#V|Fpi-jo zm^`$*Z7$wJQGkw+bu$z*Q-t*ete?T@8meIhm4i^UgYxFzDkn=1oy%<+B^O(-CX(Jso?ik_o18P{~xI6|7l$~j1D zj(;1E>*8ZMVndYA(6-^J&e}J)Th?x!P11^DZTr=>*V%B*ZA1E9S_8`y>of&DP>Zzk znzYd!F~6o#;*iv5d5CSIk7sm%xK=WA&AwT}tBBdlB?+UXzg_1#vc%G@x7>ecBR2bi zP1aBTBp?*TaRCU~-pV3!Hj2UHr7dkBit~YX93)7yefNy6^Zm*)bp4U?B6{r+HNJlx z&o6DZ>4wa=eQvjR==kA4Q(KcGnV3pQ^Fdm#Gdjr&q&*@{-`5!{G;K)EajZ?P(J7B{ zW|2jIRnVZ+T6J2;c)x0DYKbCRSKrpoJ+B!fNhpm%ScsD$Ax^gk?@vY#<1t*vlU`jMuZu|2-nWI%`TVoZ)oDK^i+|lnscaKvYbRYxwi%n!w0AczG2A{C z()rik!#u)nEhFE2H*ufanrJ@B0=+bSUbbi2Q9jLxz3oBTQGIA8#wNt<&K}bA0-@uY)EuKMvAE4s{fnIDS_& z?Eb#efXQNl3rZPc+gS^YrJ$l9h{tJcmum_Fu@0OL)}4 zUh~@@e@4d|Z6+?Glen;VNC*e9veyL9@Ba1yPmEc zDZF|6w6jN+42n*FI(fW0_3_z*DUTz3Q)7|zI>_yYbHdcXQ+iPKR5`4fZjK*m z9`QH{R_4Z$n71n}B$sU(=b-K}m@1K=ltCB-Pv50!4)v)WZzagdb}K(QO0zOiGr-Z- zK1s*OPh+>u*4$2rOn8CkVv}Ag(deX+y#nLU7~LfjnsIXL2$9c}$AZ3jTPBxfi+^Wl zf|Vj^9@ECiqvQ}E*`8@zib@@|lvL^%5y#P0O7|k#PyJo;u547}7*XX?ds~ZZd~@7{ zhh?|UQeSsm_;RYdri|Gh>g=sicywAsK{WT7DXK~&w+PYU;<)xG9WSK*EvMjep`tHU z67!>jOP#Ml+ny}j4KXS!N1s8CE@Pl#$$*OK0o-1oJgLzYsTYa-|HjgB@sb)8G^r%DnYMNrKP0MoGs+K9id zNSdEZC8lt2q6AGMX-ZwDlFQLr3pAw;omy$HsU1V5bLF%RIZCdr;dcC{@#rq4Rg#e2 z0SRgCOB1j?NwFwPA?nM%5bNVDhYhskpRbM(YHWS}x?~xF2RMgAI(0bS{ z?TViQQd3+oi@RhaSM%{VYcK}POOP-V`AI3J+bYHZQHiJlB_s8&wKW+|NHE3r|Nt>RlPo}uCD5< zyRZ9q|1P^sWk9hEAFEjMEbWJ8I9XgiQM9c;%kmdpdjGk1I$O$eiCKlJGzO>lz$$tR znrv8=!hc>Ne!eqTBC1$)ZdcQa@ani1VpE%c(XVDua2cG7>D^qA;Q2N6%4!ggzTW(h z4q2Go-Hl5NoxXWTu$+e9d^rX>Z`_XR_YHqp$uN@(BG?m|+8O;Dh$=PV zKR|{q$1c>UHPU#+J}T?%y2tnQ`>@j{p;l4z_0guz9IKqRm?N%P^<`Vr>#`rWUH(WMB~6gV~@zE57wr0$oHI9VI&8HQr-){M8MgxA}L* zlg^&aS1UzTCCRS(4zG`AeFNWuu9BJT5xAFAe2No;mZn{kJ!UbFCv$4H0$s#;H;?OH ztzVUmZLPS;1Ak6pSZYi+sZ8l-GNhyqZ@6yTz;(}sNMuD;du`3b@BumCE^%lt>A@B- z&OIlr^rX8vrac72V-Lg4K17W6H=5d2vNxBdtRD0(pRC>09^n!N{=~aDJ|tQnoGsTo zV03Cu&o>!Z^ORRwk?%DMuip(emt86W(!NO$k26Qmh8t6Fn>=pwDaf3`ip^a9J#2Cz zsW2%aAN984F<5xKZXLGuJo>7?XtMt0TJKxmnc)?KPpj3icrE!sw>@ul{@41qR`KJB z&N_L@Sk+3trIFJxFi}aq;=zJ;JTsQZ{VlmQxBb}t!PUq_#?`Y}yUj+gt{!3Y^k5W? z$am{;>aVIZ524j`YAgY_r&H{T&lbJ3*6^kS5T`agQtvO));{~SYH(ZTC@ zX5_n-GRe2N$E*+(9VUqVZu9z}Kr_N!&ve-(^pD$@_>0Tu_bJPoqrV>9F}EJmX7A|+ z9qci_da?%uR++kez=gUFG3|35m!_>}waD{l-ABD|`#0}5V)*?}HkE`Lb`CM`Vnn`& ztxkj6+m{_Rs$FWHFRFkl-ERtanp?RxNyDq*?g_a6Em(-XtfPx`&%aI?;A}&pOCt6& zA^gw5S@LDK{r3r`C`a7?&o0W?bHeUnl7;GiwCo;gnC6G~3(H(^eBYRU$0vH~ftEev zLg?q@E2YVK8laRNb!TY%nh^O=CRgVUI7;;4-+#Dmo%W8Y@j9ecR&kztO|q|FpHz5ou&cl`1Q$Cz330o(T_+pK%QmuGqVDSBIfyUV-uO!8U@ z3kys3>=v<~v-2MbN-Fi9UzWS4rm}eCURtA;hl$>2iEalOeQuLhX$rpfKf-OMsQKZo zPER?F9EV{7SG#!`j;x25(D1?`jp4pNuy)sL{-Wa_2>Ta@%1xBhe83HAp48j5)xVb5 zp-2SW?%!&L5BwC@(Tul zjP1Xa^XnsL4v8rKkGB4!s8hec;!OYlMgOl~ft!wU&xsTE9-W{+Gm5OMV3cF#e^%%J zyvqGw;+XlllwmMOu8(4Qr+Se0GwQPy-@`K76u%vRx#0dAV7##Nf2OK%`{GJFH0}Bk z&L%1+f>`5}5dIrFbc1Kz2Il6%+HeaXUIGcxb*6Gd2j1%LQj=Ff&5G8{&rhaTZ9X>y~>- zE7_2R*QvB#emM=h)rwtPq#;hot&;2CZW$Qwr_mSb9xS_{$vJQ zNh|A+rKm!e_veqdqZ(hNYld7Tq~ny9gFb2-pLIm5br(WwoR3veEMc_-0jr`o6p4N*GQ3IweDnihV7s30S@16>6*8F zJPT^Hza%edW-0;s$0UwH#ACO6y=>08`V!Kh!?bdeyTKjUzU|!>ssAN)M(g96rH}fh z-~Y)4_~*ZzD{~Zjtuf^$0@@aFuHtbFhK;DTuCIu z7eo*o>GUMW9<(A!tZ}f{uH~1?qOywq^_E)NpFaiVG+3#jL2WUwuo$AF`ZMBLOeucz z8D(X^b+_6__VzT(cgcSuH-f+-NZD12t7Hsj$r+Mo7K ztnvCl#mCdoCA_`6N-aBQ9v>Gj2a$j^fEz~WV_k^J)hc`7oeAI;nU<|8;3!ASRfIs^ z8`Y3d5sqp^{)xuFe@v(V8vYv8CdMTd$6St7)B`#$jhXY=FzkMxSJL7%&poxRc$4yH z`ZyqR$*x!Qn0YhDV7{2mYNI8kUQH3JGYzB1Ar-d<_1`F?N<0?sU)IYS_(3QC9V6_X z>J7saNcdBGY}y@a{^%x3w~(>Z!B0GAt$+FI1L^ZQmdM~*Db-&$uFDrX7eYlJzvh>; za>T)+23gHaTnt0*=?i&y4p{lAYjR_iuyV$YyQI4erlEXi4CtT&+KGQkuJ_NqEtYXN zdxF>vfoXIwn)a2uzm(~^zF}JnEL&VndM&|Pw(js+O;*P1O_8g$K76TqteT!;$6scNcljI4%*-3a~%=0>DZpzn2;5?F8p-^H6QKJEuY!g zr7aL=@F*JC!3xeI0`os~>PR0%`ZUaI zJ_>Ai0|ne@Eltg2#U60YVE=D{VL+YbB|&)016(7Pm7gbn~^ zvmEgG8e}rG3-g;Uhue}M$z)Czx+3AqTQ;k-Fe>deV0)_gKdi<5a+Ng$r-WAgS{hfB zG39ytxmjO%pAQJL-ERq-Y}O`Tw>PV{lYwUwKqz)u{(lQj=D_J9Gx-r*!27TP=(x$W zyI5ff3Q$afGbrcKA713)_Jkt|u$Y+m#wNsNVD1W|fZ@d8vu)$@_NXxf&s;_Mii~dv z%r2N2W;&R%7QPJ6b!#U2!(Tv7d!A#52>7VDxIq(l9G}KPQ=dJJA*ot&>2O?tB zhoIcy-s$8qc}BU6FJKC)RdH!vPjh>do%Y3GEB$eldgOgL&E)q;j*#|^6)Z1&N$7GF zxpfH(d3VgCzE{tD?99rfwP>y|12;R=*Sma#(H*p82xKmL*dme_?J=%Ud7tr6% z2H;HU37xY0$G}z_&L4p`oTu80o`m^J;*g8nBFmk-!>-0Ef*d=j`)v4fYKy6SLkf+m zNP~CMhR*i>z>JxqC&s8u*BPFhL)(5iGJ1Qo-43lsv=7S)!-7|Z9Opy z2`t{`ahLyN_pYs5Byi%mb)*qP_|3t}2edKt1XslK;A{%WQ7j|zAlG%hX~{9g_HW9U zi#g*k@OWj0rIFnp|4fPp^MDWxPlZVwr9nt|FcVLT&#zeDsICA_70Ex%+we!6a1)$6 z*fo3Cd_bS6-;OiCxQ|C1hAo)!XHf97i3l%1{Mha*lW0WY2>S@t9zmQ9=zDDcc*zq~ zV9W}qyqG3mV|KODjd z=|#|&CqZe|{imW)`o)H%(TC<;+jQSuDaj|IvxW|o&yH=KktbHLW?G2{sHheoKZ9wD zX)-y%nyTl*Kh5tM_xx;dr|L{M!FV?({n{eG{DX}z_X6`&SKOYngkof`g8stE#_(VJ z4^)*rmb{SPp$Rf~ zsgcbUl?tLDIEk=w^69E`k_i#&bbNm(3XSsX=(oQh>?i>GAt7 z8Hv2!{-80WdesUSDk&((&qu-(W%~}c<=UZY3Hsm{D`b)It_{#iee>3Rqbi)HvEYho z!#3Jey!2lft(Y&GdGL9`7F9HW%KQHP)KP9-cra%!3H;7bdYdtkp23R+ z1)mG?nmy=kPtteLN{wZs^QOsPGBQP$544fCnS=k~Mz=aJ#32PONkN^H2I!7}fgCQP z*6&lOLKkU+>EEorSfAIY(<{-J`LrKhK)XV~-!k%fC-9Ety7i24s1FVgkH^_^&4N`y zzq6Fj4fPEii8Uf(3Nnr`pHCUGP{=t9A~peA@;+zqIboe z1h=)MEEm`kj$$)KjMNw{RL8hBvP`KL2F5#)JKU;7r$2W+`BcQC1*5vs`AzbBg&@!> zd}4)CTX~=>qf61qbq4PwiU_Orlfl}q{fFAlhliCq4gT;9n$wGFIn(;`d-(Tow$(*u z%vd(IUksN90t0hz2mCvtkVJO@=rOMf+rV>LlFm5`65k#YvvSdTd>4gq^B>mDFV*2( zH(z>C3D*&UVWwP%&3JbSuyJ0W5K-=Din>Pp9V9I-KmFm2=k5cf$8cc&`v}t&iZw5f zt>8w+Hh|`foCh`5c+X4SZHioU^<*$)-$^#Ru$v&GF#n_+#C(YhSVL82yR3pS0>doy zl@dh>RrFI1s>K-8(hz$?aYAuc5Yi^#50A~rWCknk7!;k}%4aFWN@6Z2%b^ zn0~D3$W;VhUyF^wuer4zSze)1p;`oSM@)?ljkSsq@Y5f%ifP2WR~VO#2V%``tHPHS z99PXmmLZ~a&~mvs5xgQz2ST{;s{#IY(^J2L7DErW91RV(96}$bpHZ(fu8nzaIg>87 z7+$U+T5YyHuxbCfHSPO{Cq}6WCbDsJboZdk@s8W6D=Z5sU|8|_lB#KUL6%ZQuuM%v zNCa0Y`DP(j?1WZ8ILml2!J$Qqf+Mfdr{^u}IuD&>%~xcN8$ z%sWrS{k($_MH6KUU%^b6!#{8wLV4wWj(Ksy3YCTFSRER3S4%9ZK59b_YC|^Q+2h6i z4pD>)nlwS6q}#f0aP<*NIkQWGt=E$N$HpW4^uyreaM~yA^Gv*HXjp&GBZ}k4e>h18 zock0ooYM97PxtLB@9P9;ghPk|LCZ%7?U!fF_JFT>E2zSf&|9Cf7rNXb-9y{%A%2w6P7oa~Rm&t6nD*umXL@Xr~Q}1QG{aMcU2{XbFvD{yf@n#Fy z9qhXOp<3Pk!AFj-+O z1FnBDJRdaXPSE4;@6-uHtb!QCX!^^eZSoDXP9fw|I}yZ@_*Boey+j7QP&u_FWlJ{* zi+n6Y)zY#hJ_|Gu#Pv@$U|YBpOEd)@MHR6rY@O~xLdaDS2OnEvIBim0rV2l{BjK7H z1E?I10I-;S4oaa3Li>L;G`eU*jvPF@+9lSuFf*zu$VMLJhp0e@QR2Bp&m_^4i1y!T zzJFI7%B(>*kvc1qKnn(!-ay5{Nt+J;A@ zdtZi*7gIIuDc0GEbkM_{w&EBWU&YNwdbd2 z>rEd#_1N9LZta&#liJX*)9*y+lo6wipA>V(g&56y>g1isZ?X;uiZb>6#dAq zWC<%oZbl0L?cs%&KxXXUf`8;1u{$M-BDfUT++SGE=*(3_TGcR%ic!SX)9F<5sV+~5 z&rrl5ECPlap#%J+fg*q@;)vo!2edph5W&pcv-AwK#tb2CkAp%nruIv#o`1k;3P%}J zhq;z3Yd3I{!IOziW|whr)E%Yxr>F9MfcIMjb#%Mkp2N7! zY&h&3>tMIdpY6T}D<%#9Q{SU}+H>n2?${RaHXzrP=-T~Cpq$LY$LGCPz5dTGZF<-? zucJlGUbpG*h}57e&*|YdvMUUTvNWkHU+KPv2?A4byV&J>+x-N@@&ZWckX>_aegypv zLh1aqSinU@&8*EAVx20&_$w4DS~gPB8}qCstil503Ps4SY=Y~DGuD#BQ>UEoy6p}YDGN~Z>Um+*2C^z(i*g+_0kwlpF!Z`# z2dSFSbM2LHIhzLt*QK{y04^!1;J&Uv_z5CNXa8I&mFRHY%2C=U2(JEU4(xx>)PBhB zC@de9_z01Yg<~3?kwD)ag4nHGz9gm_M2e;}t$ZsYtY9f14PP6z)vsTi!yZV$Y!-Ls zi5gA}jIi4VX9M!t#no81{i%6hB+z!7#rin*eFa>!yeOVoNOTJj2s>Jd&3%0#naGe6 zOfs}(Q(UCb3m+2!Xk?n{u>&j# zWOhREbHwzgZ)A_~hUfLBw*8`qP3MEE&n`Cq@8_?gMNUi3DIV5eFQPHxnBNgXg}ZJB z8STCT0%+x6eHaG3{k`DQr8x$I(nm2|WD{s-0lTxbE6v9x>bTTwkR+Bf@?hgs;`5R( zS?J9MXJg+(!lc7U(y3(eoxiicDc{4Zw>O2B%VYTKGNKfU!EjP*sN*=E+{AGo;1{n+ z#Bd?#h2`z6g{2XuNu~5D-bLIGK*kNZK@4L^`IqFHifqDECp3){md8vD3X*0DHM+lv z$iEq)07WqLnLS!ySX@W3mtP(WRm<4Y)wu*dojsGC9b z@5UYHc*c0YJ_ZEZ>o~4H(yn}^wg1*c`q?$T+B%B4?}(NCkHo^Os1Sy6-`sx09 zbMV^xg&B!pO?D<7XH5tMYrZAdk0y9bX*Q_TToP$=#7qHE8P_aVlvkGB;b|m|r|Sbu ziyix|;Bt`tnyG<+gJcF%}zD2xhWYAeZ`u=I{f`V$GJZ}@X^DDPHIUwII3|*|Bm?Y+B&UjO=N$SrXoaW7~ z<9>m*@U{@9YEE19Cq+~Rk0QHij-j`^8om(#BTP%ncdPq1Cu)(6cx;LYA#>S^Im&fT zf0RyQ1u#r^g@QPUX{Ndn#jz5p}AMcQ2;!DK!3}TB4qVS+Ra9$O0o?cvaT8oE;T)ZZL67s?khP%6Ek_RRP}Dk zDI#Xq3h|j_`The%n&x0EiiCN5jMw{ep9d9h!_yzIf$4wgVuw0jn}E07pJ$8?&xi9# zol{*I+%e0Wt`hCt1DQX#j79u$i&XQDxw+gjZzeq-@5ZueQG6lC&}4^lr4>-D(Po{@ zq#bPti9O<~T@FE2id3PmG?OY|e>JF2vw(E~>`nGf4MuGooc}TS*y1xLHm<}I>1I4y zM@0DBuTz_R!?#47nkAIaz53)fAWSB@jCzkCuYisbK@r_lzb=T*`IK* zEHt6J`%1xzC8Zzja#YS3WGX1IrK)AqR0=e#QQY+gx~`qbnk(RIeVMe8Ky2C z895&%cH=z$4v6q@gHGC3RFYM!29LP8SN6}C`x z!xq(DJU{(dh{P+!CJ)bd-|h%g9K+`Bg4;bKI~#Ho2X)Kv_)VL*RWpe$_NV&0I5-^i z<0AeFHutt@{8KNq-a&jxw+N=7(Ej4;RFud@~n8M0nkTw)& zPuuF7Dp|JQ=?R^E#|F6>oQ_?6xc5EU{G>y64eo&2MdFc+aR57hSm?L_# zQtf}o=U1)cBxKq5WR7kLl&9R^dN$rUGCuuEEf@;F%UZUQv9`{M@k zY^QGcG z`1WxbHD(gI1UwNnKzV{vgTV$*uHHWyk8v;OJ@LVcZyON!1-0Tn69sg{z5b6dFiQDh zs(#{Rj0s67a+oR9UPSTV$nF)gzy+d^zQNF}iKPE7X|x{wp~F0%_e4gM5{D&bae-Qu z(H8ZJ$kSIROi8jLi!n)2C{o$@uG$o+?bxM?K~ST3mzl^`3>SB#xo%`Z+SgQXhi5YT z(4kx(oJydS#+k~#EPmEdfFhGwTRB~j?a3%Q3r!UKOXi^{gM#Lixx7ZC!rG0Rv&A)@ z@$D9WN|cy?p{CY;v!MeRxV@KQ38oa-)BO}qv>!ps0G-tPz1Z4rc<@-WhHO{o?&5eO4%5&je~7;NIRzx~eF-EL1Q@JNb%t0eFY zTKw|k>ppnH%(H(>8)}?0zSNAePZ|p^dDlF>Xg7=;Q|fxwUetf?dKiPUb8E+wKeoKS z)-9?n#=w8EWk`Co?cql$M2JBMc_+*)nhFfbLdFZsr5KE{QRyGuqC^U@gyyLr(9EXg zH&0dzY+;!mKynTLxYFkykG9JoD*x?vN1|nQSJdPmj{VF+n*oZAFW=B#5e2C-+FiVD zx9m?qbGIzl->jlt7JxWX-Su-%5_~C4=cLqoYTvdNZCOg^oez7u;+WPA$vFeWRJh3eYomM4tRBd9Ny!+4ysE{2fmi7|-5 zUq)ZO+NE!zAS9oOF1Ak|vQMsDf}#OG2c8~lq87@y_Z$EvAAJgYT!(D=lo=iRujXL3?{i`&VSInToV>* zEKw9F*2!b@A-Z;!$R2+Fu}v+iRosNVICV{{@vJRz*Fuldq_7Oyc*TnscWqn+(hycz zl0xDU6hT@lFO_@$)#t1E?vRmpNay@0Ed#6TIl9FD4yCg!^=UMAbA-pH3!wxPTh|Tr z#}CUj7W0^lOoZWPt|_Ij?3OPe<5jhu&&vopoa~g2x|Bj!5$2`O^u4BvnN zP?1<(#3RVT(cI(v;@dqI|I8fB_-%^OVN_JB^|rX;c`8v3a4Ej@Ri{iQGjVEcZpMlg z8B>;)dOotODz-1LgFd!h41bd0YprpPA^UWUwInV-L?R`M|hHBY%rD$zE%YJ1c z(^R+Z@iy5^hNOQX^f_r{R{HWmORmNRs`5_w@X^zww^mvCdg(dy)-Z2Q zLYbjOAW`rC$pt9oRUoS>OS@6U5HAH>D~Lq(Wg0y&-ChMLyCV8kHyeW-^%DFNc2A`! z--xhIRoCSo(DQlz78Cv94-{biYOiyP%3hsgI)QE$awzRUW9y#+6+Wk=PPhyG-6$y{j3!*5PW!v}XJemav^?=W3_`f% z$dH1_W!NY>NB!&TKttSF{ivg6A%L1mR_I{tHQoyEG!IP)&HM*7PK`fl)&^HL0@Ex9EgWb4E53q~u9amA^mXhzJ?foFC-Qdkw%3BoU`lS1IxTwNN8lm& zM3_%@<$VtN|2#i`ei&B!j*C|6b*K04cmh3GzL4!tnZK`>alGCOhu*Hgr(Q4D^hRG- z(A$UiOpgXlbz^pHp^&4pQoN~C+my_+_~jP zEf)z!N$;p~eBD@!mavOUExH)Q=>dVpRD_az;{GTJt60%Hqxu76QDZQyo_hyjkZG(> ziN`UV%ARh`Q1-8|yuq%R5~K9Z+M|r0HMYBnLwtqVSk?Y#sbm%<~mD2ZF43P}}q6T2G*rpx&I$G*2Z zZzlrne(N@EhKp^HN(Nl{bZg>~@MGEFeR`jlX#!81!n{xVu`J;gT_slC9mdP>Mp)Q1 z1DNI@#}M|C5C~&KliBc$G;X)S5&h6cFm0R$!))X#Dh+^ecag7hT0gjWxWx#X0Xxrl zzY&z0@lrYvX$S%|CzC8^dxGn!4jB;GFxdib_+Ps>REr|pDXx^9`t-HMMzlvsCPKdy zZay1;N3$u~YU#(eIq3GG97mpvW`_sLrc%_@MGL%Z3GtKq2q9nyIQtg35f&EC%QU#E zYHDov3tP&+C$(&*82)gl_|WVDQvM^G{?$QjN48nVVq__qT_*1AbAsW zlNIkk^U`?gHIhB)-WJ~Lg{|-FdLT(reqBYam)w}zQl9T*eXJ{28x2a&VLZa2(Rk%7 zLLBM6x(yf8+thmAGEBc`YAUT#5(Fu%fk-V$S^g1D3pTS)_yEpX;ldxbU;A{;TZ=nO z>q@FM4DzY=$JWh`hnPH65dmb9-DIPL{CdL2MQC$go25yGm^8{yL;5QbL#;cfLXDfM zheh*dobGR6!$`3XM-vDmvK?lndw+t;4YmWVq0~o(O8UPtEzx-a8x3zOc+CLsn$DEJ z6>14&Y|1*NRJwcD`Q`5x%{X!;4H>+?^h=93RF_lVvb|nF4lH|YgE!_LxL^s{2y3uv zsC)5>E5m5aGof1PnCbnlc3dC_9+OLUny zU$6GrYV?M?Kb8fihMXU|a3zcGDOr-0eh0&0(&T3HZXTZ0Nv>^DY~gim2VoJSMwSms z3&}5W61ts04C}t22z;PxJ;!rs4^Cy_;ShX-L~w&1+FLBxGN22?&GtM(sfy_(iy;*+ z;dC{{?%ZNiuj90~KX~#H8WIjM-E!hc3Fb2cQI0SOPfv-P zx(U}m`f0Z#BiL_;e9ZSm9o32|{+-CwOznG=@3+2vMX+3V&y$raZ~dP2S0`S{tzCF}br4h1S@%6WN$B7-y5CJ=GLHN+T`cwo#w{9 zcXpOeBNWL&!B8Aw64=^8b&Y6)kk;TI9q-mTyGvTWPZj)^LlJZiUZ z4H0Zm4^oP1OV+i#w~Z{WUE&GFPHT{fiEK;N$XE=z$?3nx*PQzzp_3ZSyr^JsP1ce6 z=SVhu^#a(OSxSEW!d0zNl_j*iO%FZ#&GS9~x!qPyef; z!8eSuT}q_-Xc~i;kDBO@_cg{3!~vFFxl3C-ZRNO>A2?RusTUF5LsRaH!=22ZpK(x< z^PIOqG$!Z^N~joUqA%mdoYXP3w~mZRKlQt%Uzo25gb16nhPLaJ5=uRy`%5}f2rCKc zG19~)Fd_!Ih?j$=6p^iS_6mqR{9^^|{6yRDhMnPGkpO zO0=p>bNH|&cL`j0i*Z9W$e5Cvc|yUdM8w6p3>0o#4J*`Xwq~rQ2AG5&8-!brdIBTi z{Xg(|>cHPvA=!AP@3BR^`>!;~qyy!CRdgo5@;{PHU%qScf85I53=w$}Y`?DYq~p{u zDkakpcRR~6Q9SkRA^@e-kv$K+MWz7Kg#Zlc__gldix+b7hv~ zok9@)!LFuCZT+=cx}=#7hKu<}oJ54AlAG7Q`s%uE556KS;({}BqOb2epa{NmKVDnj ze7=1cdEI@yy1$>h-X3vu`%mJj67Tgc$M@OY+(^b`@sH01V_kazk2!hNzS`!%H}G(| zo_U}VAj7sUP~VT$#!`4xCc}}1*NsSQ!Rr4$ zON&0#D2JJ3Tn>Z`5GVJ@c}$$|-VQ0h_tV6b`vNGJzS=ls`AI)ktk5pj-}$j%_V3H)bK}e)r}>+61_#;GlC;IC>Z#iz_l@ZT zSCRmckfAYEBAd8Oe>r!KFeR*c<5U^20t3LlUwGzZMu59Si7=Ft?Tvvm1jG7EsLZvD zeV`pngapHj)YGbaCtn_eie~b~4M4h}>NW7{#iXkswq0hrj2p31VOqkFM#Y)_73>|? zmeNI3z39J|=0g-{-e%bFd7W``Q^`bbu3(pk7PXN?$4STc0eqFq4bukzv95`k1Jul2 zcedJbjk%0fOWDAgD>|8F32_RVAzFoOcsdL{6M@~>ZJX|ERfMm)yuxAh-{hfTnK7$E zyT{)oL;0mO(L(dWupjMK%5%NW$GUYke9(|v$qdFhhh`qfN+^T+@<2qD%L8U`){4V( z;v~ZGAZ1AE_~~5iZ=La>dWU$Y;-N85Q220@^4!VB$ghM6=y_mYrB)n#_g<^G1RpE| z#JS|nq0Ufs!X0>gZcRV zr;B4n?yQHxdMHxF%oLwLMSXX3E=cP&G=}Vsd*)NGu{sB>lsSe5b-h5JZ5LBh)dY$N zHm2@{qx6zT$H#lo1P>v`ANX8kyf;1UA{o601Tcd9;gQ8CJe?~)l|!^}$g=&AUe}T$ zGad3$^11mN!*CaVkwaPLi7^Ecse&fQGSb!?#21j=IxPs6oZe6Q{rwK*j2m%!tH{tF z8S}NvC_f>INie|CvAa2YoF2;}6{*Tm!x0f_>6V0Qu@(r4hC}qRUM|TJzVE>zUGR-R z!|NTG`8-NhZ`7q%HjK>6;qUu)0O)`MZW;OKEiH}Ul=JEZEn7I62ZagZ$H}~8aTJY1 zyO?C*gN(WNSmakjObxrzKDoa-gaWV=TsjX*l%106tTnjN|Kp$}2TXf^|C`u0jeTj@N>KT8;(ZABep2CiS zKCZ|)zE5D1ok)fw^-&~1oH{p3r}mnj*B~;2yb@|j7Jnw(2oVc;tx#jOsfl}c7G^Ga zk?dcu!FaO?xCAqWxPPu+$tY(Xl_0FjW?%|yMrJ@VTVzxa&%(PdlOuzRe?|!ko|@sx z8oCoOs3i1TI)P^GFR8^Qj*tPpcj&6sL^g>Jf(Kh2y!oB1-^&-hO=Ov#l%mXxMVJ*Z zH4cOl0)YAx4w}Q70b9nUNUAlx3qeE+BYPpcRX>FBsJ~oO7(cV zr?~ySL8!o$s@r!%s>ft5l`@=5#Lkp!U*zxMa`gM>c2~+nD!mdRrNWYS@5jTu3Q~PO z60?<%d5$xF#X-}m>PhCx$dLI0Mc0evhp0i0MJBx%yPNA2eQT|dx9(0mi&6!iKwW@%QWm4dd48b+8 z9KTE4>S}OYT-MGbo31M;+~2?E^|)URFW2<3so(}9dJXLb&%GDT38^|aB^ zy`x1K4CQl}yYYFJpP7M^(<6oz@?}oTm}pL12Ds3z6E03HK>wDJ;j+Chue}1(r?= zdQ!P7hly>LA)&hG2fizUS`UFKGF}NMl7>#z8(Odp#l*#vYR*VdwgR$gS6i&vWHGMs zTkN8S#LgzX5D${6raYryE#JuyIed#`l1rLu^po#8aYdqYSutvhwr2HJG#Zxl?JBi@ z3@x;6I%V$H4LkUJR!z@YYlOKl4;W~gsP%6H@O7{X^4l5_{Fqav(8k%?#nLj$5}nbP zY$cw|Y%6C=dA5KY)<^^rOp>)S>u(Xb>opQ?N9kBV??UleTKJHdKQ^WIi)_wFUFtU{ zq~A1bBo$9g=-F+m>wMnfvc2oa--J%jt9}XfK#wo&_sT4o=(K`&J|B4hiER65G4YI!r>Yj`&l3MkTut)tQp>#jk z#df=hWZZL#8E?uw@|SZlXXg|8(|)}%gxq<>JtRh(aBnFnnxOinttO%xUe2xiPvPkJ z0*;xw(}0Efl;>626BkM*Q;5bM%T>79!N_Q+jkVPAOQj{FUX=7xQq}SuqxZ{nF8}RDwax zgi){qs68Z%y?w_F^%Wp7d)*@AA+7f60`x!{`{bE_o`8qotUpPE5h|JDlH|B%`_tg+^<)^wTDE`% zbdX9;K*8>|kG&&?1;;LFD92#XM7|CJY;Mm>A`R<^{iaNg&~U$PUc2jx`)=@DkZ)-s zPZF6D_DO-aHvsYn7WbJ9{+_<#FZ{~9J?1mXFDK2YQT29-RA|Bq=wHztE< zfjZ;4Y3k)}V@5Rl($75XFjBZ^oHg1lPhhd#H>|+z?Lza|cy=@|p5q4rJA!VnL5qyv zY)@Z=+7>!ZdZq5Ul{^NYf3$Cp&i$%%QT67g1XyQw{Z)n8^6_Mq6zsTfoP}$FKtQRT zrZYHNFmEg?Ur}1Tu%TJ0)WL?4?}n<)9>a_{@M<22xzyOJ(T!hk9B{K4Vwq7A2KNj7 z3Ro1tKy%X(ORxsshw#&c387S=L=xumk(`U|z9T_Dzgw?=U}qNLNCDbNYD%e2ME%Z7taxuCbht#dR+GYWRdoC8=yTkTQ+gS8n_%FljF{mWC$!|I-N67a z?bl3($F<*H*>}&O@D#%qQS5&zwSPa=5ph(ilV1p!Ki>;~t3oo?kj>_Cxh}7BF$r94 z4UqFS&CW+b5x>GuOe9?pKLeT2yQpPaj%l^Z5`iE^yVH8${EL8511k&NKpmiNS_=k4 zb5f62Oqb!2>5(aE=ffuHiccm^&H0qMzvF0MA39+Opb)t69u?R_S2V!+-v$*XF%(U3 zGw;m~T{mD!ZvK4fq;bj7-UpEceFq&Od&c2PP)d$1k_jy-<&0@h;X%PYeNGMJxwlam z6+Lkj^Cw<>p&VBe53D$DUX<(yT(6qo`L80~RG+%7A_iM1QAI;RK)-pC#78C@tz)C<{x z{H>n}xqEir$ZU8YM8Ne(`4vF{(4sNPF%rBy`fhv)1EJmM6D`w@AQ%4nmOp|X+_@^_ z?1F{?Dc{k&_8OJlCBKtqdwB&>=4c}RB3{KI`6e{fgb4Lx16AXnb;f0G+<2!O8_0M? zdF~7*`CEzqqlfp}ZCMlxtH01;5ip@6uUX}6PLkIy{Rc-NFz=frwqJ6XP0w#Wlz@Dv zK?8J9nSSRXSJcbAt^IMNN*{aE+~3eWZkg&Y;EoF-i{>3uxOoCSjWrt!f}PNP9y~`F z@0JNEmNzD5g`XWLlp$eDUB^@kgU5j{OUYZQow+3RDpg%Ay=2PpS?4yvnLHFJ6$z%(2mf5kbJyiUB$%yqP}@5l+FAx>}Z zpX(>PE?Oe-=wR(}PIR59KBRE44!x)R!4VUNq~LPwFPvh#UvG##HUpkpRV0{WmJzh@ zb{9@HK6a3&8)hu_?o^(52ix4?IHm!fbaMRjyPem}nY>M?mOrCOX~j65AHhPAbaR)p ze^%A*M?_ULH?K5u?H_+0v#of99zPPA9kcP><&SQhs=Q6M2QBq|Q`OlVI7d^vN;`h2 z=}zx+=fCYSvRdQrE2d}DHsxyUp1LIsSzzblv2?q&LycXGGt_9F$~C;nUr?ML2vV$p zpDMx^xZ?D!R;HpP``uTr0=3U4D#z(q_cq~S2N?quqc4cUZRvHQjS3zWFG=dtT;cce zHaSLh+8oo}NGfYx2 zT(C6sUff+W0IHt8xbGi;ey||(`>JbChT;BgILCh|tnH)z03$HzN=%@E> zPYw;xscHjzdvMYtar;5ma#%>LOn6~w)<%&K7S))Uexr~G+oH45kR-|4wzNi*1KC>V z-Mg%LbMFAwzs4FvAK)R`(h@RYs-xa9{Sbr7tA{_s;KO#vOZ9{U)G6NQx``Hd%9gKN zQ@bq25(lP&#lB0u`ZAlE$`e+qTizYHZtDL4!so`~9x-7v?jEZj4bUWAyoH&B^KQruPmzo0mO~4N4-Z>Avpp?b13Q2l3*B-^v)3I0RO@OC3^q zvOLZ^KO#5Bf2toN!8D>~aN9)nb`m4-NFFtOfy$Us*8R#?BOQ55i-sHExN^FpOCvrR z1i*^hzbe6&lG26S>oK~c=cV2x%tIf7#~KPt5TYr^TkPy-f8{SWx2F?CF-5@4S2bop z3*VZzQz83XUXoUUY-$y7blH*OeHl~~j$7tplw88OYH4-$CDZTa?K{ik?MGbETkw-z68#7oj&ly?) zNHuX_99ghGE*!NaNZdGCNP{)-|6q>GH)oTVK!JC{HoCS!Vn?RGTvSB$MwTb|Gw4N% zB@1WFWbA%9p62d*6J_~zqtuOzL7{LJD$x|Kf$Y!BuutXDrGRs4ntV^+zrU2@N0@&Y zbNB8I-oWl64fo`avV-6FKIid0rS z8Xfw3D7t10P-cNV+VjhO65~K!kxg+A8PZpa&+hnCRcHFDc5!N+s}01l`x8F~Asi?@ z{cIVxVcSx@4v4N(M(UyRek7GyRtAbI+1Y#GtOvW-6JbV08rFWG`ZiQ+Wqt&NWv~&@eyFp=Om9hb<0m_y`st48^ua_@!%M7l|x-ftBB^f62zI% znk}d!-^vD{ViR^O5rM4Ql>@>!*?2wR$jo4*#W(t1(P66vMfX($x zFibja=tFp;OQJh$>>V?kS++;n163<8xj*TIvPkU?yQ%nC?`o(qfct5Bm26Z}01v*Gl$o@!L=143ZEzYD_ zD>f==`E(LnHkjqm1xk_4)Oq-hKWQY=y?9E&TI}$9v_&@EZnn|)CpSlzXD;zD7_5uY zVzTmkkaOCq3!Yt!H3R!S04bEwL&RCUcX>o)@D1jFC+n{){IKT-7AOIWfs2JpYbY7H z%g}q0gC~k+!LD|cS2j*0?^6(8#zhr!oW)?Pwp%$HmYt61kZC{}HkOC69kMCegq%`w zVxcV_nMu4{pA9w&15wDkpMH;Z+t5uYxE!ZQl1~^KU?xLr?pUsuY2rwOn?awc>p&0r zb}TpWUk2_p;ZA?Sc)cwr%%;J#Ny!l9IOlSM;x`yNBB4?t%OVOr_%veEp9OQ<(w%CHNO&#b+ zDdB${*>99(I-?8{t&u0;wjOEp zkdgi+sswK_Jz&s-|FL19{SzA~Zm)la5qS@09K;x>HZMAWGT4rU@K$1c@GoZZ$23_8 z34g>m@L@^?#E0%P74?yU9s{+#pSsmk{cl@Aj&A}@$JOlZZKlp_0XTW2fg2ssA2%y* zWm2+fEejM&I9E3KuQwz^NbH%-wr%i!ED-xRu=9;ytTnsoQFFexwg(FG2r`OCI~vaI zPEfyV4IU9ZuY#>>*dQgE#O*Qz=JQwRS9^R|1@1zrDMs>FY@O~7Az9Flz4+v_1p)}W zaqaT$iLAjZR#)P=3wtXfxQxa^YeW&{WWm_bFbfD3z%wePwc)8f%S@Ck`tYNjG*|jc zO*qk`51PxK8%@;69F)vOhHNwn1paDV+-`@uoV}l&JfX1R9v`+(un;{hX>;$f9;e6vG-PuA}k*F{(Z%&V%l> zmGr@7#LO$M>0oKtM7j!yNvPhMC5#fgF;LkY)#&fGSWI3^5kG0>Qg?mXbN4KrC3TXr}>vI2`Xf6Qkf5)tN+MqG_+e;)$O55bqSa=`Hee8^KtS$4F|UavU|rz77$5UNef7LIz$pX0i${ z9-sj9X6~Y9uV3uHu9?`n6U&I`yZgdaJKo3%U5)GKUVoEMn})g zAhEGeGO}(Go;;nK$X)fhX5!v0r&BbFp9h+(bz*Kl`=MI3{LM*Vw@003H4NbmAbUUb zqG+6Izd+FyShET}(B}Op2$z7bobJ!IV4>SV#!wd4J3G8_RitPOITQd&;oUJ{2h4>e zhBY2fC?#mOT*83#s3d8?YsUj;#kK2kn^0E1IQpj!;4kaqkiW(`wd_o_g=3dc-Nl-H z%3eiQ-+K+^g=aP@oC(NdHHMQHtwH#BQre23&-9|7mrs31?I(h@-_zmAAExJQGh|lfh*J^NrFJ-p@;4Bx1gRRqhdd z_S&rd<&9QmW-hdKxhfLP{~`}Oxh6E^KAV?$vH*J~fg+Xe{;loP*8Ox3Ur8^(39A?e zeHXUIFW`_4hMj>(0X0enyiV!rqM*=kvoV;}nduM*ftq3Rc`=C6V{}8o{y>h*`y-+3 zxz6qtf1R)d1Z#1kA3@jwRui{}4+})B6tnbr3gn1vfJ(EnRFR_t1W1l~BNstwd_$wy zhQdr9L8S_ex+*-A44i~a3&4p2uz@07kpAM8N^~YBQyr9nkB5FR_#yQ7hy@TCqg_g7 zK@)f6o#=D+U)*euKThrlGv-;CAE{Ceq!f$)S2?Mf#6ghFzxi^#uc_{90`<%Cb7dW_ zRnr9ClX^?kWLbCCrU%}T^1~7^Fp0;AVt~8>X8S=sb>=Vlf=q?s|0JiyNvQ(UNQI@t zT8)Beoa@(CZraQDUf>Ngj`yDyUJGXP z25#@OjKI`|AIQAbPG@{bl#6RyqS00J{VArG0zWwBLZZWFkaL;hp)oM)T2m-K9-+|E`1A~-ESAIgwZQP4 z2UV$Bid2sJPV$2y^0(5EH*$LCZHOXHly(#&20csmJ@1ouhbuM7lw{Tl80<0@0k?Cc zz(*5w1vw!=U{Y?yTvxX%mx!w+^Qe-R;a~*c4Jj4O0L)#tJ^CF#RVre zorn$2d|dLRciQ7(PcNM{Q;vDE28T!>TcTr;;9-%lh-PNCuToR?KPgc-i%1#B+J=ZL zf~BZXD~ZzmfVWv=nNjFL-F`dP%jT|nn>6rbq>MEP&9_;14)}b|dUAZtvBs4{|Jqa6 zr}J4j3VmY`MvE{dH94&_vf8fC>AHIV$0;&X(W8ouKtq>WR*p-R51WzVa>IJu(?O_Q z$&Ga&7OH_65tsl z{`@FfHKnhy%^H66)NO@r4t?rpobeQ61C)`bOwWBBKHZgFs>LwY+f4B3W;$pI!oi0>ia?go{ewk{h=qO3(P#GFRrntK1xHTk-oMQ+apKqN8Sdc@PvO<`fD z;eCY2<~tJ6w@YTL;)_8&T4gR7`-X51ep|II(GV5fuLuM?*@ak{xQ!wl+uCja7p6ob z6&5FrvkJdBXi^ML(Z5b$Ctq~UyWtvrJGjFmHbD0FkY#InFygX^Pi>MkmG)ZmU*6RS z3=0}ve;eq1r&G9+svtkerxqhU)DkjQ(RB;F-jp6YH^i_Lk!iGin0&%}?m_bzE;m$W zqKMB-&7Y@>T+PH!+XfD}+Lwf=>SlQ|1@Fu63^wbIq=}}`X!0mRq*gvI8skB2pupX% zwY$bP9DW%@#LtkT+zDk zM_@I<|C%roV{t|j#_uvQltsHs5d{4%-$svyy?Q=4sDFJVkInOr9-QHcmL)3~-S zk$GFM+xesCrYF~Aluq!=J4nE0QmJRDhTQ$12d58`IDY+VsM0B!|NXq!e&G~& zI=)!zeIn<7-d5psgU854+(7ue_S@)pSy|+CTLv9A5g{z%DOPDM*MzCD_Q$`OAouHh zetRo4guJUwEEZ-yak$F<2seZ@LF}1bjs59OXI3R8APt#ZBl;eq`w)D`X48-%+NR7o zTE_oEPzj%IOqpxNG&^v=CXu@vQI=aodjIusHO5cBB2^?S;f($(M@Oz>4tI+zk(HnwI0u^N7ZP=Ijua&+JA^9)vp1;0wm~71ioQCKQQlN9FrY^Rs$w7TO%gGqHrBzfL(M50SdEak8$M zOdm4Y-Xcx63NkL%o1ii1NYMok_g6wi-Ehyt_RDL|>oQY}QB1e~&bGy!&wx!FSL7xO zLEK2wZ1YHc=elBru|Bcn!{=0HA-Uwm* z6lf?_{i8HLEo`+ZIxPsNDgS|14E^|I!~6V0B)<0BTEscTc7W$hfRES9)sAN%@|AZ4 z$NR&Q_l-3pa!6C%5N=O2m4S&VhHVcf3p5$l?>U+)fzM@M{@0AM3UV&87UtR=AM#NJ zqQmZ+7r@pq{_GnIua2?9OxR2Y@%F8+Vd0-7(L#O?2lGzonm`CQc=exe*E4Z{>-bq}y@~A(CRWa0}SH zenTqe@6|9TI>DRdmW;gY1%qJ%kB~&qm)JOV3<(z49$Uzd?VP?KzJM^;`03Xwd8!%b%x4qX#ea?L5iHVY}%x#xqwLk1zzGra?^ z6^(hi{-8ue)sfCC!qC>>D5{aGlc}g040diWn3-OZ{?0)S|B&6f#>@3K4WxAFx@)y6 z$NULwdeDZ)@JwK9@vznGjhH%MYmMf)Zr44X0~4%&ZtruTnyF?16oF}hz;ZGJ+uo8v zA;`||&t$gY&?%PB^1RbBSkTF%=9*YTq!gX}nI~a_Rr5kIKY;bWQ<7`S;%kuN^N2j3paw5${;W0sr{?2h?n==oox+^;n1Fl4$+ZC&Y5K71CjG7D`RBInI%y z!~{+SB^VubI01Wwq%vau$q1j^-%pnR=-l)=1FctNlM?Nxy0^;N1LHRV55L*A?NtWm z?(H4r*SusURfeDOYGL{ZF=7kt3z`Zr_L4`bxh5}x|BRe9jZ~xu3nMA&`+||e5sLAR zspR7EHMQ6KeeyJghnrp>q1?LvnRzGu2dg6&E=@ddp5*Rro-LKH`I8n2C~d)tnNrA2 z6-k|9Ow=IrRx-j%Czw*JWmmojJY+!Oqo4p9G)<%u>&-Q=C27}*rb0K85A41PcXo}m zx)G+{=y|@A)|$PF0!r>K*y3FVQ<_Y1gQc)b4AMr8QtPeoj${NkBv}D zaeG&bqcv#qim)XwUxs^+Ughok$tt@-JY3uv?@e*-gXF`Ls%($CkI4C-dRnu|Gj!!` z7FgRuxXrS?dq_Qr9*1Yn2*L8lY8r8+=1|Qo?zWGT(H^82rOpE{twTp9H<{VOru}R5 zj8%&u_sE~SeKH8Bc0t955ylLwWx=Q5luR8UYJj+pSi|`b8#X*JwyA z1V5_(>ra@^SWQZQ{20J{wEM}_7yD%%$rD}=c>I(2^;E|D z*eMSda-(qYqQ{QR&VA5aJagBlf1QnXwabbyf=%Sd-3>!y^Z#)t$YfBZzPd_?%-_Dl zpG@nSei%cOi}`eXqk7*qRcyFm6x}bJ)RfIEJXczQ_Z7n96PP3hH}8s=3hCPVQLbo` zf+SL8yVmLx%z6Sponu=76^#1jEf232nsP@Vf+{!p1F)J(EIlxN`Jt@|3X}wIgx9>B zJ@h0`Km}2#E|LGPq={Yi(tL~Zulpf6m(^-SAq|9L^y>pU0431N^*#_@RD|eqgUb&3?o&jW|d}2oRfZ)eT!J*?rA*K@8 zWgR$zLZSs)rf$e@2MMD1<8OIJz}Q0bvqj~|MI#`Q5_(O0 z5Kz6oxX@Bxk;&1+q~BMFh3B%jpr+Y zF?)W`@NrGi+aW#&Xo6?-YgU@Mo9^WoUrX$L!9;&6+i{1aR50&4;iFu8GR|TxgO9Et zWeHtjm<2~{2A(RGFEm?MEd9pGLc-|XF)gQ(7e@HEiS7AztwU_$U`q>MR@aw~ixQ`7 zf4vA93@b_@D1j=60t{Z|x1m?3NjR_=9@%S7+$FDcash4c%OpsO<}F48747;k49Vuo zVf&+a&?3x1gr{}jB*(=)pM36X?#k404VS=xcpkn!<46eFj216Lz5s%jw3R#&~H9F#rQouNwF$f4THrSll&e>Fm=;;27QP#C=;mR^7eEk)7@+~`mC@2 zKKxdB&OON7qSfpG{=CdH)l@0VUdF9lG-@zc&9J4|Y>=`1i*Vw^>1dk!^ft^NE5HL? zZGMD@gL_ZFAOG|V`XBRpFgy8@BZYa+?%KfsODkjPQv5^KsU1xqW0H>!30Bwrv!N=7 z=IT28%5`OvF^k!|=a;b|$2jRGwom;(jOkahG(=tQ7fv%Jf}CSyv~7eoDP!>;m!`e` zvK0RPCKUyN0_ghD?>b1+h6ddaqCrm9DSF84%QkQp`sD{w?4q{ zyB#1@nb>>61`61)xW5{o4Mv>O+~Y?CY=P3!r_Ot$D@Zu|CXScj0|CwXBY_) zgK|TO#?TXPtxEkODT!8%^Hb`TzW>`{WUC(F>pT#b*vqC7vI?RG2*Q}Q0d`Tg0;ZV+ z2>KE3E-HJd?E^^vxw+i?0fV=Z8gi;3t;m9ds`|^oxorB!n!0`3UKiAn9@m3ZkXF>t zFWG;70A92rLt;lPNk21fWEZfe>0H4tYS11=bbMx~}mnTl0I%i$CUjwIq zAXqQhnat7Qpmo|}9o}Q?7wFksFEIn+MF$)Rc5b}0XCb< zlL2>ZqJny#uXwh!5tBwb9q!SCA|(^XrAXK$bcJ(`@`Z|}%~lrzJ$algOh00GdQbTX zdX?O95lz`|H;vNsRInI05%@&SIekw_Eab0@4#XAOyb|UjvR6LGayFe8Fg5XW+1R!H zJf=6=sAv-ZBm4~r5%PtP9rZoWequAUYHDhl+IWX{LoWx`!Ypi4|Jb7pf^TPf)>H49 zfbUQN$bE^1xF^8?kvRP)Yz&=U<69hYj^;Z!C)fl%1<{Kk7p{NXpIX>jZS=<3Iy1eW z$((dK)ApRqmQ-{6K3JoI3bQr8(X(J|x@bA-aDGpuT91kProqJQk<0OZ`Lk{7 zcOYR_L{z#WWAzBfe>(3xyr9;aWQ)AEt}8~o%blv?h>|gc#ah8cJgHnVz#%DlYzYN6 z21f~Aa5>dkQju9>{K$sOTHGXFdx8@1Ku-VDhnlwZcYdfUpT?DKgYiVYE&W?DuF3ld zq4zU5J&~UyDuD8Wx~|J4(eKl*#_-jAZ}FC55phd*t*5*HC{5>MiqSx>4u2pEV2!Jj zbiXe{_;JTKs&&o{9BEnw-X4ZHm|syn<7L&HWXhFgtg}p1*%|b|&cJr(k_eMHkxO7? zws7Y#U`z*TbeVIaqf^k%*_K|$GA&9dN3uWv@GMLz4x#g6g%aa}hzy=9-K*8WYqkAl zza?MqIqviys7#T5t%?6*>* z8?dDEjgat3I*@3+qwICd{1OOjWm$u|aPt6Mip$opd!dC2Cz{f8#O7aBj-H-V})2*$;Bg z4lWoK+bY7>JkEM)V;u&6oHVF@N5;dP*qA&K18V@_b`u|_pBys0P7mN8x_ z*1gkadGoww^Hyz7H9#^Ukpj*4Sq7~=A`tsoem~#|k5wV|3ZQ)29E~N+Gq?F^Hmo_| z_uT9EVaDySlUXh~|7Edw8w?kt5;|+%?fJrGWc%T}9@2sm`@(sdNo6%?GFuB_Kux9ZKWAhLW*Lfs;zRCM<&e>#}q(8Vy+8*ETY1oSh4kjwB{8X`hH! zZmg^51+O=|hb5!Hy%g;C zhX}UuMR~KF`6RF@JWdxeYPv`qh-QFTc-B@IFi@jXy@Bwf+{I3iQ|9uFQj!vZdO2-S z*=Dj|kVZ``W!_oCO>qhHvLI_*Q@&MX#R>`YVaTAHQ?rF7_HI&RQ4xS%HaoFOCi0R% z%#7WQ({#@ETXEU=GM!eV>11Qft^aosn0pMEuk&KqsxTFm@^CC_bxW8q)xpeC8p0){ z!HNJlwIzP{q*+hir=ME9)y;aWTgJjL*JI|`Gp0ar(Cb; z4zK5rp5B|Zg(ho|D`zEv3|mKdK8`B-P;!BbFhBy5p?ro)%=idzE@a+ZMEa)uj+v$$ zClC+s-5(|jUTKLq(9i}z3?7)y`GH5fIr{5(zKO{my35TixPoj00-~+sP*tkJN1#La_A)%L zbI2qU0P94Ne5zJ9uybU&7?3N75jLOsJ$C*iw0ViY&xZ!eAJ!G{q zhJ8XB*bmZB*6-?tXg_Hru~%E$re-B$Ha-i$xDhapxLWjX_b1riVuSzP{6HNZF~J5u zH!)0ScF4oAE)H}EbUWfEk*a5>=rh4Efbtbn=Gb;Smo7Pq9BAZ?jfyMiy!rjy+Z&W{ z&3{~IkQDWKotUlLZoBn<<+j^t@Y(sXMemv%67&4hdkU$MYoK|{a|I>rkWeE!+c+-D z;H@XCS(V&#_&x4Bk0?`+CYah*_(k>6hnGBP7kmLisdhEz?y>FGB!)<8{mbg+Z4mAh z@`K^%R$^}>?uvZuy1W^|rMiWaCRnup;8tZ1Vl99Yva9u%e{@hiibGHTK^+Um(T`*4MxgZz0;m)=X1g7=KJ^C z`8ltLaj0G1R{x(d*1IRJ8bU~am6CLZA4W?j|f9B`a9ex@_xJ=NO+r~Z+EAGk0}e@;vfedI(S2~gn)(+a+rMNQhxDs| zV#*9Rj31Y79cv7B=bK_CarqhjC1z-CFa@elV*8EO-8iGymPVBi$bvP6vZvHSPD&%>ObI&Qa*Z8yhz(0or@O;8E+Z5OrGccwFT9m(lV0j5syxv( zRt@HQAtGVH9Y^Ty8zdFihWDj#WeWITPqkV*EaTA|g~G?VCkzr(MWGcP&<-a&G&}Jf zdlw5fNxI@ev>pZ0u^YLnbA4b)0%uVS$S~^ndkrDbqMYF?=gD;#jZ+z~TTc^OX|67(8cm-+pO1>ner1Vm57^(2wsl=A#%#xRXaU$V5wXwM9kb z#Yq}x;b4@CLNYk+@j8piZkfbKJs$7(yQ_lf=O0+(^x`vi)|Uni&d+uD-SYh{3jM!a z@&-@h9wJPdj<<{uI0WS)VUt5CH7T@Wkp8e3NW(tWhtt)`8PgVJi=*O}NY~B9{706` z@4f<@fZH)~@iG(z#?_zaMsI5TK5VV^74G=tk=4N!Cear(px1Pgk@YvHv zI}{jD4p?;!F`~kO(GAATD9!YL<=iM%dGv(HjFMxfK26~#u|Lyr1&@;L>B(!s_iurNIKD< zShNXM4v66TI3x>eKk4E5I@hB=eyd{Ab>FR~t1ls?>17q8LK%BIl;lz>FOWy4r_f}1 zw>Gnc%UvHmNq1(SGF`xx&XAN_1-Z0^bv85h3%b7m_BnpP#z1K`7+|!G?6^VNPY z)u6T`ygmuF2Cz%SC+l=3_JF%a)+%~6f zDQ6N&y&Q}%#s77D_8;(iTp}Um-tDKUKc{ef)_I>N z6?tDf{el9r@#ga6yM)bnbv*s^MmH`idY=L#L72$ zYeIQ?NEnS;nL?w}YHQ?f`fMPd4Tn&Nm%m;2%gU>X78 zuDd1Di5cxUVbdey0bdJm-N~Qf;f`){dBhmJcebKn@ou`Wx3<-+YQuGYx1wTeE{(PL zVl!6-U>-Xjd8UL!G-lb0NmXL=)dDn2s?*1Y_cT%RR0hO|DzGs#JHt$W11dw}e*jTb z@_|$~Y#+M&Tu+%O-XDxz1-=inWK#cy;tl>*gR_0Te2ux48$kW(cUH$x@)bPA$Dg2G zr72RWcyaM=TO|!6he|?hp2BdbK+U02&5K)x*0do~>2$7@V_H8B_@2-uyb(^(bDSnz zYdAW@MMN<0qg^6JjtTU*sRoxxSq}t!W^kHL{^N9+LPja?ue`k= zV&&R(TC>%HAMU{rRElVxxyAogZDjQAuad&-Z9yx~ZnU&V&ZtqW=K}38mkU4vT$7^( z?4rs7?wjAx%GH1nbR%D%6XpHCn;6{Tsjga`lAAyESmr*KM~pOwcI^ zQPJ`nK1oA7M~ADz#Cd>V872v!p=nanTb~qlm_m`06tn#WX!Ljq7Dr%%0vH6ysn=Pt zG@)3w0G+{I8>Llqek0Msbpn1hc>08)m+9<^Gqnoae=mxh!(k}FroQ`K*t)umq;9mp zZFaJpt%wm_tG@h8R`JCB8Py)(p06K5`-pe#=fBGR3#`0E3Hk(nT@1Ab5@RgMa+wAV zGGA|g+)@fg?ckZ}yUy8c`H77teb==GU69ZF+j$)wGpiaAWq_Pcsr!8v$8Cdvn(e#r z^t^I~WAc)0-o=4T-UpUGwEcq#3pqvr34Xf4`lx}AH&_-W#%0v@+&(H#pGjP<#bByd z=JtUL>vC;b617sUPXpet<^?2K=n$r7xPbiyRd*}C2yEkMNw#vR# z3F`XKFqQ#2Y5!!0F5rk=!;r5I)*{;I1KOWCPH&cdSgVf(GfQ2p$;YK zNg_2-CnyQ*4x1Ac=r~;Nj^T=3N0npI5!=*Vh`$sxnRDffm+K{{Q910St{p?mf?!r} zgka*yiWm;vNhvc*k>SSB=9&@Br=jY&$tVnP%`5|vOIs6Ramo>RQ4q;jkLmuw$~7BT zAiAKC&H;^|?<)vS0?MZe|BKY#Z^A`Lb*~+??FZLl*Ikn$+DK%yVl1T6ltte25EAkJ z=8=zDrcC7Y`RnW$HAvcrM|e`>m7)D=)b27~J%+ZVNaulpJAY!YTtX{TUx~5;W|7@f zEjFHcnPw$%bW$4YVZ@Nc#rrNt&rwB#T^EY*K#3-@!h5Yw`xTR%ey-{LO8vps%hWEX{7M+xkND42H!3;v0kWu&Ao5T?6?2S<$Ef@qQ zsWe~?xPXzyWoZf^_t2vN&2*AG73F@;S;$WyvWi+Skf2ej)6P|mV;VFc|}8C&tzm# zGbuxd6sjpo?asU4%E6)) zLcs)5h+KfJg?#W17c7CDGxssgLFD1PUIhcFzXCS|2pK38IO3DSi~*aDWO@aWZ8Xq}G$9WBL>4xpJ?l(K>a2cUI-L=WQ#sff%osRr(%7t|9?A;S91Lgc0KHH>{) z7?JWlfb7s4p3$+rQ|Ur+`sa#pRi>WZvmkAI)>!ziI31bb zzJYRmG+?UKF}+`6DXv^GlT?+I7hf&Cmi_`SU1^~yEh zHV9in1FXK0*Qlk6ji!Iw=$kod|M|}0;LARWGdN@#5;EK$b=`EsXX!Tjcc|}C&ZYI2V>1O> zD`M^bA28>MUt=E@eIRZ3zqI`)%$Jnk+CGAmEish~>W5-vD^y3s$?aahm#aga z%63ncW;UDm;YLek=X9On+{VLl@KvIO(3`SBw?lu zobu7;i^p+loCzxosr^gr-_5sX8K#JNb)%Ww;I=ny;#$HBm_ZSr%XP>Y?Jh$7m&{~* zJ6Wylpd&2r=b+dkXo3WmD6ssR&Vp^G@TY2G>$|s;I&=G912*VLL~8t>)T1wy!p&*$ z(({Zq>$c^p0VK`b123$QSE)lks$hJ%k_$|>VhrHaqS7t#m1=0;gF?@=X7gdN)O56$ zG8_kSFssxLxW~(P8_a_Et5`G6S^{^a52;C%TJ2o>jsH zK5pv6h&-PIgfMAb%-sJl{nU*s-CExZ1PrIb6Jv8&E62Xzz!2?BYY_xH1H{hbbJ4jE zBGUv5=__5R)Gc%y=q-wxpR;;1%Fvhn$7fO8x2&zZc3)s`+(!wbCUJkjnq0IowYN^t zwyLkTvhB6`TEv#gAG@cKB+l7VEGiGSyk5x8z{K%gQ?DNl?L(qRng7iCe!~ia-35`7 z5)u@!ESJvzfq^}&LNp(XM;ewZMD~}nSBG&Q5+T>wKU~vNN7kzC@&z~Gvalpp{PTko zT_jt*EB9{9Kayry6YMBAwejBx_`YK^*tliLF2-M|+aXL@<6HH9ZivaoMW&31C3!?m z6Ogfza$u_11Ci%{d5uDKV)_|pD3~e{$3_fhTlBNOcHZcyY6IKcI6tSwzu!IV5w@lU zE32fq*f3?$eO}f+f)qKDkoNh^0@t<+_zi-lul1_lc9II8q3S->peL!$&jZugt-;)# zo~N};w_yVmc2jj9fZX;n*{e0A1j&+$%}S@HUKe<>%`%1_20xw4umNhGK1zdS^l(Y( z{WMOJxJH&_Di_|4_*I-T2lal%eK?DY5~-#p>lfMbeH`O2({Hs^reufHbPEryJ|0yP z?EYq6BX6!&$mz0Om04*imh{H^7TFGZdRW;?&XaufzM9KwEg4S!q+xY@gevLg^}iCx(ciy7MHZ?S;8EAev$+ww@8;);udCLS82;GS$zDv|+mmxH4bj{F?5^vK}U%Yy-7eBgt>v|9qGa?uOS zf^Q?tay_nCEMj@GtAk7v*p|qB|50k(E=GJO@}MeEW^VtjOs8bNI_8#8d^DpNjk8$7 z`{5pi>-NL{sJ)&)9xH}!!8j|pDs6;j+de)7BdnKMmg4E!0i zr&ebTs>U|!I%qR@-`_)>&Qtm69#1jzMR?zIux;N@i^=Co+0&y`%v$N-u}ywh)BI7; z;IcP_-HGkz!TZ-hI_O@~ajC>sUMyKCnGnBB+sr!Y$biu*4%32jSyBqv`E&`NSO{JZ zcO0CAi^nji^e2xPDnJ2|<_?01eEO46NCfp;hMXe$qLS8z0$oDO4BW!2o-j9kR=6on zB+|9;Mpi<|o`{H*t6SCE$)zb;27Kr&#JdZUycx%dpeqL5JgT&CPm_(9FINOzUkykr0NvO`{cdwkrZ?-$hO|LpVJYG1CgN|U$zVQl64 z82bK?Q-u9n0KcvGBay3K0}+~#qft59^V*8$at*dFPVv0J*ceQ;9;U_UTB`lj5p|mn zspDWRVY_oTXaXC~T3tk9Zx(lN>qd8X7Cdl*$*_GNZ!q;2luP7l@Bt4qJSopp)k^Ek@a8gosaOJQ4w<$ZW1Rmt>R41|BjgRdrMDlXZ-aAJvJOf;CuU z2$!pLZzFZ=>3MSY5qt1)oVgeQdwAd+%Q!ah(~Idh=$SG89HgaA`?v1(c-Tl-=DJCp zl%<@@KvwQ7$1a=_*6euq_=muZHb5k|#6w(!)u3fK#XTBFtCSi_(te}hhI=!dlqA#8 zdCyI*MUf?{Bx{fcOn>1>QW%(QAUKVq(B*%i`U7Y%kXg}M)u>)L5eCf$VMh|93T07P zsde5>MAHAXH$_~a$MzNxTwM#u*5TO34_Z<4K6_pfPcs|W}u3J=g&u+LJ0^NBM#59uVlLby_Lwo-+xtq%KQxzP`c{FQ`qL%q{}1;-2)_jJAk&_3dMSpji@s zOP!R}v3{YJfh~lholul+Hr^=4Krjl4BN$Ka5)z3i(KZdd?B&WEUsq+&K&1>~>8VJ2 z=-~&AuCfd8O0(JI;cq>{*~LMc=@vA#l76+JaDQ)!_QM`o(=Q#S* zERK|rSb`4IVS%c&NbD?2jN!zCbTGa`;d43|u!dmAn0A)J$MGW|1k)g`8q_(wS0s(f zOR)+I1q6d)5L07jyvDa4@T7^QkaBMj9KMwk+5uBb@uu7MOC)(RVneeLTs6a0hCqhF zrC5bp0-Avo0kH;`2fp@=Ii9w&U~nj5$q7ah4xY_9cygInzkHCyIu0DLn3}zp{kLtr|M%wk%a62C%?Q$A?TGNQ7a8hlgQrd@)vBQ# zQnv0KqH2_Pyw&pePw(eff3@K3se;5pe?`ec!Btmg{KkJB;fuE|aO>wfP&go`(~g}3 z)kaEEaikSN#L}qA|5RP8+nO(l02y$x*rH1z8LUJP+0-Z+pi!@2HAjNSp-5th9S8xe zVRo*`pZ(RN{NJBy;dDPv`pB!`t!1K<^W}R_5fYCNTM1zguC$J6`C0z*3!md_cN{@F z70xdXL$aA9Pw^O9>dC_}n(oB;93gPmV+Z)w!Mhk6faTd5%dO3*t%FrUp7P-1o_il1 zWbIfV=g*$!-uoWl%$bvTjiFpW^Rruc{hL6NWfE86){hIH`0O~1!9|=~V#}6!e)09! zlG31XAnm}7*XHco8-sUSZNmfiEb`e~r>JB?9-3_0F~o2D`WogZ0*bP<(BZOOo~>IA zDvHSr-~1-L@4bPAMNl;iG}=7(ClX%xlY;LE7~!6~+T8kC4`flaDxUq<8rE(|aJj`M zLc62fdvC$~q>WZ>60Ik)EQU22qc{&PgfhFyf=|&L@KM-960P+l<-!>CZvZ`#w1*yg z_@0PdTtJMCer}ninKp6t6hlU67sNKmIN%$Nek{>%$f8mzOtCQEWW+al;Wd`yU!A6~ zgJ2C#GUhs#q)0h>y2X>nPtr1%AXy*Unq>R-b8Ou@h?s;kXCC6wCr;ocLyU6ix>Y>) z8Q0S{V0rbcm6@p)p)eGwQmNE2iLz=;x#>E?`+skcb_;9*jRx%517oX|m%hN$YPXon zEDsK5+;>or3KUgkRsaz+fnW?yK|+DS6A~^|NNr%QZ;)nvgrgk?MY*qp@$xR*f7?TRx?c9#La$4Vn<%76crcwQG8cvMEo+btxQANGFhr5LM||~ z!1FE_4m8I(cX|w|52NY`Rg2bR@X@WGILK{tPvKLC*9v2+#(B#x-N-%PSj*(eOR?E7 z5;{yxcKGJqlRV=Y{cOE-jD1g2w(m}vpIE|)P#;L?t6Ca^u&t*2r#IGk{!i90Hg;~V zSp#DuFnXXk+wl4K@-Iok2)U%NP=GQA#)y6OGrkAEjys%4Tl~F-;DpAYiS!J zF)+de`4oP{001BWNklJIT={6)Zuxe28XyK!^RnTaFsur9@y^o&IYEiaf z7~nHs_!bLG2Whvjj}<6mXf}nf-`a;;^4xHh;@ljcyY(>MttXX!3Y})x&S`dS8^#2f zm^jY-;t4A0Mq0%s?7Lv;5)vR?}?7 zrm?;%?AQ(K*TC!lJ#5=Cz}Zvt6h)Q953^;XVW`q!>$a3X{lF*_Gk}57e%O6^*M9PQ z`;q>$(0}^v#ZM)|il=4hDEYEMeH!g7tu6Br;_FA@%ot616`jNqw2Id(?iE#WW+TR| zjn8Y+c#nkA6EqoQnOAXa-ho|Gkr*P7dErtg{lvH^{WRta^yCkVAo|YpY6i(btK|6q((0fne?ync-i5FZ~Fiw`cC5haSEsM3qpQOj|5Lpq+byO-TD8 zcmWqHU?LzPkPxt$p%X&vq*0 z8Uy^}?c==jy{CBl+qUqvuM5BXhiym%AB1bJ?%>^Fo^it_zH$2m?|I(?oSPUW4=t|Q z*Wxpu_!$t->NN$|Tz!V8PM*dlv2xZb)^X_gM&ABg$GG>QX+ovJtd5afdkMNb!FwoL z4w@~*c4Fv-w@|OeP!W@2f`LK_HYZr6ZBj_9BneO`Y6L%MsO}Z2J1os{@Q*8D34-ZF zTO=1lm}>ngg;ShJ>_U>*YHCO^8VDxD#U6l32?D_u43122!?l;t-vDbBqk@%`Kx{27 zf?kwt*h3FJ^zg%hs-gsfgqSOY5>!jOtmu;&yu@&(qN{{aObVnBnx)FrX!IfVmc&?E zvokEuO#^Gt5PiNVlwxv;ypl3LKEnLDf>7~bQcg|Oc=N9xrPY_4@g6(ZccHFiq05{+?C#;Hf|R21S=dnnWIg}i`X(N0wI(E z5E7L-Dhau@s14Xklf9P(wr{9Xwcj25QGga8HF`v84?X-KPyx!1qlM$Ao1C8-!7_+- zWf2|06Kyn%i^Nl~0kxi>LN1jU2!v2*18YD~R2(V=Y7{ReAy~R`sKjn}HSzPGh_Yq_ zEKGWIDSAO0FH9{dcp>x|ybX|+V%D00j-o|O1;=NMtg~#{W;k+4nV(fiV&LdXP)*l9 zMFNBneWpdxZgHpEkw!_FCW;!5D?JoNgvGp%c4rJnKhDJ8^;9{1+VG99&2#pAgEWoB zrQm?9^d5D@pw#jZvPNLIFEDl95Y*rk0W-|G^P5<=S{QEhac)BJArgMnM!4s}6TI*J zk8#<~F^-%X!pSH>V%NbJZ=az5eJ6SQ+qQAnHv(V$a+TZ<;KfquuhDTwXtmdJ$9*l{ z{jR&1m>i~6Eb*e}5Axe@dpehHNEzyftM{GdsdJ|QOKK`OUniBVWX5vCb%tBNG#Dcc zI`KO6k7mp)PO^6EILXjF24z*fpW(qRhz#(ZxGxN&qQVgB#8s>;GV5<}+r3mGH2wbpjs}LlM%x(|_!34pGK(2ThqJ8o4 z*nk%ke>D*2G9?nWLorjyD4v4g0yvAP;p9Y<6O%2R z^GqxaG1~#D4@4z(wV#u79e(Y1PJ=y&lG1J_w3qiHNrpEWUJYv25^5Vz8U(T2`S?*D z_&>%mX+a2{PP~% zA>Q!D26#_mDvYjLjjcddRcv1@FjrFHo$nfAeqK>g>UG1&h_ZG~)afJ^CeH~YYaCzx zx{!#$+GVbPy5adhk&#v`xk6GEP969B?(fW_%^|e&<3I2BNYWm9=;3=q1XKFjv{44? z!v5Vg9(lM$vjw&<#WzD4Dr`^*n1)jA1K(6aTcb5m5kNB9t(31ne3p(5B9g|obau!9REkZ7)SXrFspyViP)AMKmrWGGl0)1V=Y<+2cGI5>&v|l*O#{ zn`yvMY6xeQxe0^jpkZ#U1>A!)hUk^R>@S^}vl7bk)mELyokH=_&O#~mJVjmxgR0)El%9fq5agA{D z1ROc+qqlT`EU9zXjg-T zQAhBK!IbtKP$uJH(x`?%oaJS2b(E0z4+MwzUc^pO+Xci#Z* z_BM=FND}UO@D#uNtGDsKcRrV9`%+Gv*vQoQZj7|}#vP~mz=sd;6F045*RIuk>@UB{ zAAj`kNYY_kp7ZjTUdey`&416@b;B&pwfN#!PS9?)KvFuzGS^-^$YQI>um6|-!PImM z69QY;j`G{T{qsEInU^6zmVUp9O0F5+>_n2Cc!6&nRDv&$+j~@$xnehS{_^s< zVgVqr@qKtx-mjvOsh18N?WYs2j{e}KU7AS@nhAyRq*);MGyKixALlcAgv47GbPqGS z6Oz41xRNZ);*LJXhd%lc^=ug}96PtI=VxDiJ=-^r;GH5Co;o?pnR89DY=C-0>Fdkb zvN>gNK#=bB4UX!1;XnUU%1dA4F{;!m1FYL%DG& zRL~^l8gehfJ*Uq9mzMsX@|jaPt}`GZIJ)Pae#8*ZUHjuY!q_ zuB4!0gz1SF@aKOvOSN_fA*{n>2Gx}F=Qr{0cOKyUFQoj+rTr{+u4jCH9b&iPb)LH) zc!crEuW)|iS(xf5YT^Q{eJH@m7UrfF+CKuPS0hVnV^zE6z_wu36uMy*eryPgVuM8s zi-_P8hvH(`uu;4dd|MGwvSFbZQ0i-hwFfiIlBYeN&}Aj0OykZ?|?yGWc zhPVMXiqXJOe?e%cEQwiZudif6;=$LT+L&kEnzJm;_LJB(_>iC|u99%9vWpvkdMmAO z^>h1|JesAk1+Y>>`%@V7$h@L0MV){oNLJ(OeU{yq3Af$mn4NSawG^LZ?jIQC6pBm@xdrq+9@~bGkWoG`>oS*5(q!pHn2l(^9xSyGcVUp^;NWN;| z-0{Gz@9=E6>=-w^Gq7=dHIJRx8D&7~k@*hJ9>t9ccH3s8UP02>iJ)!47>f~)UMlnr zrkIW*1>_FqQHrG&VK6|aMx&?@w};?UgKrm+M6g6l7nL#x7eLC;XN~Rtk~3VJjK)-I zG>OIeU?BuHUZPB$7v^S(-cqWhDU1ykq@fer-Gf6s^fjQ7MZyvSqMm{N3O2QLlTAYi z^f67JPO%`v6tXS~94wF}kuVh{SO-jp6EzkVEhH9bu&)k{dSN0WB8st=>XrsJLci;ad z9(?Q|bCVkwpWcLT?82uBgisbWW7kN$Zry8I7UINTbV0k`m!S-`jYYW?i}I2{1qH{7 z8d)gq;RGNp6X4?kij+#yazhj!FI{iAsKOSzLd;`?5JDN0RO(;K&PP#O{+=l%)feW$ zprL$xJRT|EtA^5Y0MNvi$5fKRC|(UA7;+h*<@RG`H-h3#6_YfgC65?_t#W>$k1u|6 z0r3SI0&5>R%Tj(X*Y0cJd;nYH$iWtOf8#8K5rQ|2tx=4xoC z5*LOYhaQ-N!45P!`1OJ1Bw!J2N}O~nhF~&8B^JLsf)J37-~ucpo?=uO-esu=Lw?*5 zPHHrecQ&@!OIT?eq1zQH25be3!53h3fpr7Q72DTR5nDb~%k8gpx3fQ_8>fdJdg$Rh zQLk5c_A^)W@R6L4ePWyt8UT1KProstJ!kpG-H_Cjv}#C0RMQt#;l#2qb0lYJwuK+i zGKp0%ebCAV*mJ8e^c{O~b(r2b$?=py}aE z_YBRzFbuR0r-24z8)z>w$nD+6#*!t=##&0MDpjfWs;sK4+?QD1d-wk4kNYAsOUPgw zcMn#__nbPF8TsP9$QP0CzWcr3<&5&|GZ8C`2Jb-KIIT7mSwYcs_*Q|ffKUV7f-5pE z&v>FrjY778+k*EgjUwVRfAv+0EP|E>VscHuQ)A)$5byeT&oVO;LwkZwpqtJ$(5Dt* zvVosas8SZRfYcNtV4bDar}#0&W?&mi(J&M%o_sMUZ-ID2R1v(@H5)BHg0>)0irNS| z1ZihJT8=Zu24%}ob%g_)T3oZUwpNe}K|QMEXz)Fhk9NnGF1q;ELGa?4$y(%+BBZDn zJVIX|tY#kP2@bE=(A#5JUX)VdWGmKG!?6gb&}WI$=pIecz#STJz%bk3KbUc}Uf!8$aG zLwS+}g`%iIyajQ1N}E0F#MQ>KzBSdlnvJJueS0nMlTEPiD~8PWlt1^7249srALbDe z7#m^Kkfg%J%S+5H7%t76WqQt1sqZAWpedx|!sMQmpZFIk3yX7na0Ql@dvI!zqMzM6 z8vOV_^L+XX2_OBCM=A~#2U-IeU~J4$i5!;~g=RAcjVN>npZmgTVp~UxQ3?zuiSRmx z=DmF8a|=9m@FYu1{bYUzJ{v-!WsV#bPMv(59ixW*2kI=WR#{nTA*~9Y9^U_FkMgm~ zd8RKMK(!C`!u)cJPkv$<@8-DUW=mFhlDLdw`KCUZFZ{LQ%0)QKqfagKM;|b#t5aw% zK8k`8v{NS7Ika@5bjq)h z%e`uum#Q1~-*HitoM{*f%jLzj$cPR5SR;Gab*<|UclIB)4`gfkV;|ftDiWsKCIJan z{qW=*3KxX863Q(d!>A62V;MNVQ0Gq`c!rODZXV}7xm#gz&d^+*#F`o+p6KK%$7iP* zA6p>L+K9sH$|?(U3qgHKgTbL$?*Bf|-FK`Ii3hPPv@FMtH@JAdNg7p%V#m&%HSW82 zFE3_vNzyL5=;H5(0FenRg(|3V4D?yv^tvivKGER!e{ThEdr%vq)k61>lDlB3(6k^D zhjAV!7EOf9mkJ*E_!PG8*>?K~T7XLu=0=3o0f_nywk_0hr8xuY031;QKm0?MU3(+` z-`{Z@d9rNeGazhZV0aTZ-Wc)Ru?DA~i?LCJlA*bRYRJQLE;Lzcj4y5{iagg{TcN*C zdE`q4F7uegfQyjx19HzI=aH8 zxgOLQiU>0Cp@gZw&UCtkVmXIi4;0`GgX0F@r+oZ#^Gp`!*nGzpvhWIb?=`&kHIpo7%9kHorfAnt z%}|$zH~SD;kY5GFsz?1MuuIICok?QAq4)ws-RMlOvG!felJ6F+g5L zmUrO$<{7SAMm7mkvjxi-h#gLqqHQ5pn$}=@3~>!uDd%gp9Drj>3x}^MnrCI;U<7%B zwFV-kC~c2n(%K;?G-Qz`p0>$(?3s&9PQ>iqSzm8C4qIV~QQW#^uZu3a_|`y`LLF_N z0f9_Z=NTP`Yxa5`f3nHaY7A-^9DdZWsTKy5C^mSPBPKjL96USi6|pKuRvq$G|ys=N@y0zs*|evUQ} zP*SSmb^SR==h_t1sS<-vT={#4)^QY83eRW0bcUC_v|x65o~3q#tpq`Ck$MguUtnsk zm+hMpe&(n9=o^ARe79%rvM2IwhKDcl9j_WxzB4YD$gp|CPz+(uxXy5#GJKFHv&N)AEc9|y* zPjPuJ=joGsSoW{PrX%E;LyJ=IvBq3(U_3Xzr_bX^*+@h_A06RlNlI$TeCozc%l%8a z?fRnN-+JImLR2;!9$8PKSw9@>&)QEQK*HWFg)2c948OD!*%+C?2q2+|4oe&MC$R;rTEm&zY9ItTa zJ(gN;os=GCPJfZ}Qv<|92Qc1p<2AyY-UM5Bz>nTA$@cvV{N%rQj-`eD6opXjiAk(* z_0EW&{fSXN^Vbm{`&fZ*r)aUt*ytQT`!6SX_j_|5xM%|5n*mV|wpwL;vvSWX4d>4( zfBks}S&YvW*{s}qn{vkv_~7T;eAOpN6l{W%+dvw^>;)lL&`NOAN`v5w%YqHk$2sYs zA!}s#wk0wVzU8STLQ;WNq4+{5a)n4x5nK$WYN^&z=KHqs!1*@27d*R7N3j*042C2` z$#ka>U3Br^1%l9*)<}~ahsPP=hUY6AvFlT;{HKJ&r&h`R2t~V}JTrldHDynOY8c!_f-|vvH^ms#yDQ#XRIV&y z>X4G_j`rs#i#0)6`XV34y6B>dZ!-wO;D9hV;Mr*mg(|*OHbmC&j_>Q^ z*s+W=$2`~?1r`?xYC$`bhfWBZgT)1UjFtf<1 z))McYo?+o!g&%qAOZfD|D?EA3qE$zP;i_wLMmJ|HtR@VNCA|FhDu49*+bOh4*376^ zwsQ4eVQ|3lQ~zw7{rlnYp&1sJ2S6-aM;naPl%Id6;Rk*w=ED!n@W;Qmic~k@TTSXc z4c_{e3636BPM&DdT21log2~+(KYC}%Zh?LGrOXaS0aQM9PxswG)Pbjf5 zL^Xp}1(PV=dkQP~AwxP*CsrUcNFf*jhY%aZJ8(^d_hq34;Kb8%4(BVJCt)GWaCwHB z7*kpeLnYvgJBzG~F8+sO&E_i%_C|d7T~(^RRgOH@W~J$w7%-eVwMf(x(JL13p})7y z%MPU6yl0fhj^$jK%P=VEBKVb<`d|b}j3zl(Up+z+uOh~fR6-0>wH9NohQd)tP@Id> zUlXnxXfWKfL?)A4pv^CqG9IdJXpI@=mC*kjnacb;b-ZBfW33Lmb^7tR)J-QpM> zTIJk@UgE@}Z5Zf>TW&L)J>TN!8O6jY;P8^ORwB1{c`3gr-Dy`ev#&X!{Tj6uh#yaf z#M1J7V#9ZxqQBq(a3~Q?8KB`(5}Q(pl8Zr%f)SQihWWieJWOgAdF8z~@$|_R7D=#! zmZ&F2Qp5D+CTY#{`A5#Otec7Y2dJ1PKXAY06?Z3W8ui?AU5f`FT*7B{#8@glF`Gt& z&7;aszGIZT?@D;!0r=>Hf9a9E z^E1b|d~OR!0(Op@Z>jM;udlH*-{gx8FlmC?gu>?JLK$taQMUQbLrPI;=6jf4+Qaf{ z3yln7Ewx_A3JGK>Wz@mid$fUU+{in2VlGv~d=Sri-plj0-LN~^Ah7(~a~)lO{__dW zE4JwnlATRDd8HeFVO~%<`obsYd58Q)q3eVwJ}e@r>AalqchcctmGU!h!Up1fh(B0+ zy&K{ze7S8&I(NjXYCK*doFB%^1ci%edlSw~r!&oiibtfz@#*>XRqq!mx+G~AU3Bqx zqnuP3q0BY{8w*;7Z`;Z+c`}cU!FwrltV0W?8WSe82CycCm>UDRfw>6AR-ms6i$kzN z2)`~2WKE)|jf~gH$nh1AT099TAqH!Gc%R5oEzM(8pRSgTcC?3G}D{%_D=)B+F4}uv8AXg7h}su zXNQ^lt5ZxJz03{U$GG&mN|) zvWHxt85@cUA*;Etp`kuDSYN}(2I;f3%96a)NBHF``AliIj1r=rgo+J!`i=Prf1yUJ zIl_^Ago-;(lM6gObq6iuFs_NJ=Q9tTV1D5YKl6?QY}>SnTE$QwoagkJBiKTiUMc9Q zZ=-);E7n?WyAl564@a0?g4m8QQ5|OY4q+*uW;I))QoBT@TBX)A#FhgsZobnoJ`OLr zIpXCv_tDIt+FyZqf~#Xse+%Qzm=n>BU}OFrpA#|XSjAp zg)uYD@pG#n0~|cw!=7ulbL~w%JUeA@El?@AyintN-uO~xq>t9Bu&o#R2Zgaw$I!U2 zxEe}nPER!%Gt0d3jhi^%tdJM5qfZ$g5H^iO?Aj$nRYMfPft|vxisuWX%bd7aAXuD- zrIjX|`f~<*&T+ER(KmObfzSBe7J_I26gBf8LA34 z*z84R?dNOW=#E5gjUUs}d{E9&iZUb9E2b*MRnHAOc60Zgo=-f~B9jvj-Lz^cSS6?6y$?QtNeW)`+Lv(hVuOZRB&zijM@uXfGdz7Lp&oDLp}&5D zBZo422VaVdVqST--RvE_HykthRI1dun$rU4QCkH0)s>FuYaMRAN~^6X16iWc%Tf?``q;;{{YAOti}WeJMM)3;*`t^t1TSp=H2TuV&9)hbgb!--<=9 zPR^&6JYJ!SYJ_IO@TB4O-vf_*$#Li@1!Dtg*Lk0yY_!*MPE(TCrhNZ8g99$P@uDR@0zUI~&&*p}c zy5R}sITA79_?=%+%V+^3ATIpE}bAo#Xh) zBmBhMMtSUY0vP5FFs3bMlk6Zzxsa*=cW>35t54K|NNyYTPAayU**Et zV;p*KYu#ZDq=Mo=Pk(M1)(503Oo>G(nRD+hedEih4$SsEL{shsD?^j8o2n6c}fr zQQ(`)XyQ?m0Wp{=q*acb^BnttqnTAvYeELKcrGpv@Z|BFKYidBC!RaVEAM?7@B5JO zXCD^QD5lwj?|zN&YyS&WlO{_mOB_3XnAw?C5;2_c4v7zN{7i-a@H@vjGdqr*+{*Cq zIez)y4Rgm`6Vzf)Z)6y{$>RWwAvTq@^O8J2JI=zSfg#|hcfw7*G4FW>&b5>Z5d#gl zI)$;V@VQJirC}5!#D#;nDnTEL=oz2X;Dy!Y&kv`G+dQWTpr=#${cr39p>iU z6KtBOuz&BCEArVySZfu&VmjEhFm%zy*N^f~z4K>Nvab>s9@{@!kOrJwC8>%p$!wxgsMx!V+blX)Y3sS()<#wjgdK{dguAv17(X_CV;j#oG(jw+~B$Rnj` zYrOxHO^zNp$}jxnIEPMbXH`9>*WwIZUcA5~kDg#+bT_x&IgYh(>y4gUZ!$EOS8*ub z3%zMX|3u23-Abz^qzR$x0WdzIURQqgm-muoDJyvk>;S!WL%XrW@#D{MY3c&bRw*p( z+1YEZV&K_Ihkc%TJimr)e_3I%@HetRpc+8ZG2aXQm zyB2TZbB3#zxPEV)M-B=rt2M|i13iZRAviOghj=`(> zW-EiXLdSCBVtnp{r{4);gxuB1v)w#3)6u#hr z2Or{zqb;I1!e?!EZyDg9{@6>Yr;2gGpWrZS3!kYC4UVDK$%FyLftrY0YQj&wyw2^H zJxj46$$EIHZF6m1xv^gu8x}SX!1;6V)h`*QB9ID1nc~`tS0Ap{Nm#u%HA`Lv7b#RM zVwGlPlH;qEMdMgn^$hle7uI>#I+lHTk=rA>=%R~nKdfmxRB_^1$}LMe7@BcSXnaLI z)(H?%h~lF#u_~;iXtfcaVq$~CV+RcJmV}5R=Dmru1c zlRLaolu@Q;D!lhEPV?lG&$4OjewN#NxV*9}Oy-R6>Bm<1SO5E0`To}pW0NI*<3D|x z%a?no7@=Jhywi>`K6n$e%R9Nex(RHBx$G?O`M{I>)uT0Dci#@a^RCUHf>kzH+MjoR zbbbDWKnm;-#f}Ku?t$rY>YD;XZK$Tg$WGz$!^)FS!jmU*GFxD6LLt7)f)gaML}GC* z#gl^;V4^aotjamvMRT#n^yTw>_Q=z`_LVzX-cqpCo+zpsj3F$ zOLw^GqKj_`9d2cDuEoKpPBB|-Vzs&%)YELYnSG)N>Tgoe3M1imNc~6IR-u)6Y(E?A#oUxK6e1c>A@zY|5)diKpp2?X1qM>7|i5 zrkf6*OcB~yjiOZ&Q<^~*0ZF*`H;RcBF&c`AI!eFJi7|l;>g{i^Ye&M9Uul5^m18r!- z*C(7mTd=%rQ6q>Mr%^zmf-wnDL5+}04?e$&Bj+5y{s*Tye{nYr(}Oiif%26@D;#~| z5S5-)_Fi`n1A_^Nj?D2VA2>*>*+v8=hI@JI8}@Qt|1jzWmp55y2NF>mmL#B?ev3~YUj(kg*A1N*0H|~dj`}44} zBt$Co)&rUQ<%d>4sz}s}I1P$l*+AThtd0BOEtWEulTy`b)@Cs(W$V@&C;5Dfys+j+ zU(2T5pb`x`p<|^FguAX={IA%wGwUr2!8#509m2LV7_S}oil?pZvou!X|K6c+19AWS zeXS{@pZC4j@EPwYM@!Xda39)EgYp$m!L9!-85~u!KwlgaivjIHT~1$5lf75fIXjz` z3(X!(9BxkR`g!`FA#$fnl6KKW7vC_}$TkCaUf07lSM~76f2n-sU{2d5p)5Cok}C{J zKpOJoaA8ojNsO;Swa-x74!WGsy5vAw5Q9_8NX2m1>uan$0}p*FOx~iR%3^Cbj~rnoiY9Np|7CpmzfJMTW4EBa1ITL5^*0ajeczj~xzB-()@(niY#3R+$C{}8 zHbN{|3JjK;EnGLDK!KptsRB^*j_*tjuect*G%9>>6+SZKm@U8=gU^c~CQTI*k4qz@ z3cj9$O`u%4r7grRrd23;VsL;Fk12DQEZqvHF1qOAA1Brpb3~|PsC&=$(JE8(o~#g@ z4HE!U=9Q^Yd_*}}NgZ$KG#N!521jj?xsthY3)<5c%|8qnpD#N|G)?+C>-t0Qh!HoDUKC^1`4JR?m$m z1PvSTL2bF(N@z8ES@m^tu_ST0o-~%iwFM)1V`v#+MPVr&=4@?<6+6Okx`3%#Dru7< z5(*3$C2|lImc?R}qwzTHo>6M<5|?7j%xunQ&kWKq6Zm{9x7=7|{F*xYL=GLRZqY|x z+)5Is45Tg2sh}FIb3BD$tOsAPMn{xfkVtu*Dlu~lM;~XO zYcso8M?}FY;w_R3&RK|KupYse*FDNIr}AJ%nQyoG)EAbxZik_Nu;AjdAx{&MenYzu z26vBg%iTjvP6+S#Ud!dFHXnVsi4bGNQ5VBNU&8mjWh+Hb#AiO8qc);q`e^3+c;xUZ zwcd>0iIm1l3@W&ICo80U@Kc}U#HnB9r+?ypj?Z1gyWX=ETnz-aY&A@7gQPag=y07c zJ^VDE`1r%LGf!i+$;~%i!~Ng?9sJk7nCDYpycVt0&{od%x766NyUwb6DKo|0So%rj z2$|o3cjjBp{0K17r;PU%rFbTy09F=+!K%fW94Cs}HfUKY>uvdFd(;H=qlh47aZ&iV zODWovGIO(3lCIeq2@wr!m~d`*O&xDThj1;Q5XeJQ{_ChSweu_q#IFQZtML|mf*K#3 zkJ2IQH`*vR4BC3d3s{R3{riW)7f_O}307Z7soL3T=l^nJBkR9Qr)0`NC)czR2h&Ji z2y`Vb9Kxu zw+gR&1zgzDWco~lvzG>FEk-!4ppqgIqnMD7s$o^q>oCVI96--!42)D681_tE0#{fh z?PK;*%zymNV=S-K$o(Y5Rj|D*9*uqY zU7f@9ly(pw@@XV;%uLU4{8+(4P1wC-62z=oH(%uASr=V&@uEP&)mxNb`-K|6^cyXX z94$g_iOG>P6bK0#oRtpn1~S2@Vk-tym5|(0QCu!mDp1LU#aV$B53#|f!I|beHuG|J zt|Fmx&{>N@;EIxadwsS zj59VdfNdu%%z{a(n50UoP_KZ+5s6)Q2!0KO<*v?xTv(_SuT;#&Cz-W*Q4Py>1K)o$ zG*&EAhuWMkB#e3ZQWYX0c_0Nb1``=1@@OQu$lyfKIH8%QWU=RhnPrPzCQaHXO6F6} zyEz)!JY&%Wi>)TxvH|*Q!`LY4F3ok(#Wx5om2k(-EpqIlQcxq*h?n=DnS}dm=fHXT z`(vurjJeqr)KpOKP|X<`jF?*yobS}WDY+=l3BHKPOpG&CU3cNhj#N0Y3V>aibMR`acknrsrUGMG$MC@PYg)Ey^9z)Yz0ujbYyP{xg`GGSir#sCpu+rov`wdAB7+X3nG-TsyNvelv2;cd&zsAa@@_cln zBSd9GJk3Tfw8M<(GGfix`x48nP%AhDOYZhyqwav#S}#0V{n zS*BJS3G}k}AdbX3#0PRzd;(Z(Y}m5dFhA>&Wet{QRa|d{Tp~2__?ktrL^V$m&$DmX zaMS1jcfO*+&Mj5`kKb|m4Z#1l}mFAI9EmEDwykO7{z&ySBq~s6vgC<`t`wlZIP}Vw4Oh? z4J(eN^Fd&}p)ss_s+Tn@1{!jAoOg^_i%(#41Oo%gYzE#0EoiuBlrT7{!>YmJ$S6=r z5aVb^o`V;c`1kKQ%z-_F{K$9ruy?$_YqRg7i!Q!xpbCSL=k`68fBHtthaVH3yx?j3 z2%A`n49J1pBQE4_X{tm$f~^Ue2n7&{;ulwOO;7BEJd45v9fyfxOd{lYP&BQF-w9~O z&Ks4;Jx|gNLmso6A zBsO>|nA$$xdcR@*@+yD$dj-pm}~F_DJ0$z0BAv4qD{wLPSg z&=c42D06OwX1+?SIqjm&LaUB#3{r7zpc05>BorlD#Y6^8l*|GZ35qO0R6|UT@px}h z=V`Ut_}pV@W7MI*N-DI6l^J)2smm9*!EI%?*+**n7_9XYZ7}9tLG*UfMHg20cRkQJV0X7Q$s;qV2y%bC6$lT=c~gwi*O;llZx-J_P> zJC}L#T!hAb5DUxAjDv?~x#xz6t&@(U=d>hv6~tjpg2XAl@Tdf9^I*Rx9TG0i5f*Y( z$uk%kHSD`uuolo715qDGj!pCGSM>AHW0#peH;ATHq+KwwL-?WlWB&3(ZDyY__&5o+ zVXvq$YXpxVh{UY;A&$*A`N+d_v_#11#gkyFaOv_Azw{qIP5l?IrCPa_tZ+n0jI#z? zfn&$c^W2e?8?K+=wJ(dI zw_qfuErVq0ajiB&1V$+oE==!au&2Soiep7~uw=)`O$^quEQY2wS!yn#c^i#tkUNUZ zkX8*lcJ_1oazvZ}Zh(Q_N+1OPM|_SIs#Un}RW-KmuQ5FX|K*S2nIkR`gi-0_5JKMq zrW|*IBf^-CB9xA5x~yT}_^=A(f>w^d^@8{l6KKW7vC7P^PiS>0s(Oh?oR2st&JXPQ)yKw z7D2LdfGElff0l=fca#7HzU`@Ch$_l*l7(Pwv8-nB_@n1})zyyiS6|1><;y(r*@wty z28g0tDX4%5>I=r|bNtj>hp1H}e*Jfrcw(gwjVuZ0xpnU_wSi$?{|4cyr-XASz#4;d z!q(9iZ+m;nBTvSB{L_%2v@BRJRFjx{?z#mxSfdgNSq6J|L8Yg(fNVS;(izq}OME#Z zDc}$ZmJ*N0U~nkbfmp~j2yMeNJcS5?XSr>dTFO{bPnK3tQM{9o%c=%rz!!>hJ}9XY z3sz7mXhbQ82lsQdzK7Mp3f~#k*iUFi?4pYhN=KiD7h=BcDuZ=MjZd z@_CRgPrwr&YygNY)p*+Ah|&Hw-)07*naRByQE zszLt!&-L?>&pF=p0hpdMcok9$*X@EWccff64K@jrGpoYZ9nTYod`$$yVWEyWS>@5y zuaes)5D_W(sLgJH9z$hLx!w^%b;EZEtFz2z>3C>+=veRs5@Alo8%rj7_ z5n;LnX%}654RolEScDaXLvx;)+7Owof)`ShZSDd+dB#bznJh}ttiV;hIT{B?tp@}sq^4tigyLpl=t-BBc_*m`&!=p8Q78?rtMRj ziQui_g(~$}~6MFh;R@nP(pUD#hi5TJ=_%TI1TQ2f5=0!&T$(EANbW_>qkN z>vv|Dn;%4M6=NfEgwbKkcYSx2r;Z5c&VV;9j4KeUv=o{e)Q%AaMdI;MgkX8aowtw- zR!OShRt^5P>c<8D`PFHo+MGM720iw^I*g>I0SdS+;H@; z=g`3d6M-1TmRzbx2pUV$AiOS$5b5J{VfQt#V+VZZV+1zLDN*et-}$PT#~<%!c43gD zzed|RT1}771;nluM6JtHDcvZnTiZJd){W}XG60}+?p4YdI?9E~j^ecw0|1>ZH(Vsj zo!YWMs*_=Q1%c~H6ENP;Rted;&aiLi82fj}oPWe4-rx|t&#{rG-W$_!mc%O6)N%cF zRrcJTqJ<&$N)#1*?;B$FY=yWD)tDgmd6A<_l6KKW7heZFVdz@V6Y8`PI#&=y79YVv z-liR=r~{X35Kp>rBNm$WB5)Spu^RYQ_cq!Om97Bq*vLzS$OLkhIrZK1SilNZ{h06h>7jO{$IBI`nw7~JP-9K zB5!-fhg;lxONCnw^s;Y@g937AxZ#>G0KDU$O!DR|%qP_g)e4Lcuwhm4%JZ`xJ`e#b zK#k6ZS4<4cI2|hxbT|$}#O&Mxj~}_f(Z*)Jv;d7XK}~t;98d^~3CTQhf+PktWn*V2 zu$+ihTfvIqf*Mwf(AxO*O~SkAqKhv6|3zp1k>!qs)r?0^U*c~LEwfnc3KM3hXe`*O zfCbHin;|#gmmJ0m%zLz>jMCCtZU`1REkG=J1cfLjHb~o}t@8MVkknERKDUJbi)9WT z@rbQ3*xTf;duzP@p3O}58s7QC;0mRkgR{bT9Y*^to=`KO?^6!5WI9&as&md-i#xmcX)NMDfni zU&-OsVw&2*wCr1%nXf9%}`kDBgtTauYfBjV)pti#$6!g15Dx zboGWfRibK+iGJzXdNNiD0>43AS7GNj%{FfVyHm51lK1dXg;*2Hk zo8ZAmPcymYB0I(x_=ER9#Z3DyD*Y+V9CqALVc&rk}&6PzwO?8 z&M$wQ*F6Igl;s4VAo6|x>bc$1_q~4a-E+_P_g%)eK$?0|Y~-ZT*9kn{ioJj#W@BFu zi%`=NodQ1lla7ynWQcRqmjC%5doG>wgv5b!7|9XI2_ls1DO)BC3sZq^*I>k>u7ae*8gr;bfWTo*RIq z3@sR+Fg*An;nkOwQb{PRGE@!h+-`aB-Yxv%-!D@LTwQbg)<5ZT@wE^M{z4%&yh9Dk8h7l+z0R{c7$sNNSxY2R^>^f~tNvN=Ee3*OQ zvxRrvU8mVG7#UJ}sEG`q^J$hrZ+J&kfn5%O}ybVX=DULoY3WL z;ibz1JbfW$VysQKc8s-fE2^c)N9Mx7V9H1Svu*6%Zy6gGe*R}`gshis<7*6-AgMve zDj)x-<%T^%ImAu%w!v-e+h!OZg4=Jh6mieWwh72{aEWK~yB7TK-{#i~AxC;&*Egqz z*Z!YkH!?}-IWZJe9D?%HQ?Kx^9y-mXEoDyRlLRYq^l76~lteHl7H#ypOJcs#Mg%}% zz$NjQw?W2!A{&pZ<)4D~$6EB_Nt0(7pWqk{wWRM)B5Yz>H0&NvC z6D^v-1jvMvCUo*fET~WuHx(M#C;&kmrj+2bxY_YURVN!3J%QWaRcGHW!#5reEUk}V z2Q1^mtNgu>4fA8~fkqXKRZx#gw6n#{VQjqLItD-gNl-C#J4&qt&I#4JGTcxy3a&P1 zSz2A@%9=9QO=;BXq%OsqK-YI@ciS;vO$@88Rc4DBmg;S;mb)yL+NkkVyeAOIZIh*H zTv((>f_h@yO`;htgBV1?TP1TtTxM7Qi8VQ-=v7`;JpsN7zgWWw5$8b z1LQtKMJZGXA>sK;yLtF2;ep$rUA>hhJ%-T~sTRC+afLtl(^vV$Pu#@$OYr0?En3yx zSesF;EpzLUA$CrbSYEo!BM+bD^7&&VhVLft?m>;K&Y3s~ttZX&M+G z25Z`ElM=F7)4EZ3biJVCt=I6|H#ma=PN1H^EeC|0!0l={^-|#KR6?_Bc>FssKNr=C zA>Gn)pLKld?>TA} z__HstEc;~IcKmBbXb>P#KM&))64d!ee zFq=cwnRd$4_c>nMt(2UwwwUwG@g`kgL7bo&-1;uzz#icbexE3b?XAD5HNEK7c!MG8 zqH5a&4E|aVRfuZtxQ>QMkg9<3k?akSlmd-G%i@gogsMVfTfFz3@Zw3!saH}o379a= zz8wulCM&EL@!rFBEeG}~$Bqbl4mN1#P;)~h=1y)ooG@13coi0E>}S#XBZVBntjJ8sw;NDy+sRpaeImx5Fc zL1Iw%{kJL)+*Tk#P%)Ho(e9orLyeeOlh~*nbqS#MuPo8{UVJy9D&O~e*A8!3HUdkb z!tr7s%iU3ewQ*4m3T9(ripr@C^M!`^Iz&dfM+jKyIWIh7Ei3D7ltx^i|B8pvM<0Fk z@pgbn+$1ci@N6gLQL~jxgA;hMNV6C5vXL>S0dEYbM5T<2O2|+EIk6$xgt*b@WkQQJ zvA4(se7jd3VFgNp1khC3zE}9*9T{g%%rV=Zq;PSwtF)-ss=e}yNVxW{%mACAD!DI$?fuKH?AJTiSWhiVxH!0|p zgxq*Q>6p+PI0_iu%$}CsnpcS6F^DU3sa;~p1d_VPszt?6Y*_Vdj|5eEa<%}HVw{T` zJW+ynK@yr-hi2g!6-N?;PS5RNHvR%Vk~W%1Jk4@O?$((tw>h0JG7_pB>+I&{$_)(q z28hF%^au9->Z6ahEv_4Sw_9CWtqvgxy`rPQ?)@p3XFb#TFs4>Qfq`1!9s3h5UR5#^ zNAdJ5>=-3zKs64MK(HoIE`u=}e&k5N8UbfbF9$M4au^YkM6fnTLzhs5I0X^Qa6=d$ z@HFQQK@Dh`>FFl#eeYH#wkpeu1(f1oe{reJsWX?j`>shIdiWgQIX;4$_;xB z&wi`R+EN}fNQ1C$N;s=jjnGw32!=vZq@41dmoKtDJxjB_6)`dUSqYrJ==j6g2@c$l zGP5*Kt6Pv6B`*oj%#`?@FU+AhDkEin_lrX;bbw(c*J<`1T;h&9w^6AzIDfjymmWGx ztLgF9Q?9o7$b)-0cJqNv1?T3z<85-U|J}M$6D%q4oBy?=Y+!a7e)+$LFMrvRRB9k| zY;T<7-TMZa|4_m!2LegmQsh-`K59622!8X|Mk%Zz%N!MUvoLjq7ry#5neP&0l(pI0 z_{hh%Ff^Rd4KP&R&5@&)qsK=1sh*Q$+&KM0tTVnE1-%S)s(?R`OVKo zR?rzZbEe=Q{>B=ouhdD6Ax{D$BL#Q8JK@R<7#oYHmgeErSD>>NV$4HGF#&|QZU-$# zmA4u;nD`)y`oQFFXw(d6&%`(&d|=0r=Uw+C{JTFh{GAUA>#L9yhOq${8G>>>W~9bvRKh7}9z{*pOO5UKyoatGc*Cx$A42p= z(mwj=t`VR3nh)um?4c5$(B@ZxleZ#2-ZVmy#bPnaVZulPK+=}J{LCyq9O z;1uzSa~@LzZ9&KlK@>FS`4h7Y7AvS3!dmcj5$6bE&_oEvZbrhm-bFjtKuH`(RQS{c z3IYxT#*(X#KkES_*v-&;3ot)z0yr)@sECpHULg6qHV^o4F8vG{788q7CG8brvg8AhI)>$P_ zGBTgxJ3?cqMmuTqYWF|BN7#<0;p1S1EW>LExXpadM2k}5Ss|+mtoNa zl6nO+HjO(?SX``e;#9`{_XPHAZF2nO0dfqK4DFT>+8IZ8<(xQcP~#{NPA&-B*OZ-O z%EhS`T~o&xgGx#WmOKdF2fQt_%znQ3%?^iM9c>(-$rv56JUe%RM~(}3@9xkcqf>J@ z5tf|e|2e+Q-o1u>lVv{r!8X%Z*O^@$!{kcn1a8=6`0P)BU2gK!2}9P6+02<&4(;yn zu@4OL(6>Ctp8-;b5?EfZabkIpZZd&bgQw{6-VJ6t4gT4mtYTVCnneR|0>LJ9rOHc} z7x?xIOAPPc&#FB{k%CPWYb@XV&J4x+B|iP*w{msf@~KUDAweg=a8hRG_p0aoY z3fGE=H;(D+|NY(XsUHP`6y79~^f!LvH@I}^((8`hd+)t`?sK1eGk*OW;!9up5`XxI zfB3p%x88ayzy9mL{+6BdM;Xh@%ly(W{nG1>J@CK-eD<@S{Tq5jef(e%vw7mwS@_ON zXL$ILXCZBnNg!lh){efHA{j>L;=O=zsEzbuNQf$aqZI1#8m*Jbuz=0!PUWQK6p;dh z#kPTsCq;Kc4JZ8 zXdeX7fEYo8rzaI+V=fyFNgKPtH->(n?|t|2jeqyFPatt&?i5NP7O&C^0oP572BK_w z>;)j;Qimx!@E&6Wh3ne1}M3hi@mWi5FyuqcOZ3#c7fKl zj4veT@@(LW*~a#5B@Pco>)GC_VasqO7C$7)a%YLWXw&Vq>G+)Wb{o=^4mk_iD(#9g zQ<-HcS%9iVF%+FZuuu$ma?{I64RJ6RdTLlh=oKOfMtZA72p~DudaN3ZT0~4NPtmx( z>Bgq72ZN)tT5#%>X}YZu=I55cHBb?}2j{vRI9y_6Ot^T}bKxqa&X52W6CJk_@YaJ3 znBeffz=UYA%_Z-xPqwG*jf9J6+&yW}ttbYJDo`LH$0sEgT!)rUadmx-$>kAl$XZM` z#%UyjID2hdvOyAmzaeBFef%(CgLqH{u_;-u6h5FG&+zuZ!TpBwXL>pF3IwH|=1dL- zp7);6HsCB2%FbOCwv2Z0UfC=bRR}>qV;N42=7^sxYlXBT7-PT~j1`ubmzbN)x#{3` zYENb~3lBD--3f$s*jt;Yt}T{|3c)Ii(%`jLnTcJNSC4lPNlDbv(VZ-`A$5-T-F=X+ zJ#AQ6afkyYr$&>3qJs$~3R6a{Fsl=snDV@9zjArj^V)2@i&sfNESV26!_gYF@VxSB z#=uw+$>ZShCS^6<#TTAh=G7NpX1Y}&OG|X|w6wxQrxPZhUFR2u3U1vo&$ikH7T2m+ zZBQAo9GY<4vqw1e>!bX4|GdLrd^rP65MMA>Tj0kZ7{-@`)ph0SWx;0-AGXjm!xWm( z&4DZ+CBfK&A}G(DPB5|uqk`a~GY(K&;cL%Mlf5)eJM0E;Fg9Ri3#X=TW_9Tt_uQSZ zR+->ZdVeH`O-jNg{_P`Q%hVJ>3B(43-0v!wEGRU{*fHs@X;*U1M&3 zj;}uS9G6bDkZhJaj~!s=yKajP#NH$5Wyj_P{4TA^g$5DL8dPP?zJ{ud!!foSg@^aOJ}Z-8MK6H|&A;z8gOLK)m%S zCy=d7FfjzBvc`KPiTUOd$EUAT7GJNC+31DpT>`#`4g66dLH}cTQ%KVL@4x?h2+OCQ zdWz3{<};K^Z%yXVqmMrNJ;&bv{`bEn=jx-6A8o`Nvam@wDvP=0tMd(3l1VUSL><|= z25Tdr>ke%ZH?BrewMb%mO?Ux9h6aZgFi~2iRw0^#lqg zccdJcFbofuz}uK<(^rx9(MKO|bF8$QymILrr>5q~N{0#F#o`Q6H0k-lOwZ4q7;wEo zmg$m@wHewr#Dn9OwL9VSYnGWS#Oq&AE)lQ$vbhTo1uYc18+m{VYDm&Lx80$<`;KWU z1R6dd)p=%?2dE7S3p&foty3(d>tv>&D}lmT3JFk+xv9;hNs;Eg0V4z(5G-CcJPOwy zQ_pR;5y`rVo}eYBUaR26;w3?F7h``-8VE?|8|S>b35>M6r{joz}jAxnt%tB8b)@f43CuwW$<{6kL!^!F#|CYyC!C3 z>&A16YpU&Ku^F+bg(iWl-eE1wGSgb(CU&w{w=-55rBo?nH%J_=vyk@D#}754bI2GN z7)-hE{rfoQ%e2+7cT_mMMfl6$!Mpf*S4*vA*fDOn`HTZDKzwXv$%}$cr%SzFqEsrP>Yk_;FNrW*TF06estyfMXwLGw z;lX=5oP7FKW;*-ub^u=_%q|P7YjEV|L3Zu$u=sp|^NJDS+*ymMSJ*P%U}_4IG$HRo zzB0vu9SJ8d<-B&aOt7w}awQg-CcRr?U_BR(uP8cLLsw#4fVzYW%?fKP<7jDs;Cikz zQr0?wfBEndmD(0=9H?W{5@ty8R@hx#G;_TBeLI;NANN8LJAv z`V)@9q~IU@ZkN?oikO5#QUb7d4{Y0>a^XV3)O0tx)RL6oO9TmMFue(q$J+tUwDyv( zRM@f4Ff?R1c|6B^$lMn4qzOq%mOB|N%+Kv5An)5!$0}FAsOCI;+J^m&Vu_tnviLVB+*%tyTA)C zPGeh3tcM*m?J&8dG=0j{bL%88fDOa^OsC3$o1r0X@(>3FUw!mNR+b>imBJe)5A3HH zO8B+kS*F=62-Z@TEBwrlwK%z0=B4#XoT)O{Epz&0o3H)F)3{0pkKx8WxcEEB z)T6YhC6<9om6i??@K6p|NwEd&*d;u8x2LKepE+C_cV(MYplYu{v$ylyBndavq1S8% zvaw55*sSc+>vyVe-HIY26bhwM4MQ72Nd{aqmH+@C07*naR3u|(Bcq)QQ*GO8v5&-n zEeq-#g)4fkn@Lo_iXh(NgXg_BT7K$S!p+1uK7#EPZM|hrqmMrN=;Qx4<~xDExZLG} z8v&Qb@;ddAB{T(+IE?fxZCO;2s`XG2d>)v;*kx$Uapf5l(j%I*gBN*zz4Q6oUE`Ernpj@XD(ewMG0c? zCW*=tBN(4ks0TF|mAEmMUg3i3rs5=)wM4C?Zm^^qh5?bd4jB_wM`{RS31VYQuEepW zuuU6v^(Q;){cTyK@IhRz>ZxRc0jqfaEhzVjH?Ty;3n}B6`;BIJr|Ra-%@82L}l2k)bgznxG8r*O-mF@EL1IREDpD;&R^($<7;KG9@y z$Z_;11Vb0mf*p0sST*Otca^ad!lS1=OS$F5RnO9y4!aK@;8UiKTBTHi`|b+V@~G}k zQgEqIN-Rl95Tg`%f%*bTOiy{L)arH0l>ki(3VAo9xwyhzH#L}?NSK-N2o4p4HL!nc zi%RJ%dA<#wHn2`uY8K4RGb1ZBaRO zcAmorMmRg;xiX)lnu1rvf~LKKssLWfEQ(_wF{Cb#<#`lpq$QTjb~YwY8sZ)%1X%W4 zdG<_#n+SAdki2B^*0a!E=i$G+!j8eMeEfj}eDD@!>-GVzwlfk8!)}-&3v4y;-otR^ z6DeQ*hH(B;ELzoExcRX1>7O+G+dr{9^dF!ILLfQ<#9H2Smtka}%_EPl(Oj>g>2{$qbd{O2DroV{A`)QMGE-Go&=N;jzy!qBEV@a>!z z8Haub={XadMarWubUAUNi7~x0s_iSRbu0^d8>t+He4gj0S6KLJo6A!HwFbPU<&|$d zzf3s@ZCfTJ1zlrMx1FX&g|Q6<4?n-g+W-C{gS9r>#_GKD_FX*u=oF7WzC^{Q813-E zk2To)?wdH@zMXDXfDx)@J70Tok-2V#PI(&|EWTUg(c{xR@zM!wc@>p{Pkm$$hYxL| z?kdsQm^fZIz06m>eg*ZWH*}cezWev^Yri)V%^OA5VEdrwx6Aac9YUS^}HoT!O^!kH8z{SK1EUYb&cLJ1@s&*M$ zn_^AM%!Y9aOix(@lmzc2Rt~$^PO5mELOpfVoaN2|%RPAN*hnq}HdQ%&^wCEjZzpWp zs#RHX6`rcx%$30mEhJvcH-1n8MhX(=@CJfcjIq($og2t%JomMed|~Divt##jWjT;k zOOOc#9@QKxtL)y@AnT?yo3OSPTWG1;I1LoAX_?7g!qj?$SB~F^v*7ckd1493D* zxl1$6xDuMU%&~p-0>|2;>?(~jKE8vbaHOspIqY6cjq9sR`}m=QiTT68P%4bH+H}re z;+f+^tft$j7ae})jv+pJ^EzLD`sBBW`V^Oxqh`M@aU zN&|AmB!bU#=BMX5aQ_Yt?(OjWd=~FR)pFtDJnKgawoD9js#S&H2nutHOI*IX&X61A zo%;*^$gQx@t;MTC8D4oF_S_z*4|&!W9Eq_^uTSvu^e7)aRAT$U4AZNg!c-7baPWxX z%4*K)qQ{36Bqi%AjbW$`6kMFo!PUSUGyy`OlIAE%rulYIUoMuL4N8ZhdHoK`OsZCub%c?ylN1X z9ATjBxN%tdnU7iq8Vw%#O2(C`97z>1jt|`fx9x6o@#F%h=gK&f(KeRRy5qx#h4!av zoatBwMjSiqd$@6H&JEk(w|>s@?Po3j?fC`H+hMG$W6~I8 zCo4ERmvXs1&YT@0*noz0KL5yZoS!32Z=z_gfmS%%DslQH-Sh#bXw**6$0C$u^_;|F$gu6ZN>^vgSGH-UDO zdj2Z=cMkHIAAbkSt8oyb2Ab>ZoPYH!^FE`SIB*F^Z`wy`xbnIe@_Kvx8{>Pw@iu-N z{H?*8Cd|J7{`yUx7dSdWOg2tzjWgd3t7yBa3BzEEq}(Uw(Ru|LviRtTa7E$FpU4ivQtr zxAC6+aVl=!rgslz2NUBp_8kbUmxT4X3TKNELb(jKgi#wGyNfnXE1pVC=oTjSj)<~@ zHGbip6>i;M;@veExZZTpciQ*SM<0KKc%xiNA2pBHY}F!o9COB@)iQoL?-kEQYhDcB z3_ylU5~x_T2za&N9Y%%IGXwm2vV|R01EtvTZd!`X1P6?aDz(v^{X0Fit?<<^S81;* zlogX3g23pWjAIYXbNsm(7GK;;E<>nfbWDj>x<*lI$FdW81w|6ophjc4UN9l%oQXjZ zLJ)#PrKkqM$VPn4CNs*0y+P%g(;*&@%2L%BGhkGDC4+&W#C%d5LLODK)VOkPKTkgs zXth$Z&JHM7!RMd_og(4l)HsDTc#Uy6&?`VRp49kQsuH@8wAnG5aodq$>cguH44guk z#cI#CDn+kiYQq-KwO!nGPi=!Z{hr)zjU^T$;9VE59h`B@NtYLjCab2yj-@pY4<7`g zTJ2h3&c^S0d#>qy^zr`{J+6z^bQ`~FF=dBOmBK?(Ql?tMLzl-Xf`vS=r#r;1wF(QD zUZUL`!PG_x2wj(AYle%j&hqb{ILCT@1hNhvJh;N&{qPw6=^Y`xComny70nX#A;LL$8)Zif#E^?JfUy^UxfNCG(Km%2!8g!g~+T|D`_ z9=xLBX=fQH&!()d1x6cF)RRS){C2E>_XR6+8GGx7(qzt4tBzc%h^zA4DbMWEGF>dT z5zF1m(&3iv1?|OoR*S7jse-Bp0@bk2@SrlkQl-`1u(TV<3bySIn6l&aiv^fKAt}?H zD(hjGZg~igLo_Fs66@u?{2$*s&CTyFbL)7C$4)J9zH^j13Ay)#7c9pPHyN;o$Gfl#CRbo0o@K6<~Nm=T`7(B<6crzvLz%?`ZdJvlesZdh*((riJ=3{rEu zdFJUUlJ0lt=AKNI?Gsxtrp)jB-Wg8MIMfyF9ryg^e>KVWcT{?N=(s@kOLzZf@TQTZ zM~@z5Y;26Vxw*|_Aq1X$@<|?i@WD6hG(7+O^Q^9}zV6tOBS+Y}b?cjUjz0S6oF=DNw_8+kAK=%bH5-ZXp{>31EjCrDKxNWc?lYa1;Bh{Og~EiqYh zykeDLEu>MQ6s4nz8o}d9N`_Q~&RT(X1R)`WK-XG;>N^>xtgv7I4EEYu4D(SRk|-=n=eY(7gB*(^la zC{xR&Um`1XL{7rXIslBuENh0F)MkB%`hLQz<7mOc9tkabi%LIJ_Cyjo&@$xtp8 zRMR$A16E1|(*>F5{#zSNcL#X(Oq0TUtP@)8oTOTzS}!v_V-O3*d#;|I<<9+%q#~S~ zYg33r2+T|`a_rrMEEf%4IvrxGP7&G0)m6{V3Jg{~D=pBHrA?L0mhqZEFQ-+2B9yr* zNBP%Jwm9Cn#Ed=4O7$*U-l8IW>G_L{Col7}A2~wDk5af0y8%RTl_nQ1EU~b4j2p+x z+%l>B#xEIOxtL-sbOmnR4UI(DH(Ic?oP%?SDEo#>IEhO8t-YRv>n#UC4CQ*@mYX~~ zTNYnHIY6T(Z>u~~)z=Tiq_-{x0y2{F#QEKvy|kN<7*sMQw=~(ezs5@!ODwH4Vvab% zXv2`@kasr%(xTdWZtmJ(&W4=r<3hU)i>nrOAWo?dr(~;!Jol)NBzilPdG3`JvcyxE zE`vjD4&K<{%*hJ#i{+jJA|uO`&ET4K;$MNYP?)+|UXKxx9EI zB{k#)JbTVE-xWe9?~!amZie{tM_=KqkDVh6kkRJj??1*Jx8KhB&QVTvwox{1Mw>He zUdNi=vy<-{EcWpO#hdn#5)tmd|9-ykg)hAB_+yVf_NJ1gZ)CN9-}~P8rv3gt`sm{g zAT|3(6g{OQAu4+)>}C;$rUvh_82&B^Xab?cu^Zt^&9iU` zYy#dX-UzepE|0yiz-@cB(QRd1oL@o)Mlq`e(h*D$tSWgZ$U{`DS|_o^z9=E;2qHZj zVhq3Tt+8(#TyKHjqRM*`Wo6LdOQ4xYtVH{Wm6%)*0@f%4S(^`T6+UpV#A})2Fx)P~ z>>5jAbRRJyK{hwp@kpN~?W2!A-Z}`Xo|Tnl=9d;xAMm0Kj*c>1AEfM3)>=&p3fA*w z+J2Qxa?}{Qp};!Bx*z85fo;5$x42jvf=&WmK|@cCXboPWS_#Es>?(8BddMJ3Zn z`x)EI`YeM_q2&W-r{`&$7WN&hGQT`a;o3;K8jDNB$D+HCU`>U6`$rirhDbyxLdwWE zB#G%Y(H9WP2o7w{rm}G(8&rGoGFjaQ|*VXuSF)#84KNL61qCI+bgLw@_?>O;V zuLT+u=TdSjU_-AYLkOA?q}RtQNn95~7qJ=QG6t%a!#52uye|dosOmVo23u(L97Sms zm3CClnv7f=1yQ-Pp^OzHuUloValF@_^ae>PNL0cSV_+pfFdk0;>+$MYstD_e;as*% z#a(2)vW2_2gKaHnl!VkIz2U9)<7E2yp+XxtWg9$`Wn`{Snh9x02r3i;L1Qj+AwuCb z&T(8qP(=zLSc0{P6B47O)?z|J@FgsUCXUPHNzOEcaz$u&*4S2UViUzBp5T;_Dup

ICKy%HbK7JNM3x)?1tb+H7u_a8Na{lZz3rlq> zX$5CNryf(WJTq11(!aUD{-G)d#>$M< zVb|PgTxk{+gU>vbOOB4ck#Bx$kuN=dg!FbbOmF<`qUdhNN=@@dMy2s>0OeNN$4SL>Qldr6ohVt(cx$Bhh6B{8^+JWqTZQB#(r-!(*68D~%Hud5P<<2lZOrRRekwWfit|=GSg`g$WnwK@LgEN6=gN$7<*LD=1PW9=o$3Ua@&{1$s1qb#VNp|B z#?nf_rwJM|hKI-Sp@{btkpg~eU&KECO1!Cahx_ikk3ad7KY85;=ggTiOixe0DN4_^ zwKbl5?zz_;+sH%hqmMq`Li7roR00wVuA)elxYxp9Vksxu%Wg9bi+G0=y$qSEP^y8g zdRT4aYzbo=S=X{PaeVp%mM@OLzy1rNYR5n~NjYDnTn;c?vJ|PO(44eX!dOcha_-s- zAAUy}$hdfUndQX-6Do*?_*g}#H4Fuc+uXFi{Wep%0znusfuROe8=l-5iY)#;RSXoc zec1D>?{geT201uvajB(C+-MFn#2^8;$pXjCaGd1x_6{oQqmMrRRwELF1&ZONu*eJD z^Re}uHaD6UM}5KsDOXqKITbFk=$7!(qR^Z|m0T4uis}|j;<<6(Bp1$mlwPB8&(08) zn-(b*Sjn(uiv~kzcaacDGi!x?2LhEw!4uyQR_6_x2E27NvkLQV*r8Q|)KR0509A+e zP%G!`KjfI$T4HDjS|dvsO$Z7$2?Tc$D{K$AMF)jq-RBcE0iGD)Tb(O z0~w2;K*bU?kQafjy6D~Q6+#*35D`o;adz3uciVqM%8`Q^H8aEb*cv-*iM&v%p-s)r zAZ8lXH5}3YrzU2Ui>3tQBT31%jqygX!gVPE-}7FHPeXezt@QFnO(bDe2~yB?kS7L8 zmX5So_fzDZZ?mtpjbnO%VP`0(l|Dh*#}6HvP0!V(f^Is1C#vXE6F9InFtw~W-z87e zsC-WoBvG;=qbNKN|&iZc+z00vP-)L@LkV<@CfH?edRg-i*WQ$r|;K}Aq2;GrtQ zXFh89%aOqU{bWv%l&kpwPfj~_?@X91FLHWCQ9FQ;;=6{MC*k9F75w>Qt9Tv7Ys&dW z!|B;o-gTtPO^0{!%BoT%1|tbB8Q|1~j8EPIH;r~Uk+;a*FxDF8)*L0T_)#H90g1BW zt333T74F?vVc(7t&t3sjvJ~Dhb+yHju@%Ns&suvBHI`ru)(Yh!XXma_UR-yyI*M8% zgGY=96Jv1>axYLoFb#5Qs45yfQ6=wCSK+0pGMA_4@IIkkGKkATg-jBBTIbyPdCu>u zvTb*TfB)Dz|JRo*xxjcMjsygg<_w z$yXjbi-ZF4@PYRx9JxVwX>OTwOBJj&3>G;bS-WOB*obU-tMSIyUB!D(@I@45Du}TZ zn()NSIlue)7kPDdjB{7Ek{RfB0he%LA?4y!#=7zB7+T@I_YUyPY2nqEHEL>5yeiAf zhP()%o)8;_$(`lGN{J90E>Wrj&{adH8Q9pIS|i-BBe10!c=mV&qz-^LX4lYZ#zQ3u6q8nxjhX`TL)9hnO;Q zP-ZGqQl+L+4N|G*2|)n`6r(W(22ah@?Wy0wX0gDl%@^9H+pP6^t!_R*ciV1kre`l> z-~kV?i+Vtnfg0tSq(W7t(wveqQ#ofw#&qvJ=ieW0L`tGYhT_SO+-v2E(9yj&Zrr$W zPMm%A-hbkvV#NItKD{-(82my>(t&{iuDa?f9((Mu^V;vZ=N{hq&UgOY$G`8s`*803 zo9C8WZXpcApZnNrSi>5g2i|wMMTa#JH{Gy}txHYDPdKmvDV^!7dL&RhiZvMomLPCk zca!0oOAP&5;Pjc8rDZ5urI{H9`-Lm3P`^akcStxip3-V78pJFV)-e;u6xvNPNx-Do zLWC0mpHVeUbY7_S2YmbP!+hhuI&F6iwis~5&VXC5HuM(r0oGgJp${)0Pf8a87{y@e zGw^3`4_HazpYCdL;J9FHp7q)z${R=FN*m%3Qr~e{YF@cMl1?@(8TtFnI>vigQ z4QqJmkk8Oo$T(6-I8YS4I09)=<0Q5jaHcuUR65I3)zh3QE}|yG+I;eEk=**7W&|#z zUwY`Bt+3(@s)B2|d=(A@60p3ojFl9L`Uy>p6cuqoU|?Wah~mR+-8#eZ@vCVi5lPE| z#9;eriO_Z{sK$Ah7%376CR2h+oy44>)}CW|}y@1$UC94kUY?o)fcA^UqGBQpEr)U>yG|w~u z3PJV0SkF2x8Xl#uTqTkaOMtnMtRibz!_SE2#T6FM)RC-$GcCNalzI&7D;dY1p1^8} zRNLSoF6LJ4Rx|%4j_I0w6?IT|5ni%9uE}ON90n!IJb2To(-si6EJev3>PTnN${BQ_ z#qKC%VqMBNiz!~pEJd4mS_8KGj8Q+uNmrs3RPj>a$eENkN`afk7Wtk}SP2HmqL4GK zDxdqt5w5-RQg&W5%-8oONDv{B#mfLoHA{~euD>YZ-o6#iWM!O2tOO%8OsCmjCq4 z2RXR^M||*4f0rkcojlsuL0}ze)?~4EoV%Z_^XS|GTq;Eg|(uJOg?6`b+wW@4d28Z;^VzV2FYM zaHwYd=$^-TWdAW#0@OLK*m*H~UVA;?yMKUp?Gqa7QCB=I1X~w`{!1hapC!SUorZNH&O4$O(9y-mu*$k$N zb4{u}meG+xCMPP?nh_cXgh9faUl$o(-Fr+aWY&Jbmi|+7027 zO)=N*9N>Tb@BrgWo={`19I{-zZp~tUq2L$J7TkL4tuGl#x@NUs!y5h@ArDAFuqev< zQpnA_Esb8!iBoW9j$D!BJb_UR9u;uTP;EBYbYzmPttK0{ZRFte5O+MPM1iNRLT!`s z_CCiestt~Bp5?Dj#hlVUP>%^x0voV-W09M#8Ro9zmil6bilwO`cTFy!KRC??2QKB1 z-Of`%n|9obHz9Gb$o17F)+fCL+K-AktN6LV5DJ~V9=KeTO$8;3gyK%iox?(444S}( zvQU-0T)iL^y7R$R1rHrkv}>@I9f;uHCaJ{2*+u+%w4jd zQo%#HO{3Vr+Z2!BI@W7LN12L%C3gS-AOJ~3K~xetTIK}R{vLL1-on8{jx_F}2Dx&i zW4rfh1&;@@gaUzB(t@L{hNF`$E}ofX>-H%&U-1Bwi$f%*w}M2F7=qL=7)9*7c$j9R zz{0#kjK|t0tu*BE18rnI^pvh<=}ZsxdR{c5(QNU=(~sc_3&c?m-@VhYGJ7pyU?H_^ z-rU2h-*$$$ci*b*{-sfpvf7=C<^`iz%|orRdD}ilHZ?eLVu*Y1OGuItES{K2Hmol* zIJk~>W)YOOgj9zUn&~11QzPi4vluZLt9Z3}VGMy(l*|~s8GLy z4ntnB@vN*=QEdL#kv)m#9H~JFe6DhZeB?3;sFH~S86iqyl*xFJ`JsgV))}VL8Fu)K z*lb5hQz(U1@{(F>bt%-V0bEHA*5%J4nC;C@~mE;=-Kt3e)`ita;w>v6HhbE%Xs; zh-3yVcw?EEPbh8|uH9YcsTGS6CDVW}AIP}r6;Q0!2`ped8hA7-Fg0(PooloG(jG>} zJf}~kXk^L6aPq`F&E+0$dtER8@&ueYV8BFVsS@~%!CqKy=ITQY6rXt}PtSAJrXK3) zGLKGIp%Am!C@~%Ho6Iu{f308GoIyR>sZMuIAGlO@ude665qy_3vAnNsP+rT4k=5s9@JA}iLE{JWQ74{ z7D~88ATX>ngnJ(VM6kwCE(L7AG-PVhFnwx>m;nMxjF>06ez?Zo#-+?J^ySenPFb9V zN0uPzR1_Q@Dzl+?j8i94YReT&!I1hI*N!dnoA11m|L31d95|Fmn?8CnQnx-5%a)gh5+wHn1@k!rQd@bEC(wryLpCavM8 z$7=Bi5U-TQ@XoE4-D8$-{IJEhCKHlE0o9Bv`W(0HEHPhm-2Hfil{97F6N@x|Ji+U3 zEz)#-G&4(6a~b6RsTDrAcY!zWD6x2Yfz0(0^~Y$^=K71^#!59 z7j&en81&%9kp?vi_9PqDIV9bVGd;}L3==1m+9KpL??PVsH^^0#&Pz_FSx>_&k3JES z*?tyRmT0CSltPR#MCCT?H(RQM3)qDjH0mYKJo7lKIA6s1UNYB*b7LggMPx|<@0!W)m%P0#i6_?-sA*;6F>~!fXkCe zbIq)3XV^I#!0J0`q-T|+xysbwFdbr*EsKH}acM#39wY@kH*C`SOiOHx(HPX06 zR&OvpKf{5v%;v%~46#RV~wHsY~y$Ii`TT(qUZ;>iRNiv|(R zMu}sG6Rvwz#O`fVoF0$yeh`8p`;Sj?;CO@AyrRm>b{08&GG%Hp0TZL%(ynBOO+F|Gdy-WM8gOdmYLQn4;)N*^~)_=+cEPGB{%~sQ6IG#VaxWEtF8!{ zI0kqysu&=tJ8IJ@V*_w>8B#6e1_lwPr1hgfj9agCsD3u_HJraAuf``;# z3~X87!=L=lP7W_yL@gW526k<-XN&*6l=rCS+0#kt`7d{$;713b92Z!rJ8paRHg3EH zYH2?+euyj`BGeV`+E-)l|2W2xiHvsAk54k3ftkq_?wFWCZA|J1*mf~AoG^a6k4!w6 z1fv;Y!7?;rIef_B)I%1MVmN-dPR$A~iU|uLyLMT|kHP#j5Ga9HMvHA;vD5N^7p6}3 zk_u$rvru<@|K17a%tm}LNMM9gK}iy&o#ww`3bMlWms?)*+Ft(pGca`!BvfpcvaWQ7 zi#K|rqM=Y$tbvMpDi&UUlV!&iL#hzF0S2X?twTzsW=5Cq^lUv|+>CP62&ZjB(l zpzsSPNv*Zqa?34z``h0>ul=5T?)kY$(jWfthtFtx&1+usqV`o)9)0vt?!5C(o_z92 zvMhVfZAV8(x#5Nzc*|SfLQl^N|H%64SHH^FzV@|ew14n}ALQnnZ+=nd2k_nRewWXE z?sMn01wp{aKmKvHZr%EV`_IqM^X+ecn};8Mn3TdxNBI$ zD!O6dB2-bXRv6BNW9>zL(5$f#Z^pYeJA94zj+HsHoN@Tab379DbELS7q`8jP{sspN zH3+Kt#Mr=@dc+q`_2JeRIq5H=RSt2bfI`@2y*5aXEwfy99DKS#Q-`ot@mZdWCf4AL zCGkorR{E=sTHBE+ESq)QS1a(!RzyDhoHYSnaOgM>HJ8-T5`!4%^U4iIh`V`6VhN3q z!dgw=HLPI`7aRm7(u~NpaaOQ6jCf3^c%FE(>PYC&W2@PekgF2&1+f{beQkOxWh{D9`(Rj$>$UNmuf?m7I{2ya)+3ditKGci?1Bd;&@W&f~I!IL!&{ zlFbODK_GPkLekD_=k5gQT;E*jlBcg40?oY)sgaJIK3AI3d3}{`cC4Xmx~Ee>G1QER zl=FNYs(7(D8+MedIWePNP-8lDYfjc$mE4*td7-CTC1J%Y(@DZ~yTO^+Id=A6Or_mV z)%H@b(OMq&8vcDib6Ise$yi!!lldZ^BAL%KNeB8M%^X=~Fg62i=Mha+aIt5eh%79k z#u7=3UDc3_tP*Bv-Uqu3=RBd!<3+p+a=X3hDA@voi-bf1(CD0g8oU$2&>=Pf6r91h zyk`kQM^;Fwwc41_L(=BRktT1rWdrNiD~}&@5QN}8^=66j(`8=ih25j`++QxU><7@G z#7s8Eoe$0N=39Gs?G-UU_`xjG3f{)JEYFrMZ4gqiAeO}Ta%iQ_k;!>p_v(%O+njP{ zSs=8uopNBxa_7Kx^)R3Q)+7BUJVTz7@=;G>Qp5Uf|yRs!=Y?A#F%I^oEi zp^+K7>v$s@4JJ^I9Pf}?lJ|7pds7SH zOCnlHg_9>XplrlTK)Eku%N3p^6=oKoxspe)cyT;=Ksb6-XstNnvS)0g&|K(aVX8=5 z9H_Exo#mR{LSF@b_#=;3!5L3uW`_I!Sr~7PV6{lO0{z3n{QPz%Rz^`f2&tjB*Yk&e zB;2#tanBD^@Jj5?upzeW-rUQs%b=Y?+#|Sj9b;q5jBO714}SzpZ9^asCuOeR4C_mt zi?(W)Lhp=%Azf#mSH)O+&H`d*92NOx)!bUci^NM3&Ufprw?2a;ec*uyc<+1Pi?u&} zr7rJ1_uO;Od2PjF@kNo4$BrH2um0+(3$IhKQsaC5m_?qM6K|NS%C-~H})zaWvBWf@=j z%2)W#cfLcKrZ4zf^?IHA@4uh>@4ufLZ@iJ;`@P?LQDpEMe$|nyHyw%*LA=8nORvJ# z!2*|Ds!a6@fs5G?d15idE+uqzoL`3zE1U^OS!}K#m6*tQl9mBH5=5+MfqyxivfM0E zFBqK3XcuDcUxfJaDQ>?srcyK%EVNe);+0szNWfrkKkIrT-nc73!iaA_BAi)rpax&; z$6MD)hU=<(F3f6y0(rh5@^pr1h|Nj_vJTX)Dj~fCb&zFBmica-q};urx?0Rsf5L*Fi!Zw~qK+Mi?Uae>gjd{B=E~g}-+w^x8sr6gBE#vUDR18C znHs9|*xWkOyrW`e!LfX#$&K53SZNua9=D{4Vy(xwma#SE?YsK;-eYq-IMIVdeF(zL zR7O~Vk&QxaDW$&Tkub{RLuz$?0q2po8PmW7~) zwqGIk31cF>`{kCoE1=lv%dgy|^c93RZiQED?Rp)Qe&eWmOCU;5XCB}H`%5mhAOc<@ zys46C0gQ6uq~~uZmCTK@V@D7D>xHKe8Wv{?n4m8)3AP2xcrikAOARDb_QA*h_eiph4;TX<%u6J@b&33PGZoM*;(Nm-^>>Q zyjlhaEgMHe>ND$jY9ga;1TP7@E?54;@5X%opIUtHz6w$Zku0NPTD)#|8C!Fl9`}Sc zroY|Cre0w~1RwYfW#Kk3RzRza_Fc|ML3!IQ@&#JJVkqJ%AXp6N%{9-_=NQSyLg`*e z&i)QqBS~xc1s>f9m7y+qdsL`#!*)J$s1b_<8sH zmw)*e{_!9G@fpRQUJTmpHedbfS9$vBr}>jV`4h_J^0RJdjNti+-n{u|I>s7)HIOSq^667P#mgsA)dIZc`ab%v@8gt$YX@9gC^6(ANkc~0_YqBn zw4Ks4C6ZFap6yB|5%)iy<&zx?Xj;Kx{w!O%BP!R40ykq zIJ$;4tYHm5JAU!1dhJx9FRP&fB-QLAw_i> z6~)>TeSN~_jU&v|3bdMlnvRt;MUBV1Fwf5p4H#u*$z!t^6$93Tc$}}$Zf|9LqCqqB zsKl5^u_fuG%6LY{`We~Mz^Kqn>a<*dgceD1TU-z*l|qGUZz@v1I3czHt}Rr1+C;^r z&SkZojJU34Jj2$a!U5C12Ha)ta4sjCA=%Q1Bw;BZ(pK z78S*b<^`U-rJx}N6H@mLQj_6LZk@N97vhkvZC*Rnwpx08fG8|!nlF}WZrN2it3EXy z0z4qYkkO^VJE^Heni6YAecQ262#O=cU~!szKImkd8npyzgx7#pprodo$elmtB&x%! zCy5LzQHpxUa%#9SxU$Pk=a)rXUc_n*Yq-$hJ2z=yIJube@U)>859U!5sbl+?a_Ml$ z-S;+`WdOA$tVC49gzZ&Wnr|~vi}5zkDV0nqM6l3ob8HEmtzbM@?+Mk@7YW<@10Ixw zh6{mwkt9agF&Hx#w^`0YoEQ*?7zjgyF#=BW^A(|9hmr(b+#7RZ&eIAbu&}Ts)SAkU z?LCx>i>x#(CJb;`CfWt&T87P=N?dV?aOiZKHW7%S-3U2)w9U>-W3Jxa&)rX@G#d^A zLt`bQy6o86=Q%!W@ixYon5R#*`N5ASxPDuahaYy#HwQYAEE$LPPg5Q%a_#mWeq6Jp z-hj&xbsRfhqrceXWtWwhoXnVO^&o+zo`yXB^f;FcC>!GjfrR*u)S}UJY#B`WonP-^ zVMh4c9d)LbLPQMZQk$1;EAh6g1blavWU(e;JppBbw_WGivZ;@0Z-~QTZticeX+XIi zI7vc*kR(+~-qCCd!54SR|eejYWRQuw$4M-iuxj`XLfp)fBx1u^+3t|5Ic56 ztSdNv{8W?Le3%b(nPY4$<9)vo@PALG%$^D%GN>17OOCtloMd5X87+))O~>KG z84FFD^O9b<`AWF`&6fXiXCFtWTs{n>E&7Yf%{xkbud;%b5>^y%l}cn7w8DE{SK#vP z`8BI#BV1e+Hul2B8x>W9#pl_w8mtnUc}zxk{55CW&%I`=PkiSwBR^StPP^xVEG+yh zjF;@wxb@aspF!T;bI(0L6G{4P1)E;TYX6OIe1k84`ODAxf15UK;_9ofW@u=LIF4Cd zT;%DepXTw$AAbf}xqttDKJkf9@E3pa7evvs8(aqm2l@Tq|9w97sZX8PzIX3l?z`_k z_Uzg7oagz)FMg4UiHY;thKGmw!$17P=Y4<8W|NP9{NvBq7hq^;h^w!@nz6Al%H=Z6 zW|P_3S@!SW&ygcX&f9i&c9y^V%fI9kpZEmB!^6+}nrrygMR%3U1IBlhIzG4P3>bJh zN+yC7gbcL6FRB^IUE1~jt_hvLMnRxHm| zkCtxb^IYGjc_ni+|38huWT>QM65u5vkQ#AmoQt;)Fu7dh$dP<|F>QnffjELfA4ywD z+X_L1WRhFpjnAc?fL9M%VRrKJ&cw5bgyb=4x5L`aZkXy40TOSQXl280qAYngU`18rsBZmJ_9TLJ~sS(6!o2{%Hr!V>ORpQ0_J#G_b4KO7s`cz-+jXf?~Gw?4*s{}r#XD6 zAB}raU*pVEb&kX(niEq9n^0dMu@O_*My4C<@j(G+D(uT&XZ|U%Wx%Ppidc!6SiEF&$04gpnP0)Kp?Ox zVL6)=gPN@4Q4G(!_|Jaj+d%PIws1h$dAu;)j=zd{$w<haY~J zX0u7LSbUy6&quvp=aEMqIj?Q==FQJ*Lx1FvN1l}+9T^$n{qKK2S6+GLv+lRFw8WRb z^rdHzvd51f=QE%A3?KNw2cGjaZ@&3v_U+sEjD0`<`OmX!*DiW{d!Mn-0}njF-FM%8 zURw|ZeCR_TdckY-H-Gat&mc&v)hh3M-}|`v=9{0jV|>@U-o>Fqhxq*GKhLpa$5z|x z^*W#YfAN_>Owky7+GB+%h$n#Nb@Zmok84y;<;tB;epAFLLs9b1XL2s zB~^IS7!0*r{O|vDg~?z9V+Erg@0CKYC5)8XlHk1|wPjKpgSLP+xCmzr)+)}xU8jo> zJ9M-_Rt^ax#e1Qzy})l>*2|^kyh`Qjd0&WF{l1>f>FfLy0x|^KnGD()1V%}n zqn5Oo(`8JUu|BM_pmo}&jU~%7-8xD|0PW_9c1Sc)ze=RxQ^flYNv3)AV8BK-ij^fs z2Q%hp3`?~P#p8*nmJ_bKYJx*YW;uRzJD51P_*)@}3}NI+n~pSbs0lE>3}R6QXIeNb zK!B)aeleu+^ai$V83a>A!VtBB25q!ZXQeg4{8GX~bC}2XfjS2+U|oMeUv-g6c{z_4 zR6}0sr1L&~P7SL8#A3W6#$na3rvIhb{PPg-UI`__Oa7S|^2il~$7)_oDYwm^%?`9a zL{Qpzj0rJf2m()_DI#sur-%`ZO=lssx&2}ucXt1$rG{52z4C#$WaaOzm`1;t7?#gs0;j7SDy6Va5YqdIol zeYXa0LUJ{!LB*1ng;LrnOa!OMB%tX%B`tArZIDaE6NQ#iTt&>B|HPzgxHqCNzt1lF;x*Q24KZUR~w z-~ewt#n{msC}lEY-$vDefR|jY7qwH0?IzYZ#0cVxEG`%}_Zu!NwwOxVWN{TW!pwY% z@yb|#Lg6Myn?ZX)!U=1)c?uf|6X%q zJ@cNT4aiH0Su+3tAOJ~3K~!x7eznu}VpnSct!7RC^q%ubTMNt>t);SGV6vdGc%rJ2YV1_fdEvw z`$tV43){@qLP{mey3vqkYMDDz;D=MaILeHSWqkPEAY7K#N+IaEff!r<-_*O8K72(Sb=dejnW^emQl zCCCF_o^k#2%NZcgxTw#CE)i-t-xJvR?ACmO7ZhGHk~EHE_Uzfi_rL%B)wVQE*}Hcy zuX@$1Ui5M9yYIed6k2*d6=}QO=Chyu>@(Ugz4TK4^iTivIc@U*y}iBs(I5R0+qP}v z^Pm6xYK|1Zz4zYBjW^!N4L98Iocq83{qN`C!GlaqO|7=AtgP^NfA@EM_`@GQZ`+xf z89wuw&phK8?|ILA*s^8IbG`=Tirl?>_ny}_Iy%b7KK3#C`ud)C-yJ)4@aKR2=Y0Cp zpXT9*A6{)AA0OwAJMQ52+i!o~{nxMt;F%tR&ZuI~Y4Zpd3H;AD1iZp2a|r!XW=|+= z6Hj$R$mC5`{_#l4u_eWb#X8T9(SV^%0Y7{Ik`;l#gHJ&mk$AQa2TUvqH6I}=)XQTW z?}4hfsPiON$p|RQ5|?O9Kb5nC-UZDtuF}xwoMv|&v)jHlp6S zLIdlHhH|JR&NJ7lGnXu*L5ho;NJUVu1gm+Z+Of3fDnT!~#a_rKZ`x5VT4{GGn}d-A zQNd%$Bt?n~Y~R+TS&w;Sf0k#7N&%roZ_fkl*y>5riobEg^-%RuUJ1WwyVzm3&ccrf)k}G`?O!wwky>asbjak?R+Jq>9 zo{eTmjgX1Sm9i2b1SkQS7<}M4W9K*?w@Fk;r9e5Ykj^(*nxAE~Z;&y&h2H4-e>1OP z4Zloyr>rcr$&z9o4WUY@V%fUMk}fxBuQajJgLjV1Wr(&ZSj9U!j$NBS(H6xpB9Smx z8d^hJe7-0nj-nA_n=e|3=2d@uC+;LPLEdjz#e{~m5wf^!*;7!isw}ZLZL?D8CnMsi zxn*WDN2%;E)Uei(C5}ZGaWt{qHmF>^qsrkKOWSz}6_8? zD^iBXgd;V>!s!w-vyRCF4PLuBCusC1h)mN?O{)hJSpTB<; z6P59%O;9p?^bba;X_1HK2RUZ9V10_#JWH(*p~_0MmC0}fampnXLDO9I|Lj4P+8G}^ zQE1kZImdw$Q#>_Q!-TmFe&awNS8N%i63JQd)K47F;ShP2yk;@XE-rJ|gNLc51=I`c ziy<$&W;3-`#((Q+ zvHc#+A_!B&3gc4|vqH5$KW5n)K63T5ltxsEpFUaWTkESVgP>Gp-get<&wFmF$~V9H&1bysM?d<}7bHl#h@yx;{^LL9 z&;IPsn4X?qZNKA=J9yKZ-n6DBUBl0fZhmRx;Q9attnQn*?e&C9dP}r#P@X;lGm{3fF5AUg)`!JYco>krN<~8F{X*LR6XL2>b1W)EkQ! z<4NK+Rtjh#K&>Sc$gBZl@nT8D<1&XYDMk!N1h3$XAu~Z9N$1*>C8Z=;t|l!ys9FLI zXa+Hfg%mI*TqU+tz=+}yT(>eiIgzF+dC?x*$t&%=;hg`I+_oRi5%lh7aO7$(Ss5f# zL9Ni!Qy}OG*gBkHIK%v0iN!%>yOrkE&#r8&sb5>69rkg;QD56iWA#-|-b zeGn>H=9rm*Vr&_xSQ<6(u86XMwx7f5DU1dYU?7t`OIjq)AyrXA zl+b%DjzF`VBvp?WgYVegMZp-4NE3_CE$=uG2W0u9I; z5NL)~hltB<@^r}Qj#AW+6Qsf_r}^9?&)IaCRg$zjzwADja~`#G52|#D;@oYrnpL{0 zE*D*LX!YP z>T@~!)cg`B$J?xn2YAzsB_2MQarXg_bwXy9(?=WwyCCYdr1gAktlLqZX!Y}^FyK9J zEb{t9`ONp*+%+!T_oFi$zV{e6zGjT-z$Sty!D&JTFY>xX&El{*&slJFkIxS7NWb zhBO)@^(`t0r|1KnBXtGTmQZN|3852;E+R4!CNvnIQHVVejui0D5p@;sozCje@uNKX z)B(grw3}_J>-yQY`%1p@_$+__V~14xD79C3+xC#%mkf~rS*yXs=`%DN36LPhFg!TI z`t<|MEi5rVGmSG2V+{opv2nu)_v~BXFTdX8*iwZc&A4Ky#{ab?Vz?0S_?b;S=66#t zF&jzPE-BZQ1MVu!@u=@ZeFZU&Cl4m{*5{DLCf8j(#AP=G?Avd6@-a|vkjUUO&yI^6 zZ@&gw)52G*$2&!xp^(L7ZP>aE-tjKO#Iz?ss1{?cyCxv=@Um^njoXwKo&ZOg5ZiG$ znpHt=_jgEM7|rRUt|C++J1?|a|-s8lLH#hJrz{^oD;;DZmIMGTTEiNC65RnN z=uCV!lA8=#9k)lQkOa!XIoQ9@BB=D@jG-q~cJ;$+`{3%0%3n8y>G6(A%0piib7eK- zlHLZB0FmHRWqnC_>t=ZOW>BA-)2}W^^rg9d2!|zAL!t(Up^d?X1|=^-U`)6AuqVTjb;`#D zWH?gVGzpv|w~;BKTAVEtYlKLAmMH5~MW+)gqMh8yE(fOF{7bcn+MK|XoM1ybf=u5a zwBu~t)W^_(M{Q30g;9gBk`cO;_5HJ4cWEE>mSAl_Ph_}gXoYalQ>_-*J6pgxgHs_0 zJwt_YdYNOkvW-?IcqfRls8{;d!It5S!%w!DZ--=3K&6b6GKF%5au1|!2bvK_Ik}q? zypBB8EYInrV~S7_ta?Npq8Wn2;IMd%@u(yOoeWnog8CW}vZ@vpao{tQ{Cx-N2v>_i zbjm#$B_<%#m0Yn(hSdzC8G;g=lR28RCaf}^U4`iLnf^L+&sAdeyaBfJy!+3t+LW$R zsq>j?hpjn38tR;#HNQcWZbrFu69884Z_{CPjppR>SxbM2S0z=8P{3j^>JVvBkHJNj z*cH$~a3lmgd%b}*tl^i9Rx6{nQYT3wH1gm>iUnb?Upf8w1WPr^W!v6j17U2eh>esq z6U1~D8i29QL-hBBOf0rL-?7ej&ujN-hb-z8f0O)A1bY5|_TDtulB>S<{QdXN%ro6{ z?pX6&D$N5DNJv5gB-7Z8e#W$)f#-&Po&vgw@QaQPrVI>};6NQC3DJQf&)U9EBEMc)^h@4@nY8Z)? zTW?JGUnUzYR-j&vxUs&M9W}?yVwb1Rc9=iEfD=Q-IBwXzg-7SgeD+5%mY7z{v1><( z-`p3IYQkc56RC_d!2)?yVj+WVv8UO|x&PTV-*{#LjUy&B=iaL#-ak3P*B&~_-#>7k zG-^<@DR16c=RbU4ic~5r>MlB^eIP4z({n7HZ&ROCderF1E_!N+{1Silt$DumgC5T< z#7u6sq~i39tT)! zdFMOdc@f!p=+L1TB}oC^^Pczc#1l_&=+L3nwq~=*XFvN{-tmriT%=Hq=6fgkf0WB${x9^h_`@FL{iuqlGOO3FUc zqT~*&SBTde01Pq25JSAa;MKF(U#8h@hSEBTNa7Mzv3SkMB**7U$tE;x1HoV<-1jp2 zWIkuvwV02Zq<}LKBEe(SN)aZ6#jC;R7Eg@YBF$Gq0Ekx#m1kbCXBNe-5~rvMzL_Y3 z!>I??q-IM*cyda`lw^&K^LPds?yE{d6r%>KK@C_0C^L{h#ZsuAq=$|i!qpCe>0*OR zDqYF2GS1E|J+{{}eBL6q2C+GL^ekF?j?U=S?B035FUqD#7Eg}6FKZenbygdHg}F)F;}c8GlNSc?+J=!oDoOzu<#tDyKm zn66q1gvceY29Ga}HK3k^bdB6rEr`NF341tlAG@uv8XeeN zP^iGeqJ@YSA#jBC32TVTim|<*_EyC^$I0mhdM*KJVe^#4<>Z&jetWx}S3lyi$Y8pR~8NBPVO<4FTa4OGh@&}%!UXFaDDg$EBWb8<=P#x=6iC`KlD z_}QFWpPXS&wT4MUzCm0HYQj#YjMfYv`K2MJf{4|%?WKBC4$hyBTUcc{OtqBdFEUjwJ|$PhaK;mV5Yi*?^Y)e8__R&HXFm$ z#}-&v?uC8GEjB9=n-aY?#AD#K!Vg;w{vjR5<#o1n=h&0g(MUKtUE&{)@5RMCDP>Dk zl8BZjbh*`Pm#F_Su>+r>vQv!4NL}a+5>OC&d_Orsf6n_ zHeijRRty!GZ@W6()?c29=_0?Cu;5J8(9=)jT)?07Im={|Ue_`By`|THzq=ye5e#z}b zgin0p6MX7ZpJHWYWwrf#-}@ei4jtM+N&d_4+GLrLWiP zY}&MGgIe~;kt46DuOWuG5UK;8n+VMZYNujaY(rjqFIBXZ&?#qFC#bblOJU+OF2et` zFXz|x0Yt?=&y+Vz7~wjEl;C|TK!c!d5<;@QUc%&jh#`g;;-?LRJcU)|+@R42eKJmz z+kB^WkfbDFEK^k3o0nM0&(Uf$$???PI0y6^>|B|eYv9GxtS+)xp5t8q40HY**bE~% zRt1YCHyO_6*A>hxUQdjWdc)YLW$V;= zc2CUHH5Mls5~q}^XNm11n`&F}D1C7dr6hia%v5lcvEE?StO+D7h!=9>aagQzs79!9 zcpQ-rK`K_=YH4~XiIt+&y!fve{bWEJ2J(AViYYnXtP^<}i};`nHXF`sc$mvN z<>#QAOJ1;RBx&R~K361=>aOT(-QKMF-bo=93ex+p+$&O zuo!5QOGHLQW=g2Wlq8{H$BSz?AtfU&!V!lU;=d)-Tf7$>iu0bSa>_e)l$l)VleJT< zG{W_5!e^{f6K2oPaP;Ugi0>#mQAX-Yk{HsAVt@&%Z7oXd*H%FW_m9CsgHWzmBzCx_ zLnEPIYH%X1F(VP>i3v=-PcOHqC|TbyJ7Z~F4j`wp~6P$y0+ydXdVTOPBt|hnINL|9` zzP-f0H$?2(H^uWa9*jql5~t2B@{RAG;z*}X$J8JzlO;JsmZPT^_|`X-J^RP;MA&Ks zrHESHvvaFZ^Kj>Qm*`Cu{_&q2D?Th7<#vqwpWQ*@Uxh38mzWxyEHR|1;Bt#Ni{#*) z;4`@Qrk&Kb#Wa(MoQRPKZkmFTywBd&8Oqa(M3JYTTH5>eP#K+~rOJp{QlY5T@R&-2 zGj0cmOA)!0>Gr32_=yu78TIsK9G_VrX0GY@zaIB^nWP_==;w}(gnhKd0$MIgC-*or zg0nHXO-Ox-n-&N ze&ImEhi_L(CB^u#kg8F}?A$CkN32k-HmKG{h?59`RS!`qM*jg>dT9*v9EN!L_=%IG zwOWnaZo7>KAAE4N?c~XmoIH7w-Me?c;C4?u@dQgtOB>o=EU*c1%i84i0s6)Vr!Fi|y6ccp{KQ%{QwuK{DJk>aCA##< z$#5E!oGsho2~ILop9d3?#Fz4fZVsuLqst1;@vva2y?M$+>v5VC8Iomu<+coLN zO;Wlb4kLUo>A0=TT6TBpg--^Dy5)@P#$UX^S?!^mBQI?*eni0y`J%|g1?V^ZeM5Ksx5OWG+ z9ZpIZV+vo@Dn_5f>oeHcW4$9HBmq0GG?E$K`X-^BHZT&@u~D2cmOM-1r)k&`yotap zVdB#mlOj=s_d=?Mo?4t*JP|4ph~gP6*hx{o>dAr3#8@mIhZl$Q9!0S987MvniSL2q zh}M;>hmeUtc9=k#6vs8FZzYf(I$%A6ZcJB4p;%0INig3_Mhea4fHdb%P)p5}mE)h$xX3mIhi(p?!uoGaTzY zhR7lZDp#Q%koW~uNEaV~7oU(1F~rMK;l}8UZIsM!sPoIft#hVZ# zpc(role{{6Y_U+((xUcA75k@VMP4M1RD|@PO zAN73@#TmKY)9|Kil{>F# z^ZcPcX+Bnj^*PG5GJRm{sB-T;Q+(}-E(Ms!NzWL1hbG z%DCDUyz$luANTpIe@^MRPyuml4o)w$=}zs$RcpcH3q`a7$ppqklqx04W1grN#+cD5 zLt|8s)H7Kwu``1I_-@M=|5Z8iEcnRMwtHAilGTMD0BeMwyS~EK{V~gFxXo>8&;lRDwI|NTA=co?z5N~+8?Ju?f7n2{P^ zJMMY9Ut>P0|$DR&` zxD$(Lj%liay+&UH?S?xMsbLVufV*D&*B@op5N3Oh9>VQrBcNg`L=?cL8xW8IAB zM`WNZk+cluczA_$WJ|bi=MK-u3+<2--LB)Z7YA3LjGDma z^9?b4!qVDFET%vTnX!eKQY}n=UL+AM=^x!+CUrf>--&FTQbMV?E5w)vPvkdvzs}v( z$EF-{bm&Aow7e5*Lac+Pgy0fa|^74VyVL z7M%s&kmr@YVA4le4p;cVqXx}DT~Eu@aj?z0B^Xp=ezAx!W1!+dTEj?YBos4KtUsRi zXBw`lMcwOX06_*tN(u*YQQ0AUuQC)_Nj`{Asz017#RAITZ3%c|u6 zv;clA=tx&JX+&u#C1lLroU41y+#z>$DL$i{vx&_*LJjL~^0#xAQQ-`ucOeG;L^?cB zz0XFePw%}tB9|=hOQMEZ9+S7f8Hg{WQI-a=DpbQ13R>diwNJ0Fw)%n(zf8qwYiw#ZIb-Kzr+Ti< zQQs8d14ZiYi({0+d-xw3;~6s@4J(htWzaH{5@%#v-zHYk)gEObU$*O`sxIvqy7oGn z2Ih(KM{tNTC_7+IqWv}q;&Rp4lp541(_r*A<8HhK<0FV`2TC^V}No#peKn+pY z?8aUot3`O|A9;mkPGuc6W}?#4KR&;A;T;_JGSM6$XEAcAV^`EME0`p`j zT^FWH6!(%uAMK}#wli*K@AYw!x7?iu`d~)kbAW`Wt}zM%o37_u9YManrr+bcD=$qp zk+5ax8#yuyq|USZIn5Z9QX4!O)!LgejYen5r*-m=9MJOI;B9fcM|m(!ZCa#u zWV;a>ItxN3Aa$lh-pU?gNa*PE9t5BdC8h^b(O=glRiAVABUSyDF*Z zTM0pXZQl1CMBQ1;+_@9G>+K$R>!uAC+y{>jVcnv+6Rr7210vbv0F4S4d63hfl{OA- zTafS-2{db01L6f`yL1dX?9}nC}35?L(nE4im{cTFdl8S$mv4mfoG|<(yynd9c>) zH*ToJ32+2t#RQS|Mn*xcvWuZ*{1VU9RLU_4!n-wSrP6z3NOBhT!q0x#$Db^e+;rH; zQDTCntpoZh(z5>dib^-&TjC3Hab0Of2ymlk5h2MjOqKSfmYqq$B|bHu#NiAAnzBK$H8g3Z~#S(UE)&}oP1m6es`wdxpQc$v>YP7w-T9wB8iI>4qkIn1Zg56!>rHw)& z;~cw_DLL-(5r7#z8=afW&=UnE^LIhokJihi7rtfq9}OiB^pn!n(k0Q3$_{MyogS= zASA@a(pZyb#EGbK1tBpw0Kw0_DO}1LA{?8`<4;rAC^Smek?CX3l`I01wD^krqylvB zAA6GAzU>2_H#yQu)m~+Mqo^NDn-nZ%&YSkyiQjF4y8iiOo3lyS5Dy0`!a^GUWblUv zX{e$!g5(>dkZ$@?fm2=^H`B2kEVqA?*f!-41|<+J@gBzGWM!@|vX0W@rdPh()I?hb z93s<4`~Mhg`L*$aU<8d$RktUR6YoBmDQ$KLFH;Ebl9cp3V7Yd_p?vtsy|tSz+YjaZ z+8Q+FYYIvdbBao|37A(|Zr2tk-F+{iI-J5aAdHvYAJ4d|G1e4fIAc;I(C3Ig7LVj+ z+NU?Bw^l4s9bu)2d$?b)BWLfIg{*=WrzQqjEP381w%#W!)_QxvzJAO`P_u%FJoP<& zXgaO)1pcFU0_}Jxw+do$5sD0REFI?;9Z#4Y$=^WI0V0s@-gm{jLxuFDAZib^eYKz* ztOZ|&v|2E5(Dpika=hrdYNe)N0!J+T6Hz20__d;~q9}$D3+a?Rp`fa8^HZ5Gpn)tx zfGI;}g@lq22M`EGnGuZ6!q(3HBnlk~8mR;n%0)po7|WTS{_JN*s)U3L8~hH7Cf|b` zFR8`NmXM$Bx2l9!NqHwir-M?CLu?-k-$|KsuCB^M8Igj&I5DAWn)==OjI5>h+ln%` z{sM8sv2A21ZcHb{hbDL|IDY|^&X{5N#gF`)o;@k32n}bS5_7=^pUF`0zCxO#y@$uL7v zikQ?M?bSYuTiJnFgJ)_#knz_liRa>9^kbu_yrc9CwbDB8C6h;dN=G-U!DLC&#kte0 zqnCK(4cr_Zc^4^Usn-MCSXla_by_(}q$rU+~BGD_lqM;x96x&5foSkxGs zH4H}^@q1R;)Hlm7=)9jo@mKU#d*JEvRWa_jBz3fv+z~g}d9edqE<7R5K+~zgpApm4 z{2CCrsALFB5Em?9IqA^pP4_Q^n}|o4fuFZQ31oCLRhPy9p2>hM-oBAA-b=6avnCm) zxkxp$NWg`qR2$49m8x|>wD+=u&&pkDS9x86O-{d!M+9y z&xnxwcHGHzht3uH`2|kv#-*@zfx<~`(`Q82GwdYDr#RB({W7L|IEZVz5AqncmUr&5 zcNSlK-H)1l&YI{weZLl*5WxlrYQ;V(9ZPlt=Ywdd{ay_Ty=bWVi4UU%pbe-&=n@Gr zca{|K>S~_pt6RKb0Uk>(wU7a0=TA;RXaaH#l=)A|5hT>Ov5w$RC0LXixwDhfT89a) zxNm+M&%VStR_Zg1_Moh~L@`C6y_y4_fG*siTKS-wGA)6mh%{$^8ix4@N`gOiPI;YN zE8Jpt!ZwXLX^g5{w3ZM{g}17fG!G_SI|#*$J4 zsTBhGtYRpgmpyS6~To$AsiD_$;hFJh0Gd9U!wjhawi=sg5sJ zLg%jh%u!YudtL&w=!Oafm%dMPE#(&;8Hrg&UJHa^8_K&}o7c=+XS@|@Oyv>!KuMQW z{9`;qYuDK%beWL&g5H=|w9L^O6kehie2^vhj)fE$7&Dt?j9t0aXB0&VQ{x(L=tN4M zGgWegVAu>z4eeb8jOq*7L~+#iO=?lB+wXvLtR0#&HJqG^%;iMD>Ze%qQl4Gl~)-WPZBQ3}XsKrz( zCM zMw-i1S)Yb~TN#YR$1q?0K1(N2Vg6iZd&Cj}19L&Ms@hM9mbwCAy#Yl(qccg zG!8e_LcNSKb%1{9dCQVcLEgM0K@^YtT7a%aMKX!kCdx_b*t-(X;n~PSnJ97Q1z^h% z`wzvhL}Sp5hlI)<2oJN+kv{tF(GjTRc#11Zi? z0cMegp)5cjyatg@)XqI+3U4!%R)7CuiZvJ96mNl3vOqyV1Gdcp9CNht37yGur9mmz z30L3BKbL_s4GojDCI} zMZeBb1QG{&Wbe+Gh;f#7>?`-Gmg=_0tIlw%vXX(t5N)1{@px^ zL-y=}`%wQ=IKuyPH|?gq6gE@hTKoEpv=41584hisP%b&xa-@{s3*5qv93-qs7tT5- z++VqLlqy_XN!FHj&Yx7wMCGpY@>iM9L8GYG%0@vi%|tNHp2ouV4dVLn;7S*4f2F+S zAl@h7tQ0wX{qs8^z%?O0P>hGyS`ei@_XgXa$$)q=^X$eoy3(%k;<|FktwE#>)YOg+ z7@OG98@ksFWWeO*CD9-NkwDj8c&^5wWwCBGmy1nlheote1sWrcdrt{G{uYaFoO&^U zM5e(mjPZ?DhbL@$7Q>vm`@9IPQLx~UNBc!3%Gwj`&0ZAk6T9C*{Wx3H!*3(*^q7se zu)CmC{)uW_igTygBx_HP_=^)(a+ED=!d+q14VQ>V?VPePCtqYFJ) zAMOBbT%|x2UhL38_3zZ=-l(?FevV4&Y}3z07}G4m z9N1z`aAQCa17AJxBKcTp?A#;1AgPa;k23!842g!<2Eegu$RZJgO4Vv5M>s=q7?#MZ z`>%)CvvE*LOVeNm*UBg*7V^gs9fbs-t^lhYVkE4Ms*O`X7=Dc_|(${ z0srKKt_0@*U6w$I*ynjaMXWPdFa-+8bp0;Adf~$1cKy?J-G0bo&9(C`6MhZLu=yy< zlfLXz5;^j#3b5O4CtfgW<%3lyQ77M1bs*i{-GQQfvsb3ciPzosB0&H=vj%H-_tYm7?Rmy3gyy%c%ov=hzD^*;}q=N zi0{7wG)MlZz)_2L!*TQf04L*5Er|g|Q$g#*iXqP%*<0A{UhfZh{~8kGqqTAuq$L>p znISHp=Le(%;c)!poc^AoViyY(R5#;37ebO1VF;DeiP6$szO~YGkLDE<7V|FI{ILu) zkG1Q3E#mk7B}5M64c9Jp^Eb+`EJ9v)87W2Jpwy^Sw7l1dd(Z^iID_s_B}#t4jp@XH zCciHcb`!co6_#*}scJH<=dba8Nn@xHEo3OcQv-Ai&|qSF-0-sfyiv z+5w%m4Lw1}is%=V0J)+D%ZO{wp3F3VuO~<#PI)vVFSH78E*8VS{HOuTSe$0gL2I*C z=&Q0!nqvl`=3ixrFfV~droLILkQ)|#RqlZX5@k5#@0qs;sbKIwZiu?gqY|M+qgNVt zX3ULefFw1-+M~zKwWequ*3oy6h5>O3fc}C|N`)voP6CN0$5xiGr>roAe)u*J03T*Z z))OPGcRg;e%j~gIcuivSMQkK9 zPDwLliGGxlRj>9KbL2YbV##D^9sYYWeL*B#k#5lNA4b8BK$lDtY8DeyJb-`O(RRi9 zcZ;i?bcfvjG#?KXAv4%?XCw$Ys6XE~kF>WRf4ii1G^!bULM#$%30w-a2oh=-7w~us(CTo5-+cQ@a$NrzUDX?JWtJLT6>P*`9#3$(HkQ8-;2#5)VJp zRSntdm8EHGfTNWN~Em4u!38Ef?bCi(@qSwm(Rx@ke|atS`b%UGP!@X~#j5CKf*a zM$GKLX+gw_xct)5r_QI2h(>H&+_v(6PnR2>@@qGHL+)pw(?j^9tBJ`WG2wKDW>e?B zOX+C#zmsg8`U{Y{Lg#;ef)ZJ83&GF@P&CUR-{&3QU8QTsneZDv=%tRI>1b&gd3Yv3 zR}1~!UL^|i*_PuoiYO{jFlI@JY zwJsb(pUiR!Q5R}F7^Yu&E;q?g*N9P+hX=f6$yqGOYf9iP=`y0Dj}Fmj8Cs>hj)}VrXkf)WRB`V6U%{6Zqdi;uMg^wIbM(!V9A2fDd9CCNtGSfFXNC;#<2u z{f!bu|L}Y{3pFPmIgWemS-F*Q`v@4AbQ&RvKqteHB^0$H?)Su)oSHe2(ZgZ&I*b{1 zcwD}TIq8+a@XwW1?|apLqt=ucx1LuOZaI1{0jDW+>+W}Mv zk=!ltTP?QbkL-FffFV-))qW@6z^W{%7uLXyH4D-L4zHqU0AM$${`-B<8OjvvjCs~X z)2E)Npo!d3H24@7qF3zR_^;_4u50=jO%rB3GmR)UTZu=25S$ z82}01B8{2T;mblto7>$4^qB7l%iP4ob8}R*0Rkakk80Hx|xSr#{b>Z0=o~=d}cWS&S z0tsZYd!a;d+t{eC?XEk zCQV}MomJ)wGHM3~NhD{a_nVuM7wqTTNT7`9^#||U=%{Ziz<@BI>OTe-U1@a^ekvcF zMQ^`9yKg;%>dQ!cG;Y#U%?(LS9T(PKCz84v)}Szgp<|aeC2I620-n+J_4QzDdWvfE zKbDm(hq;XbKM-$cqJ8esvCH^wherkR73Yt zz8E0y|E@m&1uN8iu_?7&H=NHmJKlufIuFw<-JW+s*y?%irv=|{K{RH`%cUSS9i2na zX@c}WMMXuB%q#56-T7sHGJawO?IOW35p|PaIJ_4mseCvAKe1JQcqnHCG8mWk1pEGN z!l$fX9K}{I>cuw*CGuJQ35F4&NG5tym||1{UL|{DnXTUd$3D~38zOPj3}pw?pHmKr z`O@PbuTURy>yd~gh2}*>!bG(LH91vEl(^{@f)%m!d+rcL!7H*!jX~`}D4$=N8j|FN z8oA`V0}7#z*8A`AFp2BX`+(UOzuiQ?QM7Kok+6E%eL8GN3iNgyZi4aF+V_P3_nkez zjz7BI>|((T7H`<#Ebahy?0I_dD_$yvtn!*rk0cM+@n=Wil8XTqZLUsXw^8?+3_v&% z7deogqpmja24CWLDKdw=eO9<(7;LK~_IUr2?75CC7ShleI%gGe0_L&0N{7SJGK_kI z@wBsr3jTQxH8F@w{#QO(%796N5}d~3`)j{OboFkWMU~PRxot1=St^AoUI>dA z+RqYmJ`nA??2Wm9ioU$x4gOz(c9=RNNxnS#6%TPWRU?p-{Z}?qvaKZn@uTM`%dXC4^=N1ecw#%bq3|08_^ zo##&*67^@Pd(W)AA38ViCfE-T`$)iC-{04PSmJ}&<(L4saa(1J(g9$E5p+lwXEl^ z1!>|UTTigBJ&fO%5_wHxnV4?JOqm%2L?p!!=w*jlpn2)cBQ~YtHw7>~(EAe@53siG zVh)~J^lNZ)7LnP|Dmi6hkDg$I9dv6pSUMQuq3M=Z?KDNXWC&+N8teYo^(S0Z^m zpj{<9NOEPd_WsWO1Cd}KWPJ2ge>=(8`v)R97Jn27BxSiDVt=K_S(()>-iFC~87z1{ zq*+$(XkU3?esR}Sv*V9AeBXzB$G>bqF{C4~kG^x#Y}!I`J{Oj{dmUHaS7R^NKJu*%z{=&HGweVG< zBcgVrLlZ46<0t#NfXE_(4|`LZvVBkd3!Yt@%kHC0*Gi5IUn)}t-mv#Oy-A~$9(N&l z6Z1ehtN{1_v;dF7-|X~MVYB5IhnM7v37|Bb*%N<@mG&SbTMFez4RaAQ8C;;o8mNw? zFO^Uf98XB94FUq1hspgVgt2?A4f*XXY zaFM??asY{Zu=^f07L@8N(kQ_13{s~!Yi_pMfR|NDLmR*N#!38ic-JkJy|WPf3IcXG zL~hQB2l-SsUG?wr@dffoBc@sNf{12NQb}c?uOCUq*zq&UT}ibo_hAy7?gSrx(4hm= zG%71?1KtK4j=h}rrByl77>mUqz<|TYDvXf3y*Iszue%|hQRSj;wmf%nR_hVZo!Yd8 zuyUVN#qWQJo;rP6Cu=UCh>G~Fls+Nu~JlWIQ-p*S^o~;VxouAYzbiN%cu76$- z3Mf&qWg))L@~k@>hQ(SqjF82=IE4LZ+MGm<)vFkYtLb9GAGEMc)jqjy5RJ0Cf994S zss5WqLs3;!V;XnT0+c~ao4i%C5U+WzG^o|!vqx|}fW^#akF#7T&qzFT{d-BEb8aWNe1{m4_3O3qkO#E8LMd%hXsRb;H;_ z3;|Rqyz~Xdxx4%O`y=8SH*Au>qT-;TOV6(T5WW6*zdc%;y-kPk_J55#_xJY}YpKkp z&*!FmW47;uw(Z-N>&{EsUjOd0i&m^E8(Gt(L8^9MpSLF8x7y9M&#BF}A1lraPg&Vp z8kSey1m3NhA8|(FNn|S+jaGYDV9VfO;HYA5K_e5=)Jn#GP2wb(logf86j_sV6s z5T#R-LyY(lQa0f@2?s?4!Af^&sF>~FKO1Xq-pEGc$kgK&6!>IZvxhbN)sy()LD~7;C!jpbdE&4hu2BAQD&wF^IMIh6eKDD?n1nF(;WQ z;&WR3Ws70r5)Cx?(CUa`jE{{~pW^#vk+fv1U}F;}6bF+b#up#1SmQ>UKhDSsZZCu< z6fG9C&8ABfnExBSt;9&Srg)^*Cf`J?VG_0ix{R{5#6wuLzp7{NdY4iTSXf&uHKt^t zbR_9>cGq2uB=&ns_s}M-Qdl0Il2=+FtZx7q&QxM5BJnQou8-pk9$3`4dl^k;J_JjK(LY*@xa^_M3%#*CwCfpC313XY*RdWC4jm zr%KEsDg;TT51K4sba>&FK!?TP=4To?5~*D5qpHxgh4i#3K`67#5sqG4&;5{Ur*p$uV{jP+( zW{16f<}izU4_y)aN9F41NhXA`B9-Jpt)!yKeN^vt(iqI8?>?=mF<3l*o4J`%Y*g>M z5$Z_te}d&W&l2jK-oZLu;>uVWsJ)FF7&y3Qv|)g~k{xbYcs#n1mzLx{Z{4l!J=d(f zWLd%39p*6&=;TSY%C7nm7mkq;y-<_145HUz?9meP1bnGW#?&1r)tAgECk|AKW_{fd zLQnT?#b{0sc9rFUfR1mL--p^<53Oh`?AGjJDRyP*8Sx^e|Ls4r)`~3wV&|vlV}JV~&z~p?hdPa`+n{pqAmb82f{Bf1#AY zQ{Aodbts!eO5XG3pT&C+A-<5!gqU06nN1-(_-{+7N0x8)V}%AXm7w-?kMfl_@P z%+|g`9Cr`uTE2i{`XK*`V``|^P>?j{ZbOwfUDLV)EJ%BvK9&Shg-m_E@ZFtt{W}8z z$!y!AzU1nfwjB@VV_OfEuHKTfk05N0EQrF`ZngqykK90vu!s616ZOF#yw~4+?m!?h z;YTwB>94-HUoWqKi96ejjh|dZ{<~0cRzfue<&$C z&)kmDw*hf&ns?SZeSm<$XZk(=yW2uHS`i?YRz3Io$kc6Q*N0@|^Y1#Q`|9Q5dWN-$ zN*=Ca53(FQg9_tgo(dCKXaDA#$Q3L@FFt*xeDHAc9tx|~-6_pMWsy^nfSJ1jw!GcE znN|AhBthv?GI~nnoKl7O-wobvjZYM*+TN&`hNA+?ie*@eux&%T@aYMqOJI4B<48n{ z5*=xw0D}4 z*~}^ZLgOJysYw(JB6CO=myBCqcsvzr4prQ&_J|tm4^y2k?i$~Yo-qkO`0_^3lFnL^ zAhURRB!c0Lelr;tdiNm#PQ~3DrjS?}2OYc3bh%`sbnb@>tJTBeaM~3Eh0@^c(&oKo zctmKF6tx6(Y5Boxf_(%jl~01>dKjnA_ykNpSQJgdX-r(}6iq;CW-Bk|e+t2+Ms01n(eKq!cE;s}XU|_G_Uf;MoQW1a2rvo#2Q~GI9p1N01~U;lTeJYSQk(g@aS* zLWl>u%WwXZJfTKjiayzj5Xy9oURaG4REDt)|AYLwt*U%Z(J%O*Qt-^{W|RKP{Q|?J z_Ro`~RjT>4HY6dQ5p19qmdEl!FiqhiU{&-SjT+*KuVqws{T1r-tZQxL(ImpPy|Zs+ z>IXt5Dsfa_bU7$M30}undh$Z_EkWvMnmzrw(F%@^b4&FoS~f4b$WK>=4=_D zdS%PRoJ{fY3=z_V6Tj<>_a|3J{mK&|Tcf9B@A82hu{OQ{+E1Kcb#lgYU%Ze|bAP>` zg_CGl0CM8LU;kn3(H6#T3cZCR_{lNGEz?NYfu)lBJN51g*+qhF-6}2Wr6bgA!xEkS zafDQd1=pRaL!O{U$lmy?p{qaeYq`-jcw8uo4~!TBD`mJ$MJP;N z0KMfv*qy5A6no9{#o+o)%Dci~gg{*9>q6Dx)aU!u$pcCsAL#GBtn0NbBFhof@G$Z5 zeP%52)HeF=lMuFqdU=7iA}`k=eB&UeFE5CVe+{hC*3~_-{d}~20WkwV>xaJZsp(tq zho;_JUocnM2-x9TpzgIE?fzaai^z=~Q)mg_^V0{>?vx93?31JcUqlRISMc zsNf$h$wf}kc_xYj)RZp!a8>BNd-m^bA@!PzL&iKUF~h#XEX1UKevyAPsN(_oKPC9d zg7s#N3R#04Bje@<;>FzJMjV0<8p6X$pkWAy=jE3nExIE=a~aHmmmMAf-x8w}l!eE? z1(hRlqE*?|y$Qe0b@|I5^zs?@+lGAcM1Oo%70dEAHC+ zX_UD~Hv7m-h(?UDo2H$KAcvPz_j+K=6La`Fa%m`a2IqIew`cj=><%E?IIBF5Y;yvE zS3&y@%-DkGx9{=l@!BDdKA)feNL|d_?RF(paFdA~IT|U8y#^J|63bH{6Q};-=8%cy zh2TWb_TUnkh-Xm!xq*Zy&%DF^jod?BX&xpVO!NCzY>@?t$!m)dPVVrVHRT3YjDmca zk#PS?ceiQz(H-|ME@`A@o1AWh#66s_mI3p>9qY!=4HUy;7tMok@RnFY17-fUdi?+{ z3bfQ5PlWDiODJQEW0YY=F$(WcHL7P~4gmq`CkrEi-&Cx>8H?G(Dy0s4g>2MyRWoYp zD@d4E4r?CX(=LbHsP=@3#P7I|K&{1vu+jcrG@s9moA^(G$4nB?70ug<# z1HPWM4!a;;f4#F82wHXYwWld9t2FTN!1*&UApA8;eZ||Fu1A5G0-&q=zmF{k%^@s9 z;1!q>6d1Y${gLf%yd*E+TWl!wwD-BajMx3={%s#(opZAc0e7eBOhl|4l*=>w!qF!K zJ@PUqT*3#CViF>MA^-V?kWhRkP9Y++$8Ix?a}d;`RO#D4AMi3&8sCr!&;aGXju1AP3BY&}I1> zTPnqx^=LmHEj|(?Q|I|kR_F@t&vOmJ6u~{tG!M!go&t_f(gIz5qo5~pxZ zEh5F8Vq0iChx3ZLcV`KFpPA?AWPzscPkWBe4Ur zm+g{oNO!|MtzZxgCxI~4@{SNus+J_+Ne7psaCD`h&IzfuE=j+Q|4_qdBAkv{lf6^x zudFvBeSmBx}t=@w4PCBHeg8VN2Q@MRQ^m{*U(Q~9L4B^{sj4j^1 z7$i$tic0VePvbAVyGWu=i2@O7x_>XnC=077UC*uVn=iNigW&H^ZD5ju#ypmGUFW+- zDTB)46SEv|=LXSj1Q)kKf|liMg#Zo~OgxvKn`?&%E)P|`QGXi{W;PJlMJNsbV6xyh zcDh+&5w;l3u>&+uka7r(B2^qfJXQ+!91pyxSg{sCOz^l0Mp-xK8yXTR6BK$VzqOw{ zgrVFhC#vdSGA&N|>ZaB0%K{?PIt*S)BfkJy{}X>}Ds{3|RH^IP$A@Camia1OdxHtI#c|KU7YUgd@XW;`#hiW^-F{JzN zK$n+}oZes2wE0^8_|nqC0g|HnL~MP2Y#o7&x|lqN9Uz&@<<3_YTH_UB z*tj<+8|@!Hk1MF>aMK59Y3+vDuKTHLn|!RRhp${%we6sfpSQs+gkq&Lowm=es~ye8 zi!OU#f{PG;lg9Mxo~DMc8(lmwZiK~R4Q#-;v*fsN_^yZ$hAFf{=0RM&Qq1&KC8qRi zgd&A*Mlc8u+8ebjHQUo#?SfkasTSvO9Qb1lGJBw@-W0(j#l6$e@@fv@&&GJgle{H` znG0y*l=8p(yX6|GwJ;88LmB;+krRvop%cS+s8;Z)F(Tq5gXVZAnuE>w)Nd^rd>m>d zTdC%h!WGZB;|>(RBTaj})i*->&u6zZ9!0ZHABD;<8X072zxs^-H>0!a!i%xy!84rZuR%m+;_L1bUc?MViDV}6beU!knPrn8)DQSl>YoOo z@}$+2H2k_Htn9(WLADWd8T#V8s81t2xZO!*7JS_)QX zSA(;I$C2<3{==c0Hb@Fki$Y7@`-ssZ34p`P^6J>%C!u&r{y_k~_7{7nVd?Tvly2XN-SZ?RGns?4Q#ImaX@Tj7_Uc@DTU9z0+{*6g!C`cdh>M>|rJY^FHe6 z(N#nSEV{R;8*%#1;@ebgMU~ygCUj+s1J?%cyRWPB%dK}A)(J}aY)gAU8}-p~i@1zb zJD$Mzd4phFmZT+n`5IgVi3muDvXW&p%IUF@en6dcv6gq_cFvKaYTU2?a7${HHib+S z9NUSgxP--sj{NHrO^5>djTnJPgfxF=#h#=vBk5w4o`Fyw|EUCC)cKuNHR5qwyWj7# zd`x1na6&2@IU9#kV=et;4<(-tagvU6zZDT_J5f8s2@N0oGl)`7G=|>^PF*pw^Jj`j z`mDvJr^Yo`9L^up?Ew5;OmbLUF_9U{nw+gDZIF5vkVT`z5_exaM(?SC`T+$Bt~twI z$o;2v{gvXS-R5#*>icNQ{jwiFb<&`obOXxfiU(;)wAr7|b?3gOi=Dm@1`QQ7h%bD4 z=iYY*Q2qFy;}sP6&@Vj3_wOd!ae{Tp?&TnvZ|@AGIT`$#bMC%^C%iyvb{`z<_X|d5 z=Dx34NarS8mAhyu5-^Cx0B7*0y=}DT^CCdY<=I{ej#k(G&jsN>My<{wdV!J!ai8yV zn#8Dxkfndcq&cDqYTzBM(`ob^W5K^|Rch7?LTyW>NcaCIH?=TfQ2PIGbyAo0-CO#&TjV%G=}(-$zT&v(4a4h!j^kPMzJ} zBi8Xu8jP-S!nobxDrO`8EaSvD)Evcd|7K{?es0s<3Ni>XEfTCsfN?r9`TBDc+kF7t zk4@M7Ioq}#Zpq=_7=ndAZj=zztD(*?5w27~nm|grAhU*tx!kwBX*P$rK4_KR9uwLqTsK>j$bCtviqA z%DNkD8hJ26-XP%>;U+OV-Uaec9wg&PNxHwYQ?a#Oq=uWO>f+gH9oAex!yq$` zp1>bCu|=jT*7?0i;!$KNEiRH6;FY>lmyMzWDT1;@8PTyMKcM`D@S*a7UO2w(CUN)*sKI(XV-ySc%B&uI#cM$8_d(4>+q$~Qub^EN|erecfX=%BO zF5XkKU$8Gb-)umllhzj6!C?@|R^I0c1O-=zElQgp@4BVw>TTQlu=xUm+fDI2*@4jH zwl6wuu2+YkSR0bB$^?qtnlk758ZI#ZdywvedcK5tyVgRNw8JhE5dNGIRd2tL3_LM+ z(P>OJDeF1irNThu?X}xh$DiL1Sd!i&$4=3k#)1M{q>hb~0m9jKMTW@WQFzX2Hoqo+ zey^E-{#{6$OV@KrGn(60qj16Gj+Df_Z&{p!Q4?XTUIV!* zI_Y+?9bjW#*g^q?zy5CzS_k|7%qfCNxOv(Hq~c>|Pg0^kF0hw_?|Yu{nj z2Bw0*KwYIoO%x57;=#2OlrJv&@KzBeWctl4B1BBCbz{+yHVS##AQv zwN&N%Vsec}=t~ngt39Cnb>aY@sCo!uEI4M(pCq+2XNu(CjB3S2$y||5^(&fs^p?M` z$t-1>)f%V6!rZeQT%b@30F^9;g#rJMrf-Um!+W1@V>dQ8w%Irv+qP{sHX3VV+ewqg zwryLD%{SlA|NUL;_3mEGIdkTjXC{5o{5NuY?IHoP2skA%!_WaYiB~@^(*5>i^-(ms z%I+}|J>CF09p@3w3r6-T41!m7i{w}@k_c6(1#U&4=w)u;1=8zG`LF!m+)Wk0Ji`LU%-Xy&{^teYS|T8R?^c0K zl{rA?I~E^WiM!==XLMXEz-!;D(teJ;w76b|9ir^29|S)NE^iSOprJM0-yfxUB-Gmh zx`(=QhNPn=4;$d@2f&#pPi9ll^bVc~o|`4f2#4=$#$?H%xn&~vYa<{Vb^qWSGnaNi z(ScGjs8T}jb$}s(;rf2Rjh;0+EfwLDfUAnpC>YE%&*r&;UN2m$X>g3#gF89`Hj>Nz zLywL>HC+@nyPQs+2d)GTWc5prpO*KJMjgo1BD;WDN#j6D8wKaaqR1jUfXmxd^AeV; zXb$39xaKm!sEcHL0^8S!a^1Obw-YhUJ=6@RrJtsap*cp8RD&5NV2~@`>)1F?mcE7`L^JPI?{dd7^mHcAp9*q$kg`d5)^A@7Ad~A zs}u)s)2}mOi*{e5c$`exEs~rAxyqrg7gVlR_k2r6y$!E(ogc#SQhM7iMRdOD?GuUbX7fIi+XDPJ_C^nKwLzaZ)EyY-o+Qf2X_ zjFr(!IVBeP{8kn!ESCx^ko83~wt?~G7##HL@n;}4Ar#=0yS01Cxo#<4?0D@Ubo+aj?;-w9lqg-lF zb<^@4H6xe@;L>E<;sRg_0H^Cw2PKX53a?E^2zTEA-J?m()eMa&!%3{VTf#9)^C|mj zWa9?V^^I(C^{N{0A(BK33<`?=>M>WsX>mUpDv1r1VjCY4l~*$Gbds26Ip=C6!md)4Y3uH569c z@$OhLb1lpyCg4j8$lC~5>aZgU``azx&5eBQ!0?xsSp&+xr5rZa)d+xI0GMIb(cZhX z|2ckPl>+`nq~|zgXMM)6L)xHRHXz1=GQ}&XH;uI0pOu1st{pYJv&U&F6d{Dx@YfF~ zQX<`KM=%VHoiW=59@EpH{L^$X2J31Rt{x{Ab1{XX#Uv9~iAb(xxq^tmJ{!gj-9F1T zu{ZF6@u)WgYDcvHNdu^MB;vs1!Z6fdB&ldvAmckT7}*-2MD++ChSTTqfk%fLUjIS$ z5tJ1q;B}+hV3#?{&PwH)d|;WRo2<*6Ku7G7i`j6j)P9 zG(1w(V~T+M`-GXA6ScfzXnN~~DaDa*ya(^bJ8+LpON<69y$Yv8aQI#n1SQA#V zgJfRqmpCz{g3ukrp7pFtAU0TlL@_xaCG=Xdqs&!|=Gxm*wga(|uI5l2O_3TTo4k2T zSjth(ps`$plDLF*qq+aD2STo^3O zJwDFTzz9rH>?SCLzBt~d2n2;|g+ymYvO%fYON1{5RtB8&EokIX5l=BejptjP5<@}J z`ur)(V=nEbH`nPT<)&)fD{ zsVOUSU%bZp=JwUV@c=@fympeI|Ids~_w_=;)W$QqpS$`9sVUkP8?s>#HNWd0aqu8& zw>kT%UF13iu;a_DFCEy%4bu%V3*iKir;zP=!7q z+;KY#TwMsck}DGiBOBXlmqq;s;H29mbg}dlDOVpaPqxcJR6i56qXmwK=|X+*<~?Iu8E0u ziLK-Y2+jR&Uq6p;t>mI9UPzRQKe(X<&qZh@HVPm-bu6%U_P&*zC}07h7ZY9?N-9Yezd|&070jsLlu01X zSW!oT#qmr2$L@#y2g?LO!6H(EEOUj;4h%-Tq$V%;8aY}c)1%Vk@+M#RF9Vs!WjH_= z5O+z71COH)rAZhrTB9Gf!g~s_uF(+eHf&~GDD>dlRbN(wl7He)r#q5`APSG7wbjr| zu0R?znm?k;vo4to7z>g2&Z8y#a|fepK_T?D?r^@(lmwqApWLFcp7{ZGAfq^0;a}0S zs&~de>{)6Fv(t=EH6khg#e zk}Q|Xfwa-SmV27f4RzP2@!sumy*S2-`&o-ZI?5u#=E3$Ajum+b3wI!RjiQ6Jq)TB! z+xst8XbQXE!|acdxqq6DrL52n9iGTC@{S?3X4bL8LFFF1_I6VrI8sJnV{g4G_|hN4 z1ze=5K-{2Gb1Q|qvEC1kb6a>#zB)FLfMFQJJP04cEcqYp z{e7()+^0}ZQK1Zz*?H+}_gUi?=(8(nCZB1rq)eHnQpAQ+H^~x3GSOLr&>+E5Yi0W> z^9iZSo1JhQ?@OAOg!7J?gnX6&8!Q8P*3ch{JR@s5`uHS`^M!tYpaol6?t(Sbj7sQp zoP?DpmgH$xQjBIIQ3jx1v1*2@!MUF!TfbouC!(oX9w;O;%0lkd-``rs-&dN4Mc_lH zh^N6Wv#Y4g95;iF=7>82qXDM1_EEG5(gF-(=i`oQ8ESzNbi4r|D;6qb&SV#*3jO=u z$_eltu7(FEOE*C5!qWt_i3h z5N^-{q+FP>2WzfukZ{KSjdwj+Vo`D_c0@l{cQa}-O|qM1q#E@f9HMR*rLo|ugshl_6{i8)mBQmxG5!sLW&4vHprvRT0*4)p^Y5S`3ic>0_Qyxz zO62aDCkS$p?n8@}ad&Zo1B-U>lYvPlC6_LMIoo06m+U)GD7yVFz&Q&FGCowe4-?xM zhC=kWNdmtdX;unn z*Sgd3HdHp0so!usCB|B|5wZbCm~~Wvjr}7R3y6{?oCir@X7Bi%NBi*SpO*k~B4T%5 zH;ZU(fsTGt`>nzICEJ}XbApskg`209VX3-Av>9YA?PZj_++9pY3xP0LA##WPWt@*S zte84)&meI1^CKT;9DT0J^=DV?JNz&?`2x?x>F*N+9Jnwfnj1l~CKlnKQBtG47#@Wh zY<#=vVqC6yZkv*BbTCz*YMtU$erbRKIx{hcsarmZYHZK-UX9cErHWlgfsra=b)Erf zmDvc!GtcWdcZ{5Efi)h&B5k`G?>U@NgKRu!i`C!SMOJ)1UF0m1^6iH1ixfj&J|{m- zCpEZCo)gadXw?Br} z#&Z&--0JnIoNV+Qz1Ffm>D8>mS-&%x?;Q)uTyA&=_m8m|c?Zc(zTn9`=ni=Tp_kw^ z&NNca?S8|izUeA3Frq9oL^4Mqtl-^F{Hx~S&@;d(@s&$H1&BK3Ny1H2I2N22b`RgG zaEfa6A{5~{Y5XYAy}I>AU*kC>Kbw{fEXclO@`PPK{yGRA@qm!9Cork2zILauXk}4B zNzG*@(xbAb^wo3K~vP2`-AU*&$H-MARA;#|5NhWsI zD3HKT{>3h53JNzbcf_r!zTc8YD)2??+v|JY>YML!=p{Qa*#aF6QHzLD5u+#Hq*N;| z4!4a|1J+VqjeL;=Cy*Fb$ZD)&QCw)^V~Jh9Yz=07)VGrn$?LHEfF{UiHSwdC;1+_v57 zQmppG6v)xiOWv*m*Hk@RR_RPbRQX3^SF@((5{WDv3N#RkmC_JB9}$6PI;m^W!pAZS z&l2Q>$!s_^2{GU`Q1O|2C6kW3zjs>c(Z*%nLHeNWc#No27dh4wWD-^>+AumaC=QWy z?#}Y&_ad$AwqQwpDG1JK>kcmS-Pn8=3#KAgCV(OnnwB|@Bs1Hm}9hK z`r3RGiMfOX1|6#bg%{A!hw1m+4WZgN=+{bpbmXSx_1?YVDat;MoPlN=1AiFBzyzPE? zR+po@_Hx*JF8tZ{2Q83M38P8F*B&VcF*F-I6*K=Mce}vZ8|VR%5&Q?br)uJ?e%;@9 zVb+x{Q}Kv=6AkiC&t6zRbtoI+iOVERfi4ub%K6{hd*c)pgYDq*5@zn-;7_w*jDq>M z_nyavm1`R2O++<6U%GC-)~B5htNnIv{;rQ#Y`r8>Us8)z5=;$#VJ`|ylGE3c-!ze@ zl1OSKKY|?ZD{h)QJtNd{pLa;Tf^AN?jDEd9M*b__AMH$LppYNc7>!%IVonUUIK?01 z$EngSJ+d$mXvH2zE`dj+V=G#XT1PVih=qaRz^JL0jESkd!}_x#&DX1&8@Zu!rOUP1 z5vTt~LHYAVkHb8A@+dz&0Ysg5I{O%)qh<*loAwG+gOMuYlT(3C8!HAyJF^wB8r9_7 zsd>(K+G#QeST zyQ4@Yfb7NNO0%s-d@XtD=$n=uO5&ze02FhC9xu5u%U0j`N;VzJrP>bt_`hE%7j?(u z&9(c`hy^odOr;wC#8htf3E|=i2$naPOf(3!FK&-t;(AQL=ePTrSB5R}lD?|u=rcEn zwS;^O3=Jb!R$lnnP}u|FaFrB^y3Hn?*(?;uC;$yRbcr}r*^&TlXAusBJ0R@fGy%5M z4@7u%xdR)<&`cUyqbg7}Z9ZtDDS8ntF#A3nl885!fUuTp%U}(2sFU`Q`4(jAxrggfPwHh8cll^sk4coc}@!VDtry!$S=4gfUr!HB+Bq zk%MdSPwQ3%1{Sg~IrXf$zkD0NDhp|G!frg9(o8p(Q7EEsrgun60)v*n(K}8yY?#ow z;3v>-AXH-MHC6PiQ5t@gt?wy`P=|tzk+U`9UX}j=dPwc~f&S{G{{@|Q?;7oAX(P4) z&Mo`2ky9kiUn!=)<0}nu#u_uSIV)=h zFcyP2KK>?OPF$uMBB@E80dXRsN^|d2W&4j>`a004_=P~cTs|C_n9mI)MG8W8fXGzS zK%gmRD2ktuBnTogibyYsz@q_rD`lgG7vME}70h~QZWW$UVYn2=b@&(JQ%j0}@_u6Y zV0FFQdj)yv6sg^7!9KmAGkZAc&*nxz|2{NGGH9(l@*&jhiVDrzo;4z>vU%~ejVdtM z`82=W2qJH*zU|!7dd-}hdQJa%iPKI5A&5#QDrrJB5@{Oc)gN(QxUa&kR0bF-lqSi#j$TQF&v>BZ|18~bJiQW=rFuOGmCLz5r1cZ|byBnNBj zNCD5Rr}8}6t+0_1Z!Zs^Qo!`N;P-*ftf7Rx_7e0m`WJP~;e`FFXh)1Ec*fI$^l7-Qu9#3hB%5GWL0d zJQfhUMTR$Lhb{N#DB;orSQCcFXV|3EKK!rDwv?l+*=8KA$xA|qhr2i)9(R71q#r(X zSN)&rMrt=&Z9RO!IApgtNdQ9Jj7ubxYy8IvZHvGZg& z*t5UtwO@%OPwoyw+1$FAj#(0tmV)JV3A^=iry(kwijCV1 zCH3cYKt--L3izbaDte|krKFwQdF0Et~ zq{GpL+oI<2(?B$#y0#aN_RTSFCG3FMwPozwNQtwb)FWcYg4OhDd2an(`!oGzRW%fv zwYVWg3u2_`;?Uk8RlJ0T4?)vQ&*vm$pXDtMy);XMj#^2{n-d0^PDx&CQR?V<>k0jH zf8F}6+wa!hW6Rwy*uQ|5{REEI`z$^pv05@76655PCzR9n_4`7FclM&`$3LT}WYy>;Njeew7VzjWkV{o1%GFEQF zzClbVd_Id38~`<}k15Jst9~x&9I*6=sKM6s4%>6DJI1U>k&gQX-u$m8$5~!@fyVxAFyRCNgb^#6SC| z*iYC4o>yl1_+y%@5V-(LTX-!{oeL70fB$4`aueLaO81%5p0o2|R8=pIL`}^i&q6|t z*;L;GsGQacu5}g0sQ&hLWR}@tJe(%Q)d_p~%OY{N0dbLvqIPROv*VT{4$6Ax4#m{% zmZg3P8qaw{`$4+|x9_VK@^A-l(p>+X**4hRTqH7T>FM?t-v#4N!0gko*o5)F;IaCV zLaxyOBBqw6px6*YRi~HVb+iE)OCb@D&$Abj3~ys4Pif@`VTAsT1%n5v+Sy(=-;xP2 zr3ZroUt{3czT8zM>z?KV&nHPMmBe1e!GbkQSJ%I^E;`+Z8FM%pbRccPY{4CEo=QUk zZo?XH1v;9?D(Z?BnH4B%=5mu%yLBx}pzQwS8K8ogc2tS){KvO!dvg% zacQR=vjw`Ti&B0YOd^gCXPtmBoBop>?)#*XnN%cOMTAr#(KfqUEz_kO_dV^;aM9mq zb{b@SHm#diW|%hi$H{6^-if`>eJq&GtL)1+J1-JsW1ukTa>eeyl^`k_aPjabp|#Dl_}Q6{iwdxM~@-9Fw+xw>nT}nP=+H+ArmAHmC)*f zwTkM9TZXej7okc;g&bH+fque;c%1^=(mHL9+Oq;loFbeD5KHZijwdfl2U1FDG^{pC zAGc@4i53b{o@wO~C_2UF(CzvN4=BkT; z>cnXKH}p8a+pNoIEBuzw>~Ec3Wo%7fVMq;V%5*SgC81=k6dXmEX^NjeqJXsZAT8pp zwi%JmABh_5|LpQK?mg4|grXcw+s7Ik+19Mj8(6KewPP(Eu{dis4frY@ZQ3VFk86&@ z{!$-4V)aJX_P}>2>pUXPqqFaAqWQ!ajJr{KXe*ESOJ*#lQw8%Pl){M)H%chYij_+3 z^nc6j_Qcyp{ht@0Xe_naX#-|&txijD&K1)!Qn)NKyc7V*hUyW)KT$kA%|w%VUoIpQ zx5y0w68c@ErV?=tJmebq?AzGg)k?!Dp_oSN(oler2B7g9vThbq!JDC<%K#X+ELH>- zj1_ub?Xj|b3{!*5!2bqH^7h=mDyX--P%Aq3YxdJ;-3|_hN7d-`$m0uv$>8nPye|`Y zb7h-!`IGK2@H_mHo$H1sJiea88*TC9-8sMuDDIlTsG6xl0|wP&#;_@iUHj9v##oMw zac-ybKU4h^zu4Ki>@On2 z{mnw^aR|C;@Kfb_J@%LP9cgK0{F1nK{D0UszIAtyc47k5PeX%FknIsK*$tFIy$fGd zuY>=b`)kn$S8qw83!oC2CYXg<2$w`+fJwdX`4khGbDp!k@{Ki!XqmsyZN{M<`VXRc zRJTgPtn)W&WLO8SzCr|D@T0#Z*Y_kB@j^-aqCeWlOqaj6@0gKE~84sRln@13oxd7X*H2SE^AsE zj|cudlx__?WlYEL^F}i5JNx%h?QhZoLzH?SxT&9WIS1fB{6Gam@NE{-jsGDq zWDjWDGU6(uMaCH%!4|=kjH<)L2^K&sT$oo;qaM7NnJXE6(o{%sKaa90(XVxiMC3e2 z?qKVjx(vKeQse>%(;_NTjyR(mpANEB@A2ePl1KlH_Bz$SL}8;4F$qEj$KYe5vKSl3 zQ=tHf<>ORQ29_EP@}LRN4uaX=UW+0u;g*Pz)4C`cQ8`GO&Z8>L(ch*l?yXy@+C`)8 zoaI!y{SX$Cyh}-wZ(g||-Uz;<$NjxkI@e+D%Hq46c&BR&&J=r-Ol5!?t~Ko?y~nNy z2eql7X%#xFgbbQVB=CZo0b}>URsD^5j}sqRhTx!DJ8+**rTG*V=N-fhep<-_4P>@l zE~~yxJCyb|JW>>^9}F7s$z+&h88|jo1^MXS3MGMl+;C22dGjk5R%x$n8ju3d0XX{4Z_>Q{K0osL`T-sJWWZx+bDF_sD(*VH zdUJz|Ozy_eRlBB2{|UqcO5Zy!c6$0Uc(0s5u;V;l2j{_GrxiLDu?7doNN~QFoL$4$ zL|l_;zvQm2x*UUvR*rAaVrdxLDcZ58Zl?6BTaNM~e{ft86y>4q=>PlYY={cFhtJ2K z4*niZIq(?d4(E6M%6W`Iz4AQ68YrK44k;IH5GCPFb=4Bpo6JWEVaNura?kMigz5J> z8A<=+ZIs)vehEzZ3NsA}Mrk&M-ozS@Eil-`0!?Dv5oUWbLiwsQk^GTe{5Znl^UKwu z0XjgR_+}_kzn@D5+Z~>XfIjQy@y@n@lJPQB7>yaRteu@B05|<=Y-=5Y(W$EuUr1Y7 z+uH`_r-Dpb2x)5FLIzAsCq3L%w~QX*e{N%&)71eazUzva$0&oY=LKFc^qyvknDEgB zCq4w;MF}@}2Ti(mUMjFwG8XZs1fEFmmKI?| zx%Efe-y;pxHFl=>@k`9ak|>}_Mxqqjhgag|5=f-29$Y@BFnqJKr1@MY-IloH*&j)g zIbsn-ef4Q@XorZ@ohakd zu=p6Hr|9#uHh1(Y>zn0dAp?!65--5qPTFC`Z%QKMV^-&d__B}L9>70B6VvO>;|)?j zHyE?SRp9^_^nCaO5g?bt-F@rH?-PGJ0SPcOA%R>C`=0z*nPS$b0lBJ$wlsQaI!Eyx zM_dFP+^a;>9IPDWRrYI?e|yj3FLJ}h%{f?e0W{&jnE#4y0nq}sHWrl7=#DaF!e}8o zg4oHHh1rX&ZVwMkG5)lHXm*;lt`9Vz0Js6~9V*FZ88VlpKfu*_uUM;Z9YSPY(dbf{ zP<9?6v3caE?d1Jlo6|NlkosO#2kT^4d0&x|znz>sx{Y5k@&pXRzE6#3;&Hi`JN{uC z96-n$XbdZLzBTJxsBpN95ELDF6(Q6Skf}|kI>00QF13A8l|b|s zgT{N)G91n0Gzax|YOEZZf%WCR;~xMQ$MZc07s>WA>kSzMp)=l8{XYgrSi{)QIw{p=frR080EBZR0GkAXw7#j_mu#@97w zo0n>Gg`QH68APK2JEQOe0=}QvgR$y-AVjZ=_>KfqZck1_ddhE$;7VECnjd>f2~uhgSC)xR?9-$aQpL=6fHOXDM}@TdX6>jCoFR8lMPtfF83H z(0{^#JzpddtEQ+V#AX;me5s-EmM9at5W2sjN}Cg-xl#MBslcG@{SU$c#%0YenP zbDf|jWyWGK=&$txqFUWZ9o8v2)Ajmu`|n?U>6pM=M@kaD{m6$^dH0-2zVq>aLg5cH79RcRXCk?uMjLf56p_KsEC~uEr#Sm zh|ZRo`G#k=jpziyRLZk++*YI2Z$Hd_)xT1;@iGTCN>RBi#J4+rysLK>gVmt&&Wu=uJUF=s2S!O1<{bJI znwcBcOqD0b%OKk4gqo7 z{l{5muXC_#9E+UoonA2UyKKti?&H^2Z}yMck7eWb$5U6aSA_-E-Xd@~zm)5bBqc!f z-`}SaS7i4#>_$x@mLr9m^C)wk{-zfZ$R~?gn;|>GOFy+T_XUzCVTN_feXh%&xjRTq z@=R{PU<1UoYcan+kd^`2#*Z@`h9)8W9`I|@u17xaiLPe4-Y##t!#a%_Y<(Uf`e-Y! zCWh)S9jPMO_$A=JfuH@cjkX33VD{M9DP@j2%sr7Lj9#ZD#-!l=#5qmB@VP8t0H*DL zSsB07Pe^3J9--z@rjHFs=NHz0j%LQ+9YZroi*~VFzTrzjE;1pae5c7(ItHh1wMNA$ zj~Gq{MG(smbY*vpfhw+BuRSB6b<}_d{(dCCp1o{#c8)&#Gj|gb?ovu_3y5cD&4n4~ zpO=$L5y?mIM`RbhduMiVWAfTPm3d*o=-K9ZIepTl=iu3RjCnx&H)lo6&3LQ!++A`{ zo@WX^#|6KFw)EZUW~tS&_PW}TRbU|SNh3R=!j(pNO~p+p>S?x<`b`L!?RPD>9f=Jf zFCrCDi$I?Z>!lOqW#t1{TZO|cdD#`RDP0FeTUZNZF_L|B=MK)xO!Rg)TJ$PGfxn6= zpOHtnJyhL3-Gp9t8T48w$FQnV4lJaCH6~t4!_tu<9`YSsc?!ys)bI&-%sJ3TPRi#S zQbt_T2V-o&m1;{RPD_7ceV@rR(8e7CGCl6^e=BPpnX7m~J#JC*fIO5i?3Y?j6@=gr zCohSqn(-@&1?`Ma8{GYh(4&$zv~@;wlj249*wa~q&+LLF;sX1dLwH>myV+x}ZxvCF zUj0Wotez}k{kzi68>;R#RNr`&^-f>xpc~0Lq5X|%u&&r`Fc|mW=`-$2pIn2ZCx6;x zg=e0}tu6V@-flMxoQG{BHcz)7!Flk8omOE+n)wc68dTjWz2k=Sng=EqXv7?1ZCk_x zP=+FgfICw`O|C>h6z!i7nzHfO?5^Ir6aFciOal+M;8x?12F-)_%~}8ZEPj@n+Fnj@ z+60#``M_hSXQR%7YjPrs0Er^;S=fP>kd-i+Dl*VwaAJets;tWaSt=Y#pU&BD$$+`X=W}38~rU{ob?bYk$e2!?bz)Kv;%f@F@8f6a|=Yw|2Q2 z8tBD2qC9-*l#scudqMz3N1>AgmNA?`GFu{YCc%cU%J07JVsunybmx$5P@{}Rsc_FS zUS5M8c&We@XS4J0N6a@5l(xcZ_m{ z9FzikY`<8#;G-WhUn)(J!%pqAC(AJ2DTTAhHR!1H{VXG~@Ef6l8LQjNQuB0YICO!T zUp4OeyrJ%MfJ+lxmTfNyz$K5zTUXLlJfH4Yl-o%2Gq=|b%Xs-JvF1oQnUcVm`NX*{ zv%phki@fe12$Dey(4?>e!GL5#FADM z+ZHsDvFh^%eX0Qk>OThBi#Hsb&s#G&?B|yk&IdQ906c@*6?kt0ZSHd7uMO!y1Q^qh z@CHTTW*Z@PoJy8iO8U$9=7J(6#IHFiwYS6AUf!s;;KV$2cOHalxr{{g{W!(Cn^#n0 z>Z^`Bv}?Yg?MjSPW&#-y*;Pl&Dr_TyRK%3&^!np*b6|UyAA0fIsEL5K-1ogs=X0PC z?W@9F1XR`E_2spaM&^)W=G%!`Bm2>F7{d)pi?hl;)3x$nMj1C$dg{u}7rn&xBve7wFRQ`CSoH^y_9PD73*ywk z-UpD@6*Q4TBjxZ39Gp+8`X0Z=+-zGK3ZDY~ppM%*CquuU7-~<0bpT0q4Z{$71}BFF z>P((+mjhELjoEtiS^}?&GYA9wLIV^OVU%xs*HeDk`tJk!5YFq-q}pr$m5%SsmnrMC zIE8Gz%wOip^H083>+kOO1m|)$*Cgq|yA#P!u~YL+*mgcyz$3HP&Ud&);0=(Gdrv4G zYUnDZtRT+dFH0|N&D^r2$T9Wm00I8kt66?XYDWPJoLA%~->qn18^7tH7E=5PO~Cx6 zmN_)KvST%cGeNN#==wPup+r<~|*D;4)g&kG7x z=5U;d&Lg>p*!Y4l{fGuF8uCskou2WJ%>Y15bk7Sc&gzfp3m-2HnMTcl<5P`%I*j{4Bkkbf%(9r}<9jgJp*j6^|V3 z^@h-BS2xw6;+y2zaz_+UMz9U`Q^&Zbb<)=pdo#6GbF`X zJ&4?iO;uU2MEJt32oMF#5|pRmFv)OTF$l|8udP^~ZNImR7(^4GdtRRtxZY>LrQ0Y$ zl2oMOPFo>|w4h!uBO@DVq7D%o4_Opx>ebM@7++C7Mg^0GNFD1P?A>sL6pyI3T<@N{ z-({lxhd5~#@)sOPON>0;lSG<)(?f5L*Mm^}E3k<)kUYV~)^Bt}tL}R^_e>_mAQ^${ zGPZcr5J^!tFSQ6gcAEJ-gw7}g_WdZNM;EB_mGhH8TP$Or(`Rl8HX+8rIo^&cJI|IJPuxSQyYyS_xatoE>>a$m3R%G zu~Qz2xYoh-Qa+r{9KGzaq1YJ~0`De_9biTy8oM>+b^o2gtrDK2i|NpwgrH{7+*i+~ zjG~p;o40Zw*8D{jfWvQAj#SuH0i?a%le?b5ebJO?qyHP;Y@s(l1D>3^wUz3B3Dqy$ z2Xo-oxiaW?jwj0V2WVQE{pqZm?7Q>>MgJpB0u+mC z$r-|>&gStWh;3ES(kxS;G#yuEG)i9+V1{ShsLK#;_2}aWedNNulrHykEeKf~@Wl=u zUjU)m&Slvc1#yx|P$np+5nQ4lMHX6e!@<9@eFCxcf5nS?)xP%5@m^gMneCmYskUr> z0m{@trdY=OSHEyw{IBe6rVsLPO{>I3%TaTvk7(Q(g5Q#JQ)(HVi@(cJ*?{9jxZL z3zN9nK3r*Ld52pWRpMc84>`w9C65zaPuRz3=4)Q7JSmI@m^qE?ib;iM&$VS0$1Uzy ze58Olw@w9VG&5NCb3lFH9)^*dl3Ai2}lZ6u)4FqQ^)F`*?t`hajDApH} z>cM+x->HCF64EDXs@(0X57xj-0!k61DSRPFuaIXWdR+9XUMmJ_9k1^e|CF$#K zx4_C>UB(xe9IsZ?fkYPEzm?-^KrI?ZM>d}lmhDiy8OXrNM7*%a!N7f}({?#3$>5ko z8dHe88<(XvGEr?Z14DN6F5Q{qIP68L6Exx68}LwsG6%E6%r?Vylb})zyIKw=IUCbJ zx!?{>={*unLy+^VHX$w)4S+Bat}$k=kj>s&*d-A0n}sMSvYxZz2Rj}kt%W5CZb&r= znY;;SA1Rx%sZ2z0%D+9*(d=#+haXgsiD^tdC$Jvy0bo=ps%CRO**=;rzUte@wNuc4 zceYx(4zWJAX=GgkTRC@UI@X>}CvmsZI@CYekb|S)2zj8)nUNf%41&6uhR_2b8&{<5 zd4f5$ZhhbPynMd?gBd|PZ{_1~7eaZY-(^4>m(TPrssl#$TE=z6MrcMyWUj)vpiH7` z7;Rsp?2C>(2d9%qrNl?ofBIJr)c^d`KonV`=uE>gELU*>pPn!CmuUudn|_Se%q`&{v>*p{^Zz8EQuhY=1_{G>2K

B5#XBQzY(qWK0uk|zeU~Z_$y+HCIzh(zQnlW@sRsNGdOv^#4JMailKW% z_a}IohYkRk8p5WFpR$HQB~T6jX;UHnRKF zx<%jB^2?72RqyRNv&_u7{c!?}JY{rW z&+uc1e@UD@>LZs0NlGL$z={SVRpvLW9BrAjPma%^ZxEi|^yoJol<4Mp^cf3!1uT(F zRK>hYG${U}A^xJKJC}YLfFdHhWTd91x$dM>?_Zn~j-h*!Vz=&!4+MtPns{%l_d$>;^R z)IXCX$?xt>=oKR`|DrZ6hTq+@b_Q+weM#0A@oEpJ#h0DUQI17RrY!G@@jX`<)Tj9$xLtfxGGdK3A@7Sh`seuem;o&E9_M z=Gsu__fmT{&)Leu$r_COzVuGVSwX0r*`w|7ue=)@`*j`pZ2Fmjk98==yGH*q>!$VH zwd-ERLnEtg2_8wJVKX&jxWpZ=T>tx1wxfm>RA{a~i2HSyl??pf z6m`?7Uo(h}-owPtJPcl*x95x6pab>1_Z{_qeQ46;)PJ0N-mSxzPI2uy#A0faTWYwh z%6}q7ldDc|LT`OV&Oi1ZVsciuk4|T1by&X%d|pyEzpRQv73=t3kej&228`Fj*VI0r zVpLjcP#RfD$b6R=wkB0{P(mYB{n{a|-KR_;o#u{Tp=NEvcIMV>FT7F+63#S;Qp#+9 z;{}FW#b_HLc}08k3g4U-d?D}sz_#I!y{7MZQwOkqa%(D(Et#{l)tRN`RQeU`xXsa9 zX)l_1PGW`Su|vD6`%5L1k3~OX<3ao)rm6l_}n&f7b>TjP*{c49h}h6t0fDYv8J zXXO!0q+0}Cey^$E+qV&!)(FiT-aGW>F10QoGrY}XEGt#4!V3Q#!@h2N%gX}+}7bo}Kx2a_jzzohK(J3m9yMm-`GDAh_j- zFMydrSlEv)O~E9)Y`r|0`X-lC`Sc^^{;5+_DwwFk3!h#&zg#H}`+6}#xlgs(&3KUU zeM{bP$RPIDMQ4We96g2GH>+?+j+b7TJTgj&IN}kwiUt z1&UsssO2;G4!w{j$to+T25@;v9>>95{24wy8-OVGEI$5KKN_?Sf9Hfn#r}uuPT1tU z_rVFlLoe+5FPS}*(ompdIB}J*wPkeGN_lyJ#dDxv#aqmeg9rVt3Hzh0x|rHYqlxPG z$j{wPl24;UUf+)5YOoA(@Q%*w>Ef$Pd#H=7N=7g2%8RqFXSnqLe?9$0(sXUPUB5kl z-!yM|-epyp^GRp)#`*b(&rUytWVJ|v*3Ptu_`+2MWE0*Q;bep-aZ<<~@%@M>@jSVF zcVB;xB0{J$N`lS7EN0UTlwl?68J_Dkrgfu z>OKVd8tBr9AACg?94`g;{{iJd8ov(Vt2`EiWQ6^s(YSW|$ z%w$(b!*<(CPcD67nQY1viOgBgH2+L&AEC$X`Z2cn5I21vl^seiz?48msr@&I$QKIM z?iAcevR^O@qRg`FnC|A|=nTgNtVec=v_wX)@vD?2nh@JbuG7>w~~jgwm={=#>R`OGdnb-m@~u)#l= zj99ZNf4R5Cq%X|MhPDvIBb&p9jiOJViBst{o z?>p8@WP4FUP{E=j1x#m=>pKMpturcx`^F_de6-^Em#%SbW5g`>c>cze8&phi)&m@w zUSmB@DD@bKa-)W6Pnlp;0(YL+;M7s)*(ijvKwP=853?HR-I7guheB_8ysZrUB(NEb z|1r#XUZ#X9aHLdzVzb9z!5Ixw+o*S$j(>#}z9m?Zq${kj!dnA(VjIySaPZ=@T==E` zjhl}=LeC@pX-$u$2n`~viQ`RHMgk#6W?kub7ne9-7*U~UA{RgPDK32WbM$9>SPK@N z<3KSlZ?haUr{FHk6-W6HStu;KCptpV9V{Le_jGZ}q1Sf=q9`cjsrGiQOgg z_s}UhMDx_+DYnQ{Px08#{eABI5B~<+54{ftZ$%N*3M;ID)>t@51gYk7X>p1`DrwI* zc0)r?hHQABD6gXI(`Is1CD4k^g>9XZ-8`bw=AWx+OI+n8q3IFWC-?-FmR6@s zrBCY-i$*_`RM8o!QD&+xDKCwl!-n>l5|}arai%WZaDa6-I7)#qqh&g{n^z})K+FSP z6k|W^6S%@it|DF&eFO7tD(x}x-Av{&AKaG7NtRWg%Sy;j=iAic$gD> zkkrm^F^U%S+3-6#YLTh!VO(We>=C6+d&^|6c4hSGBo^nKkI!XEZ>xC@v}8dLiKr_| z+QzcCtKbL&7;uWCG&=oOetau@127_e0xw;;#{c};S9tVb1F!moQuy(Y zR{W(8kN7@wzGuhzA0BZYJ?OJHQYN%qKtU^Z;~LWT@TO)w=ut(7kggT;MRPGzC#o@V zXmLu6vaBeIG-!6NAY#xTZte^~@>2!tZ}qiqg*T)KIg?dgOn3(y3iMQEcF-RC}`3VA`e$gW0Nc!E06It#zleE0!!DPlUWxq5TybIKpZ+{3f; zuEQ6Nl+tUnBGn+OCRJ#s(#i5oGegY@0y9aSH6<^4455b9Nm`Qkok=Ry)9hR}A$6n| z(tAP|z%2jLb=T}k^5-90sN3|NPF{MAb3gZwm__Bge&%PX&fbpq z`$)OUVXv^lpBzFJk1%eJF_mX%;uLYG3{FqBA#PCH6(|nU%cBxv1=1kJ0f7dUmMrni z_i!qgPK{gIJUpkdWXOyXr9db!f;R+eR1Q!%K)fX~qY5x^rS_OKi~_=x!eG@g6F z&8Ue?#gpP6z>PiI1`2L!(9{Xi1N8Qu5yQH9ZHU||E<-n$C777I-n&-f!4C0@8bcqTwKdQORJ=+j; zmzyVB3K2)lvijC@1xQMiMh`>@$!;N&=^%>+jFS9H)w_PwigZ>z*)jr6>jU#hR7YJ| zpA0xVJk5v^1;%Et$9Hw`P2bcGe(#mGEfTIieMVNs0bO94`2 z!ki0hEH%XlhDcH*2TJkks|w zQ+BoQP_$0ti2#jcB9ugamRWr{Z)T+FmtcalP-9Hd&M-t?M61S^Id(ZJp(euK|^ z@r%6wKmQqy{?t!p70r_3W>wC&!V2F20-M~&gTn)!Y#-%-iz#4@k+B@3XzpascX7FZ zvQFQ}%%%miB6X}cQwj|fs>#cl&KI#o9SXOk&^MzHXM>uijkp`3Xc3Jdni4x02E<%) znacZHf;5;E1UX>rQ+91e%?Py5URx7*b0 zn8rtG%N?S7qH2AO9R>_US?319Uu9jk5IM?jdzr{A`HRLiK=E)Dmp0E04X%z@@>z9H zM1UyC=h4%MoCq#Y${RC~HjU=eM{NshD=fT1QCLnQS)SWEVpNfouFEq)gL?}k#ULK& zCM(f^dBX+yeTLenWkzd`N=+Gh?8S@h@fz#&DMFRr=ZaG>^bNLTi6S|qds6o2X- z;VXQzFvxZ&S~~+ZMpZ)$6+KZ#Nb0&C0x!M%BG-1tSm;w&gBhG$AM&GPXR|fD4ETdW z2^6%<04oY+)0U>*$0t{j1EUxgY*b_RF-ESaIkasqEi#BUSIR?5(j(v&i3aK|4aPKI zUOk1gL!q)MUOGs{bL|?x{;Kiblgb*xiS0E`9|wJ9l1im;3M*&@ra)0ZF*2kl5K3ki z`0eLGhVZvPBz)-Il8awD&+h)+R@lIEMMfHvD}B3+l`E|9&c%u(U15cH9XeS|ifB@| zR3QW(SJA(fzz*AGd6M45k&k`$F~`V;0|c{+0i zP|lGPavh6cbLD486i?j=7y+kbL6~-=XQB`w=10rw8OfxnEp2N~G-Fr9)AjH$yk3#MA2@UB=gy{F0ha(CKp+e^)zx)X68G+ z8^OCKauqjXdq80o2j^d9@BDe5|3818-ue-GAN(M_du{`-L8@*Gue<72SYd@XMj;iY z_b5V)N)W*%b+t`uPesTBgDIjFfk5;Ikp}TGrQe0y z9v)sw9nmuxmWGftKB@y=6I3azB}k%BH)Nj^ev$oHu&V>w&?DlMI%X^lH8mosgm|jL z^P%RHKgU&nf+$X{H8;yEw3f*y+7yg?pv{S>H2fP;oWLNTlVD!rIzhYy+X6kn^=9gJ z@1*YWp2k(^NVkHDHCl@pQvxmSHPC`sZh8|zZ=j)vsNkN;qD5kU%n2ju(rG@QSWGl| zGeUbT8@v5#V~p(>sP(DJ zHdk0m>bGX8%a;+Nz?HL){6v6h3vB>Dq`=K);ZhPn07>spzaE zNNQjWvmh? zJ(HjPIiHPct{g^PUxojZ>_Q2IaOX=H;m}aNK%)h+2{^5 z>JU0y0wRK;w5g~m^*`Ps9@D)sINbzxCe9QLG6G%}ikwi9{q_87PC-o|m5%Pq|iJp{6Au9rsW*`xuQH5@yP5Cb~ zSL{eiBR2DyLaZl?0}EyHew1hK+oLW7RW!yUs?kLvcM*&9rb|+wdhb!?o=S72B2&X*FfET0DRBuLwqv$q%Q01UtE9CYDVz-r|7ef$m_JO^MBWzCP|)O?jVzQ9^Z`qP zi*n$5`R?0f`ZR)0aBAqbk|JLsDiOD^P)_f&^QI^Rh8+5cex5Cw<8OQoArYC;FHwd8 zN}w}=Ot>a$Gew_>#~A^b&bc6-6u0hn84;N8q@qMKaG{oxiA@;$gczngD?4lzw{n7$ zoQ_ZPte;^bdq{MK-EnTOzn|5xO(oFE1p*!BEy0Ca8-_Nf)kq~1YHtW4m{}$?os%+P zomG^E#&;RX1jA{$#Ka$^2mk3!1yJCLs7S1n{`lp#UYfpa8mf@aX zNtzVD+28fMNJ-ka!uqj;$JyATKQ|@?og^YOk)$^JKu1N?f=(1mCkjzVJ(bFbzKmXk z${meHLBzaa&{W(SPw|S4SEZ^Pk8F1XZn0HP#tpELOQ((2TRMqH$5OK+nAz!B6_m{ zsi_b>(s_E%;^&W?>xFYJGB0_LcrM}3#BG*>_Jrk()Xm#l zJMUcF(pApR5=$&`HN?CO(wFY4E0q+u$4oxW@8h8;P}P|#9T!R;Fp(}1I-U*7Y#WI+ z!W3hIdjvg1C1TVVEk;Ageu=Fo9eSX^n2@sIWBT6HF_aNo(o)M!L~?0=5TtE+WqX{1 zIN=Mn%Vc0QJ^?%AlJ2od2PlO_f;0@uJvtXU)^JzwTWdBalfKn2@LnUD1IS48%C-cqJ#1S-mVkg4eMd@_HllB*!?jEDFEk=GC z3+EsPR-4zcQN9c9pv1fwUAVL6k*aH09n=T|j@QR{jlPWU<0c%TlRzkyH3W0RLmGJqN-gz^ zb`F;K_Ci8I>=dLzLxFaYA6hehbfx4Z!eJX}!zzg{n|CR|97bCtQrcL@7M7I;c3d5)e(+PA;1I4RH>~{X!4a25&Cl|J$GN#IU6E zz-aFfV}+a##h?z@ni*K7)fxJpAcT z^5mBv&%T`#aX zjm11!v0c66zXs2i1+M8hd`>LR&ud>^f0RV+=V^I*#-cCh>`e>rHTT30s^oIbbUYo< zNgmYo`|p3x1g`ZYq%X9KdAs`kEZPC|%GTrwnEoluLmZBr1DPpHdnJ~Tlw~GP^tnfz z^(B)1vHH>TanZ5g?=+hY(N|R0FYtsUP%%=zu^EBz#{$4KWZtYe86@}D!o89b& zuCACR{}j=*#1*|mR1sHNj42J1?rAi348omsazLlMh(fE6a}ZXU`ZgD*PcYW6(7NEh zO(DmbhG!{c3>349h2$xkY;zE}7*F#L@ncXLJMt7Q2MB55&uCH~j8leySWRGyNJGaY zUy?Fc#P)r0UO_WSRSHJ$0o#j$rN5kk6iygIz-*q{Zf0~{B2ep4roPn;%_$^30eU$h zDpwiLEWZA&;0i((W`FOFf=;UBNt=(~1tNhdH64mt_9YcSl$MGPO-fry*IWO((h{UW z3|4)OyX1Cm8{A0k1&*^Bwzw(W%7zcpw^)S6JBsZ8K6eW5&+=R`y2SSu`oCht*%>JJ zj{_G5$7nrLNkfe?ph7XG9qf((D)408@W%C$djhNi(+FKCh%&`|nw9p-+8_x4R&XAD zw&l0K_zZixN^s%Mm#y=!-?T=#x{BK+jO^v?Fq!5nOodg4cyY>lNY)zSLeK&2*wD@N zy}kM76WnoE&0l@FL54#xXJ_BoA1iF6@#J=4Y=s8Z0fdqm3&xGpx-bBWAiVxKO#Nxv z!I+5gx|7?Sq@*7OFR%0^mRRE3g_qn+_T0I1eD<@S<-rFZh;GTQ# z;Vo}@3qSaSKS&7QSqJG4edt4c{_~%oJr)r@@{y0csQdiPXFkJk{Kjt_dF~f};TL$* zo8I)I?)SPw7Zbg;e`%gxR1fib6_Km2lU^${cCl=2HleUozQ$~V0pbo8!6WA$d5p=K z)3oQGX8gnxJo(8_Q9t@sw%ReWzt5fHq?n1BPVLFW3MJ+ePbDToPhh&B=nPqnW0uNn zLO&h#Ir%49q1ey6eDRQdfv_Yi9+|5fd-Md~qOa-fwS{dg{+tg+W#(PlKi_+G_JnJH zJblx;?9&=;!S^(`pKJWI+&1xl9X#)Q;QAj+q~E=^W;S(6a+Jr4vGQi&OXa$e&aW|_4HHxz)$|?Y~FARkA{4Q z@0Cj|@jZd82%RhUlKL=a(nX{MDKg2{FYxrli{}#jeD9L9gd#484N-=f!0KS;vuUU| zbe4$0pd|sN^O(uXj%We%3Z(*#mbgpzh01T0cNM3;Q0+T@Wl9Zxe;4VpxCrTfTB-x-^y~3>^YJ=0#`6T&KOHC9@ zUYP{&dY06lIA}w(WhzgjRuiaj#`%Uf#HGf)NUBz^QpH7bg~mM~lEQc_Cdca4a!AVv zlXh0dAX$OcD<#w8bni@IeTl$Gev|>F0ZBfrr8?8_1gGs;YI`{?yEOJSrW&wtNF@y| zyWkx{fuXs#7EWO1TPRt&Ztq<=1*s-rt_2vIb>KYQN>PhRKhkASNZ+`$AB}F2<0l~Q!I9PSFt&ra4HM{f#5v8-}0&PI%lgBcndE-fVVWx z%|TOu+=9pTa476!$$BcluxzO7h%yKFQKY7HCl63xMYI;`XF4C;#i`p4hIf0e^PTX!_TFeFd^`O?4=ODwU(i;tHK zN&4`^4|DIm_wwL_4_;CF^L*Ib+vEQG@8|ye?`L~^oAXmbuwZ4SAS0X&|k9F?xw-`n|=h|@m|>2I`VPzq>8+9yPhVjBAFD-zCUIdN@zPg zmvVRe2gE0yVtW2*hT3rUkN%j)KlZ1bh#iBr;Z8HwW2D9iTHq@~V&}B6OA}yGT8m80 zXh}q(dhhW$Pm`b7mswJlnB`PlnTIKLne+_(xye6e;qyHq7)b=Gk(88$&j(0?5>oy< zQDZKnpNXPyzs%Qj;b$YpRG{_LrXywho)w`BZRqlZd{GfQJKn_+n;-qWE*xKDB;Jvd5+;tOQ&!X>!4U-fHyk}foBPWCcCrhujEf;gMx zcHNluQR%jVKL7wA07*naRKunF{(=Xe`5G(7R=D#mKg97n?`AGDx|Upci6xdmz-UPx z(Ovq6i6CAOy~He}ASO?Dq7YK7Tr?w^5hV2i1*t^bNz(7q3!-cCk#hqx#3KbtCmn?r z#J0q}Mx~+@q4Rx2jo_=)b~kOD(3VevL<%nx`KdzXkuKk8rVdX@!---Wm_lq3gw{aW zqOyXZdx%1GL9I+vUhRlEIozdS(ycQ#Axepbz68|L&5($?pcGhC2JNjVYwVVf(S?1~ zjUaj5g4KCw_YK0OgG4-sXqL)qL z-Vl>}Uhahr+=(73HBd>x)EWet5w%H?*ine%!D-mX!Wh#rfoba3#EDE0B3%fyA_QqE zWC!sP!A69TqC6T5^8!^ztN?>5mVgnoqg0{u08(N;!fZ-s5!adl+uUJ4#45M4~c<@~9tL1xOuq>_}G=XmllOg)EYvZe2ndd(y5s3=vD`h(WmBmKf` zp#Wxt;pL0Liv;TBHbVX9ju5HL+k7o7lC1Neqy+^8JclpMHjzgno(w4v!=*!V4_+ir zijolp4W&E50*Iqx47@<-7--9FoMeTX%RNJro;>@V;w(>#1oKoh+OgA2k|`6W ztgZ-m-%_z+o}G=H_FxKh5IQ7AN;4_|hiT)CyR2%Ll9d?wk(G{DxG;qDeUlEY1C)Uf zAXYF{VQQoRx6~*K7mlqbAARx_c-xw@!9Fk~%7C+@hKuEZ7N`LwP_&V%Ga9B~Mz8{> zCf$qShRuq9_2!#+~Y*8Wmdgt$cF81bT-8WEP$I4#A(F2 z#GHie(FY|#RwoK6aXmjbn;_-a`aqJtjJsET_CI^Isgq0Eja=53%8`1_gywV5`-4f| znfD}RCO_?RhLluxG-Vb*d?f4%=I{6Xdt77~7YWh+m=_t(UZKg+;}YhC>J^(>*q<+K zrf*xnA6a-FKT5bRzIOTcFKhA@r14eJ|NR!))sx#ZqSl?*tBHU?jGT0%IDMK2e)WIm zu^;_W{?#x2PsH^#%sYxAAlH9)v&0hL9DH5|FS2m&5CzwC@5~Dhf>RVFYJoO-B0p6S zUm>_)9x*=z?+6mWOT+}RfYE`Rr4(h9Lu8WQW=UWTd_eRDe3IJ21eFP70!T=~9xFcO zcsHd}O&*Kpj02P*a6?mZE{@qR98(y@vkq9;u2I496sbrR_A*=JNd1E2Vp4 zL{L^a$U&K=Pp$-CN2J7L zipiAL8)z$vFeJ)OQYNa?`3{{JNRH{` zDLS8Uu6vjrc?@?$Tq&hwtuENKAuF8X#sFvKDZXe2OxQ!k3D%;XTwhb4msb9gzpJP7 z;<FPnIqQK;`|U;3qA;)5UjAotvJ&kNo3C9VrN-U>3AaPA*I$N1}C zV)L1=5FYwV*5U*y3bads6E+^BE9*!lh)qFhtzG3o6}(wjW^?kIqW2WHB%Qec|!tWaZ-dI6`h-g{|y`N>`AwEVT0)yZ=U> zyC!<#*022B5mLI}c7CtAv%Pn~_={g+w_N2j|Hp4r+;Kavd)Hejj~$rD zB3ZFECqt1r0i?5=Lej=bU-sO4Hu^fmP4EVEls+pZc#Wfo7pc5GoJJTVq7ZPIB3j^V zVX*)Xa4e<1>sKg)(uOfcz&sGWvy2~2cAC6SP=0s0$`=NqHBq6&?lMKK2IC^b>REnwY{ z_2PC8{4vZAs6twBjM8D&;K72*Z>1fxU5X_@AJsKRsjpGfNYJZ=D+pwHkkLcPZA7$O7E2!4pr(aHH#9U>Ko z)8-lgCxry(il?}Ny~&umYzUgFLplN1`D*0MgH#r-!F(g9Jf>;$|~q#mo>rT88hJb)4S_u{i649TICBN!~#7 z9$X|+NK44>x~Y06eJAVKQdm#&d+sA6g$<~RRn`!KbQF^nhG8Qu=ss_omg>>#4p~VW zqj70>lmg9is%i98ftLJloyQ#hwpitGxCx!Iy|vC=H!D?(6p=gK+^Tv8I^|=3TGXq8D@fn$havPAanu+Lgx|b#?;e&R0~S$2wk1W?!q9z zd+scF!>L;su2qaj6Sh|2#4s#ew@wHhMM(XadosIHDQBnTTHeD;EV0BA-)>yDBABQw4~iW&fpENLsm99c=8Oz7d}UIc#-CCpTU3p45!XKMJ36=-9=JK zxO*zo6k#n-whI-iGT>cGBCbiwhY&~#2KQM)tr|$4goPyOpb%%soV@ISmN`k7?z zHV!*FL0WwBviCgK-+ke@W{|6sr;8$zt9`Clbk3f?>c+ouTyy*>^Vcum)vW!#@OhtE z@lm*QlL-5dJ^;a0&`Ep)+I-vCyp}?(1>~^GC!S!jR+QDf6 z2r?v4;;uw@OgfIyaxzZ%N(dkoE+H>KMYgCJdVzXOZB)girm>pVjR`fbfk1(avLXfj z9j2v3q@ZA&Jg$?3Hmiu!h)b)9uy!C`lfQSl6&mEaRve+rjF3LPL`VRFFK zBL$nOU5pXW{@T)_UZSFOaf*l#advrvQny%%x6s;oEF2)NnGh?$Q@ceC_X9c+B>!!& z0thq~Sxp9JHI2P`d$V7nhwxAZm+>QBu%KD(!c73NaK| zkrAa&P;*xNE?y>YU|mlT)Y)VUWdo?F!UV=sYMElRh$I4LpO$I;6pTO0L3@f5E3e`n zUe8+G=1h2;LoQ+3<^U>?tOE5M#>7H7eBUWtz5A5e&m#&@VHVmHV?+>2EfIw1aZZ$` zq^a2ky$@097u_5J0TY{L4Tz@21`2UL?%ukeyP;>)?MdnGG6z%hapjN*iqFeizwg(X3H{bDqp@bJS= z&~+!E67a}Mp=@fRI6ETs`Xyiqfu)unNB9DTn(U`hs`zb?$Qv}NkGYM5ypyNL9 zGgXmQB9sbvL+2H)L!5#ypLXs$CcH94?%W8J>w)*a`8Hm@6S#0V;`U<$?%5Vr@Yz`K z#_gI@+W?Mktz2=O=_{3#`)Ltg`X`rIVu>Zb>u_C?q-V~Y;n#lc*RD#C-f+VW{KQZE z1aE!oTc3B8>e#Vky!+kn=H2gpH_trt48QX`zjGuo2@+BI>%ac%{K~KV3T65H1DzKF z?|a|-c>CMmK6|W7(&4)kv+^xteP@@ovu8OzIiOfmx=_)0K~n^FzxXB2{JZ~!_=QK2 zC%%SQ#3PKhx9DE;3Z{cqMqho3jniLeBTm7cp$jXL9Iz~8vvo^kV(?_|KLkoV`GdAG zm&!?EA(ia8mX#Oz*C?ckoG`NrFoiO}APPxa-G>Ijk#YM>vC$uYemc)RdV;iFczKb8 zyF5MKa(iY$N(*)@%7@q7#&d4}Id*fc_sH{Y z`~}9M06hKRZ6NwV(WJKo`m6RA0vW6FvT|!tP#F{2AB&rm-SvBgLnCt<& z;Lus5)(Vx9DdXg)>Jioacl8#_!AT+qX?wnf_)0pjI!y{vPs4H(5F#ciIemy=GNC^s z14woWGNG^$K|0p7V3QkJbnJ03I7jSuSk(<~ z4!2R4$7$_RMloViq`yT^NSY-QF|U-WUg>jv?KQaU+&Lpjbw;wf_kmJ#rF(D%l*o_nPe&T4yV){iXnq0HQA+lUlGmjhITI^}|g@3`rhbe@9T+z>j7y1(w7C@mp)w#`c4mrxeC2sO^J zcEWlqj8&i}f1z)#;c;m+?r&Ml`_IeBcAcTHg`!rDMNQ9I>j*Y1@W^b5aB za@x(ma_zgs5=$(x#CIOo9ZA}&JICYk6|cSH9q-_0e&%Pcsv3Ph+<4=S{NgYEA|L(e zNBN^a`lBPSojG%cPkiDNy!XBD{ifUfjo?+UdeygOKTCXza0iKaH%dW4D5gT3z;4@e zu}O)=<1=5Q=^mqkG?^6vF;*_^FuMP52?CoARUUr0J6T_mNYV(QpQQk4;E^UZ?k!4E z9mQ+}ss>qTk;tu(iFR>X^_eQLXBtJ4*rh;lQqsHT_w?_xYb60)MpPQ9bbor;+vXFN zMBW;Sob5N;hY{(*zGuX$T$vbu`P%d%pPTuHC0-y13+mkbSR>SxQb@zad;b(W*yov7 z+zoY2Js2<;4xe9+yTlSN5zJD$%`r`0(EapRJePQ3mj{AQ#*4*CcZb|?unc1T+t;yR#l z(mo8HwJ|&8CZ*L>-5za`V)hEHv9N*4gy0iY+FXWQ5k={!5D`iNkuE6>NsE6y0wux# zX96-wUV08gIYuLg>{toqUb>~k0fpT~uyxFzPClUmjqgxOK@cYur9$*E?#>1qpi@Q? z5i2O&ao=Mk7tzq61l*GP729M*?q(`qrS%?*f6{Yl~XHQt>QvFnx+~ER2dm<)%H)d5RdEjt# zjF2B)HgHf$=0GNvl+p`irn{pilqN_EMW|S>juX75(2BKojT7-k?vXcAvq4I?5+Wm% zGLuD%`(NUv3=^T1kiCo3NLQs#B!Fhpaj?IORZc9|AO?nO#_CXWbwMh%Z#?ArLsCs^ zFAId~ZNdWMv(>dQ;eS4XAr^L7L6?+tYK^w zeTu4LSxwQ9#higu(%i)>gqunA0MTt$ex{^=gf26OeM-8uoOyCUZn#~4p&+X8|fRF=PpMGP&k@A-yg@~`+60qdh$?RJl5V7tS53^ zX7i8PHWq&_o-BbY!ml|unZwjb~d=E{kyeJ2# zl(WSxAres3*QxDBCUypw9l$W3qMDSJDWqnAQPHxC=^mobVi-b&>uG9LwivSOD;O1c zfm2|XzW*ZAM5t*^kdjT=W`#ozY)nG|Qc|i?2oywAlo*5qEr<*#36yk{G*k$!HIxk5 ziYut>U_NDqRo21*TGc$`b&A8Wq^8=}uTj|+tMLR8CziY5P8DxpMNYEABZ!WuV?k>M zrK3_280XH9M98{Q`c0TMxL;sEK^1GZift}5&(IYCkrq{DERI;DWCOG#Mx!+-QGyEU z9b&7Q054ecO(Y6<>XBP5Qm|DrPM|bnU=s#(IjG8Tayp{4m+<_oPTCm25MUmCpV+w@28?qj6 zV9QQ2i~}S>S=1aWPq3=%C?z+o-b^$>7!a`>3FZV=SoUg5^biq77=K%?a-ZMGVYQxy zrzV)Cz$QnqsnJf2po5eq8kM?GDoxfS5g2aO>`y0%Z-4~?!VRl6s}4w@@ByXQ;1y;H z9_V7E)Pk)Q=U=?3B-|PJ>(3l=*eO=PVFQOm<|FZb9DeO<`0BTS4@T?$Blvat))Sx+oVMdD1 zNYeaJB@v$5xAn@?bmVyYmFVDCCsSuZP%>AtK9{Xgzm1%Wa&%)$e9Q2x6qZs z;Sy;44C{q6v>P~xV_f$U6-pmc#C4=wN2)P_2_Bq%xr9=&#wsH@Am$SAL0Cb3fVmUg zC@>0{GKpu<4pzfWjQxDJCrCb}o4Uc+$4qog@IWa8N;QNr>TT}BA_Id`gy@H~Zn&)x zixTk;p`pMit)tc!C@4g8!H8hlH%GieS;c(9*w4_~c~myKK?oS@(lIQYFjS`d9ioCrmuy@X+Pxf=EwRKBFBM!@B{ z=m+Woxva|)!R=t`L;@luYbp$$KFc#7`uAM=tv}(efAc}M-}^4EC_Ho$LAo4`FY!`A zmf)v*S<CI3=eMSVcwEmce;_cY`&f=l*Jeg2zv zAK--dex7+z*LuIi6jo+{2Bo8=VVeAJX{e>9@|r{0ql<0w1`V2sTj7dy?7m(>%rOx< zDKV+hOl}5;KtV%G40&YZ$p_X1UMa8U?#UZi)irPL(7sb`^7FS#ipvA-Wush zQU9_-TVjsIQBRCOOlooWmLFK3@~@8<977n0vacNzKg4GXV##J|ln2vBWBpr{(+;`u7S3LiL z4}5^(aQK4n?`>~;8z1?|M>sq@oISU{zdujf{3bA&O!&eVzQEbDXDNz;TW-09yYIf6 zx~^ZSW*7*mhbIek9PO+OdH z3X+1fPkCP~OJDrgWA$h00RM zW|;VJtBBoz+ZqxAqAe~LaVZcAT&h&5 z;9#zZq>!PQOFE%LfkIXgtCAO{wsh>%$tZ>Ov>kO(<%PbMW3gsq8rUy8VrXfI95SW$ z0Vi~mpG$$7f5ZnaF?6ac@5mNF$ZBpyv6JCyzvNP{*+x-sKcp;08@Jonv&I z-~06&TNB&1ZQHhO8;zZb8ygK8+eu?Iw$a#0<7d9VXZ_#JTKBx0IrlkdUweP{ikY1U zDOsI{p8M|H?+m@k8Y;!NzmpeRfm|x6sw%T~YLwL${0RLCiP35ePNN-~SG!srgp|Lq zpL`tufpPIl{-Y|FmpAi>Ir;ugaiI*cStCx|Fs){|6w*8DewOHF_%zO=5$>wSL;VU| zNhMV*JB`P{Ttk|QDmsjlRkuN4lrjreZThqLP>7NiUjviF;O+mb@hiM__`nC}&tvC0 znWi0(Lk*;aR0{_R`j?XS=0rk)<8{wSdbQlYPx+1YJ!vVcQ! z;uq_-kN*sE?+3&up)f=y9C(J0g4D|Shk@7r#Mgc+T^aN-I~)XN6wnc(q6`oT{OLTG zVzS*i==c3WDHNPQ@4pHa$yQj=vlVi5VUJ}`2=OM(W3Z&f3a(E}Ypmw8rgU@1yt1b% zU=ToR{}i}-iP#z0h2BaAZm`L(*M8`fnh;Q|%q?wr$!O67$<5<7O_WNe-gS*psV%>0 zN(jBB^;cfdcJr^FCr)t!&qDe3JG1=G?@l8})w`2(#t?1~` ze~ZbR1)es(@C#o0K9zf~u|K7^pLRY1Ch*V)_?0bx@5G%rfku{a?IIlVaN7}PX1ijv zQ0m9yJ3X1^g(9dNli~BVb_w&&!;X|cZ}}9M$k z)b$9P%3S8bNi%XuOt#>;*R~eZE_|iUPi&TwzlnmU!->hui6u#N$W+8kAr%dZ4>iBR zA3RxVv<`~k>0M^2?UNC#Q_|(Qne&W5h0l=Kg+f`%rON%a44M1m8&&nEvtfj*mcZq2 zlrFhFBF}h6U!*DoW28@%l9mp>gUiaUQ*wstMxz!lb$brum+2;*f_?xh?=Nbe1*Ekm zLyZKIpUtgFKB6>{?L@_mvn2Igl$hFbZKH10p0o1Dn9{D&o)RY1v|*S6&}Ua~JenUg zmaegeS4RR#q)yTBhPf_PAMk25?6BgkM>uqCE`NHXCrOKHNZ{8U8&$jG`=gbZSZ)cY zq!qrik!_tI%+i}Vjf3yUDv{GmzCoE{X$!kQ#@o=v%!1GklmHv}I#lTu(x9v_v@(;O18efeC*ouyXr2Mp`k8-RYXU?+@Xrvzb+- z;rV{LYL=p&iAoywcmFEra7*iDz9rv}w2&sXX|4YY@qnl^U-qA%Cy%s(B>Orij$(Mb z392{K67#urx)gp?7k&(LINA2UK6(!Rdai$6w_w{#EqJGJ4!X~=ra0wB@IEOa{-F6! z>Wc~Ne&KZaeD@7HZwrcpA@T_+c6C0)vXjj)u@N94 zX+c6{P38cY=tdSGBCv3T5g|@}H$nt+no1=ZLVci+!CM6v_+@QjN)acfY;XQkn=8|3 zbzjY1%hK|A+Mj&pMMyX|+Mm2BcBE{CO1Jw(b@mh2<}!FK=bNUZa;dBqM9$`i@gH zs^@9vFD0`-R&D4WuPWHh%@%V^C0b`M)3 znp71lyuR1E7HoP*T-rXyqMi8FC`H(vF_eEsEaZjJNY^cUuCLJUbDN=6ZyM2OeV?sl z^6)$n8gK_O4!>C-&xd)9e-jLWQCLa#Kw0H{)lE7?>n?+*bdRlhRhMRT3+t~kn-Yes zfCH1TDQQSzrIVW4vbBMw2HkCs>dF;IK3f&o&rl^paZ+>GaZ* z9339_J%(}};wb)MbA*>}WWl)E-wl<`a{r#sC?*O(y&hUjZ*^!tR3^P(U(TQyBqgbm z_&~&)De4Y)PrgJEKnsa+aM2^S{O+$BqcI|T#Yk*Pkz{?>?$E`~UX;u}{0pXPL|vAV zTKC?aqhaQH!zBDnH(a939hDTw_Od4XNFE8*FQ}~Jr*xKC2omK!+xxx*YKP6DwEhk5#H(Fg29sZ z+Mn2tf^Q8}ErY`fKBd{Fs77fY^v?5=L{)8ywLdD-n=*?DCv5BB^pHIt&2z8zU>V zo}A6s$-Zdi<;$EtfP3A z!4(73MNRpuLM<~EkVD9oU1%KMn>`3^D?JaR^#PdcP5&Wqzg(n~OKB;4 z@6zixo8O~?{zh$wu6OeafD9||pP=ctR2?b?PX+A9W3DSv;_IwIVi6IR#osPeUbc1T3{qznLFC!#nBoH zFz{3x@7pCbwrnTE7&7qn8&?)s6pob%aI(6~(ccV#PqXqkkUq{8+EE$^eRqv3-86}> z>#N5^ess6nYg|Fj9|~2n{5+b-XoLzOwk_pz>7=WS^-!Efio(m_ef!LqR_bg+vyk+X zxOCFeN_bZ+e!cXJXW_Exl6Fq`nGa>dB{z}H`lD>*uEs$JnA<~d06ujG@AM+KO=n;C zv1NQ8{5jh; zgfL|tO_-3@lE+ML9QF}_ei=i#glAmbBHWg~Mj(@>WcC&hFR<&8O4;625(w;k3vnc@d}|9}T7=+GDy6*5^~{CbHp3$^fJCIl8-@rC5D1&E zcHJT)7nU#bzi2{n>yMw*;1jPQ^G%SE-BbGYLv5Laf^KKl&d|9kU`AGOB>R?pDhonN zRf%VS7m>1^T*8Wty5o;q-p7;VlhqDYM4(!O^pH1=2TFQ0dde^9JFF%6Q?_9kN0+7% z{&jw{In(N8XgBo3b1XO^R6uFpPHaKrLH4rS0W-|66NvuCuP!8Ije{Z8>Ju zNAx()7IzyEOx7QFO;9N9H=iydL=~r?!Pt);Woi}*fpnWKm3(a{fO%xo*GP7IP~bmi zcy{r2CAMy-E`VUh7Em4ReB=jF{{E2}?+J$HovS|~Ki!(4PgT+FUFa6kkpD^0O3Tw= zwS-WH!U9z1?XZcUma|*0A5vKR^un|%!~Fg@geVkkXYCO+>+$E3y0NT5Aq%iExZ4q= z>Tb-$j>|hL(Qj2t`CkE+{3aU3sXTL!hk9ioY-kjb-(SM&KltKuF*`4LJGwqJJy`#l zKZ93DulqhW`U2&{n(OR^K5vumLB8+ChK7Lzd~Tnsj+1};*nRCXVUK4&>+fKKZ(w$o zK6f(zLT7)g!f`!gS8jAK+57pmP~Q~vLDzCfAq(A1nyQ{KBsw8s2|zaGL5O7!!8_{(-;$}_xpwZ+sqoR}{ z3x`OikH18}XhT2V`-wr6OrarZp-5_de1vQ{}3j#wD74FjUcV-5PjIf{^s67GGMD(wK zJi{(lRl{Mba@jk~STRCYWY28!JJ4IAtnfc+3{_(c^W96*c%j~ESScHo=~v*GMC5H@ zG!%4Jx^&E?%D*#46-~yI#MnomW*)v1a>z3PMn*^Y{siHeFwTB<-6Xt2(N-9O8%!fNjNWa1geV zTF{b3a~X|mfUHcqT+g&v1B-v~cc;p~5EWFkC(Fc`qGN?_6Y|{sYWyf6DDOr5#ioX2 z|AbYX%#1>IIoZlq8aY(Tc@wU(#vjujC@71>2Nvx)8CclTOIUPUEHd2`V|lD9dV7Y^ zx!=-vqaWb3&{JK(Ff`QMe4PSb%m$Wxu${~$5+3JVw72>o;&uP9xtAm-FU?fPpVtH_ z1$xVxI6@|Ea++F0=F18FLbeyl#v~Nr2)pO}w`Rcaty9jU|6l2&Pw-x%&vPFr^vuoJ z^>)=&ReeTSIgLM>+4p`#ZhD<0a0iPiv0>2Tmu{W!8_687hw#1%8m)P^6#VDq zoDIBk=Vts`tPmPu{@iD7?C9`a@Ls7iJn#;F_I}yu`_K=8GVL79kyZ|q=QTUn_LtRE zB-iD|5VVfT17eboljtqOrO$o9e%zE$|8k4g|E#%!Jcp~=)7$#gt(L<6AutY?9eyEu z)&p3~gfyH2s!{E+J;~NMae~$J)RBk9w5pP@ zS|w_f{?J@E*{{(dN)n+5IdrX_c~q-wiE8NeVQ1q!x#wC7F)3%@`rzB`s8*L1;h<#fB}5=q}SE)~qOZ4EK?bA!7wtso7NU6IJ^VWZw$0 zU60#2NRaHv!&QT@@Y~a)9Z+>(XweGD&9WrIYE)xbGoueEdS<3R^BF&A&aqYtW{Uvp zyWM6{1kvsV&bJEg5v>!dD4Cq9=V170&FgGS5XE>CcmqYtc$|^~DPbuZ*)H6c8c)Sm zJ7zEy{g#5tu?H$ml^HJ`*GhXzZY3@ih%C?1F+d480GezXDcKY)h3Xqdmil=7 zuDYBX8G6~UIT#yR49kfn@;kGQC-qyTyq4wFtLAXG@Mleh(Cc)buh?2ru zhyh#X(+Zgk-{M$oT=IC1p{F7hWg)2!Pm>m=GEbN>ib#!Cmkpv(KlM~K3>p$^ie;D z;&rcLse!R&ZDT0IqaJlGb&`{jUNV&YFE`0kg-E`bE>*Xuu98|V^XvH>r41ht4Zhg= z{wdR(OKjN3ETeCKH8kbDAuwZq?>ULXY=$Z@+Q{t|vLJ#zbSu?Fl_c z%eN-zIFlK4%3^Oi=v@BjCT%r2;YQQob zzHaKUcEdWLSL1*x+dh@`BFr*>pF8hZ_eucU-mkEy0zfBL^^Y0PrI^4th@H&>&~|a> zMWa6^PkyqU_l{_7imjEUi^E4O*ORf4|HF}I2hOkRkbQ)G>1nee_`l5(Co)- zLc78wBc*m?qb?QE%q^OK`*lM~At=@yR_HsZIYJ{4RYVOQ(;0_KyY|TF^$zLos=&nCrIKp}CSXFc^Z! z&;C)p^*AN>>CQ%bCh&SN;4|Xp2Mv6`wx?O7ch_x(JvhM8IPf;k&08fa!BDA+1vny; zIO^xhLHP$4f$6bj)bx>0A-`uX;oZQb+DtYAV%q;!2Yt;qZ&+DB7Z;a>M*S-Co!WnE zpz(7K>^#v9k|_L5$82C?US1ygB$4kSTF})=(3NK!CR)&GW>5^aaX^Z7LEuwY_2?TR z9XKtZMm>SyAvv4FA@724r9maIqWl@obC%owT9J?95RhoQJ=TrVYz&AIpFfY5`=x%o zB*m2=Et6-)Oo@fdSk{D(&t?t6q>C&t(vKfWx;0kB8k~gH=v{6NmTz5u>fi)qaIYGl zui)!_dl+`!dHgO)w%a>%_~=At1*4OUBuuL(GkD0I@$#m_tXoOO&|2o8CoLY zB8sgxd)Hn5`KF&dCr)Xr-0T0GfJz%8SA-O1&_3AI_vq~Nd2hT={k2rj{_Mn*yVZTVh1!Bx?6U5|Fnn@;jxes`hpfUr z>k*sG6<9E3eSy0C$3sdtwFN{}z3@WVAJ}nz#-92Gor1Xb+0Lj+qe)gvdOa*X&_4{x(FsZD+>YGU#xM!@)55O5-Cd3qAX1%x+J^fC3cKJP3d2@Ob zy^ir@mPQ|1v@7VV*ty3I=YKujKIHA>GV?=2Lpd2so*x+#etQwv|3KRRZN|A9NKPd3 zzi8m@4${pKxE)4!_6@F&0-e&%$}RhD5c+N+#kC~EjX#f!kNVJl>g^}<@8XXJ zh!rx(8^Gh~f%6`2^Z%42PF7b!Ub|8Ul@VP5buLzHAp{zeeVVnn=!q~0Txz#4B)t2CVh6BU@nCQ(%H;zMZ1my!EfaULO_ULa- zg1=MWcyYO4gK){MVG5uQpmt6|3)hA;)J_WE%d~1X!c!2K7|R(|kt-h&2WA?qv26@d zf3muYu~LquEfX%_xl;Oylg5z1H3izSDrIgsfM|<8*rpVmS;=~P7M_WMAMQ`Ks)Q*F zfTM2>Xy`McixPGFY)4W7a1Df|tNj!vX`nw~xSWoO~5KovkQ5IHjHb;uFoP zC9E-Nc+D{qY`Tbj2D++mA|+b*JVIk&SaOYI78#%kZwY^sQ@QTdQsFc4Z+!?s;XH{@ zNg8w008y3ysZ>X(TgH#r?>Ozyi$a4ObCCpFYI?}J(ts3PDoRy51@H)Bwp-dLA{nB) z@bp!)V~-*nLZxOTq9>+x!wIRI8ZAf4WD1pJR9jjKHL#ZNg*^Be5(0#U5^|d0zq4XH zP9Bsx>e-4j?j2l!Y@u0uwu4$e;pj(Lp@CACqL$QEJl|y$6K_*S`aqYIu7k`y&EIym`OF)C#J&-ZBVHSb=szpIwW*HwQxx5#=bN zo@)Qc%FWg<5VIFVCkz@T6a}uExwyVrIzxgKJC5M@(ct%t^Sl3yx6ZK?fq#plbc~II zC*QgVkx@{5kF%{48M;8`j{kCP59JdbppU+w@A!PafI8)VKKF_o$9LYaqb;|#Vaq8m z)daxdm}NsU@|VwcBgkXJ5{jM?$O}nGtMN_+;zDnE2lxT&c4^j@QtP*COD!Hzj^hRt z>wjMe$|cdWCc(+Wl-3^+bqlo2(h?1MQqk7q~Qlo!%B!v&+cq z<=QPzPf!SAOPQmCCNIT?mUAhD1Ya(Mdp2DJ%qLoh4_(k~HqOQjdbvs4+#Vtuo38;7 zs&~qN@}ea7Ygfn$ackIZ^vUTHWoL9u0$$j@Zu&m11A2^3Hkm)&gPIPQ!Ix~rpTO-{GQwS!6td%&cRpD#8R>;vZfu8&$WBSATKv>C>`YrgH z5#Th~8+f_!-i^y9PLC%x=d=*?j<}@?xt}OtBjwHiY``OY(lagrMx*s+{P_>=nuQ zL8xm7giUp1G;f*XY@6kpRtG}lz|`MTyXIj#CJxFCMeb4~laLz~Pe`#Wq&nM4a*(Rw zXftpU;Gt--=ud&+yG|QyHpUKx zfhs~VwOA#nb*~MSNo@Ykg4K@)NJrp>wDu1cuH;fee_I|n%t}Mma2lxx%j&8&IR++J z0sU%%+MmG)@u6^QmP{*V9Z5CcPt%wU6L%egcX>%+)}%;0Fy{v@7dNmF;STcO)iWe6 zHe!m3v7E39NFny`#vff~I zII;U%oOm`s)M^Sa_DRVUcvPQK%bweQBDy@2JIc>y6@j_^Q)fFf(&h}fr9;JAHe)&~ z$ePji4W%8HG&zt^Qk0x23euK_GgJbR+_zO(H`Nn)2(JrL0el=Ue(cB2s2)F6#%wan zk6)wt-TfKCS+1|BZ>Eu$nW{+=Oe}O#;a0H~f?6Hf zkuJCKr{VST{Cg08h>90_MzPx#Fwh z#Y5hu5WO2}i`OuU*G}3mMC~I=ykDF@tjSaO+hO9zW*4Ujtq0)UwU=)PaMT>P@*1cJ++EQ;c?i&+*-;7b{?+Y*%` zTd$_pyU}R7R#o;`Ca`wF0dZvtTYzvV?%Mxw@Fob>3*f2T!aR9FP}12pjBK3C?XOT4 z*d$bN%)KrCypBP_=!oP2(`KVa*DM|yJSj4V0tOeb`*3-!m>?HL-Qzrj8aqOel75_$>M+t z<Cq8-1^~ z6`s6dzUo@JKrf;diLY-?xC!S>;J^7SE4_s>4exT4!Y+%m4o@m|;Oe3!4Aj~b^KV=k z=-;+z%8C&&8`~Fptx9wM;N8ChlW zHVs2rGB;T1AvWU)W;1OEP(c9?ftw3;x1L?GNq6X^9qN7~Yd(ov9A&k~5^)B%2oBgA z4sS5oZ7bQBFa(wN@Ndm-5#=`H6AR&$K!vOr)|J(iDKPI7lIadQbpeB@V@=?77#SXr2{R zEEzu}$YPG%3#F3fqp!)DX_PRLRX*Vdg~}9SC^X~%P~(J;;O^r=l|t9=)(NrVYA1cP ze`t6nMcZLA)d|+&o=U+5O%&wQaL1Rk(N{B(nAV~F9Y{z~X?acZwAaj5q$}xJamp-? zm>yDyGIq9$+v(4_%o!DV=UCs;6avM_SZTu*vrEQ#EyC?n7>PSiHLu04-FGOB1Ieux znK&9O6-R6A6V^#p-5RS^HMj=x60|wgzJWEMX|@+kKM6@q=RUeB7GXYP3io^cb9u(X zmRf|3MN^HY39T0RY%s(Ei3&o_E*MK3=3TI9lN7qTMdi8Z; z|4@rNUi-i0b7SQS8qiiK7xdb$MIc~r|F1WS{iqHoR(XHLXf`lmRq0z^NyqE zb`@ditMP33*3{T&? zg=)5M2>|vn7<oCB$JXgrR{c-mo48m%ej^ZUdkQZ-*>>ZZHWDb+fb@Xw z%wJihVHeDJY0G?kvUf->6gb18!~AT&e)o{2R+FMs=hcbeQnXAG=Q7Y{M(k919noyd z?i${qv-v~}hd@H16;H3GGP9;g>zHw8lwZ~zxTUD2iD5kAWdePXm`Cliq-S3F zMCJ7K!l?D|IBH#;{qt9QryluCBa#Igne=lNyxmNG`q*3*9f zj^EWgO4;$dGFl<`eNHO6iu4o=OHb{En}R8nhRnV_I8AJYc7#>y@HfZa)AiQ_}>B zysN-HAhv6ixQO8U8^Oq&LqLevLxtrB$KDLidW}m(an14#snn z{8hoeYapcxgX$p%X>$0lF6uBCO)Ou$35!bVJZkInX24d+ctFB4$W~8d&&^ zz+*A8H$RSrEF*RWmnEgFk+b7ypeV#=JCm6AUm4KLhXLWvXSMY^v%e=fL!k1OJ0UW^ zp}lgl->BJoVU0)-3G|Wz8x^?^vJzeAf$MczSH5N$Q?|@y8{?bTb<8AKXh-Fl$eM5N zVfRajvpCo5o%hZYzO@qTx{mdUJ~LBV%hhBj;^g(^x8h@S+_J>NTuy=K(Jxl&o2&)P z8KUHZ(XmtgQyM#lSO&gV8v<|jU)o0PUrB49*ads$%Af93 zB`q7*E}+w0?O!IJYb%XS2I?&qwou9!e)j9-adnHcP!sP^>>weouTRG3`#*^fv^-87C)wlq0-Y!_+)ytQV z-TxK?3ZpTt55#k6;p<+oc@ec~Fzo247A1D1o8`SU=>CB@=Av6j%y~-S--M@hj^|5+ z7Ru7rSSsq{?TiL^qph>di{FHdBbrLBP3QCW0E7zAQ)DKE<_;m1wo?d*VAHa1nsFnj z#3l}91{nJ4Io{f&IN`y~a}F+2(z9ZQ1Dm~2CNirYz#|k;!I|VVM#?D1ayzgt{?X>D zcN389yXzG+(AyJ?;SIde_A10e$A@8w$EeN60tHm)96A?%96CJn)Z!?@azwD9NB@X< ziZ0?ZmoO{FWDFH41wzLw^v8uFKuLubbLgZ*Zyz5TG>BMA6k%F{#gQweC%I*Qu>i;; zcn6kOqphpr0xqFXA3b_u`Ju5aPC@byHwg)ZoUwE8M;+`u=6`pYYeLY`>j6ZKGtL@( zj%K~PXqvtITawiKozp)s?P$XqYp3;6ak9GFPu?;?sw8LKCt@Y)fg%4W#XdLQmZ&{R zTiz6bW-5_pH?i{Gk2Qr^R@EAJdmCLAv6awG1EF|4vxpBK<5*!VKQ-=t{ck>^3sRsO|Ftzr;^O} z_P6yu2^i}#zkGhZvJ>j&Uc;W^TY?sc_>EFvl-)_~MWy}ods|{$Y9fUq?_Q$Qo+Hv( zG;J2sVrd--5h|KltWSta8n16YPCL3_RK?1AsuKyt6h7IEl`rsIXdjhYjsz{5t!SU4 z8XagY#{ELH&%a41)W0Uxp_ef=lAW^ZZkd?@6YHM4;K;Pbl)xR$^G499Pp3cP8!zbf z0WTWS<1yB$fRmncQ88%}sX|g!n#TCsa=PwlyyZ|uO~rO*V!MTaOey}2pcL5hOO|Bs zVi&l2U}+cbe&D}XiZ1s3jC6o3T?_VQiwtz+{@`fKkW*3_H!QWNG?H49;e+lVZac}Ej7B(u z;gP}Lyy5Kv%+13oxK?F1{Z>*#E%^l@)vTi$w%jgh0QH=UEA%&Q5XCl-Fcq!Vimi!l z)g_CHM`eTqK&d|;&*-L9QQBJOY7QWg5ho3G1*1fQa;MAL2guADCIM5WV#Lu=Qc#n{ zXlsrgZdpQ67ABZjY0eMcc<_l#ns`#*r~?<@Z^{O0g@zQF$3W5=%I-hSuFly1`s*>b zeg7L)f-I{;#Gf~cF%h5tIo%AEfxUU{m|zoeaV;j zOq-R`&LP3rjp>L_ql@dRN*Kr6^9joI>vw5hyniaCGX(iX&6Vvp;3ek@;!&)qDNMBd~gMbYevER)1VG@~2ZmWSSGxDA+_4|C)W!JB7r`DPVF3kOt?^9?cNnm5o-x2fic{jH^;mFV| z^N*(l*?u^ncAtq|fgzTOI>gQ~U3rpI>Y;tJwdS5OwY{vh}fhkMx`lbR?s@Ij4M}E3YUiSO9<>pX6MV&uowpW-3A^IO?DoST6N$_nW1LPio6HTovg<=a!YYl6+E?)a z4xQ3B)Z1=0EHW0qxi!&7F-^CX=-U~jqg(Sm4R^f?Rjypj!YSTB#ni}+n^>`l9EnME z^J44ls`H%R5@lGiz3~8JBbJmxY$|N1`>W|y%jnv?J5Efv`XW?B+R%pix6z*Q{MvY@ zhQTx5zCnK!X*e}%02~HRN?6#EC+JrLNy0t)>fV=TF&Ds~I z-?d_g&X{3eQa4&{{=p^GGL%t&DD?liIn_I=q*KmwA*j`&UlYP%UVn&S3nehD;NDmw z{M&8wrYG{d@=5PiFi0MgAahOfm`j)q${aHtmTB`WGfL`+9we>4ydsgE$(Bm!6 z0@HR{jn=0--oRRyM$nKlDuxeZnfm+RDx+&3{?n%`gpb67xT&Xs%r~9p1m^VWo~W~8 z#ssJSoW8#s!k$Nu1wGVQm}=4%{Jb89UH4T$xG`W3adS}Ij`-sdT28q6@Zn8}A7vFp z*NWGzeb+Yy1s1@T-%b3SF=8#lG!(;r}(`bzvzD z#%6qc*soTOPjD0{}4F*QqPozRA-TrBkz549Wx$bEq~Tx*@z^>63(L%1&GmQA0uhBQHaM z5dHU6j=UmEWhThr){gJ{f}rbkyKXrKNzQU z@Pl+|8rI~~)6+jt!j(PfwIcYHux5=v3gm0qYQ7kZK=?0A zXDH+CQbA_%5e`3&c$*`hgnc$GDJ%U&bYX_(rt}<$k;N|^tpdXk5_4>!G>&b^dU_bU zpG|R@o&=@qyZ%!TeMq5!7rXB0L1hbAW2^wdSpkF*9gX6aUn=t8^|ah;vpW=hy?yj+ z|Lthw`Mi<)&ZCRBCuXGzg$L#j=XcYKe}D`Bm4CGC*0(##yguuMhwnI>*6 zaeFZPlLeN{S2Sn)yF5-hRq8UuWMW#DGcyoJlWbMAQ%lC{UXMnF-*%~2I9;oaPTrrW z_=8`myWRHSSLzKdt0$_izi^ViPJ|@|@w~BrczHfuts8;n{P^J%Xb3N-XZyR9l-8j-)xogBgUz+N zjKnlX#1v~Qv@9pJxCbd}KTKZ7Zgiwuqiek|!@iPXYr~=_VOu#Qn46m9TEuIzVfIA=eSlM(w8vn{@EQ=7rvj8&jv6)NC_) zP-&BF0Ntl3ogmJX8*@Sssq zgi*%H2^si--{_Le-DLi;Lf0v~Fc{_rBDY`}xIH^mT3q}#meB)Ar8sj;?~+M$;y;xx zc{Tc;EF6fhnA|itbE4il1ohm>CX)lPED>UpLvXi!Tlgl23_gPe90Jk6gD-Ls&$EWH zw<|((QZ12^f^86X54|qFuG0HP;jYN#ruAu9-d=6Bjh6-*SX4|KyQ#1ay{~gjIvC%$ zszTg%)=FMxjM5d-gDm*2#c}-d?4D#V`yNLs? zFl7cNO`|eD*o4VYT%CI+SK8&^8D$3HFtB)Zw?}^7>X&kiLIUy7eM7pAzF&-EuPtSY z#2?Nm=+{jWu`5?cH>!6VE&iniFsopTyIofd4A8dAx2&2RUA$OyP>pvRixcgHA)!9nw?xVAmIurPr5O8!j`UzjE)~ z+7oM$H5)9I1&#YPvgZ(Sm{2L%m;ot~paUyzwzttwZ}*Aim?De%@N5aa59Dg8qw_Sg zN@@uJ-P&n426eQlnS}c=xliFuq)423JSFQN$L0N@nuw@zsS@cXZ{{7a`sW&=Ufll; z2(^6rOeBGIH$B6I;-KTyF?+$@eZiN2mHfIXU*6r?Y*5C|zl0s1oro>r_Zv_ct!s4C zt>7`J;N<1Q%BuEp`)S($t?}{_awC*N3A`v0h`vss8dLgmAfhL+SPUT+Ra`tzwg@Ys zjuBoB4;L!&B~q-W83Cw*jUoSQI}KMZhakxtg2V+$-GFYqkKpgWvpuP2ZxuAVARNSQ zKmB&q<2V{aXnfrDcxHHQ07~QSO#N89&%VAFcvis}DFRnQ5qvLZso(QfeT3s8#D$1J{xz?0b2-9oPLLE#1n@dX|^5GdV$7QH2tvNEUki`600 zZ+G!@zcEC$G7bs9yYP3oy|+Y^`aN5rz?(m-&-3E&!yHws@%i?pihp15P?{6Mw&!2{ z3Ml~&k)7mk&P&Huji`aCITIabfigO4li+DSUfMs1} zROYeQKRbW@FcH0iH)xMeSNAFO8*i$RH=kzFtG4Gf#H(IO1tLVhR|N1b_XID0*;Ljg70 zZ4D5-EilqH5-S73PBN%2xj(TFr`ORxe8QoXBH&WhEAzn2iUidlI3!j;Mb|v< z(hsHz(PG~l7Zb`6O??xhn@~+YziS|QAd~{Jh}fhr!$vMEOPCf%aL~`)p9@OTA40YI z0!`dEDX~p}09np5{A0&nm+~AE=(I4c!avv{eaBGVy?VjaFbxB67)04JLkO;^_il+8 zUeVAI^fHP7&>hN|6;1CCvITquL-e+q{Mr#6Hu&I_ol>*Ef$8@xGJquQ5>3GPBK}R_ z-+A__?jmrkV~lDN%5ci`s{=JRk{BsH6WP;Q7Du}bP}GUhNl6AtJ%iv`Py>Ckk^`7G z2{xX%G4rVFlhEp(7Cj2k?HLQ8d?_A{I#ex@O2Ff^Tm1Qx8i%p5av~U zfjIC%HRzr@7*s5{R!~-5?L5&6(u~JKqQkiU&kI2O@rO82eci7`0|V+B6a#ZVTXlzoI~^Y* z$`#!H`l5iL=b10VT+Pqi{>as=d`DG4-f9$#=j_~<{m>cPtG<+jiH4cg81jH7ux0;q z^xXX3ajlOcrJbz7msw|wKOqd68mO}SM+haa=i^RXW}SKC`?dI`_lA*Ulqd3{Q53uo zlGkDhGn2lE?B>iMfyFE7$QuPMxCj$PoR zf`^1yhi6Gcs(+EAk|tdgqC~nRUBTI1=PoF)*b|q+KDzpjiTiG#@^dvDKK?1+6a=jJ zYrnAz=_UCI%0a^g`};^}zvQMf0~)_CHrWFt*FreJl0r=LA+EnGpcU*B-E-^X>2*vf zT#>9^CilWeq{Q(uiXuKLF8)NsWCa@iw#XElExg1{6I8(a@$@Z~UL%(zoN*Z9I8k=m zp!c@~IJKfL9j%%THfy1QnbJAu=tfx12GF{=kp?^gFDXNtcGa{ZuQB;Y4~|Njpx0Vu zM($&VBK?}=fP6-$g*LMb*{0G04$P^onvJ_3wld_nt+ar4)5MiL^FSKOJeXyPi>QEE zqbQ^L510SP)H{aP8LVxfv9V$_wrw?b(%81K;-pDqyRps2ww*=|8{4+e>fZZ1=e*Z7 z|JM8dSu@Yf+|P|bXhlXBY<#b&xNFhBeX2%OUpfWVvUcEQL5_(b6j#!xE`wMy;5hrD zJ|SMZfGEa9+-k}T!yUX=E~2>2-vW~jL5uWc9Ytl0-7DD;>kBjWa!p8xi32&p^c%c^ z7+8o@^Q~|(^as3EvPcnCRs^NR3D~sJ<%{C0u$8opFyC;;SrzQGC)6?U(-YYfrqfSV z)0Uu8D6DDywcCa3J}Jzx((UD~kms@OCWyEha|gtJn{bhq&&d`g+uP9Iw9y7?387T9 z^W~15UYGrMt(@FffR+mM(?8=lF;v09Ki|IkTD=6J3XL*<-Z0<(v%y;PI?S$VecuO; zfm-#`#2?$l^;!(weH+~`F9F0)0b=o(pmyB{$3M%2G{sWp%9v@;HW;>6R%npE#t@`} zc9KSz7Gg$S`h=fzFML%@L=oFh4wD-f_{Z;HMq*_oGRhSz&WE}@$hEvqed+ylLJes< z<)?^wqAjTw<5tFDxrn_N@ozQ`H#P>wBhm47&1c2e+>It)q@Ot2VR;>HZR~D>?qZLY zmulz6)~Jf8F>)>03qr2H?{P**DLA!1?{>Y^x?CDiho)!PadPnaWa5~Ze~~((qP!M} zOVN+lY?)lL5E7mGeXU+P*m{F77VTv{C=$zim7J-+tlZJE(K6^B{P}rs*~(|=q-$^Y z<#a7KNT`O2u%M0GJ;8vz4f9od5%=u19J+4>^}@yxX7qxQX6Th zuJfmgy!+!F(_oDS*0w9}3w4y=b^N%gKMi$Fk zi3U7n{p^;K8DrAbn`M*_ru=d?7A-E4+qWu+F0PCv9XWvw>l`)WnNs@KKF}A3HmQt5 z{*Dc?#tLKx^xRsl*DrY-m_f#a439yLkhC!)8wI!#R3f-WlChlB_LOPFGogeU5Qn2A zaAYFyo>sAyWtWAYq!iPWLUWcqkoU#8#?W#?NNMd~c;IbLovz0qcj2sPH0xL?w0VTv zhe8vH3NC@>=t%mlo|J_6jWo>>j8by2XsC=}JR8H&r`)^YiNv)^WZsgRqHqN*bD zpMT=c}-O!e`AIgRX7h zNF4ExA>SXIcR7!pVIG~kgaR)|g_YKa)47MBwqwf^$lIVTRbJ%E^2dXvz*R3~jXU=y z`U!D>Iw@v7#Mdrz7dYaug-yd>RfV}e`lwm>qV#ip($h{ruv<)}OM#G`RtqP50kLsu zm<-<|pUuzlhRjCubwy&)i=fR3ySG9k{r&Fgd)j7qnPy1K{fbZElMCvmMzxYI4n+M% z*QmEZhyKa1F<9j5G{^;Sg&2eQ?e2B9rU8Gq&zXI3DE#QbJ|JFv28HQi?!F@ICL6() z+IAQ}XbRp2*A82C}l)Z;cHc)m!ytpUy6j=Wbs2ASUTS?*QO=Ml!FLszoT z*AMcw`*-4_wJI1D*YlVe*ZCGLlSaMbg~~K8|2%^NZzN-k?eFdgk-ODA(4y(L3EoFc zcF(J8vSL@rCUoV6?&_B~6e|+zH1?ub;okk)b5BfL^2-I%z8}gXde&=YY07mXY$9q- zE4#u(yGfn7$Q|kWvPdFj&OdVcA9%N^Y0Oe7kjX;xCR61eD)px{TAWtyywc7%LX!j6x(g>8AZiw^;&)%eR^4ZwC2spE?AUS$6_I1_=WxF!#^wv*w z(j9!|%9RIR%8o`N?NMyaJ|-(fx{5A?X&jk>R#lQGDJGYXoXl*s0MI6}CbkT)5@#U6rzHqHS5caY+y)Bo zbE@+8)j1(5hPcKN?JjuC|98RMd(UU0Btm5IxkVbj4H@qJqtmx~Uhm|4T}&McJ@WoT z0Guz@csD?)RL)EK9?lPE+RZI3I!3L$(x?9$5djHWpFBLK2-j6RF2CT0w zZ{0;?XO%Yi)Vhr2yGIg3h;jpeZdm=Db$TbdXfl&dAKhYyz?z!JQtqSZkRb2!X`nZl z7gV~RsW&;lIg6tEtu-)XJlg7t*~q*Ig;%mDd_+}*GPm<<;K>Kp0+y);@e&5IF)+K^ zo$q1S*_9z7pd*PB4C^a8-zMZJ`EI39*~`YjIB7UxtEdlLXRo%ae`8pVB9Z3tqP4%p z76R7dE;j7$q5ijDE@8+bK-93;I?n0*rvXv{Zz0BZYzNmI!i5=QoqG2*ChdWZNKT5& zffosij&*@tQoMr~(!)zR`<}4!NY%TG!#>=H!XC-fds-cnTHmR{@#{->R1tjezM7??szMb(vnEm`HcmF? zQ8;Y{MkSaj(rZRQsBW4}laJ}>)gy08q!mx5X-c1KBglu>5ug2uUjb4AL^ z?Sg2qEFh{esU{nZbS>1{qbAVrg+)lP`>W4(A=uZA{=yXC7x{bc-2lf#^24DD0=1yg zmy zi(}V+YghY)eh~kcI=-e3Ez37g9g-9PGQ*%JDQD*v<%E0Y?Y6xDgJs(pn#ll#hCDCH z3(;#9)Jjoua9v&=DJ5n8V0_K(0YD($E>uTho0C@2N}ZqBF0_lC7tHygy~RCPwtWj@KSf57*s5pmhCDvUTj1mk3WgRE>H-Fx8rItP^=hJcPB$y<8 zD!qt_Q7oaRr5HcC#R$HR3&$=4PD64{ZVj=32fCvbrxlURMfQQlzHiVyk7h9+nw*Ld zbRGG(c)C#TOMFE;cVqdV77X9j{oa>;WRHMUEA12i6f6J6=2i1W_p5{74fT&i{)^V# zFAk>*GoXFvDI)g?-tW-E?{MZ0^hUJdQ;6X|gDh?kDIe77BQzDtz5Pdd0r|elQy^~QxIOvfI#){a*6@)X|jr=wo$RdJtk7dGE4KWl6jmzvv#j{>D zXods=gy{r<93&%4)ckfXpVU*E=jwO$?%#cEV#u%UCzhyJ-aIF^rDW@ANU0qbhjB>p zNPoR&CEl+-2tHV}5(aix23m~=Dj#0CdHN5o;-3(HRgTx(2+2*kM37~_Zg#ZD@M1-h%;{HkFbBx>3+AJv zO_R_Wib2)}yl|cPl!2JZ4$zFEKpJyVB?;}FIiqdfM1h#`E^)?V!4m%w7ilRn`c{BtMod+2`3p!Z&H~)8|Ry!k_ zDsGxr@hMY-ZJ_~&ymgN&@HbJkCd9rATKTkOV80u(*hUl`XR(^Ou3{$FCyFMevFG)*{F!a zKqVf;bmclT)oS1Zy$w7A2WbHX)*yyV3QwS%oD+2|i4u9W{GNaRmn?w?_FPqOF-&rJ z67U3R`f_^QWJ7uAX}m0#BJm%S`16km5w%E~>ZHd5KCYp@%#Nflwmr&g>_+Wu~A` zQ8~JEQAT~dLP6jkv%`9tCO8%;>9UrzgSB51T!0QyQ*x63cM%xem-z7sxS!$XzRZ`l zg6u(`-#0(s9lcRzL3zQ~b#cDY|1ws7tRJ?&{!3IcsoVOer*}5oMe{h^4kJDQjqdIC zKgUVA&*{0_s-Umf&Mt7*6w$Yl25Lp5q5Yi0)!)t%vhu7t6_iEF_IN+!NL#8TJ%mGZP_i>j($w~*hk}n;H)lOmk{Sf`TA|4)t9fP^kLLHy4)dv{JE1ZS60w{m~< zdi!k6O?l;|kyU(aAT~PH-vsxM=%&abU%6z_%hMWWXa&CC=$uG)v7_OJlw!F(|XHK_(L@Jtfj$ z#f&UG=LtKFr~$YUtl9SNs`V1#E*M3yl_*kx!Z!#Bi5E>aD4UNc!Q^Fd7095<86m1u zAY6=`j4MNr&KNKJi#`-OFrcZmaSJ{bYA&~-=JJy{?jPs`s`49uy;a3jMoFhYOp>r? z5ZglNqUY1^eqG-+OcD$qtG(QW%!f zwZ8{9?9;WLXY`ZJ7Iv2erYh>(L`fj%)m-L>G1yDJSnDr;E5qZBSK0IRD30X#^&*JY zLoyiyNN75B556x#S=vYW^Ix(C`@B(Ih~$<+O|PjCiW%xD*7t^Z$*MRkI){&7+EI6V;TwbwZvpi z;yQGSujg6ShFdE;^b7^0CKOb-BWN9va)v`qFmbI*XD$iCxO;e9IvxiX@=eAk0lx5C zc^r-S&fJN3RR`mzAq%ZZ;n)-r0z>dj-X`OTyylOAtZ@QN6pT*5Yl>TR^7yqfN)r?e zZ9r3Bmq!T#6`<32JW$7$Byp`AjjVqVBV?(J18Ut|^tX7bTD=izf)yhfZP>(ak^y@{ zM%z;B;gWz12A!NNwm7i*Z(=Bkkmq}bekB>WhiN{tOeqbP4fHJXH4L{Dhi0KB8l8Q5 zXk{5x;DNw{x{iv;WHE_#gpMY2NPMFv|3}R6>QRc%{q?l|Ly>sCs-#jVo%*7 z=VxbE;d-)2zX0jNSxB>%>b*Ong>`xB{#z;ytG$A%a6rPs7i>t*+AcXi;m8t!$U z%Pvr)^cxH)z2HYbB&t9!h^y|gzF$$XBS!oJ`1&^Rb@JfgfO|dURU;|WEsl1I|6?KU zy0_&0DibBqh0bN}Jj>9ZYh<)w3~MK90S2S=XfpmP*b7t};e zgkO4I?>wHFQko#En99#>P0yPj8O|rKpMoDlKW^d2T|5dwTjo7u(w+LUT1Um1tI<5) zqrQ8HiT;pJXH@+oL1ay!S3wgcT|(KPDbAy`NtqjlDM~eN<+yPA1Na1(Tl^*A=t${x zUtSOiUU1+4zAngrdDz_vovH=#1VqG zbfL;=waGX*sOBMJaKhU?|N*W7zfxSp|;^9g%LG@BMq0krz)+-70lix+Q5oI^c zWup-0$#_#+gR9{%gD+svttTG7#hv6bBlp{_E@dAZ0l%lU{3YUmtkX5CobrTY7Cn!$3N_ zC6CX;nVd$z58fA$H|^BO*N+@Uf1law`hMF2n3+<9uXJ!lnkZl($5u@I# z0|+<1nZCKYH{SG?MZbvGzSq8U7kO_@G>zD)tBo&>14ZeyAch&8JLwqG*g$s*K8nE{hNDjHAO~DMEwx?^)i~oXmV>SF zYwEcV-}5>+7UlnRZPGX7m(&Eb5SuQ(=IB@9VFd37{;v6+o{7~QOS}4tGt1;bMq0hD zVajtX~1cQjY@|^zdY%5Y01w^>Zs%eB&1Hf^Ks784E&4R%;`k~DZio29~qKj#f z>A|G$+PT|PcG7ogHcZCKR^2?;FzzI@b0vNW30)W(XBgmE;$>1Q;aBzvC>BIbBoX?p zm$VCn<^N49>IFRrFX3KbkPr%)Rb?^m&c6Q)B&MkQ^6=#2&U@P8QoX#b)*+JlpjBp+ zXr(&A;Xsa_zPf)w8NIE+`g3);S)BcP@r^!0x@zmLI0^;O2vJsl3;U*SG3AIeAVWAP0%JXV1Mpqu7*R)E z2YE~O;mLx!+;}UpKpaY${I8Ie!c5@YW4Rf;>mxigJ867Ca~|*SApXRpc=Tchr4VdV z5W$-_XA zIz`EFeS`3?1acCgn!G0)gs7I6P`&q~o*`y=ZgsYKjk{&S%Z^Yxu(JQ}HV#&x49<9Z zDfC1LmpdVf01KL~`T}xo#RJiI!gj_zme+c6a|DLbg%j#^uERYOWqsC-vz$E^SKW9K zYZ)fRMj#x~2~Q^)?}D<&Ilvngk%%>IBdC)lIGsQUHdIk>^kQs-H$xMkhc93FwkQ1Q zvDnrICR}g2guuA~DD{s`d=B=X<8PmP4uj24D7(+Hq(*7mV>Gj2%U^a8I@vvSXZdVj5N zM{h`Ag>YcYu z$A5||f zFST7QrU2lBMDu|~0#l^8OvwG*4t%)(LseqDo99!+kn`W%) z@pL9954Lc-A|WGybM4^XH7WBEti@yJ0mhz~fg#A0ZH=^#7A@m8)obs^yI{`8?&r@P zv9G-&pRb>>wY;R`cKh`{LD?aN8%E>I^htY~(k~D*JBx>3VxX8=FtYU4M(U~&+Q`@> zR0kRJP1beGp=Duw`$QOmlu$t(7psKz!$yD7`n+pMz2Lk$#Gx9ia#no&T=s3Q@dKZ< zTO8?Yknzjy-8X{eTe}mFg61HbLCEmKtBXhlMfv8Hq?)=@NqXpEaGZB9rYGkOjjY`g zr$8gjR*!PAAJ~l&lWzira&?Ui3CcF4# zvYICR!O;3?_#NF!!DY%pK^!QQB+k@$$V743zYk7<4hQ8ij~E}WyHUCakzptV?MPEZ zRY6t(WgR}JG^gTSfHgp|`5q*Em$ljnl{7e+H5XjG=M&tHAzoHgatDpfDCJ8R@qb)^ z7})u2*=Sj$-{5aNj8w9ul4v&L7Y-&6`QfeHByNwQjg*mObhwn&@Uuvs)(+H+n<4Vl zykGDBi<5(9=cyJs1?Vo$ndr*91Ev;&YwBL&IVI6P#pQupU!~_YFrAox%7;Xx)i*o9 zOH@3eOC5Af*-hZ!j$(keyn#sm42~w zq?yy7L7s2G z@uNO-THRyl$lvcg15%#dQohnz&IOiFYMo?}$db$D*mX~~?ejlXuRLC58JbV$l+FfL zZgWUa;DG`dSuV*qzq`da(5Bf^JR!G2*_*8re98^h*T@jNQ)?ux6it-dMssuB0dW$DI5({*iC86JB0S<5hVj;jLQG6 z>k=lU%-L9U_jYLVc@_X@zRQrd#T!_2ei@_D3r}=Ocq~_>!$-))5D&*R!lH~|qZlMN zVJzDZOf(?pNFwvJaY9R?#nzE0i8Rs=Jda0`gVoQulP+&5-2W=oEF`JA`8WHrW~Jr- z+qO>^;bf#@UQ(oKA`9q?I0jQ~Q}gOku-vsZ*>QsBd8IUyXYu&X7t`!QX;KPVHMRr=5u3ScD1t6}22qTdRz5 z-`rq(m*U^O*YT^}Y0UlgR@a=q2+}M%oHf$3sB3L;(QaS%OfG$lY;H|(6P9*A8gyTN z{Y*`wrcU$J?A$|kp#rrvWZF~prwCFZ#WT(@IpOL9#-Y?Dq|5k<{Jmu+1Lnf{6|0*a zs9ICflEO8%+9670dOK0GP{ODEA+F~GRFryxW;%l~iA3B2Lj8{+5>k%9Nx>Nv2L%&p z!i~ot?x0}xt%VM>IDYpm<#s^im3KF(lmI#S*b9{m%UR&9bn`0$K7C> ze+N%cm~56|N`sP5?$0mCAC|$yg{I`BL}uTVVC7mVZcLFR3x@d{ro1DR~y>zg7QHUTBcf*LAC%FARM*D;Wx9Mhn3*Z z%~%mwk!UkQ))xO$(uzxZ0$axC`OQ|*bQ?1G&nLuT7v}cfM3+MB{~#_&-w6)UIpxA` zEcAQ_d;%IZ(qgfA>-~?@9Gd8?SM~&I9jTnqHrcrLdkv{*(tk}_!_Jsa zZe;rLz0GT>R=P5PA$q7=^oQ24Udh!jH^$T_vwpN;BG#9Ddb~2Ara~tul;sY`3%zsJ zj}RidKJ@#Ni*1B(E(9C0D)aXxphub$;$6@ypS>zMK9n9=AU}R^E-dLIOEU zE2Ht;2JEkVufAO$kG@`Q)Z_UxK8vOYIW)flet5^$yk}Z^1rC0of^2`DYW&bq=aL2R zj*2S`Ko>qY8XO#3XPIzZDtLiy74i)-hv)qixD)VeBpT?kUU{U1sjn9qg#P$S$l-|6 zF#2@7IwUOQPv_Oq_cBGcYMk# zDki$pd(bUGTMNZ!YvX@>^vF}f7^ir-AcnjId5WJ zI}y&HPy^%MpB5H#V@^7%5)h>)LljL@OUsx{J@pzq4DD7Zjr^tDBITeJM_Mh3$t)*> zMh>60teC7q)fKF%&pN!(z?IojXE4}*Um!nc8XU`bN0OFP)gBO+MkB(O$2i(1tIx5C zN^wZ(DB+^aLXx3W92%HH5?WqJQP31TFUn#fAI_167b8*$tsJ6d^GF;9Q-hJxekW|- zyDvz=Ui2Y=AJd*);Eqw(h8Kyk&hvjLs$^F;=f5dtAci~;^Nr}M3?6w3dOl*2e6}tI z86`1GO6>&!JGon-o<*`YQlLeJ(4ranPs1YZm z1U{TLG?C6AgY}5ZWs(uMPu+G~$wyInVNRdNp==GCTKJz%+uJ(Pg9UL^PBE`@t?r!hd$MjVRUi`kau!>sBj$iV<(FAamudeSlH`m5*q8N69Sqk>mP!}Uo&mZMl)|ZH)PeM@ zBE}iFk+1_=WOD$eUy4@ge^|qD#KZO&?K{ja7#l=q_KLbf8$a$A%HeIzuf3UP~YHWBlFY1m_8Z($kuyuvq>T z^Rs-!rb{p*Odv}IaW%Dc)8_R7rq_s&PoLif--E zn$+MJ{7gUR-LEuy3+>kgEswO|wVRzOv|$Hx1gh{?+*X%{yiC%eZW}sspx{@`^=8(Cfh#ZF%1CECZw@nZu@6@E@j(?;^aA@V^z9Z|8 zFJJcgY5xX4Qx?%kbKr8yVD4jc&9(gT4hoT@&~;J<@p7^b($>cn8zw?_*s5>?T^6wQ zwDfjT#(ocqr8n=sC=fgK%U$eHIcOL=yxL)oJUtwDSb650lg-9!$%@bqyBuq~AG%yb zcmP+;!UW$D8^yxhta#v7hT4ur16UKFF)C@T(_g^9bcelU6<_>xrN*&BpRjgN;_A$= z52eJg!5U1S%UWJ==T~Q5R)f`{8cPcf<dJdH(ZrKu=Jas#SL+^9RbeS5Lqsq!5U2Dp9T$5+a_V0S7G&(4#JM zKrbU!aO?B;X37#a=x)#bye4lQrDP|dAN=nDV*Los1(hB~%0rU4xX&7f;t5zP&jBQI) z(YSWB5G3{2laqHYHI9yqNe#s@?pK$2K>YX>SOZLmuT9`K56W~v7G-Uv(aXp zRx&|~53;XsogX3a!F@#6X#48n@||eobMr%B`ja_#JE6x1>KkXiZTqx!=1Xk%n*tHh z&z$!Lm{UA;0%z_C?<|8@@6<|yjNb94GamCyo(6vEb0!+GKK79oYY%2{#<|9;g_^l$ z`wzb%=?0hRo5|y9tEo)llem|I3I0jSgEFWWr~$>v+}{AXvO^X79Ztm<8d1-2zul5IIPIy}8JBo} zw>A>30FEm&>~=s@pYxv-UE=464{vyiq0l3H8eDe*%GD+)0g27vf0|ve5EPO1Ykimt zDZ`zn4|vraOoy>Mn)6Kh6Dc1HZCA+JGHbIKO<(wapD zjt!>`(1M`A8dUh+{8tJY31w)v;lW3XvExEd5$78 zC&LOYehVB^t0!N$Rp$&>C4=&i<+hk#0e#aV*Q&on1n*Hh(imMBxs&pVV1a6L1R5e` z{YnTn6VQs6EO@0qh~o71cjFV68quI{0(d(Ovi+eM^flw4;?IoCvP{N|;`+8*KbmfS z;^&>ufc*yHp!ry|h?L&a`C|(TJC#>>9YF=o4(M|SJxXfYagQKBDL)sT;A=A8|Er$s zw*Rf3zyvHP0lzccg205M)5ID%o+|oKktKU74)z2k}JJ<%dp}h4#O;Ho)Rh2$Q-7E|YtkxGP@t@5v$O_*r2O zBuETvgASaQOTO&RF!SRsK|%el-orZDV=?QRZ8%{;tv0IMPeu6ir!?GB5#T}RS}A@Y zX@!v!D*V&&3>W2L00v`i>AZ(Q>MSM`R;!dFz6lZ=b~d_<&JoT>)9b|X1KsDqx%u;g z*z@D@GydR&sjjRQc!sI_IrI&<6!&fkN2%=C`CGZrf#Ndqs%>wrux->p2oHMtR-)bM z<-0^UX1GR~WPMm8cj6(q#J0(0NZ7GeCYr@nHd&GK9vrglh z&1r_I4v1rkvn<;B5cSiyI6z^gqy#$7&L#kilDlD_dfB|cVdCrbb801}2=G^k=O7N2 z%4E4okP0Y;tl4_Sg!p@$_-{2FHI+gY_IwN4{%Wa79dT?p{d{`FvVC#Rg4?W8kW;#| z3?m~tI&5+SQfvY_T_WEO{7}T=CnJ;qj?7K4mskS6#pKFjC~`SG!4?p!E~UPs9N`Ot zZ>UF`C8U`X6EAF)x5OC&aOgmh?gwoC8!UrRpiBBZ3`O>E6r)ON&jLe_yA9zW6mkpt zb6j|5ZtXpai8D^QTcEu$K^{iX``01t!#?B$;f}0Yt(<`D&oq-8t`as%qE`co4fx+b z5cZM&(&u61jepYO!XN(+aydcHLraXszsHyL_9^Q9m-{s=n`r*%+v9Q(GrG@sZ*yL8 zaboYCS!KB$ZMltPIhb$RIFl%W4k4q&Wv@bj5pUdE0u343y_}cI41)w0Dg;-Hgce94 z%tZl?EjT5!E$BnH zCwc69$$t#0e*W3qNw*ylxZC{n7;W+;diVK}dzJiEQf4HjcAWh+l34f0S{$|jG!=k%7!VzY2r4s( zzn29i5F zfMBHD5{JwL?pRWZ%N|UJ9~DVRkbARXj5Vf&*B1JoMhP=zav|NiS4p_c5F%5=ldNG zhJYkJqNMkrD4C+<(~&i>%=?=-mPs{`Sb|j*KUl^c+=s8=o~BiAgO-_27-Q-T$CJv;iWbcLuZDj^!2@<=ZDLl-K$u)bHRK*9eO zAQT;%dUGd+irH~Fparb6d?>|Q#{>j>HpAurWn3c>u z^Flt%qV;<4XBAoKI6#a{bTT#(YE}`PT!#0m+EyKjU4$|O?xBs-k%e^so4y&hshEvR zA6?wZ??vVS6$N1iF_YixX7#elkM4JQYgVY(+$9)JD3Wlyc@t}yCV{x(KPiJ1`*O?u zH4*B6*E~Ne8-%0$-Mqs_{h`gr$X&7yUHx|8c)h>*#%S^5n)! zDFN(l_ZrG7)Q9cFG@ucd53Ai>7Bg-*M<#1mtS95aEpYC1vGgvkWFFN7S+|e9jZ3OV zpHiAm;ZLMgQNEP(6q*V8w~E=~B`5l&i)-3${insPk!ksJxEzbI0;gj%qXpnewl zT%i6SwuedK2pWp>)NENkHeOsw^m=eQPp{TsYU|wBG51$+#ba#Cru|6Wt-(L-p^zv% zwPFuu-eT0WMX#dXzrVy4%~C+;?-s4@=FCE7eaYU|ip8BkA>Ime%G#R0Bcnc}?6!_` z9!0W?-G$%>5-+un*7>ooXWGe{q5@@wVwSq$yBvTCew9+NBnYA zbFoRv8sf?X76Dd~6>O}RPHogCTu*A(cN zBW;XKPcCI}h)k?Dn?d8#rtV*hqX-PeGJRt^7(4ZPM+ghnV7!SA{V*?u5YE6>XZ!#= zT-YshLyO=hvk|08`|ZN$WkBYUn{foUTie0lEDnwc2A>n@?1U!f*38K9XKTQ(Lh;~qiYuMXyz1sBJpWL>x8HNxcpZo*u194Qhjc`EKi{sn)$ zTBE6juWyh{py-aN9r{htc{DhyHK&9PvoL!;9`02A#cK(0pTiEXqe9{lgYU7aAf94~ zLAUsBlF;B%($BknwY+MxOdAYHRpE$mjz-)n=y~sG=_pe)pQ7Ad2Q}@=iW7CZkUtG{ zG}x+jO?x}^7jps%jcWHfyrX8;m5M_d{demFENdi*-6 zZQsg+6K&bo;>o@LZB26peR@D1Z*_`3+O>#2QzA?}UWQlwGo&6Tgrim>_~`}fhqD&3&>DT$i`_3Ke>MW>2(*N?CmQZ}4L~g77tQ=3 zpiF3$ssdNE9RK~3c-Y7PiCs8s%)UtaXZR5fe4#u_ZBvI4$Qc*3Ezh30{4IlcuB)&HEnn_gaz~cg$TbIn{t1*QMM&;V42dfoZ&mk zK=>dC{YvRT$X2XXtWUQjj7DITgbnuW5(6${Q`GA8U*D43c{e7S4bt@^Yk~o-*+y)qJiVD6>d~XPvaUX9_ z+cVJ{R@(wm0^>J5-yG}j&r6-9mabxxVCot_5ngRQ<&p6019Dhv8qO}9uQ7-Z$#XxU z4W8zRZ_aQ&kTE6}5;sYNb^2eUg0zeFAY=1r<($HY84fM8Bd*>?T|lhft^Sd(l1Wq| zkP$1hnw=}^>degKI3UH;fvLjaRRNESI9fqTyf-Dds#GA*Cf16HF!{NN@j?kh>{tmq z+^wz5lkQ}12Z~vhEJqPj)zlb~Y=q}j3yd8%I z`C%`+(Ho&u)#NS>S`DHCjiUZbX_o%kRiaPIXx5^Hg}ZQk5W!OI3VEibn@}o652u8g zY%gvdWb^o#zC(=&h55_H7eL=OiGKqt|F-_}43bA8%3lWW(e}gk=#J-`Y~Pg>mcRp=?!mgs93!KwW7UleAZJ7^?q!7U(B{ zL=WordpBlk`bg?EhFFOjpo)httb$ex5T+2M5JQN<);^$4&J^G%lB&i$5DHGDv-Ts$ zI)`tzkAh01^XiO zfqD2#TgSaoZIegV+mqf&%`RT**8Yfs5oL8Qb;wQkg#rI=7N)mDON5a>79`zHU^;M~ zQM6|N8_66!`sy10&_^NS#W5>t3Wib$;0SVyf(jbmnrBZv&S{gsigcW-OW2a1H1Zf& z(OWC_8VVixg)BsaqB+6x(e2R_7WXl4XaZc7vGYr#o74rGY@W@2G|ApXrkQIRM&D7n z`cK1oCrmejO=ew*n`Zef@$)?Q2F*x?3wjpsrF6#nYpSmcLx{_@H&sXv;ARCHvO9#%YbR z!q)8q`l9@4+4-=Wr)7Ajb8`0ELIzrL@}!`=kaqE?vW7m`VFB@b9q1qzwCtd>PG_yL4}xQa4~36Dx=pELu)63Lej zRbn@gjmVzhgPfxK07Z7j%^{=qUS;Y4&FYW+9HF!J?W_ID+25j24iBm0G2IFwxz*gL zHT=qz|Jh>=VkRxh6uB?x5l;k*PhOQniqzE|OH%I8tfE7{Y4dk^K>gesMjV2r;ofJ6 z===4(pd1&&Qx)Ik2tAeZF*kma1cHYh6!GqqP7nw%g>gJmfF)cX!(b6-u@Z)MajYx0kD4eSD!BF!O^~G{43z;>WIsOKD7HCXn*5~L*dX`{j`JK@~WnJTm1zUKMtu1~n0Lrrb zN*Vtt@vNFF-k%LN7O*m0M6O;Ir!^UH2w_YZ5BGmufMGazYLYB4FL(+-`kz%!Ng9J@ z0AA2<=S2*P_}Dx6(X?;?R1zBOw)W)L&`~Bq#H>qrHdw?vJh1 z*fS7l7YD5G$`tI5T%n|ZLl2&^q@mh3(73Rv30`xUk2xMDO+@dCwn}#i^?8PmPP+*$ zh(5<0g&Kh$w8m#Cf<8VvLc{-ldfPQ83`vH8|4MSWrVo;OFQsANjH{IZKG8P1V`_!7 z^KAe~q%&K%fB|VOs!7O+nzuEtNBKqJKQv-EyBc+TQ-HGBU1-NdmWJ4dWy;Zu;$wdLl zH@0wbOSKQnW~^@SyRYAtgIWyx(WwvwE7AZZMZN_KHVJcj=Uz}GMt#gSndMeX0Qqu3{@H>O9u%9 z31%*A%-`EbZn$5*`H2w6KN3<(bT~r%J$!7XL7esvDtCRwiT6IlQF)$<(8mzctm{4} z`wQ-kaO%LX-?1-QK58649MYg?{AJ@LVY&KDAT#ueC8d&3)N6u6Q^ntLIkHVjPgG&q+U{4OG9%;)#q`qgf_IoUznll=I~OLTE6~V>4ch=BX!2 zMiWQf!EMvONdI67i$>$a#C3@*?<58_#n4uvOm^ds0Pkdo&QR@*n+&KX&{jCZOoSM` zCbM6Be-JOBFavEKISQ+ChtGam?*Z-kN6CYmuaA+L$TBtLjqTehJyS9jJ|zv(4CHhn zp89qsva5yWHU4dzT|`wE#gzKm-tFZT-tYgJPuOFBS&2WM4TVi|i9GptkAK|%xPI-q z{<3^M+gsO$5V;Cf4AZ!qg8CWqRq8b#l|47hh%fzSnY(A)@$+vD>+42CBUz)u#QI}* zP_}Am$}qX|kWGuIz^S}cYChp2Ci5@lJM9ox2T+qP}n*kjwa ztv$AFduET#JvQH*bMO7$pI)o~_3EsOjEc&Pq(hb*wsC=6LL!hI4p9;{0nJWyIvEz} zwmT%jwF9I;IQRQPU32f5JJ|jwm%d$Mxmvr z2greenCA`mxG$X_SNQlw(`W4)bQK1kJt$e6q4rb+mpjI|Oq-$O7X-LEqU)Fi5Z_~g z#00UXYIDUt!Czs5Apw;j3`RzpJRYjdD}ZA}Yle9qgkuFug-mZBmgsPeIOP5_jrwS~HF68w!gim|9yijvC8*2RU}Yz?x27Cwj8}L?E$ETgCG(k{$E;lw$TaB)4iQO? z=10P(9POIA?2`9`aw*F;eWnJKDU@5b@X$Tz2hwTz`hvj~ys3sv0yTi=12`QJRi)d* zjsU~mkOq&E`Im6E3WHt|l`|MytXVw$osG#B12r}V+)Du-dVyoCB;0Y z1+JU#3GjD)^j}2Ky~AT3biPM%?ss1DNO@j>VfCGzljQvGoN}ALu+wV0B!qWwq~m_z z>xT0Q{wad4L=DE8PCye-YkcgdP@_O2M2xB-*n3_{!U>`RF(swZ5#m@Xj55?-3K)^<1^Aj2vHlYCy~&03X4nTo-h^4@#xbxN&JcQRObEd zjZM7*;4;(}M)UN~N05&uR3It=jwIa*oP}d_1P9FENfBLs!$j-brv=1b7+8%gh0eD5 zB7P)e#K^1Y=t`0P$$Iano5j-%^Rw~QcSbMFbr-yCX6uoo_9GZ&9L6vPBxbCUV+y`H zOc@klp$kV2@xsx*U1IGd=2rrNCClK_feCiABv6J626W+HV$X2&xK-Ta;Ot)|g9WI^O|gaFFFha)=F~&#<$>5yLo(%mrr|i8Gv1 z!#J<#>oNEPH1n_F+b58tH+buk%2`Z$PcF_SO8V0QZ3DAJvYRGVFtq@F3tY$>-70r& z_(TK8Dp>p96L4FO&5oo8yL=<-W^fM++{K4s-0s@?7*IE29z1NKSeeC8J_wIXk&$7r!pyR#^==+rBoAG)O7lbiG*_lMC z|1p66@+s~c76In|1`4O|P1s+W?!Oe!M^{%uS*$m$gtw4QqJkh|Ob3;C#}0;G575v# znS=jH(9tN((&lo6r0;haH8e>4VeqMr@C#HbM0Krg5rsq%U`^|AZ{xD3^$aHV_nk8w zZqBf^@&{Yh+eL*lOKOX1?gvt}Nv&?cRF-Kt_AzhsrX4&DORFKx zR&j}f%Ai$y2(!(?tzkz1kdwLtubKMVNKNlNR1X|2ZVk+e`J6YWUd+<>Adv~sWhB%4 zNbAenYH!S(!*Wc7#C6H(PmK#j>NgKxcw-^sE9Y; zs7r>|f((PDl5nw3p;>GwVkK-&X~%g0u?(D|_K%lGn(bR#oJAZG99IL`XLNXDM&&{)m^g`MFSgfM6B?Af2#3O5lR=8<&QA&eipg>vW_#{KBdypv9%_YfbX9xXjUs=+Gr&)_mc9AG{T zr)f>N_f}s>T5Q>nkmJ4qP?El&ybr^xS9-p<9IhyrkyXEIx0lwPH@GVYu^`g?O!j;Z zTxmQh|6KwrAa5+?v2N_ZI_!0n9Wkv2VeRf~f6Oz%9p$IAU4+2m?2z!O@K{*S2xG(hw=nhOPt3#W)Qjkryvoaqb_rYAqlah!kUCSkJR%IWZgnk zyHiMtiDXNX_2T2fz-YKdn@1(ZseS>M(vngB)}awpGEBxPbI&hG2t@-vV?<}TV9X+P zDR(FFqzQBbtjCK=ut->m<3yZg$dzql1G9~$P|w&27{6BMmIG+Nmt9 z^8RREdbpx@HG9CMo|V=PeOTyv3o+uwA-6AP-tXD8HAC%01<$b}W%utQ_<8V`|Ce+~ zpuV876)h(lcs^e(%4~nb^}J6RUy2QnjsZ!BklP#`QqOQPg=4*v@q&%`w;i%?`rUH& z+#b<0LI$*BLL*^p86K@9^}m~jH$sqQ)|)|5)AeNTzbH==ED8k81588H->&U^kK%B} z4LaX!lFs0X9aF&iKn>#iQxJzaO-_`A1)yjb{cbzmNQs#ksbcj1^;>`(2Dc=2FQPPl zlSiK@zQR4cp;E*iQzzBCbkG!a)gsAnB8~K6t8qe;OXP9TNZFKklFM2z)p(1+Qy96f zx~12fzl+i~v;#hhOMKz>ek6Wj`Qj#9qYy^B|3Wq9tcj>p%ziE;S`s(NJ3SA{ zMkXGz6jw2t4g^7vs4ac2D16?%-�~!B_gE_@NJI3c->A{01OunBH*fUgHw-K9v$* zP`k>%>A!;VIk?V0^2!#JCQvaWorSP}5U@i3GxWf(!AZze9u|g?+4m_9J6T9G|6LH3BS+91yQ9&8GAP*(PZQGCO|H3F2)J zW5hTK0*U5BD#-#mTp-HfUrwlLH*n)~DIj|6gPD6V)urx`_K-AST0+GkKp#$~3qLAN0TJv_+1^)!QC&_|2?SC#FVa zLc7MX;TV4a^vBl z?_V*ycMBR1FT5?CD}Xr2azfvX+LqGaA^4}4bgD<-w)yXN6PUfg_@1EN)3?)Cf4$P? zD7~8u#)U)5Cb~7J-K08b%fxvjkiq0z1#(ApoHl)v@hI!{+RplZ?2pR_-$Ua!AX7%5 zn+)A%EbCtb_k(Kh2eqHi@JH}01d9%zE1ozr<6u_7Ei#ib<~zcNw48$?RM)o`#HOK2 zh@FYOVfq=F$T?b(xQ_qV0b!xhl1{iF^6a|Cy4s)30wZ(Fndy$3oTSuYUlG|RU_A2>F=$6KYs^RU;Cyd zk(e70aNaicjmLylv7R=$s6+KD6_8JZoPEiAXU~46^#*bkjJ7%4!X4|mKXl47d0l#i zS7(ooK;*`W2KWEL|iN%diDm)czBrd;GaL$_BDM%PTTi>sF zz6Ceu5k64cHoU??dI<39Xy%BtJHw z7V8fzG~DngXP7}qg&ClMO=8>F0~WJc$lEku9(7^A7s{lyaJHt!-Qyjsph9vO>{~V)+Qs5%%N2{47-wy8AmblL`uvnI=gqKwn|kt!8si&E%P%}3zY#nv zAe!XOzzP1SVBIO5`>+dEDr5_Y3bUMJ%AUTKRu^sj3_lhRbp4_nzGtd zWAM1KM4aDc$1OsETP5G2H!jG5TxvdiFoX29S{BAK24YUAR-;fPMw2e(EJ4?y48Pjo zjs}n31;6Ru6;omO9w+kwjX?>*I!)W+iXXHA%W4lvOj&cn=eW}|<}_vCw1T0pz5VY` z=p6_cz79t@UY+@){^l63@(f`ftCi@fWf<*L&a_ps3zG%rm%C?{4olE29P-JagEk&A zP4_4()y%v2A>2#g9DMNT0_>xRF1#9sYKD#T9MQFe%JJd`&JpPf!@y-5HW(n%EjorI za0ejAF$mG@7ME$eOt}PjV2F!j^H=~c6cO&b1iW#QKLFCP<@w)myg$Jf(xs0_;Sgl6 zJnt6e6Yk!Ivz2>liP3~NS*w4wQb{BqebYw%bgJnfA9heX{*MPO!zccS3Qsgg^yA1L zggeUBNko&9@TN$0WMDhKR8p;d@y&i-?3BJLF>W zRim@iN;@^^f#zD_RAYD%{@km8b_~Nbr{Be61-jU{sk1r*5V<`jspU%_H$DhU&A@iZNphX= zFiSwzs;MEDR!nlb3Lyg!R!sF|Gy)1GfT}9H8eTAz zPaI`>V|L_lL20^Jp$kI)kir?Hi_3~3P^`b!C=XuQy{m7G9g&D~HhLF@F8|;q)xH)@ z8Q*%U7YFM0c*^=U;veHB(b&zj_L095Yo!TfuuGP4b47m`+{Da@ffRe1Lv1NB2%a}E{0W2k`_b(-t>YRz;Pywt!M*M|_OXIml zrH^JsvYr8QP))1DO_W(s*!~i2x|TvPud`>xf)-=YUhEk@Qu1R9=zS}<|Hb-nXUa1N zZ(#2D%DE6?ilN63;tb=9A9{lBpsJH%v^rS3TD9-4! zLrVHjFc6EV+RXgYb7UqFR+?x8TU_gcTm0KkTYst#eULA1&$i7ftz!V~>md}|hQX`T zr}yB#iYXuVR4+)Y@Jab^fis7l=s$?gim|O_G;(pHGA~9#42IGX46l4h&uhHybL#c=IHa9Hm0e^^{ zKpFrPgW-y#J#upPZ$W}A5Sw$$i-qLa42|6CxqD)$?{JBD8((;j-%zyKieSsqpIRL^ zbp$_P=<()_^G}Mo;fp#sa=#G;xrE%tgr3g+0(gTXDFgNxaQyf>M_};EwQ?|frt8@k zB@nlKuvwuiu6t(a{f~A1%=5Ze`B(Tz1eD{o-6$pCL6(t$k$g`-DIRv+Fzq@za+?q?8h2-qA_i)+dISz0fZ}C zQ!`Abij5hCVk5~gMLA5|A=T;3_Bh|0xDp6Eh%HJw88F-!6e7*Q1pq80O~1@kqZ3vA z@5s}MM-YZ05?8ERUwO5l_#l!9DYqo}j;)XxscM2cvkpU{v8JmJCY*kBRnQ|1K6FDW zKS~>)s(@bm9$D>c0a&~;82{ko_7WCy3MvA=Rr^QGHQQDVXsBMRJ{U4u9}enUJWfj( z5H#?r8%`&qo9{7m*ZV#HtoH>-H^ews1BBUWvHK{ptA*NHbhPU^B4jQ!mhw zOBs3xiwzMocUO*}gxEF)ANG6eS!Yr{xHq24T#Vd-c4-Rp8!j-^Y;aU~+=u$nDr1?+ znNyI;lZXcnBIGBFjNK!e&MQ1L7k3@G6U9UqmH(lz>Xzp}Wecv*CX7UtEV9BIEz)7T zT5C_oJnXN$?QwlV{ym+9Dkz9X(Khz>_cw#^_ubt|5A-}y?7Do#KB_&~ z9VmvHpSrf)abc76DTmN3cxY8r_b3|ZG+`sP7*9xYWaP#T&}rT^FmL5u@Mh&0Geo|1 z(RY8p<`^ERp>Utj_a{&S=jJ&2E8n6Rdw9BUumZL*U` zu+Mt{D)8i3Etc%*cFXb^e-11G9USC*zs28@VJH4F_U$Ng?@3$bha$4|BwtU`ZaYq17I))ju3}z(MeMQvT?pVJ3 zKbo{%^Y2MVO-g{oONcZe4d`MeWAZUiqCYE<3cVJ`n?0R-vFOZYV&;iWc5zPf7Xhtt z4(SmpXomrf4Jd-BK%Ds)v%Isf8?RB(#Zi>X8^S$0bczVcud!WKP6Ctn*#g zznNa_UWWbu!1ce}RLL5AIcechmjv{~WcjF4jivGFI(Hny#>MCJ^Ojw;C3W(@8rocw zY@k{4zf=02(tnB?0SNZDy7ZLv&yR*j61IXn z3J*hm(A_RsSb?gT%Qp}KvP&@u;hIqR-`0B!%KuM36j6uER82nuxHJhnHh^REj->`K zg0Pyy#YL>q8{YD`eLI3Bm~pqBSh=DLn-vHjr>ku5M$*vf(?f{|C}qffl*#o>Ols9X z1f>riu1tKtVRTCmbB5TFdh=%uU1urh8ZZi2v&zzkEVo5d)0$y+h=N0Bb4i2~o}sOM zaOgCg1H)dNeES9a{@cb)9O{5hY;&)HO*d)qZ?wmj(ARInWw4;LiJpuT(-a~N+1L-f zVO4#a_i?qE1=Tly@2R6^Cbh>XyOrm`WZ=n^hQ}|hV`*KV?x(M#r;9&)n*jCJ_^<-! zX7BOYZPO+LD>H0=EvAT|%zZBxH*cxGAw745H;=S1ngxbfX^+&>od(6c9ot~T>tXc6 zxEls?Dp#qggW!Yi8Sp=d0A(1m_S^j%Kpnx$TFFPrprd_&W*u>QLeETj$Tf$&6g+8! z)rO66j2ZK>(oX8E?wkV!8K%&7(M6mZP%RlZ$o}9das%N`ByX3pWFO_uYu4NXMK09E zz;j!At%xZ?VdQZxLTLXD00i$t&v-fgq}QS^0gjizSgo7>#m{p|1_=a|_*NAx zJD6SN1HX#0p#sQ`r5+Grwvg0N(a#w0O>gU={#OfNDeR;I)RYQEBpPIlbjZcV z@%R;XTLek(v)9VG%JT4OG@atU_=U|O$qrK_B7HTH+a#N4JOwM*2wfMP_5yla2k6xBssUqd2B1yReGzv8DyjqJgaA{rkue#47}{)>Ok{0Uh__lw@vV3 zf!~LGXc_}cWaU)xQUg>u=CGm(ocpf?|B4v3-J*PB`qVS9I=c{%Vl+rxF_&?SPbsM> zLv`nbeKtjLvIwysXq`A4R-`*b?O!i@t&qZUwNviF#N@&BGxcvRhSg^bZ$O!eqnATR4il$=$K5y zjXXvK2Ny2R*^Rh~g{^e7elqzG)|G=DXQeTQ)~6l0IQjpdJ1aXLEB!KlbUrH4gTpIG zxje4ndw@j$MP0X@VIcS0Nqw{6lE_mGy@jCq!FZh%zJTg%bQUnQ#-ay;%NqLNg7t2$ zo=>2?8g5RTQ5#oi6(T})VfupM{$0^%2GZz z)Dlz74^06xmQz(H)zb&BG~+w;*U^bzKV}gK16=7eo!s0_Dy-lIPzA0!NdmP(=!Vwj zQGU;9U&aF#1L!{@h^+TV1&_KFW8|D>U=XpIzp5su0CaN5h4ABQGOoVSFk!n{c2@;d zAKj>AUK-{dkQj*@bIZgp?#tCQR|xoRaOqKrb@j-7L?bTXyC$$if?t6{6GT|IADnjI z6+a`HGu(q4>u=UmQ0u5)B|%-Bh|VQkpx0UTAThX7_&4CrZ=WX zFR)6U1i#=Y_Qo_sIkF1@;20_Ea73grTihT#g>#Xy;58?YkmjVrp%z?w9@m)D9Fok# zISLUooR5|_4Oxg>tXs)DkNAaFd55`(<~T*-gNYH$&GlsxyEqU2e~P;8`ESBZrQj8b zZ57{iz7~DL7JT=QoMWRkb38-CJ&_Wy6%%IUmRKyJ4=>FwPNVA{YsK?PcIJP}0Fh)5 zSFdo0gP7;^M9tdWeYiGZfDP9P$Qx_mNE@Z`P=(S`!_{Z;$HWRC9%pM+eN zF&pdtUB)+k8Rzwb+c7QF*8o#@!A516DH6CaAr6W)BrC9KHOCc2gwn^f}uRw z?r`tI4qP(atXXGUF|F$h!~oni-2ADVxiN+7$&8600p9`ROsABSF<#WwHbW_zc<_qn=R_ z#w-ISQAe4Q;f5V$l6)+Q(MSam4!=jLS(7$Rp7hj%a%zF*%|oI_RTIQV;)!&-Uj3(pPDd{E4oMvmnRK5{4a2 z#Ej^5TWuASY7O}*(NrQ}bV`LvSX?}u+kyL8#11%iyq%@y*5=0Ht>;7f0hD4{)cR!7sB3#nr)OQ786usN_FjOF=Ag%n)(B{a*a{ zm{;G_{NwDt_unKv4qYzpJtNyXz<~o)qt+AsX})nr!A9262rNFiPS22q73Q?+j!cpn z-)MtdEtxr{>0GHe-IWg>8Hazb7>1NG1ByEB%ug;ox+sVlpIWf^zSR99&xf3cd0q?mD1A7)=&x+c9iS zs|elEmf=$5rF=FMv`gVq4jM3P)T%or)XQ|EhwZ2nXg!t{?mJ#**m+&n6_GD!$Nh+SNET;P^QW5L zT{#Ho7Mp@D=<-n$$#eYDtN2J+#4_;toFj)!3BochjF$acB3wf-g@YtSP`QxkuZ`Kq zxJ?{gI|GgheQXE_I1D4qa;puVm+JqE>F2k=e{wD;WAK;-%Tbcw*ADT=xEm)gUZbCF zp4V3n{{C65PooGZvaANjfdnz10CF@LHwH9-v%pR4d^xCWtPC{ZZI!aOW|w3zvbkJ< zx~JscNlhD!Z3;d!2nWyADQ2H|NIpZ9kCPOaAs&p|yXD~xmeUau?cBI0oE%0UOPYXI z)y*Y(Z|HZQILG(b^Uc`zy|&D~(*#!+jYi|Lv?l*FG$Ke;XvXi#)uep$Ivo;`_EvG{V;06f6Q2D`{jWyvs}sLi zqu5I6`LqMT9_ zHfL+N$eNz^A*ug5R;!!>>^A>v)yD<3ibTiNFs^r%IH@>4dN`yUR#Xc9btsauetB$0u#I7fJ|>XQc41Vr*xMjD_*5GWG(*?gS(9I(t7{=QVlFIPGv8jD%XKnB+Vy^)Xj4U!o)adAE+mR*Jfsawoc5@R zg*i}La7|QVw;Cl|YHznCb&$E4{Uu)@$W+4<>fq`EfUL%aB)(aYyeo|5i>IrIawQR>pFS8?|svEybj~bHM0|2dyN{0wIMvhH%%ei zjY&n+JZAoB)=GhzPoMS_szm^G<~4#YoED4@ndZFAJ4h#oypnggoEzF1&HX;As^ z9StEf%P^`&(jdI$c3}+wd>1La36ErH{@1x zm5kiw5lR$$&+DeoY`6C%G5$f8JYNK&@|C!x>fhl8;>BHwT_xhC{x!G+u)ROV@{W5w zotE-B2kqo^jIIt$RLZI~Qu)l2@hZ;T2?SM@*K{NjCqo#(pUks;E@5XjVrH?EJPCuh z!-Qot3U(MudQ`pQ`K_vJU8!Ks7#|3`Pc3IKx&b1XP1ZrPP$Dvz-(zr62f3YBN8-Lu zWp&-QVnvj)%zHEP-ih2OEzKLd%wZ+_WZ@3StD+G1g2Lihw-2okPpT3;dj|>8BeX_ zw+>?yCILhcfuIEtj5(-3-(25or?aD@W2MvVm^05WyGxZds2|QLGyPt~Wp!bh-9ER= z^?sXu=h`Rb_n&*!0M{IaS21+ARr4&N6ypgk{$|T!94;5!q8KuC`COB)0UFnUp`a2Z zPHI4}Zs4|L1V96nXs8khxe$gYZC!*p1tYb}L>Bg&*t{dlNf_XV2a)&F1TchaRHr6xMYW7mzBnwU9{pv=IOn|0P?5X zt8MQ_V%-F_*ZLuMeTm!zeP~385G7m(-*}f(?KC{FFdbs&C==wW6R9IBlEjE?!>r`U z!Un!s`^n3*u zRoZOSM|ECz#2tL^jNXuNBoA<5B^@N^(6yuq15HAagPd0=-1qNmc6NnxdL#&*VFIwK zlGMvwt;z8@L+)HCBK_I6CPHzK6q%b4{bR*S`9`YgCIFS~ap*Xuo>$u5cJp{`SoPfe z>+j?$2M;Kq@hyiFK9yXk(b*hsg@nZ~wYYM^>dUAVj4t<01%;G&FG^Lf`I}!8l{cg6 zP!(!LFU|F^He1fLY|{z>KCN4QwD_N(Yp%41ya?ELkV^z$Hc$o$Cc3u~W9OeJG?i#U z4yMOM==vVHPX}?0n-@vO?XSGo#-ni`2<*KFIWqcQwA)~a9lXr}GkG6?#-b7I2BBBd zn$}(Ff!wW2thXvV0-(C6bYVot*bpUyHUk9)R<3_v9-vK+KS=4Y2k-8nqy;J&=msbV zw*!WZq(!^6yQc^G`oI8nr3Qccef7@N;&y0c*Bi{)W9AhjiHe%{-ErC$xrBbfYT@^boUrs=hG*_1NXXR1NKT%0z0&3MH^2 zbU?!)uT4}@6O&o0lQ4oP2eGxw2=9O9Bl#}>tyqR=h=*DlRyjzDbOR-;=(QB4F;Dd-Z_wIs&P22~fww9E5#X#hH?d zlUDDLk4`<~x$(J9QuF@bBM z8Gds#hyNL#5wfjV#9OF(aPax*SnQ_olT ztpW~i?0WCaSr)+b!hBYSG2ZFH8S==r^-8=4dUjdKs8>OGY!y{9Ty|Ncnk$5q?T+u} z$n?XK@iVz`u~Qh7tE5V^rzAy64C{*(}`W)P54fn8Tex(MPskr--u)1;sv^%r>v z#5?J$wTm~2rX)xaU8YWB;{mu?dmvy>M#$6`e4i2vY64HwU+*n||3 z2JJWw%to{dwf&)kjTTM8$KW37@$7V+_XkWC+!ihq@eTkW14D;3b#t}$X*PFQ{{e~V z97ajnvLvqw&EB?$<(6xZ2jI9H$zai_m`;>G0dCKgjJT>0HwW6@p$g% zy94;sL0Q?U#@fr(v%^0Br@0gyGijjeaMHd*a^;?@7-=8ua7O{MQ#y9XIa$hXJQgl~ zi6yexam}vq=WC@u4~iCSo&7bRN=j0h98iPZn6LnhSU*<539cwF;VcuBt)h&~?Y90G z>8~A6;t=|AmV$amX64mOaz?^sWLP;B^;B!(ubmpH6Vmc+ImD`H6UeVk&P1l@pRuGi zV5Meb^x2}^xRFo(p2o?tlTn*Ki?S?fX&kP{I5~C*)hW%c$*Vpz0ZJ%>k}CT5EzhjR z&s8f6&3>zfp8Z;pf)0CXK+aT{oC8BWwlbG%LiKY;cL~HO9_(E(ObYI&>c&sy@nw)( znI%nV*$y{zu$!MdpHNSIkB5*J#HI)R-6k=NQeb;mFG!5SVQUWHMK_4Aok4{fKTfqW zM`qx0Wgt97zi@CnQ;T&3Ot@Jwi^d<9)&oZqCDe3LEPS_Y#VM`FZj=l}y(7baQpT8D zOdVAoMD6Df6!;p16IqftsTLR{(?0LWI9i}b(c_sffRa}bRps(m2Qs$WZ%A3el+EOp zf~3l4m-t+IJ0SkCcQU18l-YJeeyX|9$mSiiC~!AMxHe?yvp`tzbRCT4t~C~Jjq*D8 zSeRJQjNc_=XDrVvI_AL>j5aJ@HrmArvO^e>(PXN32Iu}N(;wdS6F=STx= z{PP>{N!;X=%%mAd0#f-RJwL>w)$UR+|0dT?(MZ(6umhL+r_g1)ocR>K&r8IBVXUed zn)qQwBij?|5hmM^08Mdr?Szzj6cO@q@pu*~=5x$UMsEW^Sinq8Y_MlaMZ zEX7IS>TWlO)%s8Avo#Rq4-*uSCq$PQi`NJhmA)W`HIUWN#n;uyU|$6@bKzhh=18uA z!&v7TU#eywtj9do^GQLi_|PFj5j*u1wdIiOyy{81*tv)EcE+ifebR9b$9>)m%E0m2 z5=#z-sjdMC&If@vQgF?G;?{naIQ;2Zi!$tDlk4P`GGfc8FqT=!S45p=wVWVaFd^S- zr3ST1W|5TGx#ayP$P$ONGuVepqC^S3_aX@_NbQjdkKyAOI~^f^9za4M8_E@f!t)E$ zU6EGSUN|C}lg;IU<2?u!v2}h~4=(=ZkMO!?kQ^Y8y@|n^306GPQe0?ri4ZO_)=7+S zQ+~qzWtbp)U`*4Pie)UJuqY&pEON7*WP*wPd|9|<=lnHfNl>sjtC^Ws=6l8zrSA#D z+zW8N9w&a`s?)0<4r&xQ2R0a3dgE$df~>V%wW<6V zk1?1!t=-1qoM2ZQX29Wh%Tp;u)DLF4RJ2`x+b4L~*9=pcnD@!9GpdXK3DF#5>|U`K zLu$K(@z&S{YrI7&CB-_S#i?Oy)O)`wy-&r;6ul{J9UReVPs+_6l-=#08hViT1!S(z zIT7XesQEFBDHcu03^swJ%;~fmm2K3ccZ0)3(}o3ARx5v^{XK@+;UW8optVe6D$9<$ z9Sc-~Xp`u0JVu?(?U!1g0yIA8s7Cx70%e1Jeytw3f|WvcU>@Cy_J3=Q1L!aDP8*>&v*a;E=>oI4|CNdd@J~kLj zD3lP8b!U!7mz4Vck$53N;s?1!zRbc;HY5(g6DSgYz#6vWN+*k8#=v`QPDL>qte(aF zq-h}>XM60NqrJb;=@w}pC9B2_Yy7PmAe5vkVI?y^P*g%^JjFckXm^`;Dhmr3ch1G& z1Z{qV;Ix+estzc_5lexL|kh2qyE69yOv1=871y9w>_+P%>4VU(cz6o zFW)ejg}!QOjzNImM!#%g0VX3;sA}1$B5iRM=s;t#fdnE&FJ-Dr6lqRgFtS zHQRG0k3Y_hv;uNPstj_wm`1xirup=t14Xo-oA1ML`)6eEgj51E1+-0(91~+m`KVSM znK0$;IdxbSJW;hf65)oW_ z;};4uZ{(JBA>D{pG-5o*G zqcFI5*6eY9Wb9r|xIflp;!!^xVT;-Dj@58LKmRbHF+a%nYWh!3G(X2QRg5nW)5FhO zp+koB&C8mswUjr$c$fr@bR?j;3GFo$7+;}O7^G@%oNvWl+iJC3@H?54eP&QAY)1ztNubSDS4SGvmiG z=i*rrQ6UOhSgC4W0@>;l&Qj9=5v*@tW8xUx&cwxq`Go)3^zA+>I;>b&2zMc~Z49x7iQPJ?og5x0D9 zrz=O>?*mu{cP&J{zYMlz>lgIKbqD+~kr@YBYpUvyqi@jB%ZIfEy&H&)4gtvtEn#s?tBdH*`gTv_Mx z$~1g5X(FJAs?e?`W^V<2bcs_f*#5TCvv{^k-ML?vfs2LeV^N0FQe4|o zQu~R^r~N)t>3++5Yyfo;j8vWZM>ep$pmm{CR&XDhtFQTaXVPo?n-A`L``USLIL$&5 z39ahF<27NBgsdbxqYRAWu?m!~9Tuq3H9nOzsPV*t-sL80a&ETXAM& zj4nW@GQs;1#fTC?1cnqYZ+Q&Pu1Md0ZyaN*J1NWeJV@uh#Ver+PS0UvKiWXn6oJ)x z)bO+Z2?@%UXV55%eZm(>=66NJN6zshBjSLyAMt;;;15sQ0sA*rMk=Vp3Qx|bCm%N( zJN;?$pM+-1@|EFOG+>W-;uhj=rm?T3*R?_H^v|&^XfO)rL>#IgB0(|Fn?o7$`bJIY zLv_DOS(MSSuBovL6iKD6(qpp5XLI{2g&HM|Ps}>d%^V^Kh804W=2mr%%+OeaF4u*; zj-b~4m!T3I`!d(YfoZ)^P z_P(LZ@ZYd`8&YHsMh%jZTEwqZ;*k$|6Qi%}I8k_|+*(BwvJcQ+dxE3O;go6G3li_; z>c46}ecf=o-$}Hhn`C#-uR$+Z9XZ9lZ9;wR|FI(f590m&?qvb*R?G+;QJAf$5scr}Qr;lN z*Bb73s#kCG&$p(;58epax<(ip!r;=fRfX8o?M}BWS$1t`iM93uD^#;As)kkvWNh2N zaG^)_p^EPO%^;O#Ps@bn!K(~dnpWYZy?cYWwyri&|eI52H zpu{E^Eh9_OPN)BAN=QmGJ4*pQbIR*aqGwD%Fa8Z1frb2M)~DG|IH(jA!Fs$~xT|5| zY!?zJS5X300vT@Gi+kg`H)v!VxOkdUi&$A^#{sx>duVA8IkyU@6)mW?(l^?>F<_7{~Iqz**q|5f!m}Z0*ROq7y?Wocz)+srGo&(84m-v#g$SH)&)AiAu{3l3r z0;P^(gYmZ=+qN5ib@c`!K8oE5t`T##8_7xyntyizW0TS8{bOxK0+bi#=sEHKA|OF> z_emC6oG_+3q(CB@7|bFWxT72lQj%irU{pJ0bhLrR6}!XiV-C5Kho#?m$lQ-6WGZREUExj$zSV# zwE((kH1y4q*BkP++e0Wmzf(#6;#eym%L?sHP9T=M>&L5Pq*_*_H;9+%6~!=Y(_3nc z;a0&ORlz<7m%a({&IlV7xYYTKqSdtDn&tZ4F+i)=#6xtsylDPOD)PQD|JD|3`8y*0 zmYK}Q@6vCifTEv*SFPHl&%2)$PC!h{6Mwbde17!+weXifyJazJyU(dHqx0^35sE=p?GWsB(=ok;d(H( zssvM3wV{UFfcMwA+HYnOYk`yiDk=-j&@MF?l2oMDb1Ymq^vQE_`?_yo^oq=?v%3FF z3O{TeJo#TXhp2U=NTwNh-{YhLwmzpBWZ5z{WVB4M?{T!o2)E^kJ>HK?qt7KREu`PY zh@eu(z9~V`g(xaYIi#GvJK+MSWZZ5y%cquUywu^WVQ{sal&q|cY2P#!&?GfKwM5`k za(RM6_X0m$YSVe`yBWefg~uI6OBHUI*xZRRjM>;bw?F3 zTlwcy5v^nu(Ok#S+E-teSJb*7Xd@JAdh|isF^fCe>{aeQbrC5eQoJC{8Xg0rM3pF^ zy8h+Eo4vyvdd?_F;YM{I*zSzZ;r4)$b=4E+w(U;L*W5HRvX;%ld3QVObT|8z-Hx7X zb~CV8+y`N~99fM*RF3gms4#M065Dk_4OtQ-r_o8br6uk65?D@a& z?h6p{&%qaUZz(|nNbT&Q!`+nttv^7KMNtK3rIbT`j-Ge2rkDXt(ZPtaskoB?oa_kp zp2c)6HObH>z*0^j6DH**I3Jz9zEgdn~Hgw?dh*XMEhb$S&1DF-x zr7@7eN()9VWq!lH*p?>^-!Bz0K+msl_zMQFKS{|w3YAcj*+xlR64A8^_Eg1B8vrp{ zr79^{eyMBRc+=jYyo<`LSzsb@f++9Ht#{bi?}f2csl*U@h&qO3uS>GL_F-MMr6Q`t za6qB+-Y`UnGbJBF4+hsjajzxs%hK+1SRaH(|1<78g8BOzKmIk_gPP`YWBO_1%A{$T z$U4^W9IYe7UtIYq{n}k&fqv`hk)i)0H$O zk8o1!e?aCn7eh}MKUcqJ7<&AlSGfPgz>rF?LbKNK1lR561-&O+-;UV-7SEEN@cb5! zC$OB45T;nzFQb36TQpSbU140Tu&5@Wpe*Hnk(rB6(s&RBT|TcrjTDmMC)w-qZlb#uEN-Sp zH_Yefm_5h{)mB}uam0{e{#;F?vH_|DdOgeLwD|e7yACt>7HHGlOr7uzhK%BwAJx-0 z+S;We!d|2T(yD4LpV+;O282Vm*YJ7I7QIx8RHb1Y; zBF6U5THm3*>xldL^LL-5|KfUZzdxFZ@Uz z?JJw&O4N068gJa)p@S13xVu{j?hxGF-Q7KS65NBkyF0<%J;?2ub7uBFKj89#Dw--- z>(%FVDYIU@wwh>ck&BijmQC@Ga~*G-eNzJmL0Qh;UlG}&xZ*RYl257NwC#)_!X%Lf zqiEym9=2RxUI63Z(Vw}gU-sx7uIbMO(8$q!A*HALpYvJ05N1zioOyHu zety-kYb2P%zP9Zg`GOt!t;^Xf9nTqvq6Z=C1#wJ>DrqrsnHJfgW=$y)TQ;t zuYl*>zNXh1OZD0$uB-k9`&oiF0_5jpQ&KC8NVZZz!QQ&}2U5rVxVPjOs4UQDv;m}Y zA)4+Q#@_0chAa_|-LZQVXM~KB4R=RnI2SsyuKS5u-In(FEKxbr6Z3BbS%O* znX!VRAUzn1TiuZQL!9cbf#0>59;RILVCa0Lzsby+dDr2hfA_~z>*j%8r(he$4bkcM(Kj&yYY?8&@$xBYVR8AYhoqa!~^S|M{%b2{@?0mhz zccE56W$A}d&^1Zpkg6BThDNDWDkabC0^p(R+_f)Ss~40`L0<~fjpqagXp;J-OOn1K zVm_>oGQVAPc2~YG{$|)L@1{uK!kKrGvBeVn2VnS}AWL>uR`$$;1u{q!OPVs_2O#15 z@G5o4j2n&=I&jC!qlOv9#M^doia!ASp3MJ!=>L4}cq?44Cl8sm> z>MI5rICMmWrL8=nn*^Lm^WKvL#aE){vd!;z=_3`;J`jC{X){Xv!TF#7)Z!(fP>Co} z52uAw?+1OTyL^(gXd&7m4q@Pg07a59oG!Ho)o9ywr^SYp<{AC&q5esi+fYvGg}Cqp8G(jys^*&Pi8g3NF1JUrAjcVfvrFZ8B1tiB4T&%PN9?M7?IB1uD##ED%0A zuw|zB^^kE+XJ`(&yeK!~gZ8rXjot(if2<&D7`5rqqveZ!BYu|t0Df^5bXi)FWdvT_ z64ogf;L#gX=?;JaW64_P3BJvz9_FfNZ6uY5HSajzuzdbuwv7Hxr$#T3?hJc=>k5Q$ zu5A9{YqBpzJ%X)@u8lZi*3@^v4=Y21z}ZDWGNP_JvhX7)r&JD0B}!$RUTSDzv`vs#Fg3ot;6EkD5j{1&= zQz&gV?*b}!czoXs_)P8`BnDGVh4>C-!Zxlb*P0EXhA~FI^?f&}A%nAQsHW+M)=FSs zwn#Wz>Afnf%J;y(R)zgkr>PXu7raW0ZjlKiA#qp*3edzleE4rD4L#e{Nd9iPMZPfsmukhj4$G`KsaWhrT ze^i6RhG_^mpuibQ`8Pt7ZP{Q%~rO9M03u|ZJ z(WTb<+f=@q&+8dvu9$~HK`Y#;MtW{&S@84PuswKE7V-jCjUK}0W7*k?|77OU8r!c6 zh?oI7J<;VPYUqUzo0pif>MzBcy`Loh6>TXhM;CPQ8L3@)i2y3nE=I|rTt9Se(Q)RZrVX(f(|Bgb_w`9De3qMx@sNOU|NO{y||P#Kjy4RMOzbY#D|gE^5= zLCUz{_`|qVOl_?U7e*%&Sb7;-S;-@Y!Xi$G`Gx$@Hl*jUkIu`sH3qlymhSZpf^kYq z=i6r;3d(SwMuJz{n8xOJn}^G#x=E+|ZPU{|SbU_QSKQ}0o^$wwmkH5l* zo`>|%8zK8pp8hfu^t;%6v3snM*3qIRCNy81fZl>hqC$rK&1L-!_nQ#d*Zs=}Qo6q~ zkZln#=EfEbb_pun2pQjaOb92=1XjG8a`8}eM-^h7bUdG?Zv@F;VN*a@SAGXy4v zvvk(?)hY7#uKL|d_E_^ zF+7Yi#{3}>$|Y$_UP3`e)X7mZ5fK^O{(pZzP8Fd$PNu7;XRtx{SvkLONLwov^r z0L~QcO2g$aQCH8LvAMm_O|&fH;b1blmnOsT1M?3LK)PD_DP~mu$+7(z`1=P3bfba7 zowAe-Wls6=(a{(`<4|w-aZn?;gtI>)1X93h>>nI`U^c)E;v!M(8Timj*Q(p`*!mt& zEJE+`I933 zyU=jNpjzQ=&R6dZjN?=|hTVxB7H%R9c3by%(W1o*NqHF~wvt9$<4tHZVH-!6cMfKB zW95{kajgGhKoi#AT^ul26}1vUj8nz*{R@^Wyp2lxu%=E#UiQrLsYm?xrgR)bCIY)Q zo}_*1Sk(v>Csn4iGZ?fJdHLldDsB;_XnrwG2h<(81}J5K?Se7370M5v03XmN^tdOH z%qOR~oAd4q6=%Oi-Vr%Zw@Lo)QXkF~*Hc+-&N%IYgk$DYRKWr3zu!H}nYLZm;tWvB z5_yA;6DCf@0_dpTMPT?|(PVFXj+m3elqs}KXn*~fV+51*9qCjitOtp(QgGh>?dA6EWb~gHRA6yY$x3wY9;99lSs&tW=S>G~uAW)hCvSU-*|5 zt%!__^miEs>Ld4{1e?{27W>pOwDfk4(b-ak*|ipI{%4G&W0sKK?~)3+TaK+!*uCkT z`MI8j!iCEQww58?20~_J^eJx%m?mdTpj2vw)*mX6Q2})BIO`xwEss9zLFho@h!Tfow+wx@3MTY@;cvSh zxtU9aLzWrzcJt3kFCoGz^OXCVP+O!y8j^Kk^qVn`eL-6|d(edQ3$Gi?B>u~(e`Z)F z?mlW~R~aD-!xTA3Wn65m<9l3tR?=j9*YCkxGIV>>VI)QG6l{3olu9m+sq@Y~AX2N_ z^^iHKnTcsvd8cRk4l|MIO~oJlD_F|o>hE*W1)FFh-#x?d{yg_W`g@{L{5V&}2CsH) zD2PTJ?62aRxOioLhe>m@44-n2Z{R(Z1;x~g$#zFnbNgj%j}XmjH*I@cG;k5r8magC zx`)j9-=P9x?w}zF6Vd7X*Mu}VOa>9%(fb&UU=%-x@0XxhcbvG6?9)wXm2q-kvXgF2 z#dW4}>R0xvZhObhV=-t}ace}SheldpN&Fw(q54~Q#A4uL$$TTK*l2U0YYdy)K|!Nv z&;$c#e_oj=DN$%jXwzX;kR!pyV|`7T%>Am&^ICyWEB)ZGRA87fj!z^f8jjO-{+OGX z%m^L9NV{EQCl{V{D`Buh;(gZv#PZO?s=$AZ4cF?XG^cv1!U?5s6|eb#0BOfp+_P6K z-q?OZZl>=YT3aW?5I@Om|2D!mDl{sx9sCK7-Z2x701=urHyp>@%wu~}AU3jF&G@NO zO{Y-Ucn6CemwB3wh!CboP2!`q$;s;Z{^f64!9=8DumJ4B`;ae_K~Xhah!m}^kjJ{+!;to;FSX06qA$+%@%?z{+LdC^S&U6P9pc5Pr(xFkTJwJIDJ;eo=hZq!a zP;yeabMSW8X|g+2!7_BjE7{Hy$$T?!0jVBW!?|$L0VMgNe%|{`jqr{)Kl5LJw=Lvv zyjucHE;9r#1xu%vuFcd~Sz4l4W)sfvuTZP?ZRxqbrq0Gv_ca&U{-9-({k)IU{v}AS zG>iH&6^ksmm=O@8!ZTrY3BoS6A?cT~5D_(7$b{*Echn?PB(1|9ABx zB&D$n4#_(P^ZP(&5A(P(Cb?!YLUcHF0#*temU4|b zSQwerDt0XH-qgt&*IbCZc-eS;bo>|gFr^1wNc^~B+OPuyADw35Hzyw}xRRPwR@O;c z@6U_ZsxetCzLe?_A}$Sozl=hipLR)AUhsML6y^XY%>Kh1kEs8_!37xNi{;7$_0{u% zWL2^C%lC1+5?$h;Am6+?^9feh9r78^pc!~BlZ`W0i>4zN__7BRiL1&k zt`AA8O)3kRYl$lGOaeEEll(8-BtgKHxg2IzIGU2urFz3m>wPx*o)M?X1ma(@12#<# zZzITry!;pe!@k|AQBhcTI91Osp?yDxZ*|=qug364lFTnBlE^vG3FvrIl2nj0iyw(s zFG-$DCk>SoZHJ{+owj@~eqS#;wLLyDvoKV1bB)fdfe16@nW$phKxKEW)?cHm_j*Z7 z>gs!XDC4?D*l0T*S#qj~_d^cQZjiuD#2mD=!!uYT80Lry?T;AxFKF**IZ3p`X;uE? z9;>nII)$*s!G&`*fz$;l4Ro@_sz0~-!=mS|XqNBCb)IB~xs@b`;&O_eo+&D3{6hoW zDnMBzhnSJAd?MsDKLe09ouKqooJVOA%ayZP%YydrefVyt_0480xOSqq+Q20mPB@k! zB_!7rv|91bNn$8kyCC}h)^4AV3pcRODe<<{Joi$=-dJkp&-c(-`#EaDfB2&n>h^uG=i*|&+@Clgj?i(reum-Iq{*Je&^f2D-DhNbE8 z$$f=Ht6VQ|JLii)6cM2bJxa+AK((hSG$)F9CQD#&56;Dl+$x~P9o!v|zl}`XOW7k+ zS|nWi6Y$_PD)>l$Y7y0@Z}*|;@dnBlSKq0mYrj}0|AE|dA6S4tFL`{VJ)9g1=vgit zT=JSFxBd-;wd-~-YZ_R36SX_2F()Z)s1|7t-kB5}4K>d-o$D_8%!bWJa#UG8MKU!D za}{5hkBR0moe&`nu^cqkB)dj55<kpktg4H9Gz7PL4MCIm7&Csc*^_ary4gvRuwn@8m3_45(n)7gkuhrU+!2MR?ws zG|&yr=XcAkm72gwVC^*secH08kf?#_4OD{^bGdV%5HF?T4v{m^keysQQt$^$g--f-XT$mxVu^~X{A{~xvfLXVVz@rv9IaRfK;An zKm>zv1^P!h`9fSXdd}#ihe}ZOdqER>qaph^BV)8jy3ZY8^nj^$m{DGtjS~y6k8mad zhiUXO*zsErq>75gMC}z7_fPl4Z<9Tmd1M(`!r0H>=6)(A=SJ|aww#|m+#DWs3>C8< z4E5Q+F~0}Ou9hCnW2Mp2Fb9!k6G+g|)Z8gY`jU!@*m;B;yg$a#o0$)T@Q65(GE{4) z(SM2O`RY*+I3j1tj;5RI8=2f=%!*4R^=G#ajUC-2`=b{mD_yI(FSWVRE_xsOfS4=o zZ+G$x_pYfG+HaAgf|zJvX=UK%a!M~gMQ?f|ZSd~vd!uJ}Kk#!NEY*3@-Y^qUGp~H6 z#QIpAom*sgLY1k4g@5#->57t#6yhn6zbvo55ZOBti@XA}!C-0AASJVS){``=xg zDdZ<3E^62nnPe~!<55du|^FnyDZuv zHR!MqS$DUOCMKu7uC$oIOE~zxk}-N(xAXNbE#cjqQNz(-5%T1(aSxPu*%jQ))iuwW zTb7$|Z^Pcsz+n?Pr4? zW=3229u6^C>`kD+&b$RlGyM{^#vm%5{tH1tgCP`ab#1lOH<2U0%GBE5-CoO0KDY;Y z-Vy!F_&8=vO77iShRVSj<;fHvg8uVW#CDQ(++Rg;N`#xTY z2Vg5cj6kuE#%5ZQn-caF>fzhXExX^0kMTRw?Ay; zy_7U_00Ybq~ zm!z3cWFVV<4+jR^cPdmBwDnBGhgMP(W2a=v_pMH$R!O6+wJS{T^F_a;u($3>qard| zF(PjDvD_fJO-J5-NBBY|H)_?U&X^3ar4$E63?F(G6esyY0i#Y-j8Jm!|_EvNm0H zz6W~4-7oC0C{igZGW5mCDl+AHG$_(3zocOukWo=Igj9&?4Y9YzR1juWNbnae%&m}2$Xv`Y$5>1 zx--ZX2hYcpd3_+BdvK4@81$J7&`m}z7&ib*03XLv_s-&wD)crP?^)nV5{S>xSzU z|$!w=k7DNwTTU%D#}E=R@6H7=4CiTCdQ~C z(dpPPDUNQq!d)JURIHPomweiTrJq|o7zaGUk?WxVc$mhK#PQ=o5RwMg)`=5e&?K(q zH$o(W_OIB3bstz898k_w2g@P~GTmj&Con$fi~NW;te};+%!t2#nDW}x9+(8}F0nW;e%tK|^=D0$#Y~Eh)-fw~Cqf9N=r+M)1htqG z>blwPAG1%YQpfWQMz9||hDZtyOjCwA%(ANie}$K&ehqev(Eug_?IFd8T!$$L7&U&Q zk$l^R!qzr8-NWV4jvV$Tqt4^ShItN<(L^&`W+-9S`(|eyocWNPZ94qCD&3Q%!-}5p z(0t{f;C;r(ZFSSY@&xB>wS2z?j~@yBCpH_R3)B5(*}TRf`tn|U++)z7Aqa)kBmP40 z9VB0-j(yym512t_B*bWVIe4 zSRCN%o= z#WK^5sK{j-5W^L#^20?%uO$#Bj9kdSdyf%ssTzTmHP^ozGc5W%mLcUUd_X*!4u;gs zM-5QFyqgjiZ1iWjp~F0)V&~t;nzLFZ#?TaE8g%fV+dYu91^#ID^!R#9p`$HeRW}AE zqz6WX=M;#75~;A@aB6=C@T+}QC(2zipF<2~(*ppqA%FFd)c&pjz@^G(7} z}sq0w(YjZTu--56oRFp$gvftj_L&rBXBGx7H?qlL|ej9cbs zOFg1~3D&y052!?+M7&<%R+NJ$*`gnuA#&!^M@sIHCu3RN9U_hVk@NA;znf-CNI?e0 zD~X9!(`;(kRrgJ>96>XZ`X;ZsZS)RZyfB&_t0rf$6Fo7%XCyFEVpZ(gK(Z;C@vpnt znXVR+?oXw?@h;b3I!78d&Tnn~?xh;VWq~ddzCNDXvV6E#S@R~G{d2FJnM;nYNXU}H zRxXVXE0?Uf_X#r~jgd)&I%CN zC9nENi;MTuLW^Y9O)68|yzHup)n!DH9E6V9V7Q$hf$gP=s-RSh@o^z|01fbiu9%N~ z_~EhoCsz&JqYL(WYff|6$z{3FC?dP zZuWZb#m#;zh(|&~?MiaMKg(X1%-d>_31vjI!QB?-%4#&+8wZ|uKv?Nj#i9`1=gZ*E zFE$$+*H-eM6}i8rk9UI zejN}pFgvSm+K86~$;1s}ak=GwJH}33_#}0LLP2FmzM^k@CyHioVjX-HG#JiW*2^F-V3J( z4guR=7>eH-Mci8r9WQ}ex63$SDfBbj(rlk(?j%?FsO=VI$q82Of($VgOd5@>XJnz zQEPne2ojf!FeRySV}Z@jeQxnb_&wIpNa+y#Ay5x*+ojDb+B+kogMc05KFERl^BtC+ zu|qoic;F@6wr3J?mR)JJ4}zlKO_qse5{FPwaBhL`f^BCKbeJNUk!6<9>cE&7exVSS zK_nCs{ms>bpioT{`y^%ji!dTtfK_Mvj&in_?y0_)wS4uHPw8%&-Z*EnieQ3O8Xj5^ zWY3y7XKg$z-C@5Neev98Kwhh^JaM1Hn;Vl*(WYjyN)yeQ^!GV=iT!iwQ=J$iF-S2M z!}C#2p<*4gyYK2^Mh@M3ew!9b7EKXIuuzbg*UXn7s~r&uMj-+y2{LZU8WqFIUbH&r zWj2g1xWSf#Ji{VZ;l)zF+yoi?ZdKCGk$}!;CRO9KgxD1w10)lMbGkr>$SN8*j$ za^U7Z;@mOzKE2EOUyWU@L?o#_!yReYBueS-nGwbCvl#;>l;V}dmd-xO+$gZg0WW>vCb>UX>R`aR)Nm4tO{YaSs1$J%WmMGU2zEhlv6UeOd)%EZVJ}`W zDl+Te>J!zr$qbDp&-tqjEK3t8eb!* z3w|;fbP)(inTHYbR6cvIs@Erd6_`q$j**+qCz1yo1~H@kP=H5dM+7q-!RzZ-YE-a9 z5LE8*E%@Mc-HT`|Ps=;?%#XAhiFAAtv&TElLwo`gD7w$WBK~7Zx;b5gtV!TA5HzLq zUX#U)g`l6VHPv-_^nTfqpFfEVbj?w*dB>WS3n5(F2ttDJ8=Jz8NBXk`-P2?H3@_X6 z&HW}KC?%_Vac`!jDa5*kDw4cN{Gyi`HJ2Xxn)Wx~n9o-S=W-tsTwPdXC3Y!mmAXQp z?#}f}G=7pr5>;dbJ3pz|f)9+>wI~VKwlQ1kaU7!~lkb`{RspcZ9w_OH_oFnP>57w| z|0I%Lsn8eO3KJwUa88O0c}41-m`32Wjl#2}Ab`LJYeH5v*y=7=+J!E2wH3aW>2@I&KC5J{@}K$XoigNR4HEr#|(!H znmF(pHV!@=QqG*@mwbR1l=8WPV$ft(#TJE?T-<^(!(rZ&(aDEa42X86ByVv~F}>LA zPx-^la?_XOJpPd$HYl59Kqs?{;&uh2;b#b8OV1o(m{z9`FMAy`g=&)fRWO958+-_F zqq3kwJAlSud_T@A4!jDf=T24q+ul@A7X+G4LLqM8hNr07w_%ax+3h9Vv9d^s7W z$75PW83{`i)Ixzk=z5~43qOC{_m|Zk_R|z_ zg7@gLFI&`K;5YKkPz<-(Xgl9fQh(|}3l9;&Bx#o5{K)ya<|9~K3ArtjF|{hbxv~e+ z?My8;LvgLFW5g4w4&RMAxtS%2kJnt20rvfAYf}@;v(fyYn32AC1Nv{&O-3OXr+9tF z{O)#Ks%TJ15wjdT?sjHyG!P@jf@chv*jqi6Cu795R2zB3m&GEAaB5z%-wbNyxf=8v zI~?9gwizq-fzRM`Ma&}T!>58_yO0*mH=ZWbCh-YQ%k_lwqu*?N-*%d;xfgBKYO-WM z55bK%_~cE)1muaM-GbzOsO4YIZ*!(MTmQ5Izd?lwFHp?FFPiK=BLiReajJd`MUF_Y zJ9g7EIAk>S`u5^gyS9-QqTf}f6o9#hktB3_GvsLP9jNrP+Nd9~l0+~z??>~Q7R%58 znxM>V3b)Il{ILKvjHKn)KsjX0dD}0Q(%O+@B{t8Rm3syH&m8PKvueCv_A~~J;$8Zy zyo!K8H-wMhC-~V&L^mR^hI!*Wdsao&ILOrhB^oA}Xcs(~n3zP|_7MIqCkw0`92}F9 zw>!gYRCyY8!?K%?aCfC0ifLkFRQS4ax&~JxrtX*kHZF1jm_W{3yLGXH*fV579vRIa z!{tr~9(%>OOYW2HFvdVWlMl5N+-cLgCxumRK=zL!-MnkgNk4xdo@yyjnMV3Xa@4z< zUi`53ec3^_UKtt2)g!|J2#4>ae>E4=*M~<1Y@kz~`n~adWfmALA?D?N!Bw2KZIFsF zAW%g{>m2?(%}P-04EYgL2OtLhI=4_s!AMXW{}2(!j9mAw_$G)N8=VNzE^H5DW+m?W zvTY1vaJ_DSKM_o9AOP6Ey?AKoHIJ=uTJdNxvCUimjxN^v_;al$#zqz=p*eU+jAIqy zn!Z+S~Dk9B40dT<%J`WE17zrRJbE-hw$O$4qKZ7pwJH&UNKnh_Sqk~szUy=sP}p`-bgGNi%v|uWRQ0G{aMem$*!bs zL6pq_meJ5Q$~P!u0aPb21u%#yP|hR&o?K?FJvdjRT3;1yi2f;2NT2Ze+=tZg^~=D+ zMd??AHa&CaQ?}Ou{MzR0#M&)8r0WVl*5O!TD3cNUUv`)A08R(|XtMpg zJA9j;jIUj54te!ek3E;`%+bhU1g;_!FXyX#T{_St+ear~*Cttcc!q<}1cs6n1$Z{Y z3c>hk0k`84w&Oab3Suj}7ms~XvS{NdO8T?B3T& zc`#dw@3)FibEN{DlakIpmQr9~)feKAWN1qTY#y7QT^FzTk#x0%P8og^jjUgyl_$La zY??_XCWM8&_cf#&G-q|1 zViQI+%fiWJ`Kvmg5mg)5#?>t1A5`zU?pxh1r|jO0->y4f5i~oWKTsSyg-d1VO(B?YeO|Jn@U=h z2=d}4Ud>;OFC<0Od9x|zIm%D`!ChuX!Tl)&7jMl&aDX6tHzn&M+vCve`erYG-XpiG zBax^~nagy8Gx_qHLN;st&=0{v*Qou3c8)*a-Lv)}zY4%bs)2z)suBZkxHKKNWVErX zBeEu=>Qk2j6S07hjR}F(R#(F7srzp4&(-Ff40B)q6l6>y)g+e{h0oQ7{B|07l_nMLOiDsWJs(jl#q6r4@{v4|`$+tgtEG3b z`db9VOhEHrV}?E>KkeIJK>|2*2a=KGvV@L_%ViILs%tg5BS=CoZPAm->9&pCrm#{( z#FIU?be~DUsM535`+gwgvd*U>8D{$>Yf2G(9uhSiNSTNj4<;b~%KYtAJNndJFbJ(J&m7!2Rh9#!#2Ofgn21iie_%~8 zNr#9)r!mi5`jXO*wyAg>^PZPrUNuF}!lrF5{zF`|I+}}}0@N)u3*aBcz1n(hCHovt z6F}1gb%{U$spC6yEi;WLE1<(L23wdvU+@pZlb?V84K~mr^5Cc%#GEqph4L+yU$&Uc z%xI2A_!fA-zhWOtqHgDUrlyPsQv~2c1>PT-1Fs>hG{igqaW)>363~+g)jpo}Q5H&`kb8pkNH| z0Djl6xx+esa;!M|XGI&UvUTXw3aj;AUI~sd#Ykxm^*P;-c#p|Hs@nSIRWg43(JR0}OCji2!KQ^fxSn#|y*5P^c!z37I~|Z@h3G!OO&k~lIVf_;vla=3ZoxKtM(jnU z)?Vwcp>=Pei(nm=X_S#}#8up}^0N2?S*@Vdc$d64nHtyM?Ki?Wr8d59RbawhNQwE4 zdAwQ*{^$KXt7gDP>?W=q8rB-ITTBJ8hJ=IyESUL66alv=MJEdeWfr-tjh}N{GN$6Zs-1Gfs)~3)#OU_>SYyQgdeuW zIcNu~HL3-wACAn+y|1yf8`lDy@Ds*hvlR}{^hV6z;x=iXN^RsUrteWS)*Fb)2Y4k- zYy@HiAO>Czoyz_xxZRHWdSMgF70juiNk& zgz^}s{vS5Qmp4BHOUV#~O|!e#*2kegf?XRIOxwr9g>x+R{!1musCP45&HngZ_yE+< z$-MoJZb*T*NxvAo*L^#5s9<2a)R(!W+lrmuu@v`DhhO-Hbdml5#CDf05!2h+%UFRz z97O+O)j5}vqaYP7NY+p!@ZFln<%4j=JoDd6R7f->M|tVrjLi~Nq=4w&Kn#OVkr8lk z$MY;yXB$0Op~ zzYVvOXsb&nl+!cw8x1+xqi|Ues4%34{}gHbc|KhA<-N;QFzcViaetcE}vrat&nji z@(%g}devs5eUWp7w1h+?dW)ms4Jke!t9J4MVCv`dV8iGfnG?0ns6~6QPIJ@1~ni$|0(@FFx1A~O^ zm0>jYOU4QNhIH&So=z|id)NH_HGV3K3ARm|Ur9oMKy)aB3i8-sIw5PL%!%1+lCPZ4 zu4^d#L0H+vT#eRGA^Q1^zduUkdBjExf8y7xhWXS#iywSM6>lP7w@k zXp6`!INGPG2yUD-!H=1hEKnZ&B;_rkeJy|SnB0t2<9=f{fx=|AKPL_Id*+81&(#_2 z=cgJ;OWerdc)`^~Em<4{M%RnotM^Ag%8wL@;XjqW9mLw;Ap=at_<1oO(Nn%%xCi~E z3IDu9B`>(bm?>!|-#Gd1kA|;DbY>7SqK;Gf8GKol@NF1<8P{F_H6hHpoQjW~J`#+ET z%XY_x1H3s%@qM0stb{$iXgHzJ&R~N(@{WFQ07T3&w9OV$6oOvhH4RJ&&|5JttrnIV zDD^nk-ZZ`3$dPNva=(U@-vb`X6cACUFxN+ur>74!SWYzJw|*KnxDeS`bBph-YLih8 zMi!m?H4efhKRcn&Y6}M;QgzRsUlegn^}`E1-8^l0Py)NW(73NXmDg$iqn>#v;OBHn zDpUJ`4APe_a$)-q`UjS0p{lbp)vCP3${@{Vp8B<3b6-*FcZfNDMw%9e3GAA zj86sqLSa#9bn;m~#@;|4@Z~o&NkTxt$&B-@K*wb@CiT`r;{BtixRC?`PSKuCt>cElqZ?(*E(q4Fm_eiG1vnA2cNh@2Ga2Mjs)&wRal3f4tb9@3kIEM z^GydaNUIs*y#VcMW<#^(_OfFmkjG zL<&PwBFGT)kNtwXT1xm>sYh@Jb3i5*kDs1f?sT_HpSn>O6fpk-?``8jI^vST-HLwh z>(5p<+!zfJYI*4u1ku$d(SmTSs0;2)H{$hH&uGMJu1)FxqCxy$G@zQHGTeN~+n-9> z3|Ih3XVy5MeIj`)?G%|71LKuwz=Tj)GFj~{6VZ08q+pL#FKs!RejnW9gsS57FFRbc zwWgp(Y>A&!${-~-`nx5iMob_gBzB#a51syxPouxfE&U5)e1HLV zo8xQVpYM&Oy`^8@!dUvB!#@Dudld~UM!kYESpy#)U8A`4y;HFX7izE4NOq16-V$q~ z(mopmb2G(DcYXfd_{VLlP>3@&VW`&nM572x_;L&K4;R;v{trAKx4p7|t@oVQ-@FDv zIl~wZAz`yp!926UN0?9V+x+}9M(cho_>TMa4o=!D^x}PQami_rCbV&Fz#S+3UIe?0 z7D203x&U}{X&hH`kbp)B3G5zV4RORJ!^^5dIBfLzmxt>!f5G04adm4rC}|);KSo8p z)HWMVDuYnOTLa_g>qE-yr>b|f(NZYoeQBD??IbOkVno8GO;HBZ=RT#T(D|%JrJv41 z;1U67SN|9?j*`qtG;L#Al_PJY=wI5o$bto>{U96=h4Xr4p~{P#B18|69cqZx9XQ#;Ox3$gB@htdtRsXnnJZdX2IMlk^?*> zG^B{V-5o*yV<$;`AY75mcwIpOIRtoT@BWk292z?}w^Xr8K~F|)7$po63N@rU0!ZUl+nAHa81OH0FmP@NB6 zor4$eZx{NDcfJp9erbw+&$E69acEBb(nt3m@+zS^Zy?R&>StlLrD1JRN`5FZ3Q`_Jm;{!QNdi;I3~X(_xha=+2luPV+> zFt0Co_8c>M!_YRX?`UXf-tL;R&&igD4X>wp{a1B`Y;Fh91?_r^X%sE^{qG8!@g>qF1zSktv1>$`k)lgy)4&TVipz_F8UB# zeE_#ZFS+PTzMj2aGrzNyD&!bBI$nqV#2vgs(UPQh*+D@@UIUL=X;gga&*k^B9r^-Z zYTl}f`>zIo?aHqZi&BgK`e5#ZJQ%?KE5615|9?L7gDk#jk2+lpF^2$uNsB9pRf-q{ F{yzd+$I<`* literal 0 HcmV?d00001 From 407d090f0a7b9071116a9b20589903a8cb96c5f9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 9 Oct 2024 15:11:55 +0200 Subject: [PATCH 332/338] name change from robotiq to ur and general cleanup --- .../bc_policy.py} | 8 +- .../record_demo.py | 8 +- .../run_rbc_actor.sh | 6 +- .../run_rbc_learner.sh | 8 +- .../test_demo.py | 4 +- .../drq_policy.py} | 12 +- .../encoder_feature_plot.py | 14 +-- .../experiment_setup/BC/run_rbc_actor.sh | 8 +- .../experiment_setup/BC/run_rbc_learner.sh | 13 +++ .../experiment_setup/BT/BehaviorTree.py | 0 .../experiment_setup/BT/bt_policy.py | 8 +- .../experiment_setup/BT/run_bt_actor.sh | 8 ++ .../experiment_setup/Depth Image/run_actor.sh | 4 +- .../Depth Image/run_evaluation.sh | 6 +- .../Depth Image/run_learner.sh | 8 +- .../experiment_setup/ResNet10/run_actor.sh | 4 +- .../ResNet10/run_evaluation.sh | 6 +- .../experiment_setup/ResNet10/run_learner.sh | 8 +- .../ResNet18 greyscale/run_actor.sh | 4 +- .../ResNet18 greyscale/run_evaluation.sh | 6 +- .../ResNet18 greyscale/run_learner.sh | 8 +- .../experiment_setup/ResNet18/run_actor.sh | 4 +- .../ResNet18/run_evaluation.sh | 6 +- .../experiment_setup/ResNet18/run_learner.sh | 8 +- .../experiment_setup/SAC/run_actor.sh | 4 +- .../experiment_setup/SAC/run_evaluation.sh | 6 +- .../experiment_setup/SAC/run_learner.sh | 8 +- .../experiment_setup/VoxNet/run_actor.sh | 4 +- .../experiment_setup/VoxNet/run_evaluation.sh | 6 +- .../experiment_setup/VoxNet/run_learner.sh | 8 +- .../VoxNet_1quat/run_actor.sh | 4 +- .../VoxNet_1quat/run_evaluation.sh | 6 +- .../VoxNet_1quat/run_learner.sh | 8 +- .../experiment_setup/VoxNet_only/run_actor.sh | 4 +- .../VoxNet_only/run_evaluation.sh | 6 +- .../VoxNet_only/run_learner.sh | 8 +- .../VoxNet_pretrained/run_actor.sh | 4 +- .../VoxNet_pretrained/run_evaluation.sh | 6 +- .../VoxNet_pretrained/run_learner.sh | 8 +- .../VoxNet_pretrained_1quat/run_actor.sh | 4 +- .../VoxNet_pretrained_1quat/run_evaluation.sh | 10 +- .../VoxNet_pretrained_1quat/run_learner.sh | 8 +- .../run_actor.sh | 4 +- .../run_evaluation.sh | 10 +- .../run_learner.sh | 8 +- .../experiment_setup/results_calculation.py | 0 .../record_demo.py | 10 +- .../run_actor.sh | 4 +- .../run_evaluation.sh | 6 +- .../run_learner.sh | 6 +- .../run_actor.sh | 6 +- .../run_evaluation.sh | 8 +- .../run_learner.sh | 10 +- .../sac_policy.py} | 14 +-- .../experiment_setup/BC/run_rbc_learner.sh | 13 --- .../experiment_setup/BT/run_bt_actor.sh | 8 -- .../serl_launcher/vision/resnet_v1_18.py | 2 +- ...obotiq_controller.py => ur5_controller.py} | 110 ++++++++++-------- serl_robot_infra/robotiq_env/__init__.py | 26 ----- serl_robot_infra/robotiq_env/envs/__init__.py | 1 - .../robotiq_env/envs/basic_env/__init__.py | 1 - .../robotiq_env/envs/camera_env/__init__.py | 1 - serl_robot_infra/ur_env/__init__.py | 33 ++++++ .../camera/__init__.py | 0 .../camera/rs_capture.py | 0 .../{robotiq_env => ur_env}/camera/utils.py | 4 +- .../camera/video_capture.py | 0 serl_robot_infra/ur_env/envs/__init__.py | 1 + .../ur_env/envs/basic_env/__init__.py | 1 + .../envs/basic_env/box_picking_basic_env.py} | 8 +- .../envs/basic_env/config.py | 6 +- .../ur_env/envs/camera_env/__init__.py | 1 + .../camera_env/box_picking_camera_env.py} | 21 ++-- .../envs/camera_env/config.py | 24 ++-- .../envs/relative_env.py | 2 +- .../robotiq_env.py => ur_env/envs/ur5_env.py} | 105 +++++++++++++---- .../{robotiq_env => ur_env}/envs/wrappers.py | 6 +- .../{robotiq_env => ur_env}/requirements.txt | 0 .../spacemouse/__init__.py | 0 .../spacemouse/spacemouse_expert.py | 0 .../spacemouse/spacemouse_test.py | 2 +- .../{robotiq_env => ur_env}/utils/__init__.py | 0 .../utils/real_time_plotter.py | 0 .../utils/rotations.py | 2 +- .../utils/vacuum_gripper.py | 0 85 files changed, 414 insertions(+), 331 deletions(-) rename examples/{robotiq_bc/bc_policy_robotiq.py => box_picking_bc/bc_policy.py} (97%) rename examples/{robotiq_bc => box_picking_bc}/record_demo.py (93%) rename examples/{robotiq_bc => box_picking_bc}/run_rbc_actor.sh (69%) rename examples/{robotiq_bc => box_picking_bc}/run_rbc_learner.sh (53%) rename examples/{robotiq_bc => box_picking_bc}/test_demo.py (94%) rename examples/{robotiq_drq/drq_policy_robotiq.py => box_picking_drq/drq_policy.py} (98%) rename examples/{robotiq_drq => box_picking_drq}/encoder_feature_plot.py (94%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/BC/run_rbc_actor.sh (51%) create mode 100644 examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/BT/BehaviorTree.py (100%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/BT/bt_policy.py (94%) create mode 100644 examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/Depth Image/run_actor.sh (78%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/Depth Image/run_evaluation.sh (55%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/Depth Image/run_learner.sh (53%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet10/run_actor.sh (82%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet10/run_evaluation.sh (64%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet10/run_learner.sh (60%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18 greyscale/run_actor.sh (82%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18 greyscale/run_evaluation.sh (64%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18 greyscale/run_learner.sh (60%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18/run_actor.sh (83%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18/run_evaluation.sh (64%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/ResNet18/run_learner.sh (62%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/SAC/run_actor.sh (77%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/SAC/run_evaluation.sh (57%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/SAC/run_learner.sh (53%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet/run_actor.sh (79%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet/run_evaluation.sh (60%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet/run_learner.sh (55%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_1quat/run_actor.sh (80%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_1quat/run_evaluation.sh (61%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_1quat/run_learner.sh (57%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_only/run_actor.sh (79%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_only/run_evaluation.sh (59%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_only/run_learner.sh (55%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained/run_actor.sh (80%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained/run_evaluation.sh (59%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained/run_learner.sh (56%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh (81%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh (57%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh (57%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh (81%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh (56%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh (57%) rename examples/{robotiq_drq => box_picking_drq}/experiment_setup/results_calculation.py (100%) rename examples/{robotiq_drq => box_picking_drq}/record_demo.py (92%) rename examples/{robotiq_drq => box_picking_drq}/run_actor.sh (85%) rename examples/{robotiq_drq => box_picking_drq}/run_evaluation.sh (66%) rename examples/{robotiq_drq => box_picking_drq}/run_learner.sh (70%) rename examples/{robotiq_sac => box_picking_sac}/run_actor.sh (74%) rename examples/{robotiq_sac => box_picking_sac}/run_evaluation.sh (61%) rename examples/{robotiq_sac => box_picking_sac}/run_learner.sh (59%) rename examples/{robotiq_sac/sac_policy_robotiq.py => box_picking_sac/sac_policy.py} (97%) delete mode 100644 examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh delete mode 100644 examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh rename serl_robot_infra/robot_controllers/{robotiq_controller.py => ur5_controller.py} (79%) delete mode 100644 serl_robot_infra/robotiq_env/__init__.py delete mode 100644 serl_robot_infra/robotiq_env/envs/__init__.py delete mode 100644 serl_robot_infra/robotiq_env/envs/basic_env/__init__.py delete mode 100644 serl_robot_infra/robotiq_env/envs/camera_env/__init__.py create mode 100644 serl_robot_infra/ur_env/__init__.py rename serl_robot_infra/{robotiq_env => ur_env}/camera/__init__.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/camera/rs_capture.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/camera/utils.py (97%) rename serl_robot_infra/{robotiq_env => ur_env}/camera/video_capture.py (100%) create mode 100644 serl_robot_infra/ur_env/envs/__init__.py create mode 100644 serl_robot_infra/ur_env/envs/basic_env/__init__.py rename serl_robot_infra/{robotiq_env/envs/basic_env/robotiq_basic_env.py => ur_env/envs/basic_env/box_picking_basic_env.py} (85%) rename serl_robot_infra/{robotiq_env => ur_env}/envs/basic_env/config.py (93%) create mode 100644 serl_robot_infra/ur_env/envs/camera_env/__init__.py rename serl_robot_infra/{robotiq_env/envs/camera_env/robotiq_camera_env.py => ur_env/envs/camera_env/box_picking_camera_env.py} (77%) rename serl_robot_infra/{robotiq_env => ur_env}/envs/camera_env/config.py (85%) rename serl_robot_infra/{robotiq_env => ur_env}/envs/relative_env.py (97%) rename serl_robot_infra/{robotiq_env/envs/robotiq_env.py => ur_env/envs/ur5_env.py} (87%) rename serl_robot_infra/{robotiq_env => ur_env}/envs/wrappers.py (97%) rename serl_robot_infra/{robotiq_env => ur_env}/requirements.txt (100%) rename serl_robot_infra/{robotiq_env => ur_env}/spacemouse/__init__.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/spacemouse/spacemouse_expert.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/spacemouse/spacemouse_test.py (91%) rename serl_robot_infra/{robotiq_env => ur_env}/utils/__init__.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/utils/real_time_plotter.py (100%) rename serl_robot_infra/{robotiq_env => ur_env}/utils/rotations.py (90%) rename serl_robot_infra/{robotiq_env => ur_env}/utils/vacuum_gripper.py (100%) diff --git a/examples/robotiq_bc/bc_policy_robotiq.py b/examples/box_picking_bc/bc_policy.py similarity index 97% rename from examples/robotiq_bc/bc_policy_robotiq.py rename to examples/box_picking_bc/bc_policy.py index ddb1babc..207031d4 100644 --- a/examples/robotiq_bc/bc_policy_robotiq.py +++ b/examples/box_picking_bc/bc_policy.py @@ -28,16 +28,16 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.networks.reward_classifier import load_classifier_func -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper -from robotiq_env.envs.relative_env import RelativeFrame +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from ur_env.envs.relative_env import RelativeFrame from serl_launcher.utils.sampling_utils import TemporalActionEnsemble -import robotiq_env +import ur_env FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_basic_env", "Name of environment.") +flags.DEFINE_string("env", "box_picking_basic_env", "Name of environment.") flags.DEFINE_string("agent", "bc_noimg", "Name of agent.") flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") diff --git a/examples/robotiq_bc/record_demo.py b/examples/box_picking_bc/record_demo.py similarity index 93% rename from examples/robotiq_bc/record_demo.py rename to examples/box_picking_bc/record_demo.py index 4153973d..1f79eead 100644 --- a/examples/robotiq_bc/record_demo.py +++ b/examples/box_picking_bc/record_demo.py @@ -9,12 +9,12 @@ from pprint import pprint from pynput import keyboard -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages from serl_launcher.wrappers.chunking import ChunkingWrapper from gymnasium.wrappers import TransformReward -from robotiq_env.envs.relative_env import RelativeFrame +from ur_env.envs.relative_env import RelativeFrame exit_program = threading.Event() @@ -32,7 +32,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq_basic_env") + env = gym.make("box_picking_basic_env") env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) @@ -57,7 +57,7 @@ def on_esc(key): listener_2.start() uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") - file_name = f"robotiq_test_{success_needed}_demos_{uuid}.pkl" + file_name = f"ur5_test_{success_needed}_demos_{uuid}.pkl" file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script file_path = os.path.join(file_dir, file_name) diff --git a/examples/robotiq_bc/run_rbc_actor.sh b/examples/box_picking_bc/run_rbc_actor.sh similarity index 69% rename from examples/robotiq_bc/run_rbc_actor.sh rename to examples/box_picking_bc/run_rbc_actor.sh index f0880d4d..5862c8cd 100644 --- a/examples/robotiq_bc/run_rbc_actor.sh +++ b/examples/box_picking_bc/run_rbc_actor.sh @@ -1,9 +1,9 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ which python && \ -python bc_policy_robotiq.py "$@" \ - --env robotiq_basic_env \ - --exp_name=bc_robotiq_policy \ +python bc_policy.py "$@" \ + --env box_picking_basic_env \ + --exp_name=bc_drq_policy \ --seed 42 \ --batch_size 256 \ --eval_checkpoint_step 50000 \ diff --git a/examples/robotiq_bc/run_rbc_learner.sh b/examples/box_picking_bc/run_rbc_learner.sh similarity index 53% rename from examples/robotiq_bc/run_rbc_learner.sh rename to examples/box_picking_bc/run_rbc_learner.sh index e46ca784..79b64cbc 100644 --- a/examples/robotiq_bc/run_rbc_learner.sh +++ b/examples/box_picking_bc/run_rbc_learner.sh @@ -1,10 +1,10 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python bc_policy_robotiq.py "$@" \ - --env robotiq_basic_env \ - --exp_name=bc_robotiq_policy \ +python bc_policy.py "$@" \ + --env box_picking_basic_env \ + --exp_name=bc_drq_policy \ --seed 42 \ --batch_size 256 \ - --demo_paths robotiq_grip_v1/robotiq_test_20_demos_2024-03-26_12-23-50.pkl \ + --demo_paths "" \ --eval_checkpoint_step 0 # --debug # wandb is disabled when debug diff --git a/examples/robotiq_bc/test_demo.py b/examples/box_picking_bc/test_demo.py similarity index 94% rename from examples/robotiq_bc/test_demo.py rename to examples/box_picking_bc/test_demo.py index a7a37c3d..ee15a307 100644 --- a/examples/robotiq_bc/test_demo.py +++ b/examples/box_picking_bc/test_demo.py @@ -4,7 +4,7 @@ import gymnasium as gym from pynput import keyboard -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages exit_program = threading.Event() @@ -27,7 +27,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq_basic_env") + env = gym.make("box_picking_basic_env") env = SpacemouseIntervention(env) # env = RelativeFrame(env) env = Quat2MrpWrapper(env) diff --git a/examples/robotiq_drq/drq_policy_robotiq.py b/examples/box_picking_drq/drq_policy.py similarity index 98% rename from examples/robotiq_drq/drq_policy_robotiq.py rename to examples/box_picking_drq/drq_policy.py index 5ea79810..47a0dc89 100644 --- a/examples/robotiq_drq/drq_policy_robotiq.py +++ b/examples/box_picking_drq/drq_policy.py @@ -39,12 +39,12 @@ from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper -from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper +from ur_env.envs.relative_env import RelativeFrame +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper from serl_launcher.vision.data_augmentations import batched_random_rot90_state, batched_random_rot90_voxel, \ batched_random_rot90_action -import robotiq_env +import ur_env # used to debug nan errors (also in jit-ed functions) # jax.config.update("jax_debug_nans", True) @@ -55,7 +55,7 @@ FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") flags.DEFINE_string("agent", "drq", "Name of agent.") flags.DEFINE_string("exp_name", "DRQ agent", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") @@ -98,11 +98,11 @@ flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints', "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/rlds', +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") diff --git a/examples/robotiq_drq/encoder_feature_plot.py b/examples/box_picking_drq/encoder_feature_plot.py similarity index 94% rename from examples/robotiq_drq/encoder_feature_plot.py rename to examples/box_picking_drq/encoder_feature_plot.py index c29d34e7..bed9fb7b 100644 --- a/examples/robotiq_drq/encoder_feature_plot.py +++ b/examples/box_picking_drq/encoder_feature_plot.py @@ -31,10 +31,10 @@ ) from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper -from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper +from ur_env.envs.relative_env import RelativeFrame +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper -import robotiq_env +import ur_env devices = jax.local_devices() num_devices = len(devices) @@ -42,7 +42,7 @@ FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") flags.DEFINE_string("agent", "drq", "Name of agent.") flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") @@ -71,13 +71,13 @@ flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints', +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints', "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") @@ -134,7 +134,7 @@ def main(_): import pickle as pkl - with open("/examples/robotiq_drq/old_demos/pcb_insert_20_demos_mai3_streamlined.pkl", "rb") as f: + with open("/examples/box_picking_drq/old_demos/box_picking_20_demos_mai3_streamlined.pkl", "rb") as f: trajs = pkl.load(f) for traj in trajs: demo_buffer.insert(traj) diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh b/examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh similarity index 51% rename from examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh rename to examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh index 1ec2053d..fc53ffa7 100644 --- a/examples/robotiq_drq/experiment_setup/BC/run_rbc_actor.sh +++ b/examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ which python && \ -python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ - --env robotiq_camera_env_eval \ - --exp_name=bc_robotiq_policy \ +python /home/nico/real-world-rl/serl/examples/box_picking_bc/bc_policy.py "$@" \ + --env box_picking_camera_env_eval \ + --exp_name=bc_drq_policy \ --seed 1 \ --max_traj_length 100 \ --batch_size 2048 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BC/checkpoints \ --eval_checkpoint_step 5000 \ --eval_n_trajs 30 \ --debug # wandb is disabled when debug diff --git a/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh b/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh new file mode 100644 index 00000000..7b5be61c --- /dev/null +++ b/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh @@ -0,0 +1,13 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +python /home/nico/real-world-rl/serl/examples/box_picking_bc/bc_policy.py "$@" \ + --env box_picking_camera_env \ + --exp_name=bc_drq_policy \ + --seed 1 \ + --batch_size 2048 \ + --max_steps 25000 \ + --demo_paths /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_state_only.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BC/checkpoints \ + --checkpoint_period 1000 \ + --eval_checkpoint_step 0 \ +# --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py b/examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py similarity index 100% rename from examples/robotiq_drq/experiment_setup/BT/BehaviorTree.py rename to examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py diff --git a/examples/robotiq_drq/experiment_setup/BT/bt_policy.py b/examples/box_picking_drq/experiment_setup/BT/bt_policy.py similarity index 94% rename from examples/robotiq_drq/experiment_setup/BT/bt_policy.py rename to examples/box_picking_drq/experiment_setup/BT/bt_policy.py index e15bc9b6..217f093d 100644 --- a/examples/robotiq_drq/experiment_setup/BT/bt_policy.py +++ b/examples/box_picking_drq/experiment_setup/BT/bt_policy.py @@ -20,17 +20,17 @@ from serl_launcher.wrappers.chunking import ChunkingWrapper from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper -from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import Quat2MrpWrapper, ObservationRotationWrapper +from ur_env.envs.relative_env import RelativeFrame +from ur_env.envs.wrappers import Quat2MrpWrapper, ObservationRotationWrapper -import robotiq_env +import ur_env from serl_launcher.utils.launcher import make_wandb_logger from serl_launcher.utils.sampling_utils import TemporalActionEnsemble FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_camera_env", "Name of environment.") +flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") flags.DEFINE_string("exp_name", "BT agent", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("eval_n_trajs", 10, "Number of trajectories for evaluation.") diff --git a/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh b/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh new file mode 100644 index 00000000..ab1c2762 --- /dev/null +++ b/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh @@ -0,0 +1,8 @@ +export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ +export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ +which python && \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BT/bt_policy.py "$@" \ + --env box_picking_camera_env_eval \ + --exp_name=bt_drq_policy \ + --max_traj_length 100 \ + --eval_n_trajs 30 \ diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh similarity index 78% rename from examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh rename to examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh index d01e7c74..3397de89 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="Depth Image small encoder" \ --camera_mode depth \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh similarity index 55% rename from examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh index c7ebd7d0..f625c24e 100644 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="Depth Image Evaluation" \ --camera_mode depth \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth Image/checkpoints Depth image small encoder 0827-16:55"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/Depth Image/checkpoints Depth image small encoder 0827-16:55"\ --eval_checkpoint_step 22000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh similarity index 53% rename from examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh rename to examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh index 7143fc74..206e4711 100755 --- a/examples/robotiq_drq/experiment_setup/Depth Image/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="Depth image small encoder" \ --camera_mode depth \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/Depth\ Image/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_08-24_15-40-34_depth_20cm.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/Depth\ Image/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_08-24_15-40-34_depth_20cm.pkl \ \ --encoder_type small \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh similarity index 82% rename from examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh rename to examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh index 76f1d6fb..c873ad67 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet10/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet10 one cam" \ --camera_mode rgb \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh similarity index 64% rename from examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh index 9575b8a5..21bdd764 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet10/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="ResNet10 Evaluation" \ --camera_mode rgb \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet10/checkpoints ResNet10 one cam 0821-11:18"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet10/checkpoints ResNet10 one cam 0821-11:18"\ --eval_checkpoint_step 15000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh similarity index 60% rename from examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh rename to examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh index 3a91346b..1ae872a4 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet10/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet10 one cam" \ --camera_mode rgb \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet10/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet10/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh similarity index 82% rename from examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh rename to examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh index f167612e..417f7840 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet18 greyscale" \ --camera_mode grey \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh similarity index 64% rename from examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh index ea1caf2c..fef11794 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="ResNet18 greyscale Evaluation" \ --camera_mode grey \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/checkpoints ResNet18 greyscale 0821-14:23"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/checkpoints ResNet18 greyscale 0821-14:23"\ --eval_checkpoint_step 11000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh similarity index 60% rename from examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh rename to examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh index 9a92bce1..8bd29682 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18 greyscale/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet18 greyscale" \ --camera_mode grey \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh similarity index 83% rename from examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh rename to examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh index a222da14..cb65d2cc 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet18 feat red 32 128" \ --camera_mode rgb \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh similarity index 64% rename from examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh index 56a9235d..da923bb7 100644 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="ResNet18 Evaluation" \ --camera_mode rgb \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints ResNet18 ssam 128 0820-19:23"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18/checkpoints ResNet18 ssam 128 0820-19:23"\ --eval_checkpoint_step 12000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh similarity index 62% rename from examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh rename to examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh index c3989a48..4f47e5bf 100755 --- a/examples/robotiq_drq/experiment_setup/ResNet18/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="ResNet18 feat red 32 128" \ --camera_mode rgb \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 96 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/ResNet18/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type resnet-pretrained-18 \ --encoder_bottleneck_dim 128 \ diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh b/examples/box_picking_drq/experiment_setup/SAC/run_actor.sh similarity index 77% rename from examples/robotiq_drq/experiment_setup/SAC/run_actor.sh rename to examples/box_picking_drq/experiment_setup/SAC/run_actor.sh index ad7b8de2..77fe7c36 100755 --- a/examples/robotiq_drq/experiment_setup/SAC/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/SAC/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="SAC no images" \ --camera_mode none \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh similarity index 57% rename from examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh index baf9433d..d3f81f4e 100644 --- a/examples/robotiq_drq/experiment_setup/SAC/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="SAC no images Evaluation" \ --camera_mode none \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints SAC no images 0820-17:01"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/SAC/checkpoints SAC no images 0820-17:01"\ --eval_checkpoint_step 40000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh b/examples/box_picking_drq/experiment_setup/SAC/run_learner.sh similarity index 53% rename from examples/robotiq_drq/experiment_setup/SAC/run_learner.sh rename to examples/box_picking_drq/experiment_setup/SAC/run_learner.sh index 3f882456..fbc3c431 100755 --- a/examples/robotiq_drq/experiment_setup/SAC/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/SAC/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="SAC no images" \ --camera_mode none \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 2048 \ --checkpoint_period 2500 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/SAC/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/SAC/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ \ --encoder_type none \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh similarity index 79% rename from examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh index 3c45787c..3f725561 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="Voxnet" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh similarity index 60% rename from examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh index d602298f..177d0caf 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="Voxnet Evaluation unseen" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints Voxnet 0821-16:06"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet/checkpoints Voxnet 0821-16:06"\ --eval_checkpoint_step 11000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh similarity index 55% rename from examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh index b692dfac..d6c4ae28 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="Voxnet" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh similarity index 80% rename from examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh index ace5e042..29dc0158 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh similarity index 61% rename from examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh index ce825099..a6801361 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="Voxnet 1quat Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet 1quat 0822-17:54"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet 1quat 0822-17:54"\ --eval_checkpoint_step 18000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh similarity index 57% rename from examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh index f21c5604..6c327d06 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_1quat/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh similarity index 79% rename from examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh index 4ab5e4d1..fb9b7ce2 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet only" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh similarity index 59% rename from examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh index 8ede2665..d49d845b 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="Voxnet only Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only/checkpoints voxnet only 0822-13:43"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_only/checkpoints voxnet only 0822-13:43"\ --eval_checkpoint_step 13000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh similarity index 55% rename from examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh index f8e62940..d254ca74 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_only/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet only" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_only/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_only/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet \ --state_mask none \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh similarity index 80% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh index 5e9c3ce6..a1dcfe39 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh similarity index 59% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh index fa5c1615..dc391258 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_eval \ --exp_name="Voxnet Pretrained Evaluation" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ --eval_checkpoint_step 10000 \ --eval_n_trajs 30 \ \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh similarity index 56% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh index e0795850..50c30496 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ \ --encoder_type voxnet-pretrained \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh similarity index 81% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh index 7b3db828..11b12038 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh similarity index 57% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh index 16f0e9bf..d6b5d9ed 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh @@ -1,19 +1,19 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_demo \ --exp_name="Voxnet pq temp ens" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints voxnet pretrained 1quat 0823-10:45"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints voxnet pretrained 1quat 0823-10:45"\ --eval_checkpoint_step 13000 \ - --eval_n_trajs 30 \ + --eval_n_trajs 50 \ \ --encoder_type voxnet-pretrained \ --state_mask all \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ --enable_temporal_ensemble_sampling \ -# --debug + --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh similarity index 57% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh index 4de78e24..0d906b5e 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet-pretrained \ --state_mask all \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh similarity index 81% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh index 715913bf..aaf7b8ee 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained gripper_only 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh similarity index 56% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh index 68f14ffe..4bf4d8ad 100644 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh @@ -1,19 +1,19 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_eval \ + --env box_picking_camera_env_demo \ --exp_name="voxnet [pqg] temp ens" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints voxnet pretrained gripper_only 1quat 0829-14:08"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints voxnet pretrained gripper_only 1quat 0829-14:08"\ --eval_checkpoint_step 12000 \ - --eval_n_trajs 30 \ + --eval_n_trajs 50 \ \ --encoder_type voxnet-pretrained \ --state_mask gripper \ --encoder_bottleneck_dim 128 \ --enable_obs_rotation_wrapper \ --enable_temporal_ensemble_sampling \ -# --debug + --debug diff --git a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh similarity index 57% rename from examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh rename to examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh index 1355cb4e..e31c7b67 100755 --- a/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py "$@" \ +python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name="voxnet pretrained gripper_only 1quat" \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -13,8 +13,8 @@ python /home/nico/real-world-rl/serl/examples/robotiq_drq/drq_policy_robotiq.py --utd_ratio 8 \ --batch_size 128 \ --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ + --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ \ --encoder_type voxnet-pretrained \ --state_mask gripper \ diff --git a/examples/robotiq_drq/experiment_setup/results_calculation.py b/examples/box_picking_drq/experiment_setup/results_calculation.py similarity index 100% rename from examples/robotiq_drq/experiment_setup/results_calculation.py rename to examples/box_picking_drq/experiment_setup/results_calculation.py diff --git a/examples/robotiq_drq/record_demo.py b/examples/box_picking_drq/record_demo.py similarity index 92% rename from examples/robotiq_drq/record_demo.py rename to examples/box_picking_drq/record_demo.py index de73dc99..6e1da63b 100644 --- a/examples/robotiq_drq/record_demo.py +++ b/examples/box_picking_drq/record_demo.py @@ -8,13 +8,13 @@ import threading from pynput import keyboard -from robotiq_env.envs.relative_env import RelativeFrame -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper +from ur_env.envs.relative_env import RelativeFrame +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper from serl_launcher.wrappers.chunking import ChunkingWrapper -import robotiq_env +import ur_env exit_program = threading.Event() @@ -32,7 +32,7 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("robotiq_camera_env", + env = gym.make("box_picking_camera_env", camera_mode="pointcloud", max_episode_length=100, ) @@ -40,7 +40,7 @@ def on_esc(key): env = RelativeFrame(env) env = Quat2MrpWrapper(env) env = ScaleObservationWrapper(env) - env = ObservationRotationWrapper(env) # if it should be enabled + # env = ObservationRotationWrapper(env) # if it should be enabled env = SERLObsWrapper(env) env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) diff --git a/examples/robotiq_drq/run_actor.sh b/examples/box_picking_drq/run_actor.sh similarity index 85% rename from examples/robotiq_drq/run_actor.sh rename to examples/box_picking_drq/run_actor.sh index d6f4c77f..06370bd8 100755 --- a/examples/robotiq_drq/run_actor.sh +++ b/examples/box_picking_drq/run_actor.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python drq_policy_robotiq.py "$@" \ +python drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --max_traj_length 100 \ --exp_name=d \ --camera_mode pointcloud \ diff --git a/examples/robotiq_drq/run_evaluation.sh b/examples/box_picking_drq/run_evaluation.sh similarity index 66% rename from examples/robotiq_drq/run_evaluation.sh rename to examples/box_picking_drq/run_evaluation.sh index 200a5d64..4c7c9dfb 100644 --- a/examples/robotiq_drq/run_evaluation.sh +++ b/examples/box_picking_drq/run_evaluation.sh @@ -1,13 +1,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python drq_policy_robotiq.py "$@" \ +python drq_policy.py "$@" \ --actor \ - --env robotiq_camera_env_tests \ + --env box_picking_camera_env_tests \ --exp_name=drq_evaluation \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_drq/checkpoints voxnet only pure 32 16 8 noFT (else all) 0816-17:14"\ + --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints voxnet only pure 32 16 8 noFT (else all) 0816-17:14"\ --eval_checkpoint_step 12500 \ --eval_n_trajs 20 \ \ diff --git a/examples/robotiq_drq/run_learner.sh b/examples/box_picking_drq/run_learner.sh similarity index 70% rename from examples/robotiq_drq/run_learner.sh rename to examples/box_picking_drq/run_learner.sh index 69987bba..c31c0ff5 100755 --- a/examples/robotiq_drq/run_learner.sh +++ b/examples/box_picking_drq/run_learner.sh @@ -1,8 +1,8 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python drq_policy_robotiq.py "$@" \ +python drq_policy.py "$@" \ --learner \ - --env robotiq_camera_env \ + --env box_picking_camera_env \ --exp_name=d \ --camera_mode pointcloud \ --max_traj_length 100 \ @@ -15,5 +15,5 @@ python drq_policy_robotiq.py "$@" \ --eval_period 20000 \ --encoder_type voxnet-pretrained \ --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/robotiq_drq/pcb_insert_20_demos_aug9_noFT_1quad.pkl \ + --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/box_picking_20_demos_aug9_noFT_1quad.pkl \ # --debug diff --git a/examples/robotiq_sac/run_actor.sh b/examples/box_picking_sac/run_actor.sh similarity index 74% rename from examples/robotiq_sac/run_actor.sh rename to examples/box_picking_sac/run_actor.sh index a00edb04..fac4186b 100644 --- a/examples/robotiq_sac/run_actor.sh +++ b/examples/box_picking_sac/run_actor.sh @@ -1,9 +1,9 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy_robotiq.py "$@" \ +python sac_policy.py "$@" \ --actor \ - --env robotiq_basic_env \ - --exp_name=sac_robotiq_policy \ + --env box_picking_basic_env \ + --exp_name=sac_drq_policy \ --max_traj_length 300 \ --seed 42 \ --max_steps 10000 \ diff --git a/examples/robotiq_sac/run_evaluation.sh b/examples/box_picking_sac/run_evaluation.sh similarity index 61% rename from examples/robotiq_sac/run_evaluation.sh rename to examples/box_picking_sac/run_evaluation.sh index 78f7048c..40eb31e5 100644 --- a/examples/robotiq_sac/run_evaluation.sh +++ b/examples/box_picking_sac/run_evaluation.sh @@ -1,10 +1,10 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy_robotiq.py "$@" \ +python sac_policy.py "$@" \ --actor \ - --env robotiq_basic_env \ - --exp_name=sac_robotiq_policy_evaluation \ - --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints 0411-16:46"\ + --env box_picking_basic_env \ + --exp_name=sac_drq_policy_evaluation \ + --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_sac/checkpoints 0411-16:46"\ --eval_checkpoint_step 100000 \ --eval_n_trajs 10 \ --debug diff --git a/examples/robotiq_sac/run_learner.sh b/examples/box_picking_sac/run_learner.sh similarity index 59% rename from examples/robotiq_sac/run_learner.sh rename to examples/box_picking_sac/run_learner.sh index 02ee98c3..5027e9d2 100644 --- a/examples/robotiq_sac/run_learner.sh +++ b/examples/box_picking_sac/run_learner.sh @@ -1,9 +1,9 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy_robotiq.py "$@" \ +python sac_policy.py "$@" \ --learner \ - --env robotiq_basic_env \ - --exp_name=sac_robotiq_policy \ + --env box_picking_basic_env \ + --exp_name=sac_drq_policy \ --max_traj_length 300 \ --seed 42 \ --training_starts 900 \ @@ -11,6 +11,6 @@ python sac_policy_robotiq.py "$@" \ --batch_size 2048 \ --max_steps 50000 \ --reward_scale 1 \ - --demo_paths "/home/nico/real-world-rl/serl/examples/robotiq_sac/robotiq_test_20_demos_apr11_random_boxes.pkl" \ -# --preload_rlds_path "/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds" \ + --demo_paths "/home/nico/real-world-rl/serl/examples/box_picking_sac/robotiq_test_20_demos_apr11_random_boxes.pkl" \ +# --preload_rlds_path "/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds" \ # --debug diff --git a/examples/robotiq_sac/sac_policy_robotiq.py b/examples/box_picking_sac/sac_policy.py similarity index 97% rename from examples/robotiq_sac/sac_policy_robotiq.py rename to examples/box_picking_sac/sac_policy.py index 62df86ff..2acf8d8a 100644 --- a/examples/robotiq_sac/sac_policy_robotiq.py +++ b/examples/box_picking_sac/sac_policy.py @@ -20,7 +20,7 @@ from serl_launcher.data.data_store import populate_data_store from serl_launcher.wrappers.chunking import ChunkingWrapper -from robotiq_env.envs.relative_env import RelativeFrame +from ur_env.envs.relative_env import RelativeFrame from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore @@ -33,15 +33,15 @@ ) from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from robotiq_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper +from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper -import robotiq_env +import ur_env FLAGS = flags.FLAGS -flags.DEFINE_string("env", "robotiq_basic_env", "Name of environment.") +flags.DEFINE_string("env", "box_picking_basic_env", "Name of environment.") flags.DEFINE_string("agent", "sac", "Name of agent.") -flags.DEFINE_string("exp_name", "sac_robotiq_policy", "Name of the experiment for wandb logging.") +flags.DEFINE_string("exp_name", "sac_drq_policy", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") flags.DEFINE_integer("seed", 42, "Random seed.") flags.DEFINE_bool("save_model", True, "Whether to save model.") @@ -67,13 +67,13 @@ flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/checkpoints', +flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/checkpoints', "Path to save checkpoints.") flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") flags.DEFINE_string("eval_checkpoint_path", None, "evaluate the policy from ckpt from this path") -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/robotiq_sac/rlds', +flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds', "Path to save RLDS logs.") flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") diff --git a/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh b/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh deleted file mode 100644 index e986e783..00000000 --- a/examples/robotiq_drq/experiment_setup/BC/run_rbc_learner.sh +++ /dev/null @@ -1,13 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/robotiq_bc/bc_policy_robotiq.py "$@" \ - --env robotiq_camera_env \ - --exp_name=bc_robotiq_policy \ - --seed 1 \ - --batch_size 2048 \ - --max_steps 25000 \ - --demo_paths /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/box_picking_20_demos_2024-08-20_state_only.pkl \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BC/checkpoints \ - --checkpoint_period 1000 \ - --eval_checkpoint_step 0 \ -# --debug # wandb is disabled when debug diff --git a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh b/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh deleted file mode 100644 index 05e760cb..00000000 --- a/examples/robotiq_drq/experiment_setup/BT/run_bt_actor.sh +++ /dev/null @@ -1,8 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -which python && \ -python /home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/BT/bt_policy.py "$@" \ - --env robotiq_camera_env_eval \ - --exp_name=bt_robotiq_policy \ - --max_traj_length 100 \ - --eval_n_trajs 30 \ diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py index a22412ce..92c3a997 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1_18.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -418,7 +418,7 @@ def __call__(self, observations, train=False): resnetv1_18_configs = { "resnetv1-18-frozen": functools.partial( ResNet, architecture='resnet18', - ckpt_dir="/home/nico/real-world-rl/serl/examples/robotiq_drq/resnet18_weights.h5", + ckpt_dir="/examples/box_picking_drq/resnet18_weights.h5", pre_pooling=True ) } diff --git a/serl_robot_infra/robot_controllers/robotiq_controller.py b/serl_robot_infra/robot_controllers/ur5_controller.py similarity index 79% rename from serl_robot_infra/robot_controllers/robotiq_controller.py rename to serl_robot_infra/robot_controllers/ur5_controller.py index bde06bc7..10a81d6b 100644 --- a/serl_robot_infra/robot_controllers/robotiq_controller.py +++ b/serl_robot_infra/robot_controllers/ur5_controller.py @@ -4,12 +4,13 @@ import asyncio import numpy as np import matplotlib.pyplot as plt +from responses import target from scipy.spatial.transform import Rotation as R from rtde_control import RTDEControlInterface from rtde_receive import RTDEReceiveInterface -from robotiq_env.utils.vacuum_gripper import VacuumGripper -from robotiq_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2rotvec, pose2quat +from ur_env.utils.vacuum_gripper import VacuumGripper +from ur_env.utils.rotations import rotvec_2_quat, quat_2_rotvec, pose2rotvec, pose2quat np.set_printoptions(precision=4, suppress=True) @@ -23,7 +24,7 @@ def pos_difference(quat_pose_1: np.ndarray, quat_pose_2: np.ndarray): return p_diff + r_diff -class RobotiqImpedanceController(threading.Thread): +class UrImpedanceController(threading.Thread): def __init__( self, robot_ip, @@ -36,7 +37,7 @@ def __init__( *args, **kwargs ): - super(RobotiqImpedanceController, self).__init__(*args, **kwargs) + super(UrImpedanceController, self).__init__(*args, **kwargs) self._stop = threading.Event() self._reset = threading.Event() self._is_ready = threading.Event() @@ -62,6 +63,7 @@ def __init__( self.curr_force = np.zeros((6,), dtype=np.float32) self.reset_Q = np.array([np.pi / 2., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.], dtype=np.float32) # reset state in Joint Space + self.reset_Pose = np.zeros_like(self.reset_Q) self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable self.delta = config.ERROR_DELTA @@ -70,8 +72,8 @@ def __init__( self.fm_selection_vector = config.FORCEMODE_SELECTION_VECTOR self.fm_limits = config.FORCEMODE_LIMITS - self.robotiq_control: RTDEControlInterface = None - self.robotiq_receive: RTDEReceiveInterface = None + self.ur_control: RTDEControlInterface = None + self.ur_receive: RTDEReceiveInterface = None self.robotiq_gripper: VacuumGripper = None # only temporary to test @@ -95,9 +97,9 @@ def print(self, msg, both=False): if both: print(msg) - async def start_robotiq_interfaces(self, gripper=True): - self.robotiq_control = RTDEControlInterface(self.robot_ip) - self.robotiq_receive = RTDEReceiveInterface(self.robot_ip) + async def start_ur_interfaces(self, gripper=True): + self.ur_control = RTDEControlInterface(self.robot_ip) + self.ur_receive = RTDEReceiveInterface(self.robot_ip) if gripper: self.robotiq_gripper = VacuumGripper(self.robot_ip) await self.robotiq_gripper.connect() @@ -106,22 +108,22 @@ async def start_robotiq_interfaces(self, gripper=True): gr_string = "(with gripper) " if gripper else "" print(f"[RIC] Controller connected to robot {gr_string}at: {self.robot_ip}") - async def restart_robotiq_interface(self): + async def restart_ur_interface(self): self._is_truncated.set() self.print("[RIC] forcemode failed, is now truncated!") # disconnect and reconnect, otherwise the controller won't take any commands - self.robotiq_control.disconnect() + self.ur_control.disconnect() try: print(f"[RTDE] trying to reconnect") - self.robotiq_control.reconnect() + self.ur_control.reconnect() except RuntimeError: - self.robotiq_receive.disconnect() + self.ur_receive.disconnect() for _ in range(10): try: - self.robotiq_control.disconnect() - self.robotiq_receive.disconnect() - await self.start_robotiq_interfaces(gripper=False) + self.ur_control.disconnect() + self.ur_receive.disconnect() + await self.start_ur_interfaces(gripper=False) return except Exception as e: print(e) @@ -155,6 +157,11 @@ def set_reset_Q(self, reset_Q: np.ndarray): self.reset_Q[:] = reset_Q self._reset.set() + def set_reset_pose(self, reset_pose: np.ndarray): + with self.lock: + self.reset_Pose[:] = reset_pose + self._reset.set() + def set_gripper_pos(self, target_grip: np.ndarray): with self.lock: self.target_grip[:] = target_grip @@ -167,11 +174,11 @@ def get_target_pos(self, copy=True): return self.target_pos async def _update_robot_state(self): - pos = self.robotiq_receive.getActualTCPPose() - vel = self.robotiq_receive.getActualTCPSpeed() - Q = self.robotiq_receive.getActualQ() - Qd = self.robotiq_receive.getActualQd() - force = self.robotiq_receive.getActualTCPForce() + pos = self.ur_receive.getActualTCPPose() + vel = self.ur_receive.getActualTCPSpeed() + Q = self.ur_receive.getActualQ() + Qd = self.ur_receive.getActualQd() + force = self.ur_receive.getActualTCPForce() pressure = await self.robotiq_gripper.get_current_pressure() obj_status = await self.robotiq_gripper.get_object_status() @@ -230,8 +237,8 @@ def _calculate_force(self): torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable # check for big downward tcp force and adapt accordingly - if self.curr_force[2] > 3.5 and force_pos[2] < 0.: - force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. + # if self.curr_force[2] > 3.5 and force_pos[2] < 0.: + # force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. return np.concatenate((force_pos, torque)) @@ -242,7 +249,7 @@ def plot(self): self.hist_data[1].append(self.target_pos.copy()) return - self.robotiq_control.forceModeStop() + self.ur_control.forceModeStop() print("[RIC] plotting") real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) @@ -302,49 +309,54 @@ def run(self): self.stop() async def _go_to_reset_pose(self): - self.robotiq_control.forceModeStop() + self.ur_control.forceModeStop() # first disable vaccum gripper - if self.robotiq_gripper: - await self.send_gripper_command(force_release=True) - time.sleep(0.01) + # if self.robotiq_gripper: + # await self.send_gripper_command(force_release=True) + # time.sleep(0.01) # then move up (so no boxes are moved) success = True while self.curr_pos[2] < self.reset_height: if self.curr_Q[2] < 0.5: # if the shoulder joint is near 180deg --> do not move into singularity - success = success and self.robotiq_control.speedJ([0., -1., 1., 0., 0., 0.], acceleration=0.8) + success = success and self.ur_control.speedJ([0., -1., 1., 0., 0., 0.], acceleration=0.8) else: - success = success and self.robotiq_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) + success = success and self.ur_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) await self._update_robot_state() time.sleep(0.01) - self.robotiq_control.speedStop(a=1.) + self.ur_control.speedStop(a=1.) - # then move to desired Jointspace position - success = success and self.robotiq_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) - self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) + if self.reset_Pose.std() > 0.001: + success = success and self.ur_control.moveL(self.reset_Pose, speed=0.5, acceleration=0.3) + self.print(f"[RIC] moving to {self.reset_Pose} with moveL (task space)", both=self.verbose) + self.reset_Pose[:] = 0. + else: + # then move to desired Jointspace position + success = success and self.ur_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) + self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) time.sleep(0.1) # wait for 100ms await self._update_robot_state() with self.lock: self.target_pos = self.curr_pos.copy() - self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster - self.robotiq_control.zeroFtSensor() + self.ur_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.ur_control.zeroFtSensor() if not success: # restart if not successful - await self.restart_robotiq_interface() + await self.restart_ur_interface() else: self._reset.clear() async def run_async(self): - await self.start_robotiq_interfaces(gripper=True) + await self.start_ur_interfaces(gripper=True) - self.robotiq_control.forceModeSetDamping(self.fm_damping) # less damping = Faster + self.ur_control.forceModeSetDamping(self.fm_damping) # less damping = Faster try: dt = 1. / self.frequency - self.robotiq_control.zeroFtSensor() + self.ur_control.zeroFtSensor() await self._update_robot_state() self.target_pos = self.curr_pos.copy() print(f"[RIC] target position set to curr pos: {self.target_pos}") @@ -372,8 +384,8 @@ async def run_async(self): self.print(f" p:{self.curr_pos} f:{self.curr_force_lowpass} gr:{self.gripper_state}") # log to file # send command to robot - t_start = self.robotiq_control.initPeriod() - fm_successful = self.robotiq_control.forceMode( + t_start = self.ur_control.initPeriod() + fm_successful = self.ur_control.forceMode( self.fm_task_frame, self.fm_selection_vector, force, @@ -381,13 +393,13 @@ async def run_async(self): self.fm_limits ) if not fm_successful: # truncate if the robot ends up in a singularity - await self.restart_robotiq_interface() + await self.restart_ur_interface() await self._go_to_reset_pose() if self.robotiq_gripper: await self.send_gripper_command() - self.robotiq_control.waitPeriod(t_start) + self.ur_control.waitPeriod(t_start) a = dt - (time.monotonic() - t_now) time.sleep(max(0., a)) @@ -399,7 +411,7 @@ async def run_async(self): if self.verbose: print(f"[RTDEPositionalController] >dt: {self.err}

float: # huge action gives negative reward (like in mountain car) diff --git a/serl_robot_infra/robotiq_env/envs/basic_env/config.py b/serl_robot_infra/ur_env/envs/basic_env/config.py similarity index 93% rename from serl_robot_infra/robotiq_env/envs/basic_env/config.py rename to serl_robot_infra/ur_env/envs/basic_env/config.py index e6e5df44..16905566 100644 --- a/serl_robot_infra/robotiq_env/envs/basic_env/config.py +++ b/serl_robot_infra/ur_env/envs/basic_env/config.py @@ -1,8 +1,8 @@ -from robotiq_env.envs.robotiq_env import DefaultEnvConfig +from ur_env.envs.ur5_env import DefaultEnvConfig import numpy as np -class RobotiqCornerConfig(DefaultEnvConfig): +class UR5CornerConfig(DefaultEnvConfig): # RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) # original one # RESET_Q = np.array([[1.3463, -1.3584, 1.9014, -2.1243, -1.5758, -0.2312]]) RESET_Q = np.array([ @@ -31,7 +31,7 @@ class RobotiqCornerConfig(DefaultEnvConfig): FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) -class RobotiqCornerConfigV1(DefaultEnvConfig): +class UR5CornerConfigV1(DefaultEnvConfig): """ Configuration for the first set of SAC training's (only 1 box) """ diff --git a/serl_robot_infra/ur_env/envs/camera_env/__init__.py b/serl_robot_infra/ur_env/envs/camera_env/__init__.py new file mode 100644 index 00000000..a951a43a --- /dev/null +++ b/serl_robot_infra/ur_env/envs/camera_env/__init__.py @@ -0,0 +1 @@ +from ur_env.envs.camera_env.box_picking_camera_env import UR5CameraEnv, UR5CameraEnvTest, UR5CameraEnvEval, UR5CameraEnvDemo \ No newline at end of file diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py similarity index 77% rename from serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py rename to serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py index f49b7e78..d564b23f 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/robotiq_camera_env.py +++ b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py @@ -1,17 +1,16 @@ import numpy as np from typing import Tuple -from robotiq_env.envs.robotiq_env import RobotiqEnv -from robotiq_env.envs.camera_env.config import RobotiqCameraConfigFinal, RobotiqCameraConfigFinalTests, RobotiqCameraConfigFinalEvaluation +from ur_env.envs.ur5_env import UR5Env +from ur_env.envs.camera_env.config import UR5CameraConfigFinal, UR5CameraConfigFinalTests, UR5CameraConfigFinalEvaluation, UR5CameraConfigDemo -class RobotiqCameraEnv(RobotiqEnv): +class UR5CameraEnv(UR5Env): def __init__(self, load_config=True, **kwargs): if load_config: - super().__init__(**kwargs, config=RobotiqCameraConfigFinal) + super().__init__(**kwargs, config=UR5CameraConfigFinal) else: super().__init__(**kwargs) - self.last_action = np.zeros(self.action_space.shape) def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) @@ -60,11 +59,15 @@ def close(self): super().close() -class RobotiqCameraEnvTest(RobotiqCameraEnv): +class UR5CameraEnvTest(UR5CameraEnv): def __init__(self, **kwargs): - super().__init__(**kwargs, load_config=False, config=RobotiqCameraConfigFinalTests) + super().__init__(**kwargs, load_config=False, config=UR5CameraConfigFinalTests) -class RobotiqCameraEnvEval(RobotiqCameraEnv): +class UR5CameraEnvEval(UR5CameraEnv): def __init__(self, **kwargs): - super().__init__(**kwargs, load_config=False, config=RobotiqCameraConfigFinalEvaluation) + super().__init__(**kwargs, load_config=False, config=UR5CameraConfigFinalEvaluation) + +class UR5CameraEnvDemo(UR5CameraEnv): + def __init__(self, **kwargs): + super().__init__(**kwargs, load_config=False, config=UR5CameraConfigDemo) diff --git a/serl_robot_infra/robotiq_env/envs/camera_env/config.py b/serl_robot_infra/ur_env/envs/camera_env/config.py similarity index 85% rename from serl_robot_infra/robotiq_env/envs/camera_env/config.py rename to serl_robot_infra/ur_env/envs/camera_env/config.py index e455e411..3b3a1fa5 100644 --- a/serl_robot_infra/robotiq_env/envs/camera_env/config.py +++ b/serl_robot_infra/ur_env/envs/camera_env/config.py @@ -1,8 +1,8 @@ -from robotiq_env.envs.robotiq_env import DefaultEnvConfig +from ur_env.envs.ur5_env import DefaultEnvConfig import numpy as np -class RobotiqCameraConfig(DefaultEnvConfig): +class UR5CameraConfig(DefaultEnvConfig): RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) RANDOM_RESET = False RANDOM_XY_RANGE = (0.00,) @@ -26,7 +26,7 @@ class RobotiqCameraConfig(DefaultEnvConfig): } -class RobotiqCameraConfigBox5(DefaultEnvConfig): +class UR5CameraConfigBox5(DefaultEnvConfig): RESET_Q = np.array([ [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], @@ -56,7 +56,7 @@ class RobotiqCameraConfigBox5(DefaultEnvConfig): } -class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes +class UR5CameraConfigFinal(DefaultEnvConfig): # config for 10 boxes RESET_Q = np.array([ [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], @@ -84,15 +84,22 @@ class RobotiqCameraConfigFinal(DefaultEnvConfig): # config for 10 boxes FORCEMODE_DAMPING: float = 0.02 # faster but more vulnerable to crash... FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) REALSENSE_CAMERAS = { "wrist": "218622277164", "wrist_2": "218622279756" } +class UR5CameraConfigDemo(UR5CameraConfigFinal): + RESET_Q = np.array([[0., -np.pi/2., np.pi/2., -np.pi/2., -np.pi/2., 0.]]) + ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., 0.1, 0.1, 0.3]) + ABS_POSE_LIMIT_LOW = np.array([-1., -1., -0.004, -0.1, -0.1, -0.3]) + + ROBOT_IP: str = "192.168.1.66" + -class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): +class UR5CameraConfigFinalTests(UR5CameraConfigFinal): RANDOM_RESET = False RANDOM_XY_RANGE = (0.0,) RANDOM_ROT_RANGE = (0.05,) @@ -100,12 +107,11 @@ class RobotiqCameraConfigFinalTests(RobotiqCameraConfigFinal): RESET_Q = np.array([ # [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos - # [0.7431341409683228, -1.0744208258441468, 1.6481602827655237, -2.1433049641051234, -1.5655501524554651, 0.7431478500366211 + 0 * np.pi/2], # LEGO box - [1.46, -1.38, 2.01, -2.193, -1.566, 1.426] + [1.4843, -1.1314, 1.6531, -2.0676, -1.6014, 1.6402] ]) -class RobotiqCameraConfigFinalEvaluation(RobotiqCameraConfigFinal): +class UR5CameraConfigFinalEvaluation(UR5CameraConfigFinal): # config for the evaluation on 5 boxes the policy has never seen RANDOM_RESET = True RANDOM_XY_RANGE = (0.01,) diff --git a/serl_robot_infra/robotiq_env/envs/relative_env.py b/serl_robot_infra/ur_env/envs/relative_env.py similarity index 97% rename from serl_robot_infra/robotiq_env/envs/relative_env.py rename to serl_robot_infra/ur_env/envs/relative_env.py index 82a95a10..737032a8 100644 --- a/serl_robot_infra/robotiq_env/envs/relative_env.py +++ b/serl_robot_infra/ur_env/envs/relative_env.py @@ -13,7 +13,7 @@ class RelativeFrame(gym.Wrapper): This wrapper transforms the observation and action to be expressed in the end-effector frame. Optionally, it can transform the tcp_pose into a relative frame defined as the reset pose. - This wrapper is expected to be used on top of the base Robotiq environment, which has the following + This wrapper is expected to be used on top of the base UR5 environment, which has the following observation space: { "state": spaces.Dict( diff --git a/serl_robot_infra/robotiq_env/envs/robotiq_env.py b/serl_robot_infra/ur_env/envs/ur5_env.py similarity index 87% rename from serl_robot_infra/robotiq_env/envs/robotiq_env.py rename to serl_robot_infra/ur_env/envs/ur5_env.py index e665815c..ec8a44e4 100644 --- a/serl_robot_infra/robotiq_env/envs/robotiq_env.py +++ b/serl_robot_infra/ur_env/envs/ur5_env.py @@ -1,4 +1,4 @@ -"""Gym Interface for Robotiq""" +"""Gym Interface for UR5""" import time import threading @@ -8,19 +8,20 @@ import cv2 import queue import warnings +import requests +import json from typing import Dict, Tuple from datetime import datetime from collections import OrderedDict from scipy.spatial.transform import Rotation as R import open3d as o3d -from robotiq_env.camera.video_capture import VideoCapture -from robotiq_env.camera.rs_capture import RSCapture +from ur_env.camera.video_capture import VideoCapture +from ur_env.camera.rs_capture import RSCapture -from robotiq_env.camera.utils import PointCloudFusion, CalibrationTread +from ur_env.camera.utils import PointCloudFusion, CalibrationTread -from robotiq_env.utils.real_time_plotter import DataClient -from robot_controllers.robotiq_controller import RobotiqImpedanceController +from robot_controllers.ur5_controller import UrImpedanceController class ImageDisplayer(threading.Thread): @@ -78,7 +79,7 @@ def close(self): class DefaultEnvConfig: - """Default configuration for RobotiqEnv. Fill in the values below.""" + """Default configuration for UR5Env. Fill in the values below.""" RESET_Q = np.zeros((6,)) RANDOM_RESET = (False,) @@ -107,7 +108,7 @@ class DefaultEnvConfig: ############################################################################## -class RobotiqEnv(gym.Env): +class UR5Env(gym.Env): def __init__( self, hz: int = 10, @@ -115,7 +116,6 @@ def __init__( config=DefaultEnvConfig, max_episode_length: int = 100, save_video: bool = False, - realtime_plot: bool = False, camera_mode: str = "rgb", # one of (rgb, grey, depth, both(rgb depth), pointcloud, none) ): self.max_episode_length = max_episode_length @@ -133,13 +133,14 @@ def __init__( self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((3,), dtype=np.float32) self.curr_torque = np.zeros((3,), dtype=np.float32) + self.last_action = np.zeros(self.action_space.shape) self.gripper_state = np.zeros((2,), dtype=np.float32) self.random_reset = config.RANDOM_RESET self.random_xy_range = config.RANDOM_XY_RANGE self.random_rot_range = config.RANDOM_ROT_RANGE self.hz = hz - np.random.seed(0) # fix seed for random initial rotations + np.random.seed(0) # fix seed for fixed (random) initial rotations camera_mode = None if camera_mode.lower() == "none" else camera_mode if camera_mode is not None and save_video: @@ -148,7 +149,6 @@ def __init__( self.recording_frames = [] self.camera_mode = camera_mode - self.realtime_plot = realtime_plot self.cost_infos = {} self.xyz_bounding_box = gym.spaces.Box( @@ -227,10 +227,10 @@ def __init__( self.cap = None if fake_env: - print("[RobotiqEnv] is fake!") + print("[UR5Env] is fake!") return - self.controller = RobotiqImpedanceController( + self.controller = UrImpedanceController( robot_ip=config.ROBOT_IP, frequency=config.CONTROLLER_HZ, kp=15000, @@ -251,13 +251,6 @@ def __init__( self.displayer.start() print("[CAM] Cameras are ready!") - if self.realtime_plot: - try: - self.plotting_client = DataClient() - except ConnectionRefusedError: - print("Plotting Client could not be opened, continuing without plotting") - self.realtime_plot = False - while not self.controller.is_ready(): # wait for controller time.sleep(0.1) print("[RIC] Controller has started and is ready!") @@ -385,6 +378,69 @@ def go_to_rest(self): self.curr_reset_pose[:] = reset_pose return np.zeros((2,)) + def go_to_detected_box(self): + """" + function for the demo + """ + if self.gripper_state[0] > 0.01: + reset_Q = self.curr_Q.copy() + reset_Q[:4] = [0., -np.pi / 2., np.pi / 2., -np.pi / 2.] + self._send_reset_command(reset_Q) + while not self.controller.is_reset(): + time.sleep(0.1) # wait for the reset operation + + reset_Q[:4] = [np.pi / 2, -np.pi / 2., np.pi / 2., -np.pi / 2.] + self._send_reset_command(reset_Q) + while not self.controller.is_reset(): + time.sleep(0.1) # wait for the reset operation + + # release the box + self._send_gripper_command(np.array(-1)) + time.sleep(0.1) + + # go back on top + reset_Q = [0., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.] + self._send_reset_command(reset_Q) + while not self.controller.is_reset(): + time.sleep(0.1) # wait for the reset operation + time.sleep(0.5) + + def get_request(i=10): + if i == 0: + raise Exception("err") + try: + r = requests.get('http://192.168.1.204:5000/api/data') + r.raise_for_status() + boxes = r.json() + if len(boxes) == 0: + time.sleep(0.1) + return get_request(i) + else: + return boxes + + except (json.decoder.JSONDecodeError, requests.exceptions.HTTPError): + return get_request(i=i - 1) + + boxes = get_request() + + highest = list(boxes.keys())[np.argmax([b["world2box"]["pos"][1] for b in boxes.values()])] + box = boxes[highest]["world2box"] + print(f"pose: {[round(b, 2) for b in box['pos']]} {[round(b, 2) for b in box['rot']]}") + + t = R.from_euler("xyz", [-np.pi / 2., np.pi, 0.]) + pos = t.apply(np.array(box["pos"]) + np.array([0., 0.1 + boxes[highest]["size"][1] / 2., 0.])) + rot = (R.from_euler("xyz", t.apply(box["rot"])) * R.from_euler("xyz", [np.pi, 0., 0.])).as_rotvec() + + init_pose = np.concatenate((pos, rot)) + + print(f"moving to {init_pose}") + self._send_taskspace_command(init_pose) + while not self.controller.is_reset(): + time.sleep(0.1) # wait for the reset operation + + self._update_currpos() + self.curr_reset_pose[:] = self.curr_pos + def reset(self, **kwargs): self.cycle_count += 1 if self.save_video: @@ -400,7 +456,7 @@ def save_video_recording(self): try: if len(self.recording_frames): video_writer = cv2.VideoWriter( - f'/home/nico/real-world-rl/serl/examples/robotiq_drq/experiment_setup/videos/{datetime.now().strftime("%m-%d_%H-%M")}.mp4', + f'./videos/{datetime.now().strftime("%m-%d_%H-%M")}.mp4', cv2.VideoWriter_fourcc(*"mp4v"), 10, self.recording_frames[0].shape[:2][::-1], @@ -475,7 +531,6 @@ def get_image(self) -> Dict[str, np.ndarray]: )[..., None] resized = resized.reshape((128, 3, 128, 3, 1)).max((1, 3)) # max pool with 3x3 - # TODO check if better! images[depth_key] = resized display_images[depth_key] = cv2.applyColorMap(resized, cv2.COLORMAP_JET) @@ -568,6 +623,9 @@ def _send_gripper_command(self, gripper_pos: np.ndarray): def _send_reset_command(self, reset_Q: np.ndarray): self.controller.set_reset_Q(reset_Q) + def _send_taskspace_command(self, target_pos): + self.controller.set_reset_pose(target_pos) + def _update_currpos(self): """ Internal function to get the latest state of the robot and its gripper. @@ -602,9 +660,6 @@ def _get_obs(self, action) -> dict: "action": action } - if self.realtime_plot: - self.plotting_client.send(np.concatenate([self.curr_force, self.curr_torque])) - if images is not None: return copy.deepcopy(dict(images=images, state=state_observation)) else: diff --git a/serl_robot_infra/robotiq_env/envs/wrappers.py b/serl_robot_infra/ur_env/envs/wrappers.py similarity index 97% rename from serl_robot_infra/robotiq_env/envs/wrappers.py rename to serl_robot_infra/ur_env/envs/wrappers.py index cb8b3d98..4cb24bc9 100644 --- a/serl_robot_infra/robotiq_env/envs/wrappers.py +++ b/serl_robot_infra/ur_env/envs/wrappers.py @@ -2,11 +2,11 @@ import numpy as np from agentlace import action -from robotiq_env.spacemouse.spacemouse_expert import SpaceMouseExpert +from ur_env.spacemouse.spacemouse_expert import SpaceMouseExpert import time from scipy.spatial.transform import Rotation as R -from robotiq_env.utils.rotations import quat_2_euler, quat_2_mrp +from ur_env.utils.rotations import quat_2_euler, quat_2_mrp ROT90 = np.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) ROT_GENERAL = np.array([np.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) @@ -69,7 +69,7 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: - expert_a: spacemouse output adapted to force space (action) """ - # position = super().get_wrapper_attr("curr_pos") # get position from robotiq_env + # position = super().get_wrapper_attr("curr_pos") # get position from ur_env position = self.unwrapped.curr_pos z_angle = np.arctan2(position[1], position[0]) # get first joint angle diff --git a/serl_robot_infra/robotiq_env/requirements.txt b/serl_robot_infra/ur_env/requirements.txt similarity index 100% rename from serl_robot_infra/robotiq_env/requirements.txt rename to serl_robot_infra/ur_env/requirements.txt diff --git a/serl_robot_infra/robotiq_env/spacemouse/__init__.py b/serl_robot_infra/ur_env/spacemouse/__init__.py similarity index 100% rename from serl_robot_infra/robotiq_env/spacemouse/__init__.py rename to serl_robot_infra/ur_env/spacemouse/__init__.py diff --git a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py b/serl_robot_infra/ur_env/spacemouse/spacemouse_expert.py similarity index 100% rename from serl_robot_infra/robotiq_env/spacemouse/spacemouse_expert.py rename to serl_robot_infra/ur_env/spacemouse/spacemouse_expert.py diff --git a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py b/serl_robot_infra/ur_env/spacemouse/spacemouse_test.py similarity index 91% rename from serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py rename to serl_robot_infra/ur_env/spacemouse/spacemouse_test.py index 5127f72a..a381947e 100644 --- a/serl_robot_infra/robotiq_env/spacemouse/spacemouse_test.py +++ b/serl_robot_infra/ur_env/spacemouse/spacemouse_test.py @@ -1,7 +1,7 @@ """ Test the spacemouse output. """ import time import numpy as np -from robotiq_env.spacemouse.spacemouse_expert import SpaceMouseExpert +from ur_env.spacemouse.spacemouse_expert import SpaceMouseExpert def test_spacemouse(): diff --git a/serl_robot_infra/robotiq_env/utils/__init__.py b/serl_robot_infra/ur_env/utils/__init__.py similarity index 100% rename from serl_robot_infra/robotiq_env/utils/__init__.py rename to serl_robot_infra/ur_env/utils/__init__.py diff --git a/serl_robot_infra/robotiq_env/utils/real_time_plotter.py b/serl_robot_infra/ur_env/utils/real_time_plotter.py similarity index 100% rename from serl_robot_infra/robotiq_env/utils/real_time_plotter.py rename to serl_robot_infra/ur_env/utils/real_time_plotter.py diff --git a/serl_robot_infra/robotiq_env/utils/rotations.py b/serl_robot_infra/ur_env/utils/rotations.py similarity index 90% rename from serl_robot_infra/robotiq_env/utils/rotations.py rename to serl_robot_infra/ur_env/utils/rotations.py index e22c4285..7b054a51 100644 --- a/serl_robot_infra/robotiq_env/utils/rotations.py +++ b/serl_robot_infra/ur_env/utils/rotations.py @@ -2,7 +2,7 @@ from scipy.spatial.transform import Rotation as R """ -Robotiq UR5 represents the orientation in axis angle representation +UR5 represents the orientation in axis angle representation """ diff --git a/serl_robot_infra/robotiq_env/utils/vacuum_gripper.py b/serl_robot_infra/ur_env/utils/vacuum_gripper.py similarity index 100% rename from serl_robot_infra/robotiq_env/utils/vacuum_gripper.py rename to serl_robot_infra/ur_env/utils/vacuum_gripper.py From c2c601f3f6cb0f951683ec5f429199682fbbada5 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 9 Oct 2024 15:46:23 +0200 Subject: [PATCH 333/338] readme updates --- README.md | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 20185470..8a521a02 100644 --- a/README.md +++ b/README.md @@ -5,17 +5,28 @@ | Code Directory | Description | |------------------------------------------------------------------------------------------------------------|--------------------------------------------| | [robot_controllers](https://github.com/nisutte/voxel-serl/tree/develop/serl_robot_infra/robot_controllers) | Impedance controller for the UR5 robot arm | -| [robotiq_env](https://github.com/nisutte/voxel-serl/tree/develop/serl_robot_infra/robotiq_env) | Environment setup for the box picking task | +| [box_picking_env](https://github.com/nisutte/voxel-serl/tree/develop/serl_robot_infra/box_picking_env) | Environment setup for the box picking task | | [vision](https://github.com/nisutte/voxel-serl/tree/develop/serl_launcher/serl_launcher/vision) | Point-Cloud based encoders | -| [utils](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/robotiq_env/camera/utils.py) | Point-Cloud fusion and voxelization | +| [utils](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/camera/utils.py) | Point-Cloud fusion and voxelization | + +## Quick start guide for box picking with a UR5 robot arm + +### Without cameras (TODO modify the bash files) + +1. Follow the installation in the official [SERL repo](https://github.com/rail-berkeley/serl). +2. Check [envs](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/envs) and either use the provided [box_picking_env](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py) or set up a new environment using the one mentioned as a template. (New environments have to be registered [here](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/__init__.py)) +2. Use the [config](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/envs/camera_env/config.py) file to configure all the robot-arm specific parameters, as well as gripper and camera infos. +3. Go to the [box picking](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq) folder and modify the bash files ```run_learner.py``` and ```run_actor.py```. If no images are used, set ```camera_mode``` to ```none``` . WandB logging can be deactivated if ```debug``` is set to True. +4. Record 20 demostrations using [record_demo.py](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq/record_demo.py) in the same folder. Double check that the ```camera_mode``` and all environment-wrappers are identical to [drq_policy.py](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq/drq_policy.py). +5. Execute ```run_learner.py``` and ```run_actor.py``` simultaneously to start the RL training. +6. To evaluate on a policy, modify and execute ```run_evaluation.py``` with the specified checkpoint path and step. ## Modaliy examples

- +

## TODO's - [ ] improve readme - [ ] add paper link -- [ ] rename "Robotiq" occurencies (is confusing) - +- [ ] document how to use in a real setting From 75badccc87f59a4c27088ca845d7419bc5e09281 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 9 Oct 2024 15:46:47 +0200 Subject: [PATCH 334/338] fix --- serl_launcher/serl_launcher/utils/sampling_utils.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/serl_launcher/serl_launcher/utils/sampling_utils.py b/serl_launcher/serl_launcher/utils/sampling_utils.py index ae97e58d..dcb3fde4 100644 --- a/serl_launcher/serl_launcher/utils/sampling_utils.py +++ b/serl_launcher/serl_launcher/utils/sampling_utils.py @@ -25,3 +25,6 @@ def sample(self, curr_action: np.ndarray): self.buffer = np.roll(self.buffer, axis=0, shift=1) self.buffer[0, :] = curr_action return np.dot(self.ensemble, self.buffer) + + def is_activated(self): + return self.activated From 7ead273be5cfd818d183e3b796dea20ed70c4ce2 Mon Sep 17 00:00:00 2001 From: nisutte Date: Wed, 16 Oct 2024 10:45:08 +0200 Subject: [PATCH 335/338] bugfix --- .../VoxNet_pretrained_1quat/run_evaluation.sh | 4 ++-- .../VoxNet_pretrained_gripper_1quat/run_evaluation.sh | 4 ++-- serl_robot_infra/robot_controllers/ur5_controller.py | 10 +++++----- serl_robot_infra/ur_env/camera/utils.py | 4 ++-- serl_robot_infra/ur_env/envs/ur5_env.py | 11 +++++++++-- 5 files changed, 20 insertions(+), 13 deletions(-) diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh index d6b5d9ed..8786a484 100644 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh @@ -2,13 +2,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env box_picking_camera_env_demo \ + --env box_picking_camera_env_tests \ --exp_name="Voxnet pq temp ens" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints voxnet pretrained 1quat 0823-10:45"\ - --eval_checkpoint_step 13000 \ + --eval_checkpoint_step 11000 \ --eval_n_trajs 50 \ \ --encoder_type voxnet-pretrained \ diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh index 4bf4d8ad..6d5ce598 100644 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh +++ b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh @@ -2,13 +2,13 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ --actor \ - --env box_picking_camera_env_demo \ + --env box_picking_camera_env_tests \ --exp_name="voxnet [pqg] temp ens" \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints voxnet pretrained gripper_only 1quat 0829-14:08"\ - --eval_checkpoint_step 12000 \ + --eval_checkpoint_step 11000 \ --eval_n_trajs 50 \ \ --encoder_type voxnet-pretrained \ diff --git a/serl_robot_infra/robot_controllers/ur5_controller.py b/serl_robot_infra/robot_controllers/ur5_controller.py index 10a81d6b..a63871aa 100644 --- a/serl_robot_infra/robot_controllers/ur5_controller.py +++ b/serl_robot_infra/robot_controllers/ur5_controller.py @@ -237,8 +237,8 @@ def _calculate_force(self): torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable # check for big downward tcp force and adapt accordingly - # if self.curr_force[2] > 3.5 and force_pos[2] < 0.: - # force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. + if self.curr_force[2] > 3.5 and force_pos[2] < 0.: + force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. return np.concatenate((force_pos, torque)) @@ -312,9 +312,9 @@ async def _go_to_reset_pose(self): self.ur_control.forceModeStop() # first disable vaccum gripper - # if self.robotiq_gripper: - # await self.send_gripper_command(force_release=True) - # time.sleep(0.01) + if self.robotiq_gripper: + await self.send_gripper_command(force_release=True) + time.sleep(0.01) # then move up (so no boxes are moved) success = True diff --git a/serl_robot_infra/ur_env/camera/utils.py b/serl_robot_infra/ur_env/camera/utils.py index c7371aa1..88516e4c 100644 --- a/serl_robot_infra/ur_env/camera/utils.py +++ b/serl_robot_infra/ur_env/camera/utils.py @@ -102,9 +102,9 @@ def get_voxelgrid_shape(self): def load_finetuned(self): from os.path import exists - if not exists("/examples/box_picking_drq/PointCloudFusionFinetuned.npy"): + if not exists("/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy"): return False - with open("/examples/box_picking_drq/PointCloudFusionFinetuned.npy", "rb") as f: + with open("/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy", "rb") as f: t_finetuned = np.load(f) self.t1 = t_finetuned[0, ...] self.t2 = t_finetuned[1, ...] diff --git a/serl_robot_infra/ur_env/envs/ur5_env.py b/serl_robot_infra/ur_env/envs/ur5_env.py index ec8a44e4..e1accd67 100644 --- a/serl_robot_infra/ur_env/envs/ur5_env.py +++ b/serl_robot_infra/ur_env/envs/ur5_env.py @@ -133,7 +133,6 @@ def __init__( self.curr_Qd = np.zeros((6,), dtype=np.float32) self.curr_force = np.zeros((3,), dtype=np.float32) self.curr_torque = np.zeros((3,), dtype=np.float32) - self.last_action = np.zeros(self.action_space.shape) self.gripper_state = np.zeros((2,), dtype=np.float32) self.random_reset = config.RANDOM_RESET @@ -171,6 +170,8 @@ def __init__( np.ones((7,), dtype=np.float32) * -1, np.ones((7,), dtype=np.float32), ) + self.last_action = np.zeros(self.action_space.shape) + image_space_definition = {} if camera_mode in ["rgb", "grey", "both"]: @@ -260,7 +261,7 @@ def __init__( # voxel_grid_shape[-1] *= 8 # do not use compacting for now # voxel_grid_shape *= 2 print(f"pointcloud resolution set to: {voxel_grid_shape}") - self.pointcloud_fusion = PointCloudFusion(angle=31., x_distance=0.205, voxel_grid_shape=voxel_grid_shape) + self.pointcloud_fusion = PointCloudFusion(angle=30.5, x_distance=0.185, y_distance=-0.01, voxel_grid_shape=voxel_grid_shape) # load pre calibrated, else calibrate if not self.pointcloud_fusion.load_finetuned(): @@ -570,6 +571,12 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 print("calibrating pointcloud fusion...") # calibrate pc fusion here + obs, reward, done, truncated, _ = self.step(np.zeros((7,))) + pc = o3d.geometry.PointCloud() + fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=False, cropped=False) + pc.points = o3d.utility.Vector3dVector(fused) + o3d.visualization.draw_geometries([pc]) + # get samples for i in range(num_samples): # action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), From 8ab7f59ec8ed74e8d2f2d87497a36b54e8f481c9 Mon Sep 17 00:00:00 2001 From: nisutte Date: Tue, 22 Oct 2024 11:29:56 +0200 Subject: [PATCH 336/338] cleanup for potential pr --- README.md | 5 +- examples/box_picking_bc/record_demo.py | 2 - examples/box_picking_drq/drq_policy.py | 60 +---- .../box_picking_drq/encoder_feature_plot.py | 196 ----------------- .../experiment_setup/BC/run_rbc_actor.sh | 13 -- .../experiment_setup/BC/run_rbc_learner.sh | 13 -- .../experiment_setup/BT/BehaviorTree.py | 87 -------- .../experiment_setup/BT/bt_policy.py | 128 ----------- .../experiment_setup/BT/run_bt_actor.sh | 8 - .../experiment_setup/Depth Image/run_actor.sh | 19 -- .../Depth Image/run_evaluation.sh | 16 -- .../Depth Image/run_learner.sh | 21 -- .../experiment_setup/ResNet10/run_actor.sh | 23 -- .../ResNet10/run_evaluation.sh | 20 -- .../experiment_setup/ResNet10/run_learner.sh | 25 --- .../ResNet18 greyscale/run_actor.sh | 23 -- .../ResNet18 greyscale/run_evaluation.sh | 20 -- .../ResNet18 greyscale/run_learner.sh | 25 --- .../experiment_setup/ResNet18/run_actor.sh | 24 -- .../ResNet18/run_evaluation.sh | 20 -- .../experiment_setup/ResNet18/run_learner.sh | 26 --- .../experiment_setup/SAC/run_actor.sh | 19 -- .../experiment_setup/SAC/run_evaluation.sh | 16 -- .../experiment_setup/SAC/run_learner.sh | 21 -- .../experiment_setup/VoxNet/run_actor.sh | 20 -- .../experiment_setup/VoxNet/run_evaluation.sh | 17 -- .../experiment_setup/VoxNet/run_learner.sh | 22 -- .../VoxNet_1quat/run_actor.sh | 21 -- .../VoxNet_1quat/run_evaluation.sh | 18 -- .../VoxNet_1quat/run_learner.sh | 23 -- .../experiment_setup/VoxNet_only/run_actor.sh | 20 -- .../VoxNet_only/run_evaluation.sh | 17 -- .../VoxNet_only/run_learner.sh | 22 -- .../VoxNet_pretrained/run_actor.sh | 20 -- .../VoxNet_pretrained/run_evaluation.sh | 17 -- .../VoxNet_pretrained/run_learner.sh | 22 -- .../VoxNet_pretrained_1quat/run_actor.sh | 21 -- .../VoxNet_pretrained_1quat/run_evaluation.sh | 19 -- .../VoxNet_pretrained_1quat/run_learner.sh | 23 -- .../run_actor.sh | 21 -- .../run_evaluation.sh | 19 -- .../run_learner.sh | 23 -- .../experiment_setup/results_calculation.py | 157 ------------- examples/box_picking_drq/run_actor.sh | 9 +- examples/box_picking_drq/run_evaluation.sh | 12 +- examples/box_picking_drq/run_learner.sh | 11 +- .../serl_launcher/agents/continuous/drq.py | 207 ++---------------- .../serl_launcher/common/encoding.py | 18 +- serl_launcher/serl_launcher/utils/launcher.py | 18 +- .../serl_launcher/utils/train_utils.py | 76 +------ .../vision/data_augmentations.py | 112 ---------- .../serl_launcher/vision/resnet_v1.py | 6 - .../serl_launcher/vision/resnet_v1_18.py | 2 +- .../vision/voxel_grid_encoders.py | 45 +--- .../robot_controllers/ur5_controller.py | 37 ---- serl_robot_infra/setup.py | 1 + serl_robot_infra/ur_env/__init__.py | 22 +- .../envs/basic_env/box_picking_basic_env.py | 4 +- .../ur_env/envs/basic_env/config.py | 55 ++--- .../ur_env/envs/camera_env/__init__.py | 2 +- .../envs/camera_env/box_picking_camera_env.py | 20 +- .../ur_env/envs/camera_env/config.py | 105 +-------- serl_robot_infra/ur_env/envs/relative_env.py | 2 - serl_robot_infra/ur_env/envs/ur5_env.py | 6 +- serl_robot_infra/ur_env/envs/wrappers.py | 3 +- serl_robot_infra/ur_env/requirements.txt | 4 +- .../ur_env/utils/real_time_plotter.py | 113 ---------- 67 files changed, 104 insertions(+), 2138 deletions(-) delete mode 100644 examples/box_picking_drq/encoder_feature_plot.py delete mode 100644 examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh delete mode 100644 examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py delete mode 100644 examples/box_picking_drq/experiment_setup/BT/bt_policy.py delete mode 100644 examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh delete mode 100755 examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/SAC/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/SAC/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh delete mode 100644 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh delete mode 100755 examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh delete mode 100644 examples/box_picking_drq/experiment_setup/results_calculation.py delete mode 100644 serl_robot_infra/ur_env/utils/real_time_plotter.py diff --git a/README.md b/README.md index 8a521a02..5f5cee01 100644 --- a/README.md +++ b/README.md @@ -18,7 +18,7 @@ 2. Use the [config](https://github.com/nisutte/voxel-serl/blob/develop/serl_robot_infra/ur_env/envs/camera_env/config.py) file to configure all the robot-arm specific parameters, as well as gripper and camera infos. 3. Go to the [box picking](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq) folder and modify the bash files ```run_learner.py``` and ```run_actor.py```. If no images are used, set ```camera_mode``` to ```none``` . WandB logging can be deactivated if ```debug``` is set to True. 4. Record 20 demostrations using [record_demo.py](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq/record_demo.py) in the same folder. Double check that the ```camera_mode``` and all environment-wrappers are identical to [drq_policy.py](https://github.com/nisutte/voxel-serl/blob/develop/examples/box_picking_drq/drq_policy.py). -5. Execute ```run_learner.py``` and ```run_actor.py``` simultaneously to start the RL training. +5. Update the demonstrations path in the ```run_learner.py``` and execute it and ```run_actor.py``` simultaneously to start the RL training. 6. To evaluate on a policy, modify and execute ```run_evaluation.py``` with the specified checkpoint path and step. ## Modaliy examples @@ -30,3 +30,6 @@ - [ ] improve readme - [ ] add paper link - [ ] document how to use in a real setting + +## Notes +- clu needs to be installed for a parameter overview of the model \ No newline at end of file diff --git a/examples/box_picking_bc/record_demo.py b/examples/box_picking_bc/record_demo.py index 1f79eead..66e26a1d 100644 --- a/examples/box_picking_bc/record_demo.py +++ b/examples/box_picking_bc/record_demo.py @@ -6,7 +6,6 @@ import pickle as pkl from tqdm import tqdm import gymnasium as gym -from pprint import pprint from pynput import keyboard from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper @@ -83,7 +82,6 @@ def on_esc(key): ) ) transitions.append(transition) - # pprint(transition) obs = next_obs diff --git a/examples/box_picking_drq/drq_policy.py b/examples/box_picking_drq/drq_policy.py index 47a0dc89..f1c54698 100644 --- a/examples/box_picking_drq/drq_policy.py +++ b/examples/box_picking_drq/drq_policy.py @@ -23,16 +23,13 @@ from serl_launcher.utils.train_utils import ( print_agent_params, parameter_overview, - plot_feature_kernel_histogram, - find_zero_weights, - plot_conv3d_kernels, ) from agentlace.trainer import TrainerServer, TrainerClient from agentlace.data.data_store import QueuedDataStore from serl_launcher.utils.launcher import ( - make_drq_agent, + make_voxel_drq_agent, make_trainer_config, make_wandb_logger, ) @@ -41,8 +38,6 @@ from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper from ur_env.envs.relative_env import RelativeFrame from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper -from serl_launcher.vision.data_augmentations import batched_random_rot90_state, batched_random_rot90_voxel, \ - batched_random_rot90_action import ur_env @@ -57,26 +52,22 @@ flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") flags.DEFINE_string("agent", "drq", "Name of agent.") -flags.DEFINE_string("exp_name", "DRQ agent", "Name of the experiment for wandb logging.") +flags.DEFINE_string("exp_name", "box picking drq", "Name of the experiment for wandb logging.") flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both)") +flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both, pointcloud)") -flags.DEFINE_integer("seed", 42, "Random seed.") +flags.DEFINE_integer("seed", 1, "Random seed.") flags.DEFINE_bool("save_model", False, "Whether to save model.") flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") -flags.DEFINE_string("state_mask", "no_ForceTorque", - "if all the states should be considered, possible: (all, none, no_ForceTorque, gripper, position_gripper)") -flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") +flags.DEFINE_string("state_mask", "all", + "if all the states should be considered, see serl_launcher/common/encoding for more info") +flags.DEFINE_string("encoder_type", "voxnet-pretrained", "Encoder type.") flags.DEFINE_integer("encoder_bottleneck_dim", 128, "bottleneck dimension of the encoder") -# flags.DEFINE_integer("proprio_latent_dim", 64, -# "the latent dimension for the state, will be concatenated with encoder bottleneck dim before being passed onward") flags.DEFINE_multi_string("encoder_kwargs", None, "Encoder kwargs in the form ['dict key', 'dict value']") flags.DEFINE_bool("enable_obs_rotation_wrapper", False, "Whether to enable observation rotation wrapper (train in one quaternion)") -flags.DEFINE_bool("enable_obs_rotation_augmentation", False, - "Whether to enable observation rotation augmentation (90 deg)") flags.DEFINE_bool("enable_temporal_ensemble_sampling", False, "Whether to enable sampling the action from a temporal ensemble: action = 0.5*a0 + 0.3*a-1 + 0.2*a-2 + 0.1*a-3") @@ -155,7 +146,6 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): debug=FLAGS.debug, ) success_counter = 0 - time_list = [] ckpt = checkpoints.restore_checkpoint( FLAGS.checkpoint_path, @@ -163,15 +153,8 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): step=FLAGS.eval_checkpoint_step, ) agent = agent.replace(state=ckpt) - find_zero_weights(agent.state.params, print_all=False) action_ensemble = TemporalActionEnsemble(activated=FLAGS.enable_temporal_ensemble_sampling) - # examine model parameters if trajs==0 - if FLAGS.eval_n_trajs == 0: - parameter_overview(agent) - # plot_feature_kernel_histogram(agent) - plot_conv3d_kernels(agent.state.params) - trajectories = [] traj_infos = [] for episode in range(FLAGS.eval_n_trajs): @@ -271,7 +254,7 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: actions = env.action_space.sample() - elif not agent.config["activate_batch_rotation"]: + else: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( observations=jax.device_put(obs), @@ -279,22 +262,6 @@ def update_params(params): deterministic=False, ) actions = np.asarray(jax.device_get(actions)) - else: - sampling_rng, rot_rng, key = jax.random.split(sampling_rng, 3) - - rotated_obs = copy.deepcopy(obs) - rotated_obs["state"] = batched_random_rot90_state(obs["state"], rot_rng) - rotated_obs["wrist_pointcloud"] = batched_random_rot90_voxel(obs["wrist_pointcloud"], rot_rng) - - actions = agent.sample_actions( - observations=jax.device_put(rotated_obs), - seed=key, - deterministic=False, - ) - for _ in range(3): - actions = batched_random_rot90_action(actions[None, ...], rot_rng)[0, ...] # rotate back - - actions = np.asarray(jax.device_get(actions)) # Step environment with timer.context("step_env"): @@ -522,14 +489,13 @@ def main(_): } encoder_kwargs = {k: (int(v) if str(v).isdigit() else v) for k, v in encoder_kwargs.items()} - agent: DrQAgent = make_drq_agent( + agent: DrQAgent = make_voxel_drq_agent( seed=FLAGS.seed, sample_obs=env.observation_space.sample(), sample_action=env.action_space.sample(), image_keys=image_keys, encoder_type=FLAGS.encoder_type, state_mask=FLAGS.state_mask, - # proprio_latent_dim=FLAGS.proprio_latent_dim, encoder_kwargs=encoder_kwargs ) @@ -542,9 +508,7 @@ def main(_): # print useful info print_agent_params(agent, image_keys) parameter_overview(agent) - # plot_conv3d_kernels(agent.state.params) - agent.config["activate_batch_rotation"] = FLAGS.enable_obs_rotation_augmentation # obs batch rotation control if FLAGS.enable_obs_rotation_augmentation: print("Batch Observation Rotation enabled!") assert not FLAGS.enable_obs_rotation_augmentation or not FLAGS.enable_obs_rotation_wrapper # both is pointless @@ -584,12 +548,6 @@ def create_replay_buffer_and_wandb_logger(): traj["observations"].pop(obs_name) traj["next_observations"].pop(obs_name) - # convert to grey here - if FLAGS.camera_mode == "grey": - gray = np.array([0.2989, 0.5870, 0.1140]) - traj["observations"]["wrist"] = np.dot(traj["observations"]["wrist"], gray)[..., None] - traj["next_observations"]["wrist"] = np.dot(traj["next_observations"]["wrist"], gray)[..., None] - replay_buffer.insert(traj) print(f"replay buffer size: {len(replay_buffer)}") diff --git a/examples/box_picking_drq/encoder_feature_plot.py b/examples/box_picking_drq/encoder_feature_plot.py deleted file mode 100644 index bed9fb7b..00000000 --- a/examples/box_picking_drq/encoder_feature_plot.py +++ /dev/null @@ -1,196 +0,0 @@ -#!/usr/bin/env python3 - -import time -from functools import partial -import jax -import jax.numpy as jnp -import numpy as np -import pynput -import threading -import tqdm -from absl import app, flags -from flax.training import checkpoints -from datetime import datetime - -import gymnasium as gym -from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics - -from serl_launcher.agents.continuous.drq import DrQAgent -from serl_launcher.common.evaluation import evaluate -from serl_launcher.utils.timer_utils import Timer -from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.utils.train_utils import concat_batches - -from agentlace.trainer import TrainerServer, TrainerClient -from agentlace.data.data_store import QueuedDataStore - -from serl_launcher.utils.launcher import ( - make_drq_agent, - make_trainer_config, - make_wandb_logger, -) -from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper -from ur_env.envs.relative_env import RelativeFrame -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2EulerWrapper - -import ur_env - -devices = jax.local_devices() -num_devices = len(devices) -sharding = jax.sharding.PositionalSharding(devices) - -FLAGS = flags.FLAGS - -flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") -flags.DEFINE_string("agent", "drq", "Name of agent.") -flags.DEFINE_string("exp_name", "DRQ first tests", "Name of the experiment for wandb logging.") -flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both)") - -flags.DEFINE_integer("seed", 42, "Random seed.") -flags.DEFINE_bool("save_model", False, "Whether to save model.") -flags.DEFINE_integer("batch_size", 512, "Batch size.") -flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") - -flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") - -flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") -flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") -flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") - -flags.DEFINE_integer("log_period", 10, "Logging period.") -flags.DEFINE_integer("eval_period", 1000, "Evaluation period.") - -# flag to indicate if this is a leaner or a actor -flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") -flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") -flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -# "small" is a 4 layer convnet, "resnet" and "mobilenet" are frozen with pretrained weights -flags.DEFINE_string("encoder_type", "resnet-pretrained", "Encoder type.") -flags.DEFINE_string("demo_path", None, "Path to the demo data.") -flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints', - "Path to save checkpoints.") - -flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_integer("eval_n_trajs", 5, "Number of trajectories for evaluation.") - -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds', - "Path to save RLDS logs.") -flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") - -flags.DEFINE_boolean( - "debug", False, "Debug mode." -) # debug mode will disable wandb logging - - -def main(_): - assert FLAGS.batch_size % num_devices == 0 - FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") - - # seed - rng = jax.random.PRNGKey(FLAGS.seed) - - # create env and load dataset - env = gym.make( - FLAGS.env, - camera_mode="rgb", - fake_env=True, - max_episode_length=100, - ) - env = RelativeFrame(env) - env = Quat2EulerWrapper(env) - env = SERLObsWrapper(env) - env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - env = RecordEpisodeStatistics(env) - - image_keys = [key for key in env.observation_space.keys() if key != "state"] - - rng, sampling_rng = jax.random.split(rng) - agent: DrQAgent = make_drq_agent( - seed=FLAGS.seed, - sample_obs=env.observation_space.sample(), - sample_action=env.action_space.sample(), - image_keys=image_keys, - encoder_type=FLAGS.encoder_type, - ) - - # replicate agent across devices - # need the jnp.array to avoid a bug where device_put doesn't recognize primitives - agent: DrQAgent = jax.device_put( - jax.tree_map(jnp.array, agent), sharding.replicate() - ) - - demo_buffer = MemoryEfficientReplayBufferDataStore( - env.observation_space, - env.action_space, - capacity=2000, - image_keys=image_keys, - ) - - sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) - - import pickle as pkl - - with open("/examples/box_picking_drq/old_demos/box_picking_20_demos_mai3_streamlined.pkl", "rb") as f: - trajs = pkl.load(f) - for traj in trajs: - demo_buffer.insert(traj) - print(f"demo buffer size: {len(demo_buffer)}") - - # encode here - # encode(demo_buffer, agent) - - # plot here - plot(demo_buffer) - - -def encode(demo_buffer, agent): - for i in range(len(demo_buffer) // 10): - index = np.arange(10) + i * 10 - obs = demo_buffer.sample(batch_size=10, indx=index) - - actions = agent.sample_actions( - observations=jax.device_put(obs["observations"]), - argmax=True - ) - - -def plot(demo_buffer): - import sys - sys.path.append("/home/nico/real-world-rl/spacemouse_tests") - from spacemouse_tests.jax_feature_plotter import generate_and_save_images - feature_file = "/spacemouse_tests/feature_plots_meanstd/features_meanstd.npy" - - with open(feature_file, 'rb') as f: - features = np.load(f) - - print("features shape ", features.shape) - shoulder_f = features[:, :256].reshape((800, 16, 16)) # shoulder comes first - wrist_f = features[:, 256:512].reshape((800, 16, 16)) - - # get images here - shoulder, wrist = [], [] - s_next, w_next = [], [] - for i in range(len(demo_buffer) // 10): - index = np.arange(10) + i * 10 - obs = demo_buffer.sample(batch_size=10, indx=index) - wrist.append(obs["observations"]["wrist"]) - shoulder.append(obs["observations"]["shoulder"]) - - w_next.append(obs["next_observations"]["wrist"]) - s_next.append(obs["next_observations"]["shoulder"]) - - w_next = np.array(w_next).reshape((800, 128, 128, 3)) - s_next = np.array(s_next).reshape((800, 128, 128, 3)) - wrist = np.array(wrist).reshape((800, 128, 128, 3)) - shoulder = np.array(shoulder).reshape((800, 128, 128, 3)) - - output_folder = '/home/nico/real-world-rl/spacemouse_tests/feature_plots_meanstd' - generate_and_save_images(output_folder, [shoulder, wrist, shoulder_f, wrist_f]) - - -if __name__ == "__main__": - app.run(main) diff --git a/examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh b/examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh deleted file mode 100644 index fc53ffa7..00000000 --- a/examples/box_picking_drq/experiment_setup/BC/run_rbc_actor.sh +++ /dev/null @@ -1,13 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -which python && \ -python /home/nico/real-world-rl/serl/examples/box_picking_bc/bc_policy.py "$@" \ - --env box_picking_camera_env_eval \ - --exp_name=bc_drq_policy \ - --seed 1 \ - --max_traj_length 100 \ - --batch_size 2048 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BC/checkpoints \ - --eval_checkpoint_step 5000 \ - --eval_n_trajs 30 \ - --debug # wandb is disabled when debug diff --git a/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh b/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh deleted file mode 100644 index 7b5be61c..00000000 --- a/examples/box_picking_drq/experiment_setup/BC/run_rbc_learner.sh +++ /dev/null @@ -1,13 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_bc/bc_policy.py "$@" \ - --env box_picking_camera_env \ - --exp_name=bc_drq_policy \ - --seed 1 \ - --batch_size 2048 \ - --max_steps 25000 \ - --demo_paths /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_state_only.pkl \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BC/checkpoints \ - --checkpoint_period 1000 \ - --eval_checkpoint_step 0 \ -# --debug # wandb is disabled when debug diff --git a/examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py b/examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py deleted file mode 100644 index fef9c586..00000000 --- a/examples/box_picking_drq/experiment_setup/BT/BehaviorTree.py +++ /dev/null @@ -1,87 +0,0 @@ -import numpy as np -from queue import Queue - - -class TreeState(): - def __init__(self): - self.down = np.array([0., 0., 1., 0., 0., 0., 0.]) - self.up = -self.down - self.suck = np.array([0., 0., 1., 0., 0., 0., 1.]) - self.random_direction = np.zeros_like(self.down) - self.random_orientation = np.zeros_like(self.down) - self.re_sample() - - self.current = np.zeros_like(self.down) - - def re_sample(self): - rand = np.random.rand(2, 2) - 0.5 - self.random_direction[0:2] = rand[0] / np.linalg.norm(rand[0]) - self.random_orientation[3:5] = rand[1] / np.linalg.norm(rand[1]) - - def reset(self): - self.current = self.down - - def __call__(self, *args, **kwargs): - return self.current.copy() - - -class BehaviorTree(): - """ - simple behavior tree for picking boxes - - start: move down - if force in z: suck - if not successful: - maybe orientation rot before? (test) - move up, random direction xy, goto start - if successful: - move up, wait for end - """ - - def __init__(self): - self.tree_state: TreeState = TreeState() - self.queue = Queue() - - def reset(self): - self.tree_state.reset() - print("down") - return self.tree_state() - - def sample_actions(self, observations): - obs = observations["state"].reshape(-1) - if not self.queue.empty(): - return self.queue.get() - - if obs[8] > 0.5: - if np.all(self.tree_state.current == self.tree_state.up): - pass - else: - print("go up") - self.tree_state.current = self.tree_state.up - - elif obs[11] < -3.: # force check - if obs[8] < -0.5: # if sucking - print("do random direction") - return self._fill_random_xy_queue() - else: - print("suck") - self.tree_state.current = self.tree_state.suck - return self._fill_suck_queue() - else: - self.tree_state.reset() - - return self.tree_state() - - def _fill_random_xy_queue(self): - for _ in range(4): - self.queue.put(self.tree_state.up) - self.tree_state.re_sample() - for _ in range(6): - self.queue.put(self.tree_state.random_direction) - - return self.queue.get() - - def _fill_suck_queue(self): - for _ in range(3): - self.queue.put(self.tree_state.suck) - return self.queue.get() diff --git a/examples/box_picking_drq/experiment_setup/BT/bt_policy.py b/examples/box_picking_drq/experiment_setup/BT/bt_policy.py deleted file mode 100644 index 217f093d..00000000 --- a/examples/box_picking_drq/experiment_setup/BT/bt_policy.py +++ /dev/null @@ -1,128 +0,0 @@ -import numpy as np -from BehaviorTree import BehaviorTree - -import copy -import time -from functools import partial -import jax -import jax.numpy as jnp -import numpy as np -import pynput -import threading -import tqdm -from absl import app, flags -from flax.training import checkpoints -from datetime import datetime - -import gymnasium as gym -from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics - -from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper -from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper -from ur_env.envs.relative_env import RelativeFrame -from ur_env.envs.wrappers import Quat2MrpWrapper, ObservationRotationWrapper - -import ur_env - -from serl_launcher.utils.launcher import make_wandb_logger -from serl_launcher.utils.sampling_utils import TemporalActionEnsemble - -FLAGS = flags.FLAGS - -flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") -flags.DEFINE_string("exp_name", "BT agent", "Name of the experiment for wandb logging.") -flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_integer("eval_n_trajs", 10, "Number of trajectories for evaluation.") - - -def main(_): - env = gym.make( - FLAGS.env, - camera_mode="none", - fake_env=False, - max_episode_length=FLAGS.max_traj_length, - ) - env = RelativeFrame(env) - env = Quat2MrpWrapper(env) - env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) - env = ObservationStatisticsWrapper(env) - env = SERLObsWrapper(env) - env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - env = RecordEpisodeStatistics(env) - - agent = BehaviorTree() - - wandb_logger = make_wandb_logger( - project="paper_evaluation_unseen", - description=FLAGS.exp_name or FLAGS.env, - debug=False, - ) - action_ensemble = TemporalActionEnsemble(activated=False) - success_counter = 0 - - trajectories = [] - traj_infos = [] - for episode in range(FLAGS.eval_n_trajs): - trajectory = [] - obs, _ = env.reset() - done = False - action_ensemble.reset() - - if len(trajectories) == 0: - input("ready? record robot view as well!") - - start_time = time.time() - - while not done: - actions = agent.sample_actions( - observations=obs, - ) - - ensembled_action = action_ensemble.sample(actions) # will return actions if not activated - next_obs, reward, done, truncated, info = env.step(ensembled_action) - transition = dict( - observations=obs.copy(), # do not save voxel grid or images - actions=ensembled_action, - next_observations=next_obs.copy(), - rewards=reward, - masks=1.0 - done, - dones=done, - ) - trajectory.append(transition) - obs = next_obs - - if done or truncated: - success_counter += (reward > 50.) - dt = time.time() - start_time - running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) - running_reward = max(running_reward, -100.) - - print(f"{success_counter}/{episode + 1} ", end=' ') - print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - - trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) - infos = { - "running_reward": running_reward, - "time": dt, - "success_rate": float(reward > 50.), - "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() - } - traj_infos.append(infos) - wandb_logger.log(infos, step=episode) - - traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists - mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} - wandb_logger.log(mean_infos) - for key, value in mean_infos.items(): - print(f"{key}: {value:.3f}") - - with open(f"trajectories {datetime.now().strftime('%m-%d %H%M')}.pkl", "wb") as f: - import pickle - pickle.dump(trajectories, f) - - env.close() - - -if __name__ == "__main__": - app.run(main) diff --git a/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh b/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh deleted file mode 100644 index ab1c2762..00000000 --- a/examples/box_picking_drq/experiment_setup/BT/run_bt_actor.sh +++ /dev/null @@ -1,8 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -which python && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/BT/bt_policy.py "$@" \ - --env box_picking_camera_env_eval \ - --exp_name=bt_drq_policy \ - --max_traj_length 100 \ - --eval_n_trajs 30 \ diff --git a/examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh deleted file mode 100755 index 3397de89..00000000 --- a/examples/box_picking_drq/experiment_setup/Depth Image/run_actor.sh +++ /dev/null @@ -1,19 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="Depth Image small encoder" \ - --camera_mode depth \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type small \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh deleted file mode 100644 index f625c24e..00000000 --- a/examples/box_picking_drq/experiment_setup/Depth Image/run_evaluation.sh +++ /dev/null @@ -1,16 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="Depth Image Evaluation" \ - --camera_mode depth \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/Depth Image/checkpoints Depth image small encoder 0827-16:55"\ - --eval_checkpoint_step 22000 \ - --eval_n_trajs 30 \ - \ - --encoder_type small \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh b/examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh deleted file mode 100755 index 206e4711..00000000 --- a/examples/box_picking_drq/experiment_setup/Depth Image/run_learner.sh +++ /dev/null @@ -1,21 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="Depth image small encoder" \ - --camera_mode depth \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 50000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/Depth\ Image/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_08-24_15-40-34_depth_20cm.pkl \ - \ - --encoder_type small \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh deleted file mode 100755 index c873ad67..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet10/run_actor.sh +++ /dev/null @@ -1,23 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="ResNet10 one cam" \ - --camera_mode rgb \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type resnet-pretrained \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh deleted file mode 100644 index 21bdd764..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet10/run_evaluation.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="ResNet10 Evaluation" \ - --camera_mode rgb \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet10/checkpoints ResNet10 one cam 0821-11:18"\ - --eval_checkpoint_step 15000 \ - --eval_n_trajs 30 \ - \ - --encoder_type resnet-pretrained \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh deleted file mode 100755 index 1ae872a4..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet10/run_learner.sh +++ /dev/null @@ -1,25 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="ResNet10 one cam" \ - --camera_mode rgb \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet10/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ - \ - --encoder_type resnet-pretrained \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh deleted file mode 100755 index 417f7840..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_actor.sh +++ /dev/null @@ -1,23 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="ResNet18 greyscale" \ - --camera_mode grey \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type resnet-pretrained-18 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh deleted file mode 100644 index fef11794..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_evaluation.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="ResNet18 greyscale Evaluation" \ - --camera_mode grey \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/checkpoints ResNet18 greyscale 0821-14:23"\ - --eval_checkpoint_step 11000 \ - --eval_n_trajs 30 \ - \ - --encoder_type resnet-pretrained-18 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh deleted file mode 100755 index 8bd29682..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18 greyscale/run_learner.sh +++ /dev/null @@ -1,25 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="ResNet18 greyscale" \ - --camera_mode grey \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18\ greyscale/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ - \ - --encoder_type resnet-pretrained-18 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh deleted file mode 100755 index cb65d2cc..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18/run_actor.sh +++ /dev/null @@ -1,24 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="ResNet18 feat red 32 128" \ - --camera_mode rgb \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 96 \ - --eval_period 0 \ - \ - --encoder_type resnet-pretrained-18 \ - --encoder_bottleneck_dim 128 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs feature_reduction \ - --encoder_kwargs num_kp \ - --encoder_kwargs 32 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh deleted file mode 100644 index da923bb7..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18/run_evaluation.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="ResNet18 Evaluation" \ - --camera_mode rgb \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18/checkpoints ResNet18 ssam 128 0820-19:23"\ - --eval_checkpoint_step 12000 \ - --eval_n_trajs 30 \ - \ - --encoder_type resnet-pretrained-18 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs spatial_softmax \ - --encoder_kwargs num_kp \ - --encoder_kwargs 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh b/examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh deleted file mode 100755 index 4f47e5bf..00000000 --- a/examples/box_picking_drq/experiment_setup/ResNet18/run_learner.sh +++ /dev/null @@ -1,26 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="ResNet18 feat red 32 128" \ - --camera_mode rgb \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 96 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/ResNet18/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ - \ - --encoder_type resnet-pretrained-18 \ - --encoder_bottleneck_dim 128 \ - --state_mask all \ - --encoder_kwargs pooling_method \ - --encoder_kwargs feature_reduction \ - --encoder_kwargs num_kp \ - --encoder_kwargs 32 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/SAC/run_actor.sh b/examples/box_picking_drq/experiment_setup/SAC/run_actor.sh deleted file mode 100755 index 77fe7c36..00000000 --- a/examples/box_picking_drq/experiment_setup/SAC/run_actor.sh +++ /dev/null @@ -1,19 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="SAC no images" \ - --camera_mode none \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 2048 \ - --eval_period 0 \ - \ - --encoder_type none \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh deleted file mode 100644 index d3f81f4e..00000000 --- a/examples/box_picking_drq/experiment_setup/SAC/run_evaluation.sh +++ /dev/null @@ -1,16 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="SAC no images Evaluation" \ - --camera_mode none \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/SAC/checkpoints SAC no images 0820-17:01"\ - --eval_checkpoint_step 40000 \ - --eval_n_trajs 30 \ - \ - --encoder_type none \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/SAC/run_learner.sh b/examples/box_picking_drq/experiment_setup/SAC/run_learner.sh deleted file mode 100755 index fbc3c431..00000000 --- a/examples/box_picking_drq/experiment_setup/SAC/run_learner.sh +++ /dev/null @@ -1,21 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="SAC no images" \ - --camera_mode none \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 50000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 2048 \ - --checkpoint_period 2500 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/SAC/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_rgb_depth.pkl \ - \ - --encoder_type none \ - --state_mask all \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh deleted file mode 100755 index 3f725561..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet/run_actor.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="Voxnet" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh deleted file mode 100644 index 177d0caf..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet/run_evaluation.sh +++ /dev/null @@ -1,17 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="Voxnet Evaluation unseen" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet/checkpoints Voxnet 0821-16:06"\ - --eval_checkpoint_step 11000 \ - --eval_n_trajs 30 \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh deleted file mode 100755 index d6c4ae28..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet/run_learner.sh +++ /dev/null @@ -1,22 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="Voxnet" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh deleted file mode 100755 index 29dc0158..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_actor.sh +++ /dev/null @@ -1,21 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="voxnet 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh deleted file mode 100644 index a6801361..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_evaluation.sh +++ /dev/null @@ -1,18 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="Voxnet 1quat Evaluation" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_1quat/checkpoints voxnet 1quat 0822-17:54"\ - --eval_checkpoint_step 18000 \ - --eval_n_trajs 30 \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh deleted file mode 100755 index 6c327d06..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_1quat/run_learner.sh +++ /dev/null @@ -1,23 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="voxnet 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ - \ - --encoder_type voxnet \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh deleted file mode 100755 index fb9b7ce2..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_actor.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="voxnet only" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet \ - --state_mask none \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh deleted file mode 100644 index d49d845b..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_evaluation.sh +++ /dev/null @@ -1,17 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="Voxnet only Evaluation" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_only/checkpoints voxnet only 0822-13:43"\ - --eval_checkpoint_step 13000 \ - --eval_n_trajs 30 \ - \ - --encoder_type voxnet \ - --state_mask none \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh deleted file mode 100755 index d254ca74..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_only/run_learner.sh +++ /dev/null @@ -1,22 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="voxnet only" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_only/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ - \ - --encoder_type voxnet \ - --state_mask none \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh deleted file mode 100755 index a1dcfe39..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_actor.sh +++ /dev/null @@ -1,20 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh deleted file mode 100644 index dc391258..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_evaluation.sh +++ /dev/null @@ -1,17 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_eval \ - --exp_name="Voxnet Pretrained Evaluation" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/checkpoints voxnet pretrained 0821-16:53"\ - --eval_checkpoint_step 10000 \ - --eval_n_trajs 30 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh deleted file mode 100755 index 50c30496..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/run_learner.sh +++ /dev/null @@ -1,22 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid.pkl \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh deleted file mode 100755 index 11b12038..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_actor.sh +++ /dev/null @@ -1,21 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh deleted file mode 100644 index 8786a484..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_evaluation.sh +++ /dev/null @@ -1,19 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_tests \ - --exp_name="Voxnet pq temp ens" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints voxnet pretrained 1quat 0823-10:45"\ - --eval_checkpoint_step 11000 \ - --eval_n_trajs 50 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ - --enable_temporal_ensemble_sampling \ - --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh deleted file mode 100755 index 0d906b5e..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/run_learner.sh +++ /dev/null @@ -1,23 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ - \ - --encoder_type voxnet-pretrained \ - --state_mask all \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh deleted file mode 100755 index aaf7b8ee..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_actor.sh +++ /dev/null @@ -1,21 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.1 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained gripper_only 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 20000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --eval_period 0 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask gripper \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh deleted file mode 100644 index 6d5ce598..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_evaluation.sh +++ /dev/null @@ -1,19 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --actor \ - --env box_picking_camera_env_tests \ - --exp_name="voxnet [pqg] temp ens" \ - --camera_mode pointcloud \ - --batch_size 128 \ - --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints voxnet pretrained gripper_only 1quat 0829-14:08"\ - --eval_checkpoint_step 11000 \ - --eval_n_trajs 50 \ - \ - --encoder_type voxnet-pretrained \ - --state_mask gripper \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ - --enable_temporal_ensemble_sampling \ - --debug diff --git a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh b/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh deleted file mode 100755 index e31c7b67..00000000 --- a/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/run_learner.sh +++ /dev/null @@ -1,23 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.5 && \ -python /home/nico/real-world-rl/serl/examples/box_picking_drq/drq_policy.py "$@" \ - --learner \ - --env box_picking_camera_env \ - --exp_name="voxnet pretrained gripper_only 1quat" \ - --camera_mode pointcloud \ - --max_traj_length 100 \ - --seed 1 \ - --max_steps 25000 \ - --random_steps 0 \ - --training_starts 500 \ - --utd_ratio 8 \ - --batch_size 128 \ - --checkpoint_period 1000 \ - --checkpoint_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/VoxNet_pretrained_gripper_1quat/checkpoints \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/experiment_setup/box_picking_20_demos_2024-08-20_voxelgrid_1quat.pkl \ - \ - --encoder_type voxnet-pretrained \ - --state_mask gripper \ - --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ -# --debug diff --git a/examples/box_picking_drq/experiment_setup/results_calculation.py b/examples/box_picking_drq/experiment_setup/results_calculation.py deleted file mode 100644 index eae0049f..00000000 --- a/examples/box_picking_drq/experiment_setup/results_calculation.py +++ /dev/null @@ -1,157 +0,0 @@ -from os.path import join, exists, abspath -import numpy as np -import pandas as pd -import pathlib -import pickle as pkl - -np.set_printoptions(precision=3, suppress=True) -pd.set_option('display.max_columns', 12, 'display.max_rows', 11) - -wdir = pathlib.Path().resolve() - -eval10_files = { - '1 BT': 'BT/trajectories 08-23 1834.pkl', - '2 BC': 'BC/trajectories 08-23 1853.pkl', - '3 SAC': 'SAC/trajectories 08-27 1833.pkl', - # '4 DRQ RGB': 'ResNet10/trajectories 08-23 1821.pkl', - '5 DRQ RGB': 'ResNet18/trajectories 08-23 1807.pkl', - '6 DRQ Depth': 'Depth Image/trajectories 08-27 1825.pkl', - '7 DRQ Voxel': 'VoxNet/trajectories 08-24 1423.pkl', - '8 DRQ Voxel': 'VoxNet_pretrained/trajectories 08-24 1451.pkl', - '9 DRQ Voxel': 'VoxNet_1quat/trajectories 08-24 1442.pkl', - '10 DRQ Voxel': 'VoxNet_pretrained_1quat/trajectories 08-24 1504.pkl', - # '11 DRQ Voxel': 'VoxNet_pretrained_gripper_1quat/trajectories 08-29 1536.pkl', -} - -eval5_files = { - '1 BT': 'BT/trajectories 08-28 1734.pkl', - '2 BC': 'BC/trajectories 08-28 1744.pkl', - '3 SAC': 'SAC/trajectories 08-28 1756.pkl', - # '4 DRQ RGB': 'ResNet10/trajectories 08-28 1815.pkl', - '5 DRQ RGB': 'ResNet18/trajectories 08-28 1805.pkl', - '6 DRQ Depth': 'Depth Image/trajectories 08-28 1823.pkl', - '7 DRQ Voxel': 'VoxNet/trajectories 08-28 1830.pkl', - '8 DRQ Voxel': 'VoxNet_pretrained/trajectories 08-29 1037.pkl', - '9 DRQ Voxel': 'VoxNet_1quat/trajectories 08-29 1024.pkl', - '10 DRQ Voxel': 'VoxNet_pretrained_1quat/trajectories 08-29 1048.pkl', - # '11 DRQ Voxel': 'VoxNet_pretrained_gripper_1quat/trajectories 08-29 1544.pkl', - '12 DRQ Voxel pqt': 'VoxNet_pretrained_1quat/trajectories temp_ens 08-30 1037.pkl', - '13 DRQ Voxel pqgt': 'VoxNet_pretrained_gripper_1quat/trajectories temp_ens 08-30 1028.pkl', -} - - -def create_df(files): - infos = {"Policy": [' '.join(name.split(' ')[1:]) for name in files.keys()], - "Success": np.zeros((len(files.keys()))), - "Reward": np.zeros((len(files.keys()))), - "Rd": np.zeros((len(files.keys()))), - # "A": np.zeros((len(files.keys()))), - "Time": np.zeros((len(files.keys()))), - "Td": np.zeros((len(files.keys()))), - } - - for i, (name, file) in enumerate(files.items()): - assert exists(file) - with open(file, 'rb') as f: - trajectories = pkl.load(f) - - # print(f"\n---{name} ({file.split('/')[0]}):") - # print(f"{len(trajectories)} trajectories --> {[len(t['traj']) for t in trajectories]}") - - success = np.asarray([traj['success'] for traj in trajectories]) - time = np.asarray([traj['time'] for traj in trajectories]) - running_reward = np.asarray([np.sum(np.asarray([t["rewards"] for t in traj['traj']])) for traj in trajectories]) - # print(f"success rate {np.mean(success) * 100:.1f} time: {np.mean(time):.2f}") - # print( - # f"reward: {np.mean(running_reward):.2f} where successful: {np.nanmean(np.where(success, running_reward, np.nan)):.2f}") - - actions = [np.asarray([t['actions'][:6] for t in traj["traj"]]) for traj in - trajectories] # 30 x shape (step, action_dim) - action_diff = np.asarray( - [np.linalg.norm(np.diff(a, axis=0), ord=2, axis=0) for a in actions]) # shape (traj, action_dim) - print(f"{name} action diff: {np.mean(action_diff, axis=0)} {np.mean(action_diff):.2f}") - if type(trajectories[0]["traj"][0]["observations"]) == dict: - velocities = [[t["observations"]["state"].reshape(-1)[21:] for t in traj["traj"]] for traj in - trajectories] - pos = [[t["observations"]["state"].reshape(-1)[12:18] for t in traj["traj"]] for traj in - trajectories] - else: - velocities = [[t["observations"].reshape(-1)[21:] for t in traj["traj"]] for traj in - trajectories] - pos = [[t["observations"].reshape(-1)[12:18] for t in traj["traj"]] for traj in - trajectories] - - # plen = np.asarray([np.sum(np.abs(np.diff(p, axis=0))) for p in pos]) - # vel_p = np.asarray([np.linalg.norm(np.diff(p, axis=0), ord=2, axis=0) for p in pos]) - # vel = np.asarray([np.linalg.norm(vel, ord=2, axis=0) for vel in velocities]) - # accel = np.asarray([np.linalg.norm(np.diff(vel, axis=0), ord=2, axis=0) for vel in velocities]) - # print(f"plen {np.mean(plen):.3f}") - # print(f"{name} accel diff: {np.mean(accel, axis=0)} {np.mean(accel):.2f} {np.mean(vel):.2f} {np.mean(vel_p)*10:.2f}") - - infos['Success'][i] = success.mean() * 100. - infos['Reward'][i] = running_reward.mean() - infos['Rd'][i] = np.nanstd(np.where(success, running_reward, np.nan)) - infos['Time'][i] = time.mean() - infos['Td'][i] = np.nanstd(np.where(success, time, np.nan)) - # infos['A'][i] = action_diff.mean() - - return pd.DataFrame(infos) - - -def f2s(x, precision=1): - # return string of a float with given precision, without zeros - return f"{float(x):.{precision}f}".rstrip('0').rstrip('.') - - -def highlight_extremes(df, max_subset, min_subset): - # Highlight maximum in max_subset - for column in max_subset: - max_value = df[column].max() - df[column] = df[column].apply(lambda x: f"\\bfseries {f2s(x)}" if x == max_value else f2s(x)) - - # Highlight minimum in min_subset - for column in min_subset: - min_value = df[column].min() - df[column] = df[column].apply(lambda x: f"\\bfseries {f2s(x, 2)}" if x == min_value else f2s(x, 2)) - - for column in df.columns: - if column in ["Rd", "Td", "Rd5", "Td5"]: - df[column] = df[column].apply(lambda x: f"$\\pm{f2s(x)}$") - - return df - - -def same_strlen(df): # TODO does not work (textbf...) - for column in df.columns[1:]: - max_len = np.max([len(s) for s in df[column]]) - print(max_len) - df[column] = df[column].apply(lambda x: " "*(max_len-len(x)) + x) - return df - - -if __name__ == '__main__': - box_10_df = create_df(eval10_files) - box_5_df = create_df(eval5_files) - - box_5_df.rename(columns={"Success": "Success5", "Reward": "Reward5", "Time": "Time5", "Rd": "Rd5", "Td": "Td5"}, - inplace=True) - box_5_df = box_5_df.drop(columns=box_5_df.columns[0]) - - combined = box_10_df.merge(box_5_df, how='inner', left_index=True, right_index=True) - - print("\nEvaluation on seen boxes\n", box_10_df) - print("\nEvaluation on unseen boxes\n", box_5_df) - print("\nboth:\n", combined) - - max = np.array([1, 2, 6, 7]) - min = np.array([4, 9, ]) - df = highlight_extremes(combined, max_subset=combined.columns[max], min_subset=combined.columns[min]) - df = df.rename(index={i: f"({i + 1})" for i in list(df.index)}) - - styled = ( - df.style - # .hide(axis="index") - .format(decimal='.', thousands='\'', precision=2) - ) - latex = styled.to_latex(hrules=True) - print("\n\t", latex.replace("\n", "\n\t\t")) diff --git a/examples/box_picking_drq/run_actor.sh b/examples/box_picking_drq/run_actor.sh index 06370bd8..be65622f 100755 --- a/examples/box_picking_drq/run_actor.sh +++ b/examples/box_picking_drq/run_actor.sh @@ -4,14 +4,17 @@ python drq_policy.py "$@" \ --actor \ --env box_picking_camera_env \ --max_traj_length 100 \ - --exp_name=d \ + --exp_name=box_picking \ --camera_mode pointcloud \ - --seed 2 \ + --seed 1 \ --max_steps 20000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ - --eval_period 2500 \ + --eval_period 1000 \ --encoder_type voxnet-pretrained \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ +# --enable_obs_rotation_wrapper \ # --debug diff --git a/examples/box_picking_drq/run_evaluation.sh b/examples/box_picking_drq/run_evaluation.sh index 4c7c9dfb..929e9618 100644 --- a/examples/box_picking_drq/run_evaluation.sh +++ b/examples/box_picking_drq/run_evaluation.sh @@ -2,17 +2,17 @@ export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ export XLA_PYTHON_CLIENT_MEM_FRACTION=.2 && \ python drq_policy.py "$@" \ --actor \ - --env box_picking_camera_env_tests \ + --env box_picking_camera_env \ --exp_name=drq_evaluation \ --camera_mode pointcloud \ --batch_size 128 \ --max_traj_length 100 \ - --checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints voxnet only pure 32 16 8 noFT (else all) 0816-17:14"\ - --eval_checkpoint_step 12500 \ + --checkpoint_path "checkpoint folder path here"\ + --eval_checkpoint_step 10000 \ --eval_n_trajs 20 \ \ - --encoder_type voxnet \ + --encoder_type voxnet-pretrained \ --state_mask all \ --encoder_bottleneck_dim 128 \ - --enable_obs_rotation_wrapper \ - --debug +# --enable_obs_rotation_wrapper \ +# --debug diff --git a/examples/box_picking_drq/run_learner.sh b/examples/box_picking_drq/run_learner.sh index c31c0ff5..21f4d65f 100755 --- a/examples/box_picking_drq/run_learner.sh +++ b/examples/box_picking_drq/run_learner.sh @@ -3,17 +3,20 @@ export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ python drq_policy.py "$@" \ --learner \ --env box_picking_camera_env \ - --exp_name=d \ + --exp_name=ox_picking \ --camera_mode pointcloud \ --max_traj_length 100 \ - --seed 2 \ + --seed 1 \ --max_steps 25000 \ --random_steps 0 \ --training_starts 500 \ --utd_ratio 8 \ --batch_size 128 \ --eval_period 20000 \ + --checkpoint_period 1000 \ --encoder_type voxnet-pretrained \ - --checkpoint_period 2500 \ - --demo_path /home/nico/real-world-rl/serl/examples/box_picking_drq/box_picking_20_demos_aug9_noFT_1quad.pkl \ + --state_mask all \ + --encoder_bottleneck_dim 128 \ + --demo_path "demo path here *.pkl" \ +# --enable_obs_rotation_wrapper \ # --debug diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index 983c4b3d..e1c6177d 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -10,21 +10,15 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.common import JaxRLTrainState, ModuleDict, nonpytree_field -from serl_launcher.common.encoding import EncodingWrapper, create_state_mask +from serl_launcher.common.encoding import MaskedEncodingWrapper, create_state_mask from serl_launcher.common.optimizers import make_optimizer from serl_launcher.common.typing import Batch, Data, Params, PRNGKey from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize from serl_launcher.networks.lagrange import GeqLagrangeMultiplier from serl_launcher.networks.mlp import MLP -from serl_launcher.vision.voxel_grid_encoders import MLPEncoder, VoxNet +from serl_launcher.vision.voxel_grid_encoders import VoxNet from serl_launcher.utils.train_utils import _unpack, concat_batches -from serl_launcher.vision.data_augmentations import ( - batched_random_crop, - batched_random_shift_voxel, - batched_random_rot90_action, - batched_random_rot90_state, - batched_random_rot90_voxel -) +from serl_launcher.vision.data_augmentations import batched_random_crop, batched_random_shift_voxel class DrQAgent(SACAgent): @@ -40,10 +34,10 @@ def create( temperature_def: nn.Module, # Optimizer actor_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 + "learning_rate": 3e-4, }, critic_optimizer_kwargs={ - "learning_rate": 3e-4, # 3e-4 + "learning_rate": 3e-4, }, temperature_optimizer_kwargs={ "learning_rate": 3e-4, @@ -113,16 +107,15 @@ def create( ) @classmethod - def create_drq( + def create_voxel_drq( cls, rng: PRNGKey, observations: Data, actions: jnp.ndarray, # Model architecture - encoder_type: str = "small", + encoder_type: str = "resnet", use_proprio: bool = False, state_mask: str = "all", - proprio_latent_dim: int = 64, critic_network_kwargs: dict = { "hidden_dims": [256, 256], }, @@ -133,11 +126,7 @@ def create_drq( "tanh_squash_distribution": True, "std_parameterization": "uniform", }, - encoder_kwargs: dict = { - "pooling_method": "spatial_learned_embeddings", - "num_spatial_blocks": 8, - "bottleneck_dim": 256, - }, + encoder_kwargs: dict = {}, critic_ensemble_size: int = 2, critic_subsample_size: Optional[int] = None, temperature_init: float = 1.0, @@ -145,7 +134,7 @@ def create_drq( **kwargs, ): """ - Create a new pixel-based agent. + Create a new voxel-based agent. """ policy_network_kwargs["activate_final"] = True @@ -189,16 +178,11 @@ def create_drq( name="pretrained_encoder", ) - use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == ( - 128, 128, 1) - print(f"use single channel only: {use_single_channel}") - encoders = { image_key: PreTrainedResNetEncoder( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - use_single_channel=use_single_channel, **encoder_kwargs ) for image_key in image_keys @@ -212,51 +196,15 @@ def create_drq( name="pretrained_encoder", ) - use_single_channel = [value for key, value in observations.items() if key != "state"][0].shape[-3:] == ( - 128, 128, 1) - print(f"use single channel only: {use_single_channel}") - encoders = { image_key: PreTrainedResNetEncoder( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - use_single_channel=use_single_channel, **encoder_kwargs ) for image_key in image_keys } - elif encoder_type == "distance-sensor": - from serl_launcher.vision.range_sensor import RangeSensorEncoder - # use depth image as range-like sensor - assert [value for key, value in observations.items() if key != "state"][0].shape[-3:] == (128, 128, 1) - import numpy as np - - # 3x3 points centered in the middle - keypoints = [tuple(k) for k in np.stack(np.meshgrid([32, 64, 96], [32, 64, 96])).reshape((-1, 2))] - keypoint_size = (5, 5) - - encoders = { - image_key: RangeSensorEncoder( - name=f"encoder_{image_key}", - keypoints=keypoints, - keypoint_size=keypoint_size, - ) - for image_key in image_keys - } - elif encoder_type == "voxel-mlp": # not used, too many weights... - encoders = { - image_key: MLPEncoder( - mlp=MLP( - hidden_dims=[64], - activations=nn.relu, - activate_final=True, - use_layer_norm=True, - ), - bottleneck_dim=encoder_kwargs["bottleneck_dim"], - ) - for image_key in image_keys - } elif encoder_type == "voxnet" or encoder_type == "voxnet-pretrained": encoders = { image_key: VoxNet( @@ -274,12 +222,11 @@ def create_drq( state_mask_arr = create_state_mask(state_mask) print(f"state_mask: {state_mask} {state_mask_arr.astype(jnp.int32)}") - encoder_def = EncodingWrapper( + encoder_def = MaskedEncodingWrapper( encoder=encoders, use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, - # proprio_latent_dim=proprio_latent_dim, state_mask=state_mask_arr ) @@ -337,46 +284,7 @@ def create_drq( return agent - def batch_augmentation_fn(self, observations, next_observations, actions, rng, activated=True): - if not activated: - return observations, next_observations, actions - for pixel_key in self.config["image_keys"]: - if not "pointcloud" in pixel_key: - continue # skip if not pointcloud - only_180 = self.config["activate_batch_rotation"] == 180 - - # rotation of state, action and voxel grid (use the same rng for all of them, so same rotation) - # jax.debug.print("before {} {} {}", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) - # jax.debug.print("voxel: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) - # jax.debug.print("action: {}", actions[0, :]) - observations = observations.copy( - add_or_replace={ - "state": batched_random_rot90_state( - observations["state"], rng, num_batch_dims=2, only_180=only_180 - ), - pixel_key: batched_random_rot90_voxel( - observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 - ), - } - ) - next_observations = next_observations.copy( - add_or_replace={ - "state": batched_random_rot90_state( - next_observations["state"], rng, num_batch_dims=2, only_180=only_180 - ), - pixel_key: batched_random_rot90_voxel( - next_observations[pixel_key], rng, num_batch_dims=2, only_180=only_180 - ) - } - ) - actions = batched_random_rot90_action(actions, rng, only_180=only_180) - - # jax.debug.print("after {} {} {}\n", observations["state"][0, 0, :], next_observations["state"][0, 0, :], actions[0, :]) - # jax.debug.print("voxel after: \n{}", jnp.mean(observations[pixel_key][0, 0, ...].reshape((5, 10, 5, 10, 40)), axis=(1, 3, 4))) - # jax.debug.print("action after: {}", actions[0, :]) - return observations, next_observations, actions - - def image_augmentation_fn(self, obs_rng, observations, next_obs_rng, next_observations): + def data_augmentation_fn(self, rng, observations): # TODO make it configurable: see https://github.com/rail-berkeley/serl/pull/67 for pixel_key in self.config["image_keys"]: @@ -385,14 +293,7 @@ def image_augmentation_fn(self, obs_rng, observations, next_obs_rng, next_observ observations = observations.copy( add_or_replace={ pixel_key: batched_random_shift_voxel( - observations[pixel_key], obs_rng, padding=3, num_batch_dims=2 - ) - } - ) - next_observations = next_observations.copy( - add_or_replace={ - pixel_key: batched_random_shift_voxel( - next_observations[pixel_key], next_obs_rng, padding=3, num_batch_dims=2 + observations[pixel_key], rng, padding=3, num_batch_dims=2 ) } ) @@ -402,18 +303,11 @@ def image_augmentation_fn(self, obs_rng, observations, next_obs_rng, next_observ observations = observations.copy( add_or_replace={ pixel_key: batched_random_crop( - observations[pixel_key], obs_rng, padding=4, num_batch_dims=2 - ) - } - ) - next_observations = next_observations.copy( - add_or_replace={ - pixel_key: batched_random_crop( - next_observations[pixel_key], next_obs_rng, padding=4, num_batch_dims=2 + observations[pixel_key], rng, padding=4, num_batch_dims=2 ) } ) - return observations, next_observations + return observations @partial(jax.jit, static_argnames=("utd_ratio", "pmap_axis")) def update_high_utd( @@ -439,26 +333,13 @@ def update_high_utd( batch = _unpack(batch) rng = new_agent.state.rng - rng, obs_rng, next_obs_rng, rot90_rng = jax.random.split(rng, 4) - obs, next_obs = self.image_augmentation_fn( - obs_rng=obs_rng, - observations=batch["observations"], - next_obs_rng=next_obs_rng, - next_observations=batch["next_observations"] - ) - - obs, next_obs, actions = self.batch_augmentation_fn( - observations=obs, - next_observations=next_obs, - actions=batch["actions"], - rng=rot90_rng, - activated=self.config["activate_batch_rotation"] > 0, - ) + rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) + obs = self.data_augmentation_fn(obs_rng, batch["observations"]) + next_obs = self.data_augmentation_fn(next_obs_rng, batch["next_observations"]) batch = batch.copy( add_or_replace={ "observations": obs, "next_observations": next_obs, - "actions": actions, } ) @@ -485,26 +366,13 @@ def update_critics( # TODO implement K=2 and M=2 rng = new_agent.state.rng - rng, obs_rng, next_obs_rng, rot90_rng = jax.random.split(rng, 4) - obs, next_obs = self.image_augmentation_fn( - obs_rng=obs_rng, - observations=batch["observations"], - next_obs_rng=next_obs_rng, - next_observations=batch["next_observations"] - ) - obs, next_obs, actions = self.batch_augmentation_fn( - observations=obs, - next_observations=next_obs, - actions=batch["actions"], - rng=rot90_rng, - activated=self.config["activate_batch_rotation"] > 0, - ) - + rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) + obs = self.data_augmentation_fn(obs_rng, batch["observations"]) + next_obs = self.data_augmentation_fn(next_obs_rng, batch["next_observations"]) batch = batch.copy( add_or_replace={ "observations": obs, "next_observations": next_obs, - "actions": actions, } ) @@ -518,37 +386,4 @@ def update_critics( del critic_infos["actor"] del critic_infos["temperature"] - return new_agent, critic_infos - - def test_augmentation(self, batch: Batch): - if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: - batch = _unpack(batch) - - obs_cp, next_obs_cp, actions_cp = batch["observations"].copy(), batch["next_observations"].copy(), batch[ - "actions"].copy() - - rng, rot90_rng = jax.random.split(self.state.rng, 2) - obs, next_obs, actions = self.batch_augmentation_fn( - observations=batch["observations"], - next_observations=batch["next_observations"], - actions=batch["actions"], - rng=rot90_rng, - activated=True, - ) - - for _ in range(3): - obs, next_obs, actions = self.batch_augmentation_fn( - observations=obs, - next_observations=next_obs, - actions=actions, - rng=rot90_rng, - activated=True, - ) - - # each instance of the batch is rotated by 0, 90, 180 or 270 degrees, - # 4 times these should all return to the original one - print("-" * 35, "\nAsugmentation check here!\n", "-" * 35) - jax.debug.print("obs {}", jnp.sum(jnp.abs(obs["state"] - obs_cp["state"]))) - jax.debug.print("next_obs {}", jnp.sum(jnp.abs(next_obs["state"] - next_obs_cp["state"]))) - jax.debug.print("actions {}", jnp.sum(jnp.abs(actions - actions_cp))) - # they are all in range 1e-6 to 1e-7, check done + return new_agent, critic_infos \ No newline at end of file diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index c11567b2..adf4c321 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -28,7 +28,7 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: return masks[mask_str] -class EncodingWrapper(nn.Module): +class MaskedEncodingWrapper(nn.Module): """ Encodes observations into a single flat encoding, adding additional functionality for adding proprioception and stopping the gradient. @@ -41,7 +41,6 @@ class EncodingWrapper(nn.Module): encoder: nn.Module use_proprio: bool state_mask: jnp.ndarray - # proprio_latent_dim: int = 64 enable_stacking: bool = False image_keys: Iterable[str] = ("image",) @@ -63,11 +62,7 @@ def __call__( state = rearrange(state, "T C -> (T C)") if len(state.shape) == 3: state = rearrange(state, "B T C -> B (T C)") - # state = nn.Dense( - # self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() - # )(state) - # state = nn.LayerNorm()(state) - # state = nn.tanh(state) + # do not use proprio latent dim return state encoded = [] @@ -93,8 +88,7 @@ def __call__( if self.use_proprio: # project state to embeddings as well state = observations["state"] - state = state[..., self.state_mask] # ignore certain elements - # jax.debug.print("state {}", state) + state = state[..., self.state_mask] # only propagate non-zero mask entries if state.shape[-1] != 0: if self.enable_stacking: # Combine stacking and channels into a single dimension @@ -103,11 +97,7 @@ def __call__( encoded = encoded.reshape(-1) if len(state.shape) == 3: state = rearrange(state, "B T C -> B (T C)") - # state = nn.Dense( - # self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() - # )(state) - # state = nn.LayerNorm()(state) - # state = nn.tanh(state) + # do not use proprio latent di encoded = jnp.concatenate([encoded, state], axis=-1) return encoded diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 60a0a902..586e7c19 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -102,27 +102,25 @@ def make_sac_agent(seed, sample_obs, sample_action): ) -def make_drq_agent( +def make_voxel_drq_agent( seed, sample_obs, sample_action, image_keys=("image",), - encoder_type="small", - state_mask="no_ForceTorque", - # proprio_latent_dim=64, + encoder_type="voxnet", + state_mask="all", encoder_kwargs=None ): if encoder_kwargs is None: encoder_kwargs = dict(bottleneck_dim=128) - agent = DrQAgent.create_drq( + agent = DrQAgent.create_voxel_drq( jax.random.PRNGKey(seed), sample_obs, sample_action, encoder_type=encoder_type, use_proprio=True, state_mask=state_mask, - # proprio_latent_dim=proprio_latent_dim, image_keys=image_keys, policy_kwargs=dict( tanh_squash_distribution=True, @@ -144,21 +142,21 @@ def make_drq_agent( ), temperature_init=1e-2, discount=0.99, # 0.99 - backup_entropy=True, # default: False + backup_entropy=True, critic_ensemble_size=10, critic_subsample_size=2, encoder_kwargs=encoder_kwargs, # dict( - # # pooling_method="spatial_softmax", # default "spatial_learned_embeddings" + # # pooling_method="spatial_learned_embeddings", # bottleneck_dim=128, # # num_spatial_blocks=8, # # num_kp=64, # ), actor_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 + "learning_rate": 3e-3, }, critic_optimizer_kwargs={ - "learning_rate": 3e-3, # 3e-4 + "learning_rate": 3e-3, }, ) return agent diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index cacc0894..4301f96c 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -10,9 +10,7 @@ import numpy as np import tensorflow as tf import wandb -import matplotlib.pyplot as plt from flax.core import frozen_dict -from jaxlib.xla_extension import ArrayImpl def concat_batches(offline_batch, online_batch, axis=1): @@ -207,76 +205,4 @@ def get_size(params): def parameter_overview(agent): from clu import parameter_overview - print(parameter_overview.get_parameter_overview(agent.state.params)) - - -def plot_feature_kernel_histogram(agent): - import matplotlib.pyplot as plt - - feature_kernel = agent.state.params["modules_actor"]["network"]["Dense_0"]["kernel"] - feature_bias = agent.state.params["modules_actor"]["network"]["Dense_0"]["bias"] - print(f"kernel has shape: {feature_kernel.shape}") - - plots = feature_kernel.shape[0] // 256 + 1 - fig, axes = plt.subplots(nrows=plots, ncols=1, sharex=True, sharey=True, figsize=(5, 3 * plots)) - - feature_kernel = feature_kernel.mean(axis=1) - - for p in range(plots): - legend = f"image {p}" if p < plots - 1 else "observations" - print(f"{legend} mean and std: ", - [feature_kernel[p * 256:(p + 1) * 256].mean(), feature_kernel[p * 256:(p + 1) * 256].std()]) - axes[p].hist(feature_kernel[p * 256:(p + 1) * 256], bins=50) - axes[p].set_title(legend) - plt.show() - - -def find_zero_weights(params, print_str="", print_all=False): - if isinstance(params, dict): - for key in params.keys(): - find_zero_weights(params[key], print_str=print_str + " " + key, print_all=print_all) - else: - if print_all: - print(f"{print_str} m:{params.mean()} s:{params.std()}") - return - if abs(params.mean()) < 1e-5: - print(f" zero weights--> {print_str} std: {params.std()}") - else: - print(".", end='') - - -def plot_3d_kernel(kernel, nr): - fig = plt.figure() - ax = fig.add_subplot(111, projection='3d') - - x_len, y_len, z_len = kernel.shape - - x = np.arange(x_len) - y = np.arange(y_len) - z = np.arange(z_len) - x, y, z = np.meshgrid(x, y, z, indexing='ij') - - # Normalize the values for color mapping - norm = plt.Normalize(kernel.min(), kernel.max()) - colors = plt.cm.viridis(norm(kernel)) - alpha = np.clip(np.abs(kernel) * 9, 0., 1.) - alpha = np.clip(np.where(alpha < 0.17, 0., alpha), 0., 1.) - - for i in range(x_len): - for j in range(y_len): - for k in range(z_len): - ax.bar3d(i, j, k, .9, .9, .9, color=colors[i, j, k], alpha=alpha[i, j, k]) - - ax.set_title(str(nr)) - ax.set_xticklabels([]) - ax.set_yticklabels([]) - ax.set_zticklabels([]) - plt.show() - - -def plot_conv3d_kernels(params): - kernels = params["modules_actor"]["encoder"]["encoder_wrist_pointcloud"]["conv_5x5x5"]["kernel"] - # shape (5, 5, 5, 1, 32) - for i in range(kernels.shape[-1]): - print(kernels[..., 0, i].mean(), kernels[..., 0, i].std()) - plot_3d_kernel(kernels[..., 0, i], i) + print(parameter_overview.get_parameter_overview(agent.state.params)) \ No newline at end of file diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index 8562bf83..e308a41f 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -4,118 +4,6 @@ import jax.numpy as jnp import jax.lax as lax -ROT90 = jnp.array([[0, -1, 0], [1, 0, 0], [0, 0, 1]]) -ROT_GENERAL = jnp.array([jnp.eye(3), ROT90, ROT90 @ ROT90, ROT90.transpose()]) - -""" # not used anymore, since we are no longer using euler angles -import jaxlie - -def euler_xyz_to_yxz(xyz_angles): - # Create SO3 object from xyz Euler angles - so3 = jaxlie.SO3.from_rpy_radians( - roll=xyz_angles[0], - pitch=xyz_angles[1], - yaw=xyz_angles[2] - ) - rot_matrix = so3.as_matrix() - - # Extract yxz Euler angles from rotation matrix - y = jnp.arctan2(-rot_matrix[2, 0], rot_matrix[2, 2]) - x = jnp.arcsin(jnp.clip(rot_matrix[2, 1], -1.0, 1.0)) # might prevent NaN's - z = jnp.arctan2(-rot_matrix[0, 1], rot_matrix[1, 1]) - return jnp.array([y, x, z]) - - -def orient_rot90_jax(array: jnp.ndarray, rot: int) -> jnp.ndarray: - assert array.shape == (3,) - - def single_90_rotation(arr): - yxz = euler_xyz_to_yxz(arr) - yxz = yxz.at[0].multiply(-1.) - return yxz - - # Apply the rotation 'rot' number of times - return jax.lax.fori_loop(0, rot % 4, lambda _, arr: single_90_rotation(arr), array) -""" - - -@jax.jit -def random_rot90_action(action: jnp.ndarray, num_rot: int): # action is (x, y, z, rx, ry, rz, gripper) - assert action.shape == (7,) - xyz_rotated = jnp.dot(ROT_GENERAL[num_rot], action[:3]) - orientation_rotated = jnp.dot(ROT_GENERAL[num_rot], action[3:6]) - return jnp.concatenate([xyz_rotated, orientation_rotated, action[-1:]]) - - -@jax.jit -def batched_random_rot90_action(actions, rng): - assert actions.shape[-1:] == (7,) - num_rot = jax.random.randint(rng, (actions.shape[0],), 0, 4) - - # jax.debug.print("rotation: {}", num_rot[0]) - - actions = jax.vmap( - lambda a, k: random_rot90_action(a, k), in_axes=(0, 0), out_axes=0 - )(actions, num_rot) - - return actions - - -@partial(jax.jit, static_argnames="num_batch_dims") -def batched_random_rot90_state(state, rng, *, num_batch_dims: int = 1): - original_shape = state.shape - state = jnp.reshape(state, (-1, *state.shape[num_batch_dims:])) - num_rot = jax.random.randint(rng, (state.shape[0],), 0, 4) - - state = jax.vmap( - lambda s, k: random_rot90_state(s, k), in_axes=(0, 0), out_axes=0 - )(state, num_rot) - - return state.reshape(original_shape) - - -def random_rot90_state(state, num_rot): - assert state.shape[-1] == 27 - - """ - indexes are (action[0:7], gripper[7:9], force[9:12], pose[12:15], orientation[15:18], - torque[18:21], velocity[21:24], orientation velocity[24:27]) - """ - indices = jnp.array([0, 3, 9, 12, 15, 18, 21, 24]) - - def rotate(i, state): - part = lax.dynamic_slice(state, (indices[i],), (3,)) - rotated = jnp.dot(ROT_GENERAL[num_rot], part) - return lax.dynamic_update_slice(state, rotated, (indices[i],)) - - # Apply rotations sequentially - state = jax.lax.fori_loop(0, indices.shape[0], rotate, state) - return state - - -@partial(jax.jit, static_argnames="num_batch_dims") -def batched_random_rot90_voxel(voxel_grid, rng, *, num_batch_dims: int = 1): - original_shape = voxel_grid.shape - voxel_grid = jnp.reshape(voxel_grid, (-1, *voxel_grid.shape[num_batch_dims:])) - - num_rot = jax.random.randint(rng, (voxel_grid.shape[0],), 0, 4) - - voxel_grid = jax.vmap( - lambda v, k: random_rot90_voxel(v, k), in_axes=(0, 0), out_axes=0 - )(voxel_grid, num_rot) - - return voxel_grid.reshape(original_shape) - - -@partial(jax.jit, static_argnames="axes") -def rot90_traceable(m, k=1, axes=(0, 1)): - return jax.lax.switch(k, [partial(jnp.rot90, m, k=i, axes=axes) for i in range(4)]) - - -@jax.jit -def random_rot90_voxel(voxel_grid, num_rot): - return rot90_traceable(voxel_grid, k=num_rot, axes=(-3, -2)) - @partial(jax.jit, static_argnames="padding") def random_crop(img, rng, *, padding): diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index 57dfe7c8..d7c8985e 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -331,7 +331,6 @@ class PreTrainedResNetEncoder(nn.Module): num_kp: int = 64 # for Spatial Softmax bottleneck_dim: Optional[int] = None pretrained_encoder: nn.module = None - use_single_channel: bool = False @nn.compact def __call__( @@ -342,11 +341,6 @@ def __call__( ): x = observations - # if we want to use single channel image data (grayscale) - if self.use_single_channel: - assert x.shape[-3:] == (128, 128, 1) # check shape - x = jnp.repeat(x, 3, axis=-1) - if encode: x = self.pretrained_encoder(x, train=train) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py index 92c3a997..1c867ca3 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1_18.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -418,7 +418,7 @@ def __call__(self, observations, train=False): resnetv1_18_configs = { "resnetv1-18-frozen": functools.partial( ResNet, architecture='resnet18', - ckpt_dir="/examples/box_picking_drq/resnet18_weights.h5", + ckpt_dir="/examples/box_picking_drq/resnet18_weights.h5", # download from #TODO pre_pooling=True ) } diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index 31085f11..dc8b8e2f 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -8,36 +8,6 @@ import jax -class MLPEncoder(nn.Module): - mlp: nn.module = None - bottleneck_dim: Optional[int] = None - - @nn.compact - def __call__( - self, - observations: jnp.ndarray, - encode: bool = True, - train: bool = True, - ): - # add batch dim if missing - no_batch_dim = len(observations.shape) < 4 - if no_batch_dim: - observations = observations[None] - - # flatten but keep batch tim - x = jnp.reshape(observations, (observations.shape[0], -1)) - - if encode: - x = self.mlp(x, train=train) - - if self.bottleneck_dim is not None: - x = nn.Dense(self.bottleneck_dim)(x) - x = nn.LayerNorm()(x) - x = nn.tanh(x) - - return x[0] if no_batch_dim else x - - class SpatialSoftArgmax3D(nn.Module): """ 3D Implementation of Spatial Soft Argmax @@ -88,7 +58,7 @@ def __call__(self, features): class VoxNet(nn.Module): """ - Voxnet-like implementation: https://github.com/AutoDeep/VoxNet/blob/master/src/nets/voxNet.py + VoxNet-like implementation: https://github.com/AutoDeep/VoxNet/blob/master/src/nets/voxNet.py """ use_conv_bias: bool = False @@ -104,7 +74,7 @@ def __call__( encode: bool = True, train: bool = True, ): - # observations has shape (B, X, Y, Z) (boolean for now) + # observations has shape (B, X, Y, Z) no_batch_dim = len(observations.shape) < 4 if no_batch_dim: observations = observations[None] @@ -129,7 +99,7 @@ def __call__( name="conv_5x5x5", )(x) x = nn.LayerNorm()(x) - x = l_relu(x) # shape (B, (X-3)/2, (Y-3)/2, (Z-3)/2, F) + x = l_relu(x) x = conv3d( features=feature_dimensions[1], @@ -143,19 +113,18 @@ def __call__( x = jax.lax.stop_gradient(x) # unfortunately also cuts gradients of the LayerNorm above x = nn.LayerNorm()(x) - x = l_relu(x) # shape (B, (X-4)/2, (Y-4)/2, (Z-4)/2, F) + x = l_relu(x) x = conv3d( - features=feature_dimensions[2], # if pretrained, only uses [..] out of 128 pretrained params as initial weights + features=feature_dimensions[2], # if pretrained, uses [..] out of 128 pretrained params as initial weights kernel_size=(2, 2, 2), strides=(2, 2, 2), name="conv_2x2x2" )(x) x = nn.LayerNorm()(x) - x = l_relu(x) # shape (B, (X-5)/8, (Y-5)/8, (Z-5)/8, F) + x = l_relu(x) - # x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) - # jax.debug.print("ssam {}", x) + # x = SpatialSoftArgmax3D(10, 10, 8, 64)(x) # not used for now # reshape and dense (preserve batch dim) x = jnp.reshape(x, (1 if no_batch_dim else x.shape[0], -1)) diff --git a/serl_robot_infra/robot_controllers/ur5_controller.py b/serl_robot_infra/robot_controllers/ur5_controller.py index a63871aa..9b00075f 100644 --- a/serl_robot_infra/robot_controllers/ur5_controller.py +++ b/serl_robot_infra/robot_controllers/ur5_controller.py @@ -3,8 +3,6 @@ import threading import asyncio import numpy as np -import matplotlib.pyplot as plt -from responses import target from scipy.spatial.transform import Rotation as R from rtde_control import RTDEControlInterface from rtde_receive import RTDEReceiveInterface @@ -33,7 +31,6 @@ def __init__( kd=2200, config=None, verbose=False, - plot=False, *args, **kwargs ): @@ -50,7 +47,6 @@ def __init__( self.kd = kd self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} self.verbose = verbose - self.do_plot = plot self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) @@ -242,35 +238,6 @@ def _calculate_force(self): return np.concatenate((force_pos, torque)) - def plot(self): - if self.horizon[0] < self.horizon[1]: - self.horizon[0] += 1 - self.hist_data[0].append(self.curr_pos.copy()) - self.hist_data[1].append(self.target_pos.copy()) - return - - self.ur_control.forceModeStop() - - print("[RIC] plotting") - real_pos = np.array([pose2rotvec(q) for q in self.hist_data[0]]) - target_pos = np.array([pose2rotvec(q) for q in self.hist_data[1]]) - - plt.figure() - fig, axes = plt.subplots(nrows=3, ncols=2, figsize=(12, 8), dpi=200) - ax_label = [{'x': f'time {self.frequency} [Hz]', 'y': ylabel} for ylabel in ["[mm]", "[rad]"]] - plot_label = "X Y Z RX RY RZ".split(' ') - - for i in range(6): - ax = axes[i % 3, i // 3] - ax.plot(real_pos[:, i], 'b', label=plot_label[i]) - ax.plot(target_pos[:, i], 'g') - ax.set(xlabel=ax_label[i // 3]['x'], ylabel=ax_label[i // 3]['y']) - ax.legend() - - fig.suptitle(f"params--> kp:{self.kp} kd:{self.kd}") - plt.show(block=True) - self.stop() - async def send_gripper_command(self, force_release=False): if force_release: await self.robotiq_gripper.automatic_release() @@ -374,10 +341,6 @@ async def run_async(self): await self._update_robot_state() self._truncate_check() - # only used for plotting - if self.do_plot: - self.plot() - # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) diff --git a/serl_robot_infra/setup.py b/serl_robot_infra/setup.py index b2e63bb4..64ddece0 100644 --- a/serl_robot_infra/setup.py +++ b/serl_robot_infra/setup.py @@ -18,5 +18,6 @@ "requests", "flask", "defusedxml", + "clu", ], ) diff --git a/serl_robot_infra/ur_env/__init__.py b/serl_robot_infra/ur_env/__init__.py index baa10b69..63a95bab 100644 --- a/serl_robot_infra/ur_env/__init__.py +++ b/serl_robot_infra/ur_env/__init__.py @@ -3,31 +3,13 @@ register( id="box_picking_basic_env", - entry_point="ur_env.envs.basic_env:UR5BasicEnv", + entry_point="ur_env.envs.basic_env:BoxPickingBasicEnv", max_episode_steps=200, ) register( id="box_picking_camera_env", - entry_point="ur_env.envs.camera_env:UR5CameraEnv", - max_episode_steps=100, -) - -register( - id="box_picking_camera_env_tests", - entry_point="ur_env.envs.camera_env:UR5CameraEnvTest", - max_episode_steps=100, -) - -register( - id="box_picking_camera_env_eval", - entry_point="ur_env.envs.camera_env:UR5CameraEnvEval", - max_episode_steps=100, -) - -register( - id="box_picking_camera_env_demo", - entry_point="ur_env.envs.camera_env:UR5CameraEnvDemo", + entry_point="ur_env.envs.camera_env:BoxPickingCameraEnv", max_episode_steps=100, ) diff --git a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py index 8d56b400..06963669 100644 --- a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py +++ b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py @@ -2,7 +2,7 @@ from typing import Tuple from ur_env.envs.ur5_env import UR5Env -from ur_env.envs.basic_env.config import UR5CornerConfig +from ur_env.envs.basic_env.config import UR5BasicConfig # used for float value comparisons (pressure of vacuum-gripper) @@ -12,7 +12,7 @@ def is_close(value, target): class BoxPickingBasicEnv(UR5Env): def __init__(self, **kwargs): - super().__init__(**kwargs, config=UR5CornerConfig) + super().__init__(**kwargs, config=UR5BasicConfig) def compute_reward(self, obs, action) -> float: # huge action gives negative reward (like in mountain car) diff --git a/serl_robot_infra/ur_env/envs/basic_env/config.py b/serl_robot_infra/ur_env/envs/basic_env/config.py index 16905566..4f4fd3d9 100644 --- a/serl_robot_infra/ur_env/envs/basic_env/config.py +++ b/serl_robot_infra/ur_env/envs/basic_env/config.py @@ -2,54 +2,25 @@ import numpy as np -class UR5CornerConfig(DefaultEnvConfig): - # RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) # original one - # RESET_Q = np.array([[1.3463, -1.3584, 1.9014, -2.1243, -1.5758, -0.2312]]) - RESET_Q = np.array([ - [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], - [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], - [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], - [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], - [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] +class UR5BasicConfig(DefaultEnvConfig): + """Set the configuration for UR5Env.""" + RESET_Q = np.array([ # reset poses in joint space (multiple if preferred) + [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], + [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], ]) - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.06,) - RANDOM_ROT_RANGE = (0.0,) - # ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) # TODO euler rotations suck :/ - # ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) - ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.1, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 3.0, -0.1, -3.2]) + RANDOM_RESET = True + RANDOM_XY_RANGE = (0.0,) + RANDOM_ROT_RANGE = (0.04,) + ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 0.2]) + ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -0.2]) + ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" CONTROLLER_HZ = 100 GRIPPER_TIMEOUT = 2000 # in milliseconds ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster + FORCEMODE_DAMPING: float = 0.02 FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) - - -class UR5CornerConfigV1(DefaultEnvConfig): - """ - Configuration for the first set of SAC training's (only 1 box) - """ - # RESET_Q = np.array([[1.34231, -1.24585, 1.94961, -2.27267, -1.56428, -0.22641]]) # original one - RESET_Q = np.array([[1.3463, -1.3584, 1.9014, -2.1243, -1.5758, -0.2312]]) - # TODO make multiple reset Q positions, one for each box to train on (randomize it) - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.06,) - RANDOM_ROT_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.14, -0.4, 0.2, 3.2, 0.1, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.3, -0.7, -0.006, 3.0, -0.1, -3.2]) - ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) - - ROBOT_IP: str = "172.22.22.2" - CONTROLLER_HZ = 100 - GRIPPER_TIMEOUT = 2000 # in milliseconds - ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster - FORCEMODE_TASK_FRAME = np.zeros(6) - FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) \ No newline at end of file diff --git a/serl_robot_infra/ur_env/envs/camera_env/__init__.py b/serl_robot_infra/ur_env/envs/camera_env/__init__.py index a951a43a..1893ec25 100644 --- a/serl_robot_infra/ur_env/envs/camera_env/__init__.py +++ b/serl_robot_infra/ur_env/envs/camera_env/__init__.py @@ -1 +1 @@ -from ur_env.envs.camera_env.box_picking_camera_env import UR5CameraEnv, UR5CameraEnvTest, UR5CameraEnvEval, UR5CameraEnvDemo \ No newline at end of file +from ur_env.envs.camera_env.box_picking_camera_env import BoxPickingCameraEnv diff --git a/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py index d564b23f..ba9b9a6a 100644 --- a/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py +++ b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py @@ -2,13 +2,13 @@ from typing import Tuple from ur_env.envs.ur5_env import UR5Env -from ur_env.envs.camera_env.config import UR5CameraConfigFinal, UR5CameraConfigFinalTests, UR5CameraConfigFinalEvaluation, UR5CameraConfigDemo +from ur_env.envs.camera_env.config import UR5CameraConfig -class UR5CameraEnv(UR5Env): +class BoxPickingCameraEnv(UR5Env): def __init__(self, load_config=True, **kwargs): if load_config: - super().__init__(**kwargs, config=UR5CameraConfigFinal) + super().__init__(**kwargs, config=UR5CameraConfig) else: super().__init__(**kwargs) @@ -57,17 +57,3 @@ def reached_goal_state(self, obs) -> bool: def close(self): super().close() - - -class UR5CameraEnvTest(UR5CameraEnv): - def __init__(self, **kwargs): - super().__init__(**kwargs, load_config=False, config=UR5CameraConfigFinalTests) - - -class UR5CameraEnvEval(UR5CameraEnv): - def __init__(self, **kwargs): - super().__init__(**kwargs, load_config=False, config=UR5CameraConfigFinalEvaluation) - -class UR5CameraEnvDemo(UR5CameraEnv): - def __init__(self, **kwargs): - super().__init__(**kwargs, load_config=False, config=UR5CameraConfigDemo) diff --git a/serl_robot_infra/ur_env/envs/camera_env/config.py b/serl_robot_infra/ur_env/envs/camera_env/config.py index 3b3a1fa5..8a723612 100644 --- a/serl_robot_infra/ur_env/envs/camera_env/config.py +++ b/serl_robot_infra/ur_env/envs/camera_env/config.py @@ -3,71 +3,10 @@ class UR5CameraConfig(DefaultEnvConfig): - RESET_Q = np.array([[1.3502, -1.2897, 1.9304, -2.2098, -1.5661, 1.4027]]) - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.00,) - RANDOM_ROT_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.2, -0.4, 0.22, 3.2, 0.18, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.2, -0.7, - 0.006, 2.8, -0.18, -3.2]) - ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) - - ROBOT_IP: str = "172.22.22.2" - CONTROLLER_HZ = 100 - GRIPPER_TIMEOUT = 2000 # in milliseconds - ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster - FORCEMODE_TASK_FRAME = np.zeros(6) - FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) - - REALSENSE_CAMERAS = { - "wrist": "218622277164", - "wrist_2": "218622279756" - } - - -class UR5CameraConfigBox5(DefaultEnvConfig): - RESET_Q = np.array([ - [1.3776, -1.0603, 1.6296, -2.1462, -1.5704, -0.2019], - [0.9104, -0.9716, 1.3539, -1.9824, -1.545, -0.662], - [0.4782, -1.4072, 2.1258, -2.3129, -1.5816, -1.1417], - [1.2083, -1.656, 2.272, -2.202, -1.5828, -0.4231], - [-0.0388, -1.754, 2.2969, -2.1271, -1.5423, -1.7011] - ]) - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.0,) - RANDOM_ROT_RANGE = (0.0,) - ABS_POSE_LIMIT_HIGH = np.array([0.05, 0.1, 0.22, 3.2, 0.18, 3.2]) - ABS_POSE_LIMIT_LOW = np.array([-0.49, -0.75, -0.006, 2.8, -0.18, -3.2]) - ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) - - ROBOT_IP: str = "172.22.22.2" - CONTROLLER_HZ = 100 - GRIPPER_TIMEOUT = 2000 # in milliseconds - ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.0 # faster - FORCEMODE_TASK_FRAME = np.zeros(6) - FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.1, 1., 1., 1.]) - - REALSENSE_CAMERAS = { - "wrist": "218622277164", - # "shoulder": "218622279756" - } - - -class UR5CameraConfigFinal(DefaultEnvConfig): # config for 10 boxes - RESET_Q = np.array([ + """Set the configuration for UR5Env.""" + RESET_Q = np.array([ # reset poses in joint space (multiple if preferred) [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], - [1.8937, -0.8273, 1.2339, -1.9765, -1.5651, 0.3666], - [1.4174, -1.6403, 2.2494, -2.179, -1.5666, -0.1286], - [1.472, -0.8583, 1.2817, -1.9934, -1.5655, -0.0869], - [1.1117, -0.7666, 1.0792, -1.8871, -1.5639, -0.443], - [1.0242, - 1.3104, 2.0986, - 2.358, - 1.5664, - 2.0496], - [0.8757, -1.1028, 1.6058, -2.2458, -1.8081, -0.7877], - [0.4391, - 1.5926, 2.3356, - 2.3129, - 1.5668, - 1.1115], - [0.1815, - 1.2945, 1.8964, - 2.1719, - 1.5658, - 1.3841], ]) RANDOM_RESET = True RANDOM_XY_RANGE = (0.0,) @@ -81,7 +20,7 @@ class UR5CameraConfigFinal(DefaultEnvConfig): # config for 10 boxes CONTROLLER_HZ = 100 GRIPPER_TIMEOUT = 2000 # in milliseconds ERROR_DELTA: float = 0.05 - FORCEMODE_DAMPING: float = 0.02 # faster but more vulnerable to crash... + FORCEMODE_DAMPING: float = 0.02 FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) @@ -89,40 +28,4 @@ class UR5CameraConfigFinal(DefaultEnvConfig): # config for 10 boxes REALSENSE_CAMERAS = { "wrist": "218622277164", "wrist_2": "218622279756" - } - -class UR5CameraConfigDemo(UR5CameraConfigFinal): - RESET_Q = np.array([[0., -np.pi/2., np.pi/2., -np.pi/2., -np.pi/2., 0.]]) - ABS_POSE_LIMIT_HIGH = np.array([1., 1., 1., 0.1, 0.1, 0.3]) - ABS_POSE_LIMIT_LOW = np.array([-1., -1., -0.004, -0.1, -0.1, -0.3]) - - ROBOT_IP: str = "192.168.1.66" - - -class UR5CameraConfigFinalTests(UR5CameraConfigFinal): - RANDOM_RESET = False - RANDOM_XY_RANGE = (0.0,) - RANDOM_ROT_RANGE = (0.05,) - - RESET_Q = np.array([ - # [0.0421, -1.3161, 1.9649, -2.2358, -1.3221, -1.5237 + 0 * np.pi / 2.], # schräge position - # [0.1882, -1.2777, 1.9699, -2.2983, -1.5567, -1.384 + 2 * np.pi / 2], # gerade pos - [1.4843, -1.1314, 1.6531, -2.0676, -1.6014, 1.6402] - ]) - - -class UR5CameraConfigFinalEvaluation(UR5CameraConfigFinal): - # config for the evaluation on 5 boxes the policy has never seen - RANDOM_RESET = True - RANDOM_XY_RANGE = (0.01,) - RANDOM_ROT_RANGE = (0.05,) - ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.1, 0.1, 0.3]) - ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.1, -0.1, -0.3]) - - RESET_Q = np.array([ - [0.4102, -1.304, 1.9315, -2.1707, -1.5583, 2.0127], - [0.9212, - 0.8757, 1.3325, - 2.0209, - 1.5508, 2.5185], - [1.2869, - 0.9778, 1.476, - 2.0783, - 1.5458, 2.9585], - [1.717, -1.1379, 1.7179, -2.4872, -1.4362, 2.5804], - [2.2614, - 1.4378, 2.145, - 2.5039, - 1.7649, 2.2541], - ]) + } \ No newline at end of file diff --git a/serl_robot_infra/ur_env/envs/relative_env.py b/serl_robot_infra/ur_env/envs/relative_env.py index 737032a8..1505ba78 100644 --- a/serl_robot_infra/ur_env/envs/relative_env.py +++ b/serl_robot_infra/ur_env/envs/relative_env.py @@ -60,8 +60,6 @@ def step(self, action: np.ndarray): def reset(self, **kwargs): obs, info = self.env.reset(**kwargs) - # obs['state']['tcp_pose'][:2] -= info['reset_shift'] # set rel pose to original reset pose (no random) - self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) self.rotation_matrix_reset = self.rotation_matrix.copy() if self.include_relative_pose: diff --git a/serl_robot_infra/ur_env/envs/ur5_env.py b/serl_robot_infra/ur_env/envs/ur5_env.py index e1accd67..1e25fc9c 100644 --- a/serl_robot_infra/ur_env/envs/ur5_env.py +++ b/serl_robot_infra/ur_env/envs/ur5_env.py @@ -374,10 +374,8 @@ def go_to_rest(self): time.sleep(0.1) while self.controller.is_moving(): time.sleep(0.1) - return reset_shift else: self.curr_reset_pose[:] = reset_pose - return np.zeros((2,)) def go_to_detected_box(self): """" @@ -447,11 +445,11 @@ def reset(self, **kwargs): if self.save_video: self.save_video_recording() - shift = self.go_to_rest() + self.go_to_rest() self.curr_path_length = 0 obs = self._get_obs(np.zeros_like(self.last_action)) - return obs, {"reset_shift": shift} + return obs def save_video_recording(self): try: diff --git a/serl_robot_infra/ur_env/envs/wrappers.py b/serl_robot_infra/ur_env/envs/wrappers.py index 4cb24bc9..eed5a431 100644 --- a/serl_robot_infra/ur_env/envs/wrappers.py +++ b/serl_robot_infra/ur_env/envs/wrappers.py @@ -143,7 +143,7 @@ def rotate_state(state: np.ndarray, num_rot: int): class ObservationRotationWrapper(gym.Wrapper): """ - Convert every observation into the first quadrant of the Relative Frame + Convert every observation into the first and 5th octant (first quadrant in Z top view) of the Relative Frame """ def __init__(self, env: gym.Env): @@ -159,7 +159,6 @@ def reset(self, **kwargs): def step(self, action: np.ndarray): action = self.rotate_action(action=action) obs, reward, done, truncated, info = self.env.step(action) - # print("\nquadrant: ", self.num_rot_quadrant) rotated_obs = self.rotate_observation(obs) return rotated_obs, reward, done, truncated, info diff --git a/serl_robot_infra/ur_env/requirements.txt b/serl_robot_infra/ur_env/requirements.txt index 9ee4a5bc..9ea0890b 100644 --- a/serl_robot_infra/ur_env/requirements.txt +++ b/serl_robot_infra/ur_env/requirements.txt @@ -1,8 +1,6 @@ matplotlib -scipy pyspacemouse ur-rtde -pynput -pprint +clu # TODO may not be the right place to put the file \ No newline at end of file diff --git a/serl_robot_infra/ur_env/utils/real_time_plotter.py b/serl_robot_infra/ur_env/utils/real_time_plotter.py deleted file mode 100644 index 6e9e4d25..00000000 --- a/serl_robot_infra/ur_env/utils/real_time_plotter.py +++ /dev/null @@ -1,113 +0,0 @@ -from multiprocessing.connection import Listener, Client -import numpy as np -from threading import Thread, Lock -import matplotlib.pyplot as plt -import matplotlib.animation as animation -from matplotlib import use -from time import time_ns - -use("TkAgg") - - -class DataClient: - def __init__(self): - self.conn = None - print("Opening Client to Realtime Plotter") - self.conn = Client(('localhost', 6000)) - - def send(self, msg): - self.conn.send(msg) - - def __del__(self): - if self.conn: - self.conn.send("close") - self.conn.close() - - -class DataListener: - def __init__(self, shape, verbose=True): - self.listener = Listener(('localhost', 6000)) - self.data = np.zeros(shape) - self.all_data = [] - self.lock = Lock() - self.verbose = verbose - self.last_time = time_ns() * 1e-6 - print("listener opened on localhost:6000, not connected yet") - - # get connection - self.listener_thread = Thread(target=self._listen, daemon=True).start() # listen here - - def _listen(self): - self.conn = self.listener.accept() - print('connection accepted from', self.listener.last_accepted) - - while True: - try: - msg = self.conn.recv() - if isinstance(msg, str) and msg == "close": - print("connection closed, terminating...") - return - with self.lock: - self.data = np.roll(self.data, -1, axis=1) - self.data[:, -1] = msg - self.all_data.append(msg) - if self.verbose: - now = time_ns() * 1e-6 - print(f"{now - self.last_time} ms {msg}") - self.last_time = now - except EOFError: - print("listener Thread terminated!") - return - - def get_data(self): - with self.lock: - return self.data - - def save_history(self): - with open('plotting_data.npy', 'wb') as f: # save run - np.save(f, np.array(self.all_data)) - - -class RealTimePlotter: - def __init__(self, plots=3, horizon=50, limit=3, figsize=(12, 8)): - self.data_listener = None - self.fig, self.axes = plt.subplots(plots, 1, figsize=figsize) - self.lines, self.text, colors = [], [], plt.rcParams["axes.prop_cycle"]() - for ax in self.axes: - ax.set_ylim(-limit, limit) - color = next(colors)["color"] - line, = ax.plot(np.arange(horizon), np.zeros(horizon), color, animated=True) - text = ax.text(0.91, 0.76, "0.0000", fontsize=14, color=color, transform=ax.transAxes) - self.lines.append(line) - self.text.append(text) - - plt.tight_layout() - plt.show(block=False) - plt.pause(2) - - def animate(self, j): - data = self.data_listener.get_data() - for i, line in enumerate(self.lines): - line.set_ydata(data[i]) - for i, text in enumerate(self.text): - text.set_text(str(round(data[i, -1], 4))) - return *self.lines, *self.text - - def set_listener(self, data_listener): - self.data_listener = data_listener - - def start_animation(self): - ani = animation.FuncAnimation(self.fig, self.animate, interval=50, blit=True, save_count=5) - plt.show() - - def close(self): - plt.close("all") - - -if __name__ == '__main__': - # only a test - plotter = RealTimePlotter(plots=6, horizon=30, figsize=(12, 8)) - fetcher = DataListener((6, 30)) - plotter.set_listener(fetcher) - plotter.start_animation() - # fetcher.save_history() From f52fa79b7ccefd19bff2684c5cccd8d3352a7e30 Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 25 Oct 2024 10:32:24 +0200 Subject: [PATCH 337/338] cleanup --- README_original.md | 116 ----- docs/images/trajectory timeline.png | Bin 1470368 -> 0 bytes .../async_sac_state_sim.py | 4 +- examples/box_picking_bc/bc_policy.py | 251 ----------- examples/box_picking_bc/record_demo.py | 108 ----- examples/box_picking_bc/run_rbc_actor.sh | 10 - examples/box_picking_bc/run_rbc_learner.sh | 10 - examples/box_picking_bc/test_demo.py | 72 ---- examples/box_picking_drq/drq_policy.py | 157 +++++-- examples/box_picking_drq/record_demo.py | 44 +- examples/box_picking_sac/run_actor.sh | 15 - examples/box_picking_sac/run_evaluation.sh | 10 - examples/box_picking_sac/run_learner.sh | 16 - examples/box_picking_sac/sac_policy.py | 398 ------------------ .../agents/continuous/bc_noimg.py | 146 ------- .../serl_launcher/agents/continuous/drq.py | 313 ++++++++++---- .../serl_launcher/agents/continuous/sac.py | 31 +- .../serl_launcher/common/encoding.py | 94 ++++- .../serl_launcher/common/evaluation.py | 1 - .../serl_launcher/data/data_store.py | 37 +- .../data/memory_efficient_replay_buffer.py | 18 +- .../networks/actor_critic_nets.py | 4 - serl_launcher/serl_launcher/utils/launcher.py | 18 +- .../serl_launcher/utils/sampling_utils.py | 2 +- .../serl_launcher/utils/train_utils.py | 73 +++- .../vision/data_augmentations.py | 50 +-- .../serl_launcher/vision/mobilenet.py | 5 - .../vision/pointcloud_encoders.py | 88 ---- .../serl_launcher/vision/range_sensor.py | 38 -- .../serl_launcher/vision/resnet_v1.py | 64 ++- .../serl_launcher/vision/resnet_v1_18.py | 360 +++++++++------- .../serl_launcher/vision/small_encoders.py | 9 +- .../vision/voxel_grid_encoders.py | 40 +- .../observation_statistics_wrapper.py | 28 +- .../wrappers/serl_obs_wrappers.py | 17 +- .../franka_env/camera/rs_capture.py | 2 - .../robot_controllers/ur5_controller.py | 164 +++++--- serl_robot_infra/ur_env/__init__.py | 3 +- serl_robot_infra/ur_env/camera/rs_capture.py | 36 +- serl_robot_infra/ur_env/camera/utils.py | 107 +++-- .../envs/basic_env/box_picking_basic_env.py | 21 +- .../ur_env/envs/basic_env/config.py | 15 +- .../envs/camera_env/box_picking_camera_env.py | 61 ++- .../ur_env/envs/camera_env/config.py | 20 +- serl_robot_infra/ur_env/envs/relative_env.py | 24 +- serl_robot_infra/ur_env/envs/ur5_env.py | 234 ++++++---- serl_robot_infra/ur_env/envs/wrappers.py | 59 ++- serl_robot_infra/ur_env/requirements.txt | 3 +- serl_robot_infra/ur_env/utils/rotations.py | 2 +- .../ur_env/utils/vacuum_gripper.py | 62 +-- 50 files changed, 1411 insertions(+), 2049 deletions(-) delete mode 100644 README_original.md delete mode 100644 docs/images/trajectory timeline.png delete mode 100644 examples/box_picking_bc/bc_policy.py delete mode 100644 examples/box_picking_bc/record_demo.py delete mode 100644 examples/box_picking_bc/run_rbc_actor.sh delete mode 100644 examples/box_picking_bc/run_rbc_learner.sh delete mode 100644 examples/box_picking_bc/test_demo.py delete mode 100644 examples/box_picking_sac/run_actor.sh delete mode 100644 examples/box_picking_sac/run_evaluation.sh delete mode 100644 examples/box_picking_sac/run_learner.sh delete mode 100644 examples/box_picking_sac/sac_policy.py delete mode 100644 serl_launcher/serl_launcher/agents/continuous/bc_noimg.py delete mode 100644 serl_launcher/serl_launcher/vision/pointcloud_encoders.py delete mode 100644 serl_launcher/serl_launcher/vision/range_sensor.py diff --git a/README_original.md b/README_original.md deleted file mode 100644 index 509aade5..00000000 --- a/README_original.md +++ /dev/null @@ -1,116 +0,0 @@ -# SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning - -![](https://github.com/rail-berkeley/serl/workflows/pre-commit/badge.svg) -[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) -[![Static Badge](https://img.shields.io/badge/Project-Page-a)](https://serl-robot.github.io/) - -![](./docs/images/tasks-banner.gif) - -**Webpage: [https://serl-robot.github.io/](https://serl-robot.github.io/)** - -SERL provides a set of libraries, env wrappers, and examples to train RL policies for robotic manipulation tasks. The following sections describe how to use SERL. We will illustrate the usage with examples. - -🎬: [SERL video](https://www.youtube.com/watch?v=Um4CjBmHdcw), [additional video](https://www.youtube.com/watch?v=17NrtKHdPDw) on sample efficient RL. - -**Table of Contents** -- [SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning](#serl-a-software-suite-for-sample-efficient-robotic-reinforcement-learning) - - [Installation](#installation) - - [Overview and Code Structure](#overview-and-code-structure) - - [Quick Start with SERL in Sim](#quick-start-with-serl-in-sim) - - [Run with Franka Arm on Real Robot](#run-with-franka-arm-on-real-robot) - - [Contribution](#contribution) - - [Citation](#citation) - -## Major bug fix -We fixed a major issue in the intervention action frame. See release [v0.1.1](https://github.com/rail-berkeley/serl/releases/tag/v0.1.1) Please update your code with the main branch. - -## Installation -1. **Setup Conda Environment:** - create an environment with - ```bash - conda create -n serl python=3.10 - ``` - -2. **Install Jax as follows:** - - For CPU (not recommended): - ```bash - pip install --upgrade "jax[cpu]" - ``` - - - For GPU: (change cuda12 to cuda11 if you are using older driver versions) - ```bash - pip install --upgrade "jax[cuda12_pip]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html - ``` - - - For TPU - ```bash - pip install --upgrade "jax[tpu]" -f https://storage.googleapis.com/jax-releases/libtpu_releases.html - ``` - - See the [Jax Github page](https://github.com/google/jax) for more details on installing Jax. - -3. **Install the serl_launcher** - ```bash - cd serl_launcher - pip install -e . - pip install -r requirements.txt - ``` - -## Overview and Code Structure - -SERL provides a set of common libraries for users to train RL policies for robotic manipulation tasks. The main structure of running the RL experiments involves having an actor node and a learner node, both of which interact with the robot gym environment. Both nodes run asynchronously, with data being sent from the actor to the learner node via the network using [agentlace](https://github.com/youliangtan/agentlace). The learner will periodically synchronize the policy with the actor. This design provides flexibility for parallel training and inference. - -

- -

- -**Table for code structure** - -| Code Directory | Description | -| --- | --- | -| [serl_launcher](https://github.com/rail-berkeley/serl/blob/main/serl_launcher) | Main code for SERL | -| [serl_launcher.agents](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/agents/) | Agent Policies (e.g. DRQ, SAC, BC) | -| [serl_launcher.wrappers](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/wrappers) | Gym env wrappers | -| [serl_launcher.data](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/data) | Replay buffer and data store | -| [serl_launcher.vision](https://github.com/rail-berkeley/serl/blob/main/serl_launcher/serl_launcher/vision) | Vision related models and utils | -| [franka_sim](./franka_sim) | Franka mujoco simulation gym environment | -| [serl_robot_infra](./serl_robot_infra/) | Robot infra for running with real robots | -| [serl_robot_infra.robot_servers](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/robot_servers/) | Flask server for sending commands to robot via ROS | -| [serl_robot_infra.franka_env](https://github.com/rail-berkeley/serl/blob/main/serl_robot_infra/franka_env/) | Gym env for real franka robot | - -## Quick Start with SERL in Sim - -We provide a simulated environment for trying out SERL with a franka robot. - -Check out the [Quick Start with SERL in Sim](/docs/sim_quick_start.md) - - [Training from state observation example](/docs/sim_quick_start.md#1-training-from-state-observation-example) - - [Training from image observation example](/docs/sim_quick_start.md#2-training-from-image-observation-example) - - [Training from image observation with 20 demo trajectories example](/docs/sim_quick_start.md#3-training-from-image-observation-with-20-demo-trajectories-example) - -## Run with Franka Arm on Real Robot - -We provide a step-by-step guide to run RL policies with SERL on the real Franka robot. - -Check out the [Run with Franka Arm on Real Robot](/docs/real_franka.md) - - [Peg Insertion 📍](/docs/real_franka.md#1-peg-insertion-📍) - - [PCB Component Insertion 🖥️](/docs/real_franka.md#2-pcb-component-insertion-🖥️) - - [Cable Routing 🔌](/docs/real_franka.md#3-cable-routing-🔌) - - [Object Relocation 🗑️](/docs/real_franka.md#4-object-relocation-🗑️) - -## Contribution - -We welcome contributions to this repository! Fork and submit a PR if you have any improvements to the codebase. Before submitting a PR, please run `pre-commit run --all-files` to ensure that the codebase is formatted correctly. - -## Citation - -If you use this code for your research, please cite our paper: - -```bibtex -@misc{luo2024serl, - title={SERL: A Software Suite for Sample-Efficient Robotic Reinforcement Learning}, - author={Jianlan Luo and Zheyuan Hu and Charles Xu and You Liang Tan and Jacob Berg and Archit Sharma and Stefan Schaal and Chelsea Finn and Abhishek Gupta and Sergey Levine}, - year={2024}, - eprint={2401.16013}, - archivePrefix={arXiv}, - primaryClass={cs.RO} -} -``` diff --git a/docs/images/trajectory timeline.png b/docs/images/trajectory timeline.png deleted file mode 100644 index bdba7c2acb542ad48033b4aa3d26191015c5d399..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1470368 zcmce-bzD>bA3r)kQV;}`E*YgmdUQ!n1Oz0dVRR|dAtgw|z@fBAcSyIy27M^*oWUHB`t*=t)2z5E)EWQ5yuphXFq(LfnWFBU%=iF0bl+^)}Mj@={_hKe9&>V`QT;o9uBf~adn3Cx?8=6!(H6%Tt8s( z+GT))IQ~0G;XT~qgT1Q@>l=G#I7rc+Re+yW2kyoy$S)|&Dj*;sBqG5tn44=-9nc)RyygG zU_bbOZI-mE?pg`?|M!DQua1^1yo~<; ze~}zFSm_|xZ98wkk`SphLDw?Dfq6_PEgr$a^2SH+4tl(xGiFELML!=F{;vmVDDz)* zQp1BOu_6Xmbbo>b2>4hy)hVSiEfUaW>TX>ig3?;jP(19`B{N2fHk7n0?D$-a6D#eL zm}sDe_OKuguiH6bMhJg#3iJX?9!%pyZGZ4JlU|UBQ{4TsdB>b&K0Q!H(4fKS-WhMmsGoi1bet8*WhZT@SI+&?S}{!K)@Lvb z#5cm1kWaiAeXA9))=J(UUn97EkD)?AX6KiW|24xav6M|x>H1qn*P`p^Xp!O2IC)eB z=KXMDKF@HY81qe>DMoC6LOdXlcbM$mJMWR2L$WRkER!4p{L`7C!lc)VUsN?Y z!9DkQ!GmeqsI=B%SZA&-w%re#6>#>U%)rrp9x1HO6SZ1j+U}ZSLA%+k@fQ_wG1e$% zGHCj-kDkG|@p)U-qRQ3k^|9Z9`j_i#wl7zLf1^H@lt*4(T+AYb#kD?%CD({wq?U(L z1*~V?oc~zA`_dF|d*|tQf*NSp_X#vUjx}owFb{M$ ze&|G6LE87|%c=~nB;Op=$L~9~OUZVir!KKpS(#-#CRW?}H_UiR@o{%|(_3MhrLF`Wj(C>*>Y%S8ZG{%5fkPUFgS!yJ!`b&T@;w zY_@;o+f&AII5ycEjSI7lz>R&?KA3tejtj@GX|)!v>AlSk44#W>DlaM~apd(dNy7Mi z##_IF8}|Ak;fCp=(u@40K{0vU*3yM0V^t>sEPK8Dq=z$xNa`qICKk0m-+ zZ)Hv-)qCnCTH907AFMSh-=z|eopDwXN7jmoCcx_=e zlrxZ0ejLWQ`&Tmb%4sE!ef+n$7S7h4mvh!#@3!vq5Zk(KH04(S9cg5{oIAR{6w??> zgPp&+{QbE27JceQe-~5VEfuXWsb}DrV1Tl4rabYY*~9Y}Du0Op&(-H}|MFfCYW6Gc z5?LIpD%yOfxfTtE74D?waH~$7d{ftw1lKJoG894O%Tc{+bLJHuQWB4EOtN6o&*d^P zAAhO`19gABovr<{NA^JU4&BbB<_@~F=x7ekfox#QxklU{MBu5Fyagyi5Sy5y8-;?A9~P zwP7{}Q+7QiUH11cM(z&crS|BZQZ1a75jNI_PlprSPfimBKe6~9Jv@D<79h493-<`@ zU%EL$U$17}K3lq5(QNd+5HK|Q`~(_F+XoU{=@~n+iFq_G%%NFBH2FXw{+OAD`b$s) zfmKgO^!wwPZu3L=A`bRtM(TD^=JYN}n$j<{Y^Y6&w;rRv?ih*W=**&+zxzWkS(&jL zB93GR3YL^|K@Leq{J5D>??q=6WtPY_7}e5(yu8s?EqRs9p6#8|0rK#;$t$jb7V}!; zNJI^Bv&}Nv6+0u6d9|0>v0j+`ZF@hpj!fL01 zn$|iP`eVm8&SR+OLR@{qt<>>v4PCGA0~B5t|7#=%8m(W7PNTK+!HUbu+Sbe};_akc z$z)9klLagR*Ht$``=1|VYRX)MMMMy$yBnLeo7c}Dt@emq-30G>Mx4dXI`vLWP|?s} zPFmRqN#^SEifw*6E9mMDka5`PxF%PEb zo{*cskwfoX$RMp$f&DLivw(ifDxwEbY$HN-^JFkYX3$qk(!DdkzsLCT@eIg8`~cb4 zx~uD?T^$=6A|_~HnavAvVAwAoZD^Xx<7j*(t;z+L&>B5ADdwUbc3WE-YNh_bcH1h0 zQIFM12Y&y6fT6A~1yaf*DckyaE#!s}p=bM&yQinJu5OFZad_66ynL`5}i*KKA6vS%QhggN713+jp z+)5uS{uO_M1C0|X8&QqksV=Tqi>5M2mR9s;1poDTxYb%Hl?%~u5eG~V0by6CLI_86 z5BM8Y>AWYmX8yr+B>3Q0`UjJEugsR;FsEOm^~t@5JMC9z>9b59kBYOUUF_%oE2|l1 zq2GVs-|jqUzsveKqOYwJv%6y!f2joDqkpVllEZzjf45yx={<&>iV;?CY;L!z zHG1diIehEJs!o;KWYfN+gM2jQ^cbWGM3l9RS%R&2*J#rJoi_z2u4)LXF?i$sqtMbe z>}FHkPKjgO>BAt%$Sl@t*#erSvV6L-AGhJa!RioT4V?GmT~KYcOGSD4)>Y=!mE`yn z%=S?fIm_aNhcrvOPgk=S*86Z3-+4Yr6iCqHhQJ(q2asu-|4?9ie6T|%X3|3)34a$j zy(7}a?-mfCK40g5I;Ecs?;lLz+iD6&p$HdSe7byFd;LZ%tAGkS4;5BdLvm0nMb;7< zBCBVe#F*p#@2;}k+>hA^7Mla(=5<@(9S8Q(tui7$~`VCA$7*p{Js*i{@n; zfB%M``VRH<;M>~T0?DVetWV{R!C<6hWR&LtocG_KQd0bBLxnpMoTt>r-v0hEa==Q* z!nw_hmv@16H8wOX1Eu_WQ$_YNba#O7<01L=-rWrgM-VwEqL*!0yvckbwduR_+asxh z)X1C65sbC{fK5#gEq6(j!YH4~l2FOhM$R<1!ua=Q$HsE6tn7`dP;jmH@7`&k&w$kq z>)8TZ0?~ujOZ=UoaEbH#k?LZM|9;!Jk55+5@AVzD&Df(|}@YD7(`Ig!?4(*3*>eps|in$&bFzRL6zfx`bn(zu=i|Fx3#2=lz zN$$@!F*EVm*z~ib%qlIKe#|bhs@L|X_ICy@0);4nGh3ye-ma=UQ#9gyXLsq9IjywfA=Aw_yRLs?0Do3^>NsxCVwXm(QuI2hUM=S^o~#$LPq2Jm`1hh z>;73FZ z)sSyPit%gGFeHMrD9E>$KaBNFaJAH6|NY3?vt~Rq|3il9G_vJyLyzCAT=@9=Th`Bi z^5fG_;l%ajD%ymm&1{C=M&E6j9fV>(hQOp;Wdggd&akkg82t(}Ewno8GQO#j>An)oAP{H4XHg;H;ZnTPG+3G>weUw8gx2 z@nC!ES(D51?QLfHj`zh8M|^zz8(pQPGi$@gYuRln=hn>&y)#zOw8IO`-6N~zU8hfH znR}jtKybql$!mwITI;mz?#)XqKNhJZ4abEE_xD{cR>(hgcXb8ab9~ex&G?V4QTM&a zX-Gjq0fm=Sj=EMWdH3m`I^LaA_L3>V-Vbu=gA4n8PS7qtJ_-Io{$2!z7_|nJ6&Tus zF<#{|&|D^~$^hbhcZ;X1n~)EnedT7Jtfa76pdqit%i7c$9bTU9$j;<<01CkoZw_5l z_ni4}uVlEA;a?}*uis}Q+8n8+^CHIj=5Q0{<0!*z559xLhe)>0@+!exTaekjq|ITb%&zcCe4 z3WZ9rdSxs55~+N_**OS&Nnveo<3suy4jDL)g;eoF@fQ$moeZ=sREstZ(8t)iYo#;(TNj{0@l_j)MOSaz_uq#VoG9BF>@>ZPp)AvmWklQ4AJIGniW_LJXh zxMJ24=`!w(b_$s%-Q(hi5s5vrt0#J3+4VWLvak$4sc)QQ*unCX$?Cgv;JMIGpkkwE zanXXDCz%e@lwlTQ_b6UxRI*$z6JD>$-m=%%d#(Endp5)Mba7Y3M&7sOu=oP8dUf-h zb|cn$KPnk$pg0;P3M4IMXvY=?{(Jz402pY-r5;l(_#(ZafNP*SyO;!cL`=5bQYPzgrHfGJa+CczAK%6G@rXe0 z!O00V<4$tdid<^G|H+sNV?1he7f4$q-2dOK?SHUKzryrp18%_4s@lT27LqN4E%XBzmnb+)?TKrI-Uvsvdqg%fDnEZU_*dVq?ABVU(@gO%uvWN z5MZ{N;)W%Qt8?~pEx~DKRer|qg^tEL6Cz}%@(7l48m9iy(Wdk@m#+O~x&dbRgKc{L zMWKq9POEgrd{!vMtM46~=nd*Z8IS5u>aql1*8+Tpqarcno(8jL1D^3H;d^NT+kGYK zH4g(5Lg=dIdp|qBsx*HDW}@=r{G;C~c&{bCWC#Q$mTR0_a;w0#tB7p0ZBsa~O@_Vy z_;DmY@PG$qd2uvY-{N~3C9G~(fnN9N_iVLj`)U!x0n^^cV!yFCjzi$Iie60r{PyF$ zsFmamk+?{VI1qmeE~tr#AEjjwjuCfe78b+jDPY(Wn1odyCGjK{yD#=O;~nDzAZGQ@ z237zYU|0X7rA>`Hy|4%X7m&#feS2t~gNV4U zl@2FP^HqPDwd?D2V2L)zic4o7Oi=F|N!wjCL2CKy$ll{Chb*hlLA}1#Y@~%@8 zUok5)^T}p2`K=$oQKpMbZjT1}*t=Br1}v+Vk4I$VW7yzd%F&M1khQ52eE{f92n!gv z&Li9JuG%pu*;|2{+1)hqmHN+fkKoln-UDf(q}AP>C!o9<4FOu4Wz0F1x(-m3;yu)v zDXTn8WRD#Y35tJQ>W$6Jgi4BOKZn}Nn7K(kFg7u*UU2cbyOjo-Uxy@WZ*LPdd721O zpV_a^?WbFwaS;_BN-Qo`O$zG@94Wh_*!>KreWjY<>zPL8;{k>V=?&tOpPf-h;L#3l z^xzvJ0W5sxbyh0+w#gzWw}auZ0%hIa`Ig}{L^K#_j#^LHjvsqILt!r#b4Z&T^{d-I zar4Qc*Axcoz4l@iD}2ETV}h-+LWzCI_=uljnWm$$@jKs!UY0)}@p zzXnY7h+nmEK_AujTCl~Y9X-x=hL^C3N+J#89D982xswU{@DSyCPJXu{3!uIyLi^a; zeeC)95JT$Upfl+deIe)$+3AWL5{~fS^F0#YsFVasW`NiIaKf1J@Va#yjI zEA{K<-1Bp(RT}WL_G1ov93ZLj`N=IJoQhSQxOY}Q0FO>;l|68A~*>6E-+gydQ zY7@yQ6sj+5@_4Eiy!G!&T37d-j}H&Xf1=8W7pU}`GTy#MI!KObqu~)gyLl*X!@x;< zOUwH0ZQSW)V)@SIRUG8)d#U{{>3_l90+q&@O7q$OWf-%3HqN+7+iD0*v6?edQp{vHxoud}v)ygfh zd7hl{feOzTho0|RDlWA~RkKd7rx9ecC*@SA2c*#(lvbqkdwLYNayk{oB&;%p>I(^A z*zfdB+P}v>{;ax1Pe=16_cpd;A|kk$v!-$Xu5^ND6lchxxdLbNKz|O8E^#a`H+}uZ zUFPaqE%4^zZE8N|`Y83d1Xwm@27Y3~RE$$1Cg|^|Byp3|lRT~A2v&XZ0Q!K7%}CWC zx{$(zEvCT{h2?u%_5;LB=2jP9$O&j)90btkKGY~-H5CgdbLFN*^^5T<8}KV zzyg*88e}TDa4@RDPejhw*t;g)lF$>N$7)rg1i79ay?&f{^wZVA)iHf&^H0#uClLoq z29Pzbx4mjja!#MthY!~5pYGo$r8TVhH;XO!=+{BUX3!gpQzEkRb=CZBlK-AazuO!? z*O3sv%VeY!ahRsO?%~^AnE3Iz$!{@Ji*4@aNrI+Af=Ysr<01%aCyFXY{Ry5q=|NUS z{{bN|W?BD6`EMim!XFSqoS0fP6AC&_X z*{^I;%nSelCHgbhS9h`)`iP)dBH73x7t*)!o^DVQ?4G8?8CCvHS`z^lD3M4TdNPVh zk0#Z}N_&|6*pQ{KG<0leYqO-y6}E_h_Vy_k4_@_&-uEhG$Kcctnp{i7hBuAowAeBANIlntkU@roK-rmdsE9v$2CF1^;YCfnf$&iY8A+YC|+R zIX{3uyRB5|1w8zPq;gZIva&kbZOk0A{x;?#a?i$?J44+`wR(og;lk~Kqcg}+1*8SZ zjfMV7=iHXZ`lUv1^j zyqPYgl_hsP$kM2KtLTC+Sb@=9)`+;IWI<89v9a-Tx>d~r;?ww1zP%Xqmw{lfwysc| z3M^spDksIZ#t`(R*-nSr4QPLf_WJ}Xy1H6te|?5+Y9e7*<=Cpo%GZ-gK^iTPniUQ5>^kfKC+9L6h~)7-)EZ{HSS&G&V5-rU{mo zTR%^PM)CyJ_H+=cu$7C8Mo@1szxk_Q{3liEAKI6IfQxHhct8_mjUO15Lt57oe`bKA zU7OXs@O-#P?;|5F)y~NoWboea%;++QdFb5Pkj?RLg6*AYqy7E;kQ>=>@J1p4f$QeW z5?D0kj2wAsXlMW?$RkOfmojY>co53szeacMoP(8JTsqn>sb`G$0NYb5(V<$6pZ|yX z4<(|jl;=GeLtXi^Mqr4rAsdAWVQ(oPBr53bpxC2q3csvgBwlpSlj=9MQ^CaU1;<)Q zj(E*qr5Pg_TC01njx(js>3#2Ve+^d|m34TBYwWgxc6d-td01c4%$(of^zmtI@7w4q zqe&))$(ec^68?~os$;cgsIUUcNw!>24ocxSztR>TLSBE4#7z=#(~tG?7BX+a!@js) z0ryzFI*(Jxo*hkn7SrW-5xDJF>Yi-)>vSVZ_F}96QXF#QsgC3@SlgUSl~UtaX<8hG z^0KZ+0JzIv#ul12;VBL0S-w5=2E#VmD)elxCu9R22m7_w%ii|K^9+R4Ir0ofLCz7= zM&W_10^j$N4;je`?H8u&t_#|4MgW@dRpF%L|9Anibr=DW`Fb|%#_%Vd$$A>a!zE8%b+mRp+5AFW!5(s9rQ_CZ-K|udF>X@5>+oI> zfkmf{k47d9wGT||O)@}UHWK^AvqruR*;JjFCiVAb&hRnM`IR5UQ`5Ce(_21m!8R~&JdlP`^vjH#$dU@V=3`y{b`uchv`=5U2*=z#( zex*7NL}^XUF|EF*3C&tD%k4o#dy2aFm;Yu>^-&U|EQ{@HxBJQi%hxmQu2lxgp&-N% z2uFCJ8q7yRfZ3cwLP6XBt`=7ReSM}t^Rnp0T?;r?qrxUD9%c1`;?XPh7ve!k1|WrO zj>Ua4kM|b{Q_Fj-=zjiG2-SGj`J4abLxxrB?9usocZykH&&@3#A2{r!i0cxAlA!atYvnhU|Y_uPzL za&LGIOa9>(Bx*etV;r^{k+qpZyI zkCGsc+{|KIQhP#xl*xG>NL|ZzE>&*>76UAUlj%x^1YJ=O@%MC1Iy3txXZqf6*bYb^ z09eBsq{6vH^dg2e^{Kh67y%Z%7I}R#Z1oBh%)Ykc!>OOHh+i*1$lUn@TyyBdCXq;D zpmqv(yQdKp^{|f-`w9I_c5I26>~}4yB%U=vpnJNaU^jmvQ#s5-M9jk5#KZ&<0oenj z??&T$1;)5MduP@2E@OdEl9Q*+FM{RZNh}Wtp$s_CN8Hq}_bKkC$B!U`{L=}!P?=}+ z_kgC~@jSr1%HZBK#$X!LQs7KqEfvlB_s~1$K{WEKBXJV})C3LG7+^m8AKnZyfjkzt zDh;ZtR!qx}EM;a*zET?zaOTt2)%_qmi8FpAul`qc39^;+YBT*m_Oql7Ar0nXl=>E}<>NJmlz<0l;@5fr6Mkek? zb-1>68i9GXZTk`+te{4tkxU`S!;unY*ytHv= z$it5ZX&}SH;-0Pi;PE$K5i!KPI1lqoB98AZ{K(t+A%D=TN(B-XRG1p(?iv#xlYA`x zxR;QD68H5Fj^tnGQnmLJXX&T&V=Q*h$~IyjY*Fz_aLtevTspk!4#?QEOmJkK;iVb* z9`vq(02{)~Or;%JO^^3%oKRAl6wie3H$9J`Cz#YaKachSEgx%9vO#2-?&w(3L61Jm z%(V1yF;&GQCfv#)+b=&2XkUy-kh&y{_y`S0s?4+BJAfL8#_5!+VQgDmXiVe#)3fJ^ zp*(TAr?>s-y=%(+$!;H|yy;40eN3>lIEB6awx`zv_(}EtpgR?it`T9+ZzdTT$!(#n zmdqHTYaPxrfbRC3ir8CPxpoMG0&*k=zlu=?6~ttN&JC1KPCZJRjHtwlZKu$0MqyWl z_P=tmS7PFTAarW<^*g{;Fhgmg-dMcoyskO$d8o;~(lC%4sV+S*qoBf@?eTx!-;v+z z2Nb#w3lwy+4hjJ0&T*MqntJR2D$IH`DjW@&lu8*l#-G#Z6u-Gj?n%PnXGcnGIkqnB z!zdX>J_4rO6PltpO*wFm^+ZX{rG6klp7bg>%Dht<=>%w|I4b5bpdGRAN@2l3` zq!j;_l;`DeKcOx4d|RRkCjOI{M+ZOy@X-J*-j*zHgs$I3tU-@aR7aflGL#%%=qvj( zzNi+-_A^B*W4>0J*?vI>`DrE%46mQn*5fFtaYwu=-b8?V&X@>Lr>7jz7o?&mfa*no z4&TT5?kw#;`tCu&m&XqdbwlG{Rel;K=I5lp7Y2U%<-Ipwd$WAp+Nqh{{WW4~vrre0 zoTSKqvug{WazeC@H4@EN;eB(Ix)aSY2=6I{*lkOn2SXB}Jk6&+k`WP5rUK{?YgsIR z_{}ZFGhe+yUGF;hP;0;yv|PYm`cR-`>d7LDBS)3i7ewXW<#Wy!LJW6wNR!KXTKmmg z&*lJC?+@u&8HctXZ!sgjdTjw$9B1E?4K1nKI-lG~Y_YX)N2(;-vE6<`4x_?K>J-P8 z6c&YGR8Fbg9$&$Rta;!uug_tzqv47O3AV;PFv7KT7Zx3TADX7l-R!c}6kPn2y+)gg#V1q6OeInm&`=^q zV9li_F+$0TRU}_XdTHZ2&vZEp$lPgf2r-t`@J6He0A1GA1*E0vG!f^CUW}PX7UyYN zJ`P_8#)V6lFjZA6q24~sU{x9zVkiZadcHbM0Qdb7O3S&dEgm33Jbjl38Jux{;~PWi z9DL&Nsm?j4J>Q*2@!r^d`ukttJ)X_ckN|vRvlefhnCyx*4znXdg+bI z4h{}zgC~xUg|;s{dU`lKOsvWxZ@NSRsg#Ri!y<=lP|tsUfD9r4akaGeKV>x6{?ZTi zwBSEWo_`6gRl~(WaK&OEUB+wYpi;<_Az@(5As;TRemJaTt6*5r)WOmGrsq?cxf;^; zA){`1k_3M-gt}q0w_}?YKYEi)JnsO{v*b;{F%`-<-z=MNFEW% z8Td&ur2)LQFumm?31XmK0Hh0=zT!`jAmoBDO=S)AGR=ywX;Bj$Di4Zi%F^tAujTsv z3}4`9%5ooAaD~>_B|36A)}O1iaryU*;${E0*MfO*o#;pH0_>Y5;ro}DslrTY?)Qa0 zT*TC}Z}3}jJtq5|D_j{fl1|_NH_W6R6-@Sy&qn@xA<0a>?xU>x1rT-Kdj>KGxAa)b zQ!z#Y6xTpb+z_dpQMKT-)$};@dml%~H{D0-AT1HQ0Ld#X@#7(QE?V{e2U zx+?LJyHeKq4#o6G>t_%V7*{w`UXh<{%zUiY2HpeSy*=N zB8?cEKutq_^@(nfwg(b-i=Of0Q9l>g&YoAaK=^zbx&P^gtK~(s3rH8q0ZSc+I`8t; z&hJ^;yhRyO4`LY9w_31o4f;qO^u-w{C#nX zNU#ptqtsVy_Y7dDFt=%s(&1c_Bp3byiE?a&cYEEuv-JtaM+0e_{OKPJL@n0~09m+L&xf}Hcq^nCu`@HPjKv{HQlq7`RV|z_4r-sob z7)E)uP{hK<+Vi|R&b(Al>v1x{B?$@3gNO#xWMY~C3rQEtLYV@D==SK}m6KCp82jfm z3?M|0AK7ifg#;L`lOTh+8&mwF!Xoxs{Ap@g@3DXo8-e7krh94-B}G#?rskLGqx+J) z-3JyRrC4cuFdm^jr%ysr+_bn1&%$|upBZA(P-rWxEWSa`Eh#MZ^vB+Tc{-{A=Q`*N zZ(6c+M_@6@I|AMzhALHUlrTHILGxXlPl-eqThr1vUCLz^7)aSWz$PHSOTe|58gY*a zK{H5BS=ml%onw)W&}CqPM^>Kq=KxGv{z}b=Omx4|R-<2UK~~@|OM!x&pVZ8kqtEED z+=EYh3!AEbFWsfw{j#ay7^G|}#{dAg{XDuo;T(FdW7c{Vl{OmkeJ3pJebdEIO~Y%C zQpiCeI#O;cGJ~ko1ngob_)5P203TcXt0ze0M_FQXF=1@Gir?d|(FCGNSGy_Fu$Lsx z&whB0sYvqe;gY^=8l&`pkH%#egO?D(D-p8SI2C5?IW7)O8rRmmHTr+#vs41wsIMn; z`@WX)D2!O+{Iezx5rG>jE&Ld{wD(Iy6^N8f(b*#iaQnnf7>v>(-SrxjYDkimXCp^J zpZa>ud`8P^W+8&l^F;JwYhMVC`Aom#dtCB4&o1Y+M+Mlcx=>PN#emvpvM80}U@;Ni zSQ#BJ65W&DMiYSeq$dhD1ZdHd>@Dd;IzHZB!MVEckU?{uVKGU`cnQkSel(#BY&((jSeKHDA3)Sx&2Ix6|^gt5w6$asE>KKYa{ z?&S1Tcem%?YR~=D{5W|8l5gOcQ={9rHI6`8^vh_r$1dMf4L=h!P|l>Sx_>%%In;vH zIfVYyRY$M;J`0FV8H8KA7E+m$8k?Fb=NH--)d=Td*JravY^46ksw%&0TwhsX`$wl8 z;GX&wCkKzCa}QC@@WSxEg~AWKY0i@X8nwA#BF>i}pWD(C9lYY|WOaq8C+s7@fKNJY zNP<5W9Qs_+(ATC$eE1^aFmp`U`Geq3ue6XbO-;@84A>pZ77bV4H;H(-;lY8MW~MC| z_86K;fw7S>JNj=fjc;gsd=Uap%s&RY?FpdGm`l_>8YKy?QgL`F@6>u{l&_=vNcQ$H zK5MIUiKCa+MYaV4#2WK#+(n8u zNH&SPaJR=x&N4 zpT3!*t$lhOYNK|U$qXjmoH%4gFa10BW}#vxC(l7WYS3YDiHU?C=zh6XIV#iN?zjcl1_RDs)FGSV{d0zB}0D`#B{GhiJ? zdXH{KCp?`?b6=a3WFrMlrXqADzkxXka!t4bCiF`1H8tZ;TGw`WLr#rwJ$bWu2Mu@I z^XueAothdNR^7x97^TvG50#7l6aanIghib3Uo!mRtOQ&fFHGGBaB2Y3$=SdaMv`D@ zX-Va($h@AC@h3WyAg2KG=h%I#z928bLH}pW9pnUgdns)OdE7_9MmSJ?-8$c}X)Dum z6}9Al=yPwjX4&jzku%HHN5>_}S`H(<5>Vl7xmA+2^JA*=RQ@-0Gxnu9$AykN)SsoD zLnolT&3nj_!DnNGu#o#ZlIl8_@}7qpp=|AVUc+1>f#$(=0Xc)s~OpjAy#`g ztaaUF-j}aEzQg~0UzY(ll3FC`i<2WYT96J?nbKJZN z@AjU%WVI4TcDbme=29z#tL&BotNU*27ALHR%dUM1dpTuMnBRdic-NS$?kID$i>}gE zE=H1O`5y(uu<;*R3$ev_l2;pkUsQ|Lyllgyw4ZYT-ZAJ{tUBL$%H5IK_$d>ug*(7a zkri#1Fa1fm1QvPteT%RBE9nH7`E5!mh_E|<1L?6_alZs?NP1revXnqIgwl`vXYE2i zS7A3<(m4f)Jzwm_h*)7wlN3L^G1UbBt&6PGL9IDV4~^ED#3+D@i`P$g(AT?~AA8e8 z`L-@I2TRoE^o)vf?FUx8KbyCJN1|um@9geEdU=~xO8!YWzpbJ&K_9R7sJ+@mr(r_W z?2c5joPpWpP-Yv0!E?PyRJfrCFzp8zkU*bupffweE{~tkVD-6_zHZOL9y64*_lHtDwN&I-?s-srII|Tc`kZ%PKm7|7m;RC>#99df zj@{5S%E{RX**@TQ*BIf-ekG60Gd48_uaz6T?gARI?n(zLmM%+FXus8V?8!FLV&T`sQ&T~ls|+zbN)cRdPs{o{zh51 z5{SB@!qvv#j}0Oh;E!GY8HwpMauRfDdRW0ON1JZ^<97s0g(yEhfv6i`cbS@+!F$En z0zE;|sd4WZy;KrDA2ZkeMm2}0;UzNpDpMwHKyU2*dwf_r6@^?4qJRUF>NA;XIWVn- z)YR3bZsfNPd-QbJMK>H|DHD$Y{5c~pg#jnn5B4YKd;&#ytKMRm7wrF>Aqqa;-sZb$ zoN?cfD|W1Tai{kEw)8J6MS*eR6v;wvw!OpO(DAQxhpKK8%_nWyie4Rg*&M5eDQe zW5l==CBI8nqdIo1TPO?T&_Tb0oGw+(=nAd+z zG0L}?R+g(e2lFD#8{{TBE4Gh-32%((b0+6%jv@J3XM}n=?Ov?l3%InD=Fvq1h}3GV z-;P09i^6z#1DCZtKw~H}c8sq$ZgQGiX_GAfrg-X3=QYe@SSq=+Yd~gEp5( zn-^bhlL%&J0FsJ}RqZF2gYS@X9fFd}$BS1TxklFyJvYMByv(X*U4R=qjxU~6_rHSGr?FC3UHD9Zq+Sfjp1(I=K{nPXCAEZPeDOV|;g8O5h#b zP`lovySh|ejM<^CIRpGYBDl`pE%Ze4gNCo?eLL_Y4)p-=V9lniiJ6JE4INrPrRDbg z(KNkHjW(sY>irapP0fGWZa89JGIQqix|Mr3DPI0%dQ2D?)baRBU@o2u?ZHiuJCn;M ze{T{8viNu5K=Rc4-m}G))zgyr^Udv$>OMf4HC%;Fgw=^_Kf;F+kJy67)AAok6mmU# z`DfWKEnF%Y>L;2IHk5De%yGC#7Qpw8^cQO&;3&o}wnkSa3LH#i-4g5S_AbXv1EW*8?mGMdHLMVE7Xa|X-{=nY@tBj>i%IcO8Th=z@N%SWS7rfEq`FkZ{#*P>w2B5rJ*fqDldm2 zWJEL#CPhUXI)3|%=1z8#H2_-sYl^nZvMLvw=jx8G?R3?gak0kJTF8ELl^z`c3oYM< zAp~GgMruwDsB!z`&|X#Jdf&F@ux7jH#99Ad&w99kS+`$dMg|OW zN8Bh)Trb_*mwGT)TU*3iD4rmT`M9fw!uIEv{Vy3vKHo}tdp1i0l$W0~D6IQEsV=!p z@6&v)L+E#?NG8ISO7|y@`BKJx3+z+-j9c5= z<2`>ka}?#BCk?;N#FXll$oA#`KRgt`pZl(cvWr$Ru>qGyQt{H#)DYbWl`o%>m~Gq1 zt?{*|=I=?kpFVT0GEhYM?&`nz?SN)`mdzobT2%g&2MbJtTUy%ko#TX2cmZ6>0%X#o z<6yFlh1Jc!aGvmKwI%V$gj&S|ALYHU=TxY?4oriWpa5PWT!xwIQedt_Zd7W{Tb1lY z14q9Th5{KIil)N5<1sXHUn_Z3Ko9VKko3OFu7x5W&%GuXn-&mwCDM14q<*Yl?PXE0x$0hds9Gs=Vtoz?xgF%a?3aAxnmfqu}|;Un(m)-wmmG zBCG3yS@ntsMFih*B4g4TvpcN&=28z$KbrgzN?`MCTJk2ClocSrDNyH5`UxW)EmP+Z zBWFoIdI>Kqo_y*5f4l%&9#VvW$eC-DS|Yy;uv1cryyT{6oOOUPIQq8BzK(eRWY6Ax z&Orf>9slp7cUE=K&q;NpmQNQ zb3_6$4%oW;rQvP$DcmDd;G$^Dx5)QGHtS1d^1?`#Hk-m{4h#p z=KWASy>8|Lef<=`;^sW>?&AZvvDa$e(+%A^*u25$%D*}o>(r7n#M_uSq9ofNe{=Hf zAI}u!6kxJ8pe#(Yv@6O(mf7{IA;1r*fxB}E$_IYFM#k*>OJ$ARnfH#Y-7sm!laD>5 zA}|_$0y-l3%5(6J1gXLqpQL?OT;3sff@uA3o&LOB0M7FtkztoNF zPoS}_A;p}VPZx+ZKh$=DgYjA9$FtF^{&pSDOLL#7e}d8ZCV8IXG~u;XboQ0ElO+45 z9j4WbI>k$K4s~5`(cdyjA+pE-)YwOUQ(Y z82g(wyi!A+{u_VVQsjQ2moAE8I1B7cYJU}UHkRr0f^zy`_qM0jH5o?VOF0W`^5LK@ z>7RMnqPye>SnrK^8^zkq-2$xBclI};dtPL=n^Ot%x+sjk3s-s7T)sE@&PrVUd^3#D{wo@_|slh7M-d8?n0It5og|M=wGqF|9>%cRzY!f(Y9{f-Q6Vwg1b8e z*8l;6yIXK~Yuw%4CAfR=1b6EM3GR0Gf2vO1`@&PRyBcP%HD!!%rUMsgGBR`H_Cm3v zLY9TI?9-+L0glDYtur&STnGjptO4q1Yq$CY{L&htTQKcTORz#_X{WsWA{Wp(ftCX4 z23c%s>3(fz6x3S#Lu%?C?9fs~*+9?cKK*h5bpOH~9(mYDoxZycE$$1C>K%6$BC%L- zshz7Fso58dGU+9j*~@d4)#cCA2C@ZDB`e95)EFis%<6;;ERREv zFWiwSebor9>Y|l5!_i0RI>U#+R|#P}xlm52ch=EOl`73!G!GCdg9BizvM_S5>bUCb+zUQ~HFB4$@{zsdM5gRI!>sIa=cft}uJ**eW9L>~Ld&$l5 zwaUrh@-c+Jg6HtqANyNKXy@0$xOqb#G|$_iH$@(Xnln@M1MXJq_n$-o1Krg`IdBz; zS`dy-mYkf}wyi5w95n%6f_wzbQ-Z!1z(~tGZ^<;3^q=jMnII-3qw0isACMF?UoK@h z{Gls63#a<`qwek0id}{u&Yc^cqu48&GUrL4Xl(2k@zYxK7Lq9+%|3Dq6)Q{nQ@^&h zgw!(1iXbY~1=?jZ_riJ0IEuEVWw+;L(sI4wCD1tstBAg)N49Vt5Cl#TvvGx9#P)#WCiM7|t!|NKI9E^A?~ z#XT1Xj~ET2GGSEHn`Y*cy)JIeFLvcZaR6b{f}l683OYHOIXJhl-rg*XJ*I_`LnD{8 z&-lV-s$zjL=9s0$^1q(ZLT@`vv}@H-T-`B^YNbGbEAF7p-b%z+8Jw=so5Zp`)Ik4s z(bLO|IEl5oXxx}-%`&ge*@AJ8p=sCVn$N)sUNa(;mxwyI zetDa5>WJYM!;4_{x7b2oG!jWxR@N`AlP2s45rj#Bs#@H~oeQJOB^3Q-%jwe^BIOZ7 z^L4yPG%tDY9~BoKw*4pC*Wb6kHqb_&)&oXmKqU^tWL+>t3+l&fjs?L{EG%AzPPn;@ zxR@AOuP+Hu-?R{mL^_kwP{e`Y$kyvxhm&Fw6sMIhzXv>PY>0~N=KJ50kj~lz$VVqL<&hWnW{=C1%6Li-zI0vrPxDYY&gUfQOTr;Zfk_!BC zuFfSptX$zp>z96Q!}=zS@&ZO9(W&R*>~S@)C}`eHqW~8(#DT)N-EZ_u-y?T?HiKX5 zm=(w9-W`7OBk`(Lup$a~dHB^99Btyz^*&7W5Q@XHshfS=96y(RL|se*JxxokB!SQx z{f?%l+%@VHGr}Hhy@SJL{@Zl`pt>GCGPmtD|K@j#*ZXjV5-Vex;v7}PeEGLLe{Xv8 zqm&`7oNm(I+b$H~0StQ*xmC}i(y1uFuVN&{zZ0&4C8kLr#L+L+2Q{gka_W>|tY)sY_Py+#v1``McVlyN)d`cHOYK({f!3nj zz|F%$0)rv}(jn(v)tfB{izWG|7R#{5+q~YOe)-Ou9?$Guksb%e3#gMX@6NuG z_>a)W_P39Vxx$otovV7x`aI1l3H=z2iVXWM+- ziU_;IfqUKQLf>CR&}xgNoRk+) z7qZ-1g1|9yvL?F~*idKf-mek51gY=~UXk|j4~EePBQgyofy^loq|*Mm{Yec$;iww^ z$jDfQVfi!f#AnH1d%G}Xu3O@rVWpCy=2h5Jz%E)q7(p_@=Ye^3?8nw~_H}_le?MbN zelc&;Q^u5~KnoS&pLnRnREVUGs2S4z5|WcysW)8c(5?ITfvd(gdo}!0IgMgM7TWqk zn@BVU<;+8YL3hSkSJFG52S$l9eiPj^`fbzhlA7!jnB~4{i{cKW2&qhVK-x1^>Zu&? za3M~V76;|sLTs#9z)G5#j(zeJbIXC8U{X(z;;2n=wBqL~<; z=`WA25&u5PyqGw=@@E&TZ9ASX7lmz>;*J)&56j#$uEH5 zfhlDW&<8#YEv0g$K;TD-5#Cj3TJkxj@)H3eVNqkl*;)^xIM|=$TV1ds%%b!34B}qO zN@XVD1t02Vi3!*R-bmv~g2i1skigv)M^T!a|2 zin{+7)qZ)I*}?XZX+!_m|-g$)}rj`2+)Y21H& z)Xl#}*ZNJlI3S^$whMR@mjBhF6Wi2c$u)rEsOn6I#On>6VXLSk!I&ihuTMb44w|qa zY_i~^(3Jdc<(jkLd^EKCF@I#nl|`td2#vUZ=G)5#&-|MtVral7?A0F(NZLHlmFCmT zD-&(3I$VUvrx^s}O#$D3#zKY%E|1%H5WMToDd5p@a&-;4evG~Ku4S)l)7kjY1}OGZ zjBs|}-nQVMFLTgS@o5_y;7yZlEnE?Mb!(x0QIh<-UP-i~ zZt9_!Y`4Fo@SUXS5g#W-ayZ!nM+lM)gV_M;OL#I}7!jcX(Yrdj4Fvs*D0|ZFPzQ*@l+Lr+;&kx<9o)zj{lw~f3t`~`eU_&$K+^m0+ zUB80xezvWqZ*5UiCT;KYgymqOv<=+YWZNW&_2~>E2T?5reYf!<( zS;I&d4#gnmfKN}}0L&!5I_y+< zl@E2p)qAL=|4}BBsg&b5I68`N=NDiL&}X$A8Kv_^Qv>2S;DB{oQ-U?(=;Mp8HSz~e zJO4feN>DW$6%ALaV&!=!y1AOo{1TPC^dw+z2eLsUTLiyl#9`pZ$%ll)Z~Z zL_`Lk1NoHU{fpHZC*4L%gQCp*qcwX1T?aa6)j^XWq;pf#)L0oBCB?h(CRpcF7B!#^ zoyOejeLI%F82F@k5(L$hA9eF`&^#px_uW^=crEB|K?ZaY+ z{a4@fW|iHI_ptZN_g4%dQPJW#C{;!H3BvT&mS)TB*%n;n5KDaMAMV~1@pz1NC-5T5 z-gH5|@jnIMX!xU-9>nqsh*ti9+Jw8W|2%X=m))MosCpDEh9}g~LFsvpZ;udg>&*X> zU`BurbtbYlvQDi{LPfqdzFKLs2h#?)Z3xQ=fi_MNbni>p+@0(ZAjFq$cjyKLnfVMs zykqb=I8pv6g!|R@rG?lEj>vH_fqarDCe{`nXw(?6%RU)bZ7ra%RnG6vf(HlqE9@^h}UeMrAx^iWE1DqWA?ez@Hlo|)T(0tLLoZ~pteEz&n z-XlBJ`%IF??2Nm3h7!6^!xmPG&$uSlE-;j@34+uzDT5tPr{iiGS94> zIph?%;G~2K%FEBk`nZo7IPrJ<%4`N0@!0(s1+GQ_KQLJ(QFYHAqs4Pi5CaEz8v&p2 zv(F5_eLr`b%25UEY4`UG#W1>?w^tw2Q9#rmJ7x+v34pu@q)%f^Nk|#1=ARCMFnF?p z=z=tfUetGeKQ-#t)leSY(>F{AS#S{TdkRs_$~t|LSRN3u<;gCrVgh&&u`-!ZwAs_} zz+KA(j=*b)<%~s=JOZdME%0yNJu=JgMBpirYX$t9{;a#AM^oY`ItOj-6PFMF)O7+1A&pfr_J^h5_h8NK`M*`f5BZ=YqipHKODHxbr+2A$gh#psBl?yvNsVVl-ri>{Dsa(Pl3mpzz2J+goqKMLn( zxht$^OKt_hxD)dfw7o_QvW&(Ct@2KRP-J2TKx{xUQD)qCnDZ(T^N8edUTt zX!}j0R>Q$KGfy+@vB;i?7@@m}9v)?CMS5371`V@S#M#-|ifZhA?@&){-TfzDkzyu= zSO%Pe+wm*d+B!IN^oV`&9{)p;&GS2*PiZ>aHPhLf{1M;JdjYUhGPm^}UkCAw`+_*9 znPGCz`Z5{0`({xc+y(s)xm7;lfqgy++&C_WDY30JJ2}#-GEPk0e_wTSs1j)7{CWO% z`ukz@U^g?kRB-w4U>xU4{^5gFKMGZ4=OK<`&x~cyRAkFluB8(DD&!Te{*^Ts3(_)!NIOzn!&NhG*;5SOcw*-SR`0~k;XgQMf@*qF-X8_A} zhN6W9hGb5d|7z?&w@MSU^!g+lJ9G|hn_WA}fmb+fqJVSrDrLNeEol#MvSme;FHXpz z`5HDc5AE+4|E6kDGh_bHl9oJ6!b9}6#oqk!)r_N!9ib1d) z$b~`u#x(9ME~#pH`%Xf8ZbDSk>YxFESuMKF{{-&!Wp>m7jmoGs!}#(%oi7)~ z_x8E|^6d@FfWc*4nW3Lo`vz4=%z!ll{m)#ho+he*n>H6Th;D`|WA+aor{=dQ`Nfp2 zUs@qECpk~?fd=PPmT(Y|C)(s^lN~d)jpxh>Sr4+)b8NQXlAoe5B_i&>^+|pqc*v%B zhx@0ELreZ}>XX0kW_>yPeg)?t+mR=q7L2DyDtl2kMDXneKYPrlMK@;T06*ZF;tjp= zJL4z1s!k4VOVW{Xz`W}z}Ydpl}0d9^X zjgze@nc_>bS!Eg17Vstwn0yAGGX8Sue*Tt3J8*VZ%kF74k41{v{sXxLTI_S-Jx~Ui zY9@Kf;G+QUR7eqHO|ef$P9lUxfr+tRloWlb7ASc~^Ge_K zOO^=}DhJ2*v4A(Is6zhc|5!>V4ose!P0gV>6kFal4vLu-niY2ZbyOE&5{#g;?NVx! z)Fz=brUjqM{O>l;DdXN%goH%)fc{!)@R>e_6;S9B+UbBJXnfdim;%xNl>S4HOva^h z`Lm|Y(7I;D?KOjYay3)v3NM|TG!z7Y*gBY^{JV>DHmHFl^Qutw>_?q3-&y(WjvRra~ve9j;IL550(Ur8s z+3y?`Mew{w2|K+E3lkGc1VJKnMfxIv-qJ~I$`x1k59tmJxXW@6p*&Vm82pkqbnZEF zfC_WO3P47_UTgW~v3Uvyede&V&sSB^GhD9bgS&+#1?45w47*}|7jp_RRu!_a7r`KL z$n&rA2=UtdnjjNM-P3c53mA4&Wx(H3^_!@7WH=#Cro*;0xObB>nZ?ue4o@9-c}OKjBJEll>eck<0=!Rsp!X71H8%PS>cqlZ)JQ-?6)i2Oe^iE{%R^ zUBPQ1S*>M0dvK(OAiz?(?Z*#;8)#Xz3y+A9RixLToj|_s@Z3TZF0;mv=zD3y6BU_6 zOP`{ffj|S2IQRz#9ufc?W6wjL0HJ}yhvmaBJ3@q9kNiSNF^yin)m#(OH9=LyP12;YMnS;fejRVna+bT0}166rUdOtC>SIqw~zSg644-T!UZ1o@zef1V%HgZ2S;aBkr+P2staC8qX@~y z(&;ZV#!M5bHMX%pueh$hlSqr$x^bPzwHhsK0^>07=C&To?xxJABPQ|B_p+I4YWI)7 z-FSuoaAqkptq0>njyX}%S1!ZES=79O<;DVb65fk55gwYaB&CdYD3tz5s+YIc@ z@ggA77MaiT9%nnCq^BZ~8vREG9${@}{y0R7AJf6T!gnE?Rc-QJOPg*_jxd(vpkjD) zGq*Ms)Uf#v;1V}6^ZH;PRl0BPTs%bb$?wc5oc!H1(82@a1)u|kVv^#=l=>;F;R2nO zjw|W3glz~bZN$dLMu9cZ9_i7k?RS>}jl|Td*)fr$BLLlIuDD^{M(WDc-`)dzh6bTwfuuI0|ujzJ@JB+5nljnL}=HUJmk#yLydat$r+n_ie(xbU|ZwT`*WV z@J2nOlToH<;NY!#+gN1!;>ja^n457%HV573<;L+1ACX*Touw=W&-dW$xl}$jqJDcf z{r!PcbBv{p6)d+$_CK~A*I$;;CBJ%nvt(rTDYside=!Dl1_d)<>rnth^4G}qI zoLZZgdx3U@)&CL&Xf9ArtG5`$OqfN#zvRE;6fw$ZEXyVN>kQQgyxN|CNEBe%;QuA~ zo#uqpG((4a*NgptnS;BYg_-mDYi(=~!;V|&B+j6ULN{5*IfuYpe?OyzbvnK^pI?ZC zE;XsLF%+#^j>>&24h`#s_@YCe4e1SOoYkqokvr=|2XY~s0v4BM+9+qfQ#?HjX`Q0{;AZeAIetz{!;rs4%qR*uMo-M~a3x8H|>qoXaz6-wH9 zz*htYlX;$!4`8PL_ZwqKztjhHaQAX$Rl1m`E`T9YdVt3sK%w%u4jzlB9|)3!b?1MG zcA?{l@lr{;g%#^slD#I(nYO?$Hth2XVT^9@@&~>-@XW6af#o;@A#AW@!=1tPoag+q zfm4OnL4Qrc>^Sg{bdso|;ky3?uV{Nx3{?}0GwiH1w0*=(j5=d$^Q;fCj))^7Cy0$Z z-sn#ny6sB1Z`QEs)kcC zOB6gt6G;#>6tlzd;s3M%7hf^boYupg4~n}Uj~y+%hCJWZsH_?@!y0n;sm9Tu_&Sy_ z&anuB7Gu~w>k;f;k4Xew3|4*uT$%}iGH@jf$vH-0X!ZR>Fyn;NDP?Dxf~6M&abyE+xmjsoNKWAq?MAa4lZYJTjZhK@-2%l>|_ zCX}gIV@3Tj6?;ZO&4?=r{>7tRI;(W$UmIcEC}CU}+VcbBNzVg8G#)OLHWU@FUO(7f zxcANqh02OkR;Q8FNevgMTbMY4*>#Cv9=fBsgns+EPuArUX2_0W?1u+7WCn#4t2tao z#xC#vf&jij;3fy$`x*(DzId%G`pZwSxC$)zu6)ZF2DFlPt$Mnj`hYgd98)SHsW+XG zt_45vPwz;wiI<`IZ)DuvIs0yz?TXIIs^aPI3mXWPfa$Fe3B^cRQ}pI#e{xr)O#~jp z3|qqv44l-Q3&X67q!7BJ;+wMAyY!SoEUf>An^0MW9WyfMtHx;_mn0|goSXfd*bpKf zdqwK5OTB1)rln@Wf#-DNiHnkNRS<}!A`1q{;NO0#;?f;erwW-GgzUM9{}Istm1ozX zQ(+($#CNrz2tL%)GKboZ3O@Nk-~oAblgKK8F8dzWAWEgyQu*-*qr`eE-yh1!HhWCE z#6y7@FEfD*2%tvt;3C>}6B&@jR#>DR`0J~luv+M#$EA0VCmmE~&qf>vRn8QOnQ&a< zYRryI=q5y#XxZT{Ex=_TvPXR%!o~FI;di~iIod&I-R0|f0LAz3^|5wC&!s1N`k&No z5n{&ZcDZ-GE%)w*=kVPL!>rxBzM(Df{Zc@`sckY&X!$7@hf=P zr-Hjs9CK$xaoJZP04t`BBfJ`1lfoYh(e9Td107!#hVG`a-f7%nogpHFkby7eY!-@$d5LX25D)F?zCzqaZoOg;V}Z0d7K=BS)rD^J+%N^CNRCK=;HLzs{3U zsqX=F?~KvAIkdZ{zn~k2JzMoM`{eQ@sEJyoB%v_5QdEgSa%jgPOe z=c!tIDf$D@W2@BuBTz`ABppn0g9VI-d#51BBBJOo zn_f+*GhQe=3Csh)>V)b_M>vRLGx3NZ6L~%5{E3f};?80ys1?UGVb{6q#uRm1T7lUu zyY8k_x8z|X+u`Q#|8|{k+Pq4wr0zBC688Sk{w^K^(VosN#eCk2VFj3Ks5#K^Ff9^4 zOq`)PYPWPsh9tI-9<0PkP+uC5ieb^7-mx`*L%Sp}dqU12R1N*{tU-#2t5TzeshgE7 z!RH7$k>S>=njum}dA}!3&9H1Kd-HZMp@9Z76v*9xNr!L5rnO}-7HQa{t64@aiIxz2 z=!Ivb6>PlhF6UNsncycg%jE%0bc1MAW*x0>4l&m?>Cn&mlB;N*zJC;mfFF3nXrHQe z^K@&QX@(4#mPZMl&4!1aW3#hKvPtDLqj7`wLYNk&ahjO9@gp9h@=kvsa>%)mT&!B= z@49s8Saw+hU)?5*#G+yNf+nLw{-W{^5r`Lk2FpxejcrCmbX#CS=jZ2Gl@Nl=&#+h% zZT4Au;wy>~EaKbeP8~T~hHilm8OZ(YH_FK3FKQpY6k;%;@EekN^e`k(@a9XrJOn~8 zz~jG017l69u&m_!Z*$qh?sf9@$z!d7Q3u=d1%+v6}2@1!A8MhAAE5j;o2YazaB;)QQy39m&U&^z9=t z%7wjw52Qjc@MPr>{p0^|-sEw|u0cq;snslQfyEy>N9{q@IfY-iK_$Tu>w|C^r|cqR zAMfcaLit%{@>c|#T95ucZ4^5Z_^EY!$&u`W7dAr_npV_7`3{2ohp2j4X%d{-G$cyV z{3XKq^?3W{x+ZGW&v=JF+Sr$v{9QIAi!EV+)1Q6GdE3QuwRxBF-j={tK21R zjX#8}iE9L)U%LsgxA7fLFzZ!U4VpA!f+Xp}B|iZ8-WI1lz07Jdgk^+D!qp!DWT$Ow zdt*aK?So-nBYQt0(c+a5Z$Ef(zI2ybskW93Z2{qsUsnV0QYL-NoZN>{Qb$@JN=r}!8HxkHQ&6;peEGPiQ znVN?z2{=`Xm5BJ4FCqc5cP%Xd8%3l`U%;+K$y`Ne!KbNZytBRA5OJ@(AJNX|$445g zGyzY(Pq;tn-NQqP9VjoF*_S(Oxv{nN#yXNZcK>bv@Db_J3Ye`Li4+UT(i){mN6{*= z5rId>w4ok49oWdh0G`Nhj!^ht-Zw)x&;8-DkI71?{ekAerutoWKjd_&HKcJP{4PaG zyrYwRmUKoAse5!lp z(4PyK$=l$RmtM|MN7J||#eF8J2RhK6Trvh<4a#*Pn(cYQy&1y=uJO}>QXB(tM89Ejqv`N)-v znr1IZHCOXRp#@nke$-S-gu}Y+K2fBZ6kT(OKXL2*X}OQ*sDrKK+b)9WLoZK;;7m4saOsPxq6YlAO|YMaLxw)F?S!1L>cAMq2o~+D!%US?iK&1fnd60nI6&KRRdlT z%k|$vU^1o5#i>IuB|z3`?Av+DX!jC#YKr&0E>^>)g??d$m) zIj%nf-qFDr_mM^8(1@iPC7jL8;;c0I_cys&vk(hLKy7*n)Z#(}{Af559>#~RJ?KuW zYZ80zg?Azxb78q(K6z7D%hlTcM8^OnTY#@frw*ZK1W(a@G~H>Ecc>Pu(Gw7J2`w>{ z;dk6@gjynx_yKv3W;i?>y|5Vk$DBno4(EHL$n{&$>=?RQ-i8j=;$vP&PuI zcz^ngIJ?|OXgeTo1#UP|QZ0orZtS6&;+1elwqhM$`gcJXOc9~^;*O_)DbKfp8j{mH zSw#yCQWb`uWt;$A(%=^~AiDd;Xe#;g4lt18`rc0ZWRg5jY_1Hw?*EYiPJC8DCljfe z6TF)>G@>>ru?uASizjEy@asrF+Vf`U-o82IZ#3$vmi<*mFay|;1rd}m`cII`K873v z)>+eA7mACF)H+nt(vG}cdM*CbwJVklK1F)QEaJIB6poGyfM28+h{xj_xK&`L7P+C+ zAN}g@I7BrZVPDf{t9EjI*2C+RI8a+hLL22dsHW%Ap|8qIU6~wwVnn76&2Z|8onU^c zSc&vn0?Jrk0m{}`yv1i;e%q~vuTv7%D|iG;i}=8d4Df{W%yyl5pnygL3FytOd#!V1 zHr#7J*W;CZxx=1bpK5BFrDdF?4Voxm^J=>g;V{Y=c?6y|_uMjJ*$^{j5~m@gQl8wD zYLaa1qV$hJ?(_ZaIOCkG!oFRUOV$MM-_W2Q_uUXdt%c%c;9>9Bibc+k~1{) z{Qco+lj4`?Uz1sjG;_H{R3(jUaQ235>!wCG0?;w6sv31@=Uh_H8K!UF3$^A*QYnvN z!-1DZ5|_QE(k^ImY#Lu<8d@`{G29%Gj>2`Zwy^8#XIS+T%T^C%i#UnL(9i$9yo$sM zMhT5@d#ptx@D@r5q+4d~{USmWew{eX9QLK-PI8&#L&1To9)7d34q(jFX^|^jMFRK_puU%oko@%ha;jV^m6QN(PY)6m@43?^e9>xMd1BO&af)gh05pmP{_6hW;fPsT zY^@sZu9|KhP%YL0+hO2y@|79*7;yT5PBZX+&7zN}e%<^Kr}x|ChoSQT%bzAkp@YOE zB*m#-sF_m{Lr{;5vbBKSLJOcNZ}kNLWhADp-=M8qhrZ%2uBU7qY9E6Iqm6VWod}=PKF8a3kM!OhwYdOd^C6?X)Ie8E}f*-;c18r~CG1#+!8(rtDkY9#wOB4?wLBEyl}!~+y|~_J2Lf-v zh5|Nu*Y!3X<}_e2MW5x8nx-IT6wP#lgh2FCU{oXzAKDXu7)#bXwIQ}g9Fyu`gFGWY-!>axqsi;+68uqK5winh7 zTLbgp);V_A$4ow!D=KmLY8wznF+}}K7inQn;==~T*v%KfkmO3@PF?qVE^*az_elOh zP;}3Is7GIJ;fuz^jMWi?52(H;a7N6F*}segCXP<%$n2oYX$MW+!^Z7%=MKb`nTLHp zv)*c2_k={{YSyPr?3Ban8SgNB&IzMPmgT8lZ7(TZ{2yIi&6ebWBXCteLZP zRDj7pAo!}*0%SBiB$ZkZev*jcL8{gx+`{tSzv*;OhE_&5vf1O6c&Qe+fH5twLWL)? zi&1$rsoWj8UVa(LT4sqKN_rK9n>sWursh4T@o)AB;?VxZwi!vLxbb%h6)aHs4)I%Z z6HSPiP_S{-+c91KZ*X?~zY5dCGT=EofZeFYGHD=qz=}&fpD;0)gNS}VvWeI`BZ)=2 zAn=si!-1t*IiKnGl{Ot3>Yl zPi$t1$!Yb@ghzdd2X3ySe_b@n-8zBPOtCE!sj@7f4<<8_l8+xb#=k(4_(~%Y@<==K zeS6E8XY%sU@eR%%sLbga@>K|4c3AyE6kb4o!;Q*FDAPzN7Z@5(xn1#%dJ2hea%Hd_ zc^gp2%9@_(LA_sKycf7+BAV;&+}+`ezW&_?{GiuaiP9Y-0E^KJE(uxn0;^da3Yzx^ z{LtXdF$M@Dpf&PNaRa;^F#UPo=YZMg*25Kkf!K=u!579V1UlP;+3=o=@i3RuEADzr z3=hAr@FYgJ{yWq=D=bl!G>>dv`Q+AL-8Iw;b)6EMVs=SgTmT^m4DRuT&bquEuRcMf zBzVc?=FPUD+zpId^@{687HiZ#5Wn_h$j!M%8YT-lnwdAKQYJjyE`QrkRuO?R&oCow z9HNi_x)&`$>VdRG%o`IRV=QU#0uZXW(#9vFW*p*(xoEeZ_y2O`TZhY;B}ro_FoPyK z>)42uPzl)_*>0(lkR};SS94~=R&gT(3}OyltfMyO@{^Sq(W8oTp>RHZW}i4f@Wy|$ z;%eHJQ(Dv&2fPUE+0!+MG;I8til?sphkO9T&gOz3;F933=JhMkf&*4MJY2Q+H4Z1D zG1Gg*egHDL>ffIaJVc1u{B6t~W9=`NfIUHvE@?8*q`*8J=3&GH3L=!p%Zg9oeN@y8 z@$rlu&AUc7K=8~rdOXI5!op_tpMZj8$)#&;DEwS!sj=3P=n_iF@NKDi{F(bBEZksD zlLV2^&65Cvn_G+ z)LZO528q<_12_fNfB|QYVc$8R*FNsFuNrEB0;)tfqf#3NmgS5TGqCSdu&6)$TdP!V z{`t+b{ww-|rg@?rWHQ>)u`&F9VN6NSQLN(#3P$Y9`KONUnh)joY%#X}WM>HGy77#Y zYAHZ(i#=_M=t@XB&0;CgRNp9Zgj*+?0!oM>841vppL#cJC4cx<*`22D2X$GpYYYRG zIwEIr?9vf>zh#0-RLU&nYpK2PmYXhAn z1MiP_lad!5Ek@XzL=h8Vl~d2jj^(>zju7SlGqU}ES+iN+lo<9P>+kTf{`v-K)G&|Y* z3c{vL8rfuU&e5WlX^4Vb){RBd;i-G%bTu%2&s($$Z~XrZO!*k<%tEEd9CYjrY=WG$ z`>zele?vt$tI-W?L_p}KI9hT8;~p8?pQ3G*)wBpJr*%l3-HG;Z#rez4Vc|6F+$#)?j_lSHOfPTW>!{2?zbP5N*~|h-b&3hKzopfmMNQYpLjO z3KG#6VlL`aY_g6{yL;IB`WK)at*C~Nf?fc037m6b)&Ic$H(&H(;!kz+70Z^`%E121 zQ8ag=Z~LNp_Ul||K*|94Qz?oWKl}Yd0rGw~gOIxYexXWst5vtn@g8{fT6i_|u=^TT z5TsCvbNBmjV)|&wTJXejXPq$(gQU46X23#c<%mc%vuYYa$_P>UBG%X|)Yv|G`9AOy zE8=y4S#svsfK(bf$(wcZN5Q6i{T;*BMCXdTo%Wym3*kp;u}+z9%LCHr$rEztAOBqA z0n+~z=^#uaGiJjWK!y9;#(X7sSfp~XLK)hKzXWs$rA1d?+UKfuq>YD}x+EafyZ!!l|M2g7Ukm^Pe0Z>$750lqx=P~1lup!3OG&d$01ocfC8iJB z)pXH&CMTJJd3f<-G(Z6eWKNw9Ke1`2U=O&p>ymi+tg=sdOsTc#Y-l(w=#SQFSf3%yFvCBMy1qUjsC zUz5~vd;Ux;bWDmm9piJ)(TXq}B$G}3b|SI|!guQ|S#@xw@t-M@1{EmEW@eCJaY@h@ z8YR@lCyeh|BWJC|RCyF|*sP$3$>Y9;Zg6)isgkn4`4UN+&MW}Bd9w#3=^ROWgA`y3cf z8<880?IUeJZ{1%2y-2`dr9j_d<$m0b%fPOG;M|+Tp3geRQ~P8me}4}VeMczXUUrWI z?vj`1fcNC;14%J=Fl*lnHlX97m4eNh=-=c1Ga%#L^!gF5hW=x4BI@6cCkOA=zgp=# zB8vJ?Cm3SkNKgV9l?cX!HO`vg+?dB*%zD^1I7Vj@w{dU5L#7gQ)AtF|qV8}c`mX6y!hl7SyP}zGxq$7lJvOK5OBKgHAP?l$MQ#6po5X z=1>HeUd8^=)Hk?B#C|)86DQx`&Yma1WD=DXIe!0V98N@CoTI7Q-LW;oG@uhOp;$-}+n@vp<05LV1lj-ThZF^YZ}L!cHPRnHDO|^fe;#ynh(#beXjx znpij@k+|LDvb(*D=#E}xzkBiyUVE8!f<F)=PR@rTRhj%A1FyCf*FON;`gScBx@8xis%chz0R7Bs; zJ^J#Dzz_@gaN}RyYj$5eVvT&Y@PLkW?B;=Wma+(7Ph*Yo(ZiYZ4z9Ok zrtnW!P@|-ji>E+pZesil;s~_p6V#jiIIWJGj?(#wa*EURII2}53K-m%u^Srl>}{@i zEV-pn@uJw47Rl7EB34)gy-R?{ph{ zq-x5EZA9pwL5rX__(brt45!(HSVgAd7+KI>kq=Ur1*}6g?!c{%;-dIKqX()42u722 zi;up8ko*9QliRiMbc0VV646cqWJ*_?ZDd!zp#e{j0G>)-U2h-_SNYw?1yDf&tDE#< z%OCSw)M?@3tNkC7rr7x|^U>qmg_M<&xbxm)m9*bnNdvP;USs_qcJb*Qx|V;6)P+#g?RlI1s+v7&YY6Wlap2 z{fHhF#+f^~=K~9DEefYYh0y_ZGe!?|%2y|N@uXqVLwltE(*npXdd|U~rtCnUdXQ9a zX3)6CnfYNuqZXLq$jrz_1JDrI@I@rGU(4op!Qq(9Y1rN7#mQqFcA!T1U45cV!#?i8 z4e4bjY#u8~nFVs9<{Dx7141V1Cgx|ER^;~oRpN?v0EgeY(Ei_{Vt0*9D-Q$P7?7h| z(L1O{P<(&}^zlE&+6Fv&UqKddzSk-_uquV z2o#=Suo=E3+}-Vv-D#q6&@jv}#dng4BjZ4`-Q!m6JQd4~S%SzUSTZ5v;c-hqNdH@Bg&e7xcZsSWmIe_LeLbzA5y2 zH?(qc3Xu?4z9>5O*H;3Yf&LkYvVdr1qBf9X)@|4Jt>QwR{d}~w9)>`blq$d>Gp(DQ z4|Ei;GmZ|+&59*Dps3^+`rsQZ5(X2&8wh5yf9yu z2&rH0#YnG6kZVA3OK3pQu-R*+QFZS@ZPc-9r?#AmwnZ3cMto|~+z30)A93bk3u1g# zm?$EC62L&)%ya`5gDdcK-#=XJhBSUz;CdaU1Xe%|EbfQ6&v*DIR}TARA`uLj^JUmW zk-YP^|rYs^ZJ zS{AG52g1uvio0wF*D|ivqD_M~NtY{SSJSSGvQFmCGlDcOrkN4A4ks7o&m6TfwkJX1 z3F0po;gtIm(e=mUSnoB8LpFc;pBHT#H_nQ0Gp5F_m0-!e)Qxjn%w#vGWN?b#)UBfF zmKF*->@TH|xwg@bI7yfkA2*0)iHOd|X(uSXWF;55+s8Ku+#GP2hZ@5h!Nj)|8e;~ zbN24{m^iWfT8*jl-r<^?rUD-&Yy|TJmPBlo4X`wmMWz@Rsune%g4jNI##tyj-7jhQ z$qUMoY;+J_z6wr5Ee&}_@S`_kOLTy92rwfCye2Fgu!Oq_!fR~KsugV4_wYH`h__ob z@g{s2T(w;Avin$9%)CUDu3Dhc15^D%(ST)lKvB(OA#D2l(N}GBeUvumCZ7IJ8tvfI zs@?EWC{Ai|1%e-uPsD=C+Sr9K;7_Mqj92{15dvBf0gj~Lw!t6XfS9|@2yxO3dIl2n zRPJ!Paen{R7Jt(0Pvg<5N#l@7Y611K`;$F(#X(~z=1+vQkmw@DrXPd!`@HcVvk8R! zJR8pY^+xy`8>smtMwbs=8W94W!@~GenIyky84k5svk^sYUp8nPGgDXWW_wI}o9kR`$=K1APmY{zh!xZr4|a^<Wpc^L5!_OSu z!pgI7mO@J=gPfc^)?{3rqmMt#UBqt1*w@>XhZ+P#!Mx6bep@?vKO+Id%)TV4^sG3| zkZH7J3nyOTAfXa1Kzi^G0oK%QaO>XxnK&f4abvQ)yuBGLCD*O9!4l|R`v5Mdu&4<; zUwQ_Mf~16k=Xpq?54_17b&rD;A%A8sqt`5=Qd3C`IEk{9EY+<)aQsd;b@;5xt|A*C2F|*$j%N zkTw@yXyiWm9-lATgRSAyIkg|PJ8mX0xGpqk;{vO`AJ>&AH+3B{pL#zH`EU zt9MlKH`ImH(mGD&&+5{|nnn?A7aX1%Pzfzv1n~XjqS4Gdu$^Qn{kD0GM3DGpDWKbfU94` z;v(~vFq1IZP##!jl0Dfll5SK{4y>-G7Jz&aJy(-5CJU1Ja*hm5D=)T+dJdJ#OsDcv>V~W|L3geEr znA7U&^Xp1FKZm+|{sc%Jq5!h*RT!b&f^mbk5nH-0r7{;s@hm{eWCa?UQ^K?R{|R#K zg^~xT!_Rl0{H~I^G$HKx_&}`XdRG^hq+|&Q$`r82hOWQ=a82wik~mgQsH) z;xOpy6f1_!orSytf2vqU;eU7~4s+_8XDp>dk6aFqj69IB#~eDHZ)F_}`52lnZD#f< zo|559H3w~-8KR3Ff>&1C+TnXlCLqp}XG4_+ zSxiq}ufC0mN2yupV559O81|?vQ|-!ZV*akLH3%VrYCXOslu%i=bY7!!>7-}It;sBA z3%a>}3}&C0i<7r+zVrx0*KK*zl^<|&HCI3DK>oCRexEiqFlnN#$2zid>i(oJ)vSk9 zXk~KcQ|Dx8U;xa@W+9XWt1#%p*w4k$xu<&sX!qxp9>vME^hn)2$DC@iLnh%yY~=F5 z7KDU0fyvc!mZ6;_`hy7bNn#D^t~l&!V{gdD z&Q2vfZ(I4on@uKb5UbhJ(fu*6jWh4J>m(5CJs*8EG*~sqfzP0KSHKiOtE*%eT%AP5 zQo1&Gzjy4ZH0vHJOE9K|%%Y_H0|l`3I9>U=3atDb7t^zpkZ>GOxB=3c^WY9fS=kQ@ zg$$z#l;5rP$ovI=RU#!WS)<`0c>s`!$Cp|6mM?({-hD(M&im&Z4A4II z_wm>jZ1O5xre8|flv80T!h}d%xiOY>)RllE8h3a7UwNWfDz6WfO1Fl#0cIwR7G{Xn z&+$KS06X=3zou-!#CW2MKC*In>RONHwS{Bt;Cj?Wj1PKwc{(GMNj)$c2uUUKP81Xn z*aq^#P1=6$M|G|#bE=SO_0N|O_Tw0sKK;b{yXh;PS6s&U+Zv077!|r3n*~M;rhUxL zP<^WQE}x4G-frZTO_ErO`^3B2;9MX>Q+NtJu#Uw|*?uKGaNC2IV#--uP*hC|uAjs1 z156lD`lw}88gZ`v;0s17fBTYW$H({Hwx+m;OMj6_%Mkl4kcE1(Y|r^^1z6N!TP1c6 zZ7TrlLnva#iF1-HOjQ$@eMe?lAbjgko)Ajo6J+Ajqu-1l;F{LD2+z}o>7ZQ04$^Wq zCQ*a2PvU+eNa!s3s%Ule##3jsR{d$9{OG=34!9@+E`7NT5yS;nx&U_Dy__Bp|E*}C0<@&$z>|GNW7#KLV=+&&*r(9qpOE6TM@)Hk! zcpKk%>}eIOxTKWI(~`z!p4pIC_YpnTZ4W_vhGq__DK63>SW#wuOIIvOo3u!?`C`gy z2&CZ{cg7pLtC_=IeLtQ<0uBM-bJQbo{UI_y8a3$oJK_;ZeVBW{wF=@4f~Bs+2n3bt zqrZxta^*_Dh0LM;)y}s z+kLyvDiS498nu&UAnt3)z3=*!n)G9`@GqW!8_?~uP_2?4DDMlAJqZiStVwh;b?QUS z;5pq7aF}i6%P-sNX~|wI81^mKrf7*q$Yu}6361uzA4h|H>X$YjA0Hz}80Yb^yx0E! z>Q}w-3XZ!!|AfH7Sg_UC4S)C3dF0Z=7Lkd-)<>Wyw@~L=lCF80y^=-^6m2mfVY4`4 z$rb+r+3Ju#C%-)~AX)|}4q@|w0}^|hc5>@wxhBNe8r>naZ8#Lv6HxRt6N zybnm1} za{JZ>B9l0Pa{OhjH;Uw@L+(bhzB+k1vW8i(N~J)O(I}chLm!DX0}!5F`_KK~Q*ewW zRJPB~P#re>ezHFiBcNM3S0=*10uki`KgNn=d^JC&tKQe=z7h`&UI_`#=h3&4FP7#sv!u*3lef#QI z{c*F$#+cygC!XK8-fmGf!FshE1}tsvl)P`-FgN3HEjOf&M~7Gt6~W$#C)`}W`!DUj z&m_>Pv+R9<@l{tJ5TFprt?20g4l#VYN`2@fTi?3e0`JelI;^)3p!q+Dx$2vClLXuX zkUTq>2=R&OZRGUBSz49SBbai2etYbfek>j>D zIiUQKhmy7^v#0QdYkJ_5$7-Ir<;k@xTwaa4ng6<^*iwxOw%j2vMcyzj+j4rH^ipOk z(rLvIdtD-!()V3o*R%3@A1Zth#^jYXD^|M{B#E&=!vCG7xc@B!*PKBWZ=GzC=US7h zEqTq>t3y+x2s*<;dKMedS<@=e?KImFU2B;DoiMBUquKm4bh6D6fYjf2z57Ptz0dDu z^*vX=L#qAXaei`#UZXb9IyeyrwVLBf>a7GA)bSHWoUl)^b@N~!;YbS?&3H$UI6kfO z>;tF^z(4;EkU$pCodk0W1GZl`@lWYMU^~z@eV=WM_yy~XICa1$eJx5@;sWV;u-)K| z0;;(SujNLM&7YGSzqTjw{aaSV`Mjjcdlu+Q4dha__{Jc5EcPXA7AE8_>;tDGI21w7 zX^*Vrt|S>sSna9S-yGP`pOqvoLWR#Re2~1A_{RcKT#f=}8tvThT0`M#6Ra}fDmhK2 z!5F;3+pt?N(M-KK(#t$?a%)@1VR*(`lCMUL5%nb7^Z=;Z=(4$X+p$tFmZD-s@u15l zGa8s^U$D2?a{js zPllj`S#+N_^dmZXgB~oHLK@j76H_!};VUo%iCDGkX z(e`7C_gsGvf0Qg63-J)(O90xuBKr7mmjmqy&PKQyFMx+)1!BL2mi|Io^bkEWY^&x8 z{}mHp8YNyFBw1X~KuISUYL-wZgD1*Dgk|7>`#vu6tA7)scy6l43=8PYMIGtK2z5An zof#(DcP@hu)#1-!!1?sM)X*tEG>DA=jr(}ll_R&&;xyjW<$G=imtErycOtAn{d~Q{ zcQCUs6m@fW;a`*LSvvv$uH2=}&ko~WgMYCZ0%62K-+7*OZ6?E{=_4ch5ppUrf7p$a+&hiBL`5%N?sRLU%$mImO5j&wt8_pr^H4JW{*#khg z2T1iW0mF4GoSduQ5t$lyA3(o7%*B$BFrkb96T+!np#|>)|9hj#tGkKZhF__8A$n4| z@QDnPn%Jhq_Y`Gv!}z;y#R~W?*z-8!WQ&DV#}PcC>>^5|7c|ci8|j{KA{K#c{6cy* z>Z-v3t61~e|0Jq#O<*W18XVnX_{ZXDBR2Lw@pj~}grd~wR{tSGMGrQqGztPq=unOg z*dHgGJF-Y8#Wv}pE6s4r0N;P!0k0XLS(SvX&2tr(6RHpwtQ;56+ho-dx4nX8vH%(@ z|M)%v)uXQl-#>{E@@RB%4B6$XqU{gq?ydB`eM~WG<`*NcaQ_|=tr%_6jgSJ=LEPp9 z(O^s=d;oe^mvAd~{rQsxL6o>2%h@mq3iY$0U)=MvH=0ir*E?`91-|-)8B`bSX9Yo-!ys0Ajv(NHkU7DUsgU5# zTMC9T4rYnO2&O2WWspolY+e5%sGwHp6v!=uK2UrAJtl#+b|VSOs=rWxU>=sjux8TA zB>g%#YIT3>Y7N>Zz8_a0}9=4lghQZfP@{S-Io^;%}o^Mv7+pR|JgWEXSRR|gRbej zUHRekLQdV|>Z&%4G$!d;{&~ZuT=ymA?NT8#MY{wm>{^k-9f4UEYQz~n+wvyvJNM~s ztQaQUJvTx$NW{0>U8gb3ZUYt~dc5?tWW{zZ_sn-`KEk37QC+nQ+dAth@p|0-!vs6q zHrdE9@gW|`c9TGRz5>>dbSa0L8Zjegf%{Xrhvc+`^9yb?S5YiCMzbmkjp-+I4Sikj z&+k#MPI2_eD#{r;PW{U_P4A~qW942|x8?wIYG`;=RMb*O;jIF{nl{h;JGDZ&6w^N(=!khC5%dLTRGh3GJJu1zxeJS7bonOYiHez}xG_JK0P1`>p>@7@40ksB%^&ffms|M{vNFQzB7((~-hUE@x~(uA|z_ z>r{q_oP9dg#43&@dJbyGb@X>UxlIHF2L!u%H$;Uz`O1UnC(EYdxydz8A?B0o9{5vG zyYpGWaRR>p7B!4vx;iNlSr$R6;7|G#$p<|)*nTha9-lW*cj^1D8vbmk%9G@}(iFvO zfV6kWLq(;LMgu32kS~+i(X@COTvwrsAa&aIaKiH}5Fz9CZLdgm+R=XdHp5d5pihYGH6T^WqF z8zxEaG+0QTHx!v#Ao(<6>W$WJ0ZEV%vNPJx|01uG%@LpR^=QzVz@nbfl zB`~QWwe&n5JzliG$Q1u|2gpGgw9{|cvzp&hF9n$LO9;u55A;t{jG0*t-kZSKvG^*-+(i~6lDW_3N@ZD)!k zP9(i1QM{XHmL=o$v1y)bS-n;mP6@hjw50}8->XN9Z%qufzaVwo)<+<&5=b7d+(y`^ z0tBxjs9@&}o4qH6#$6+0agND;s-xH1H|Xz;@b+#an0ie)=^H+mgON=WO8lghYkOw3 zN;jfiQuyrq%M94Cktj(gsl$sPV5u)!{q{AX7=C9SQxy_Jn(IKlq{2rSzD$r2-hW1(|v%4EMpg1 z1@`38MGK)huWxKXLvSz5GC1A2HBGIFnhR(?bO;_stZ62pgo)WPTI6`no!|SjN_#!; zp>)2#@u7*|I9V^%ToCf?v!u%_FR)S9kQhQjrG*Fdh=+i4?#cJtbwB(F84PhW>#`Az zaIao45~d)+-Yjp}zTzhYTL=p(h9{icP*5u<8Dm6}X5r3}JrL|uznpjB>8T^9H+4;X zJcqfnrJPByrU;L-R2neg*M!A^Zgx?|3a8^PTD>BHA8zP?S%TTePvl&`@@Tb>!PfCc z;FXP9w;fzo@#oY{MbnSIGDU!K%7r=~S)C13rxwaCgAqajB;9kuhVbD1vW~cS&!kVH zM!aGgviKOS6}YK_&JaHCEn=Z@1N-uU((&P_?YqO}tddaAva-vI|J(jMw1^SF=>%qT zW$Zdlgvs!G^N_Mcx4YA(4Qte+EDz;QkIP!i5?l|DW+{ynKReEDEHXP5q;Iwc-!d`3 zwV3$sgiqO+NTS0W$t|C|Cloq&EXq^hPd)vZ-N?q;v=cPk1Ttis{r@xH1KgWX0X@T@ z{deIE>TnY<{n$_OT|(uBd(f^yVA9bLob)X7Pi;aYsOCRInNE#hnO#CI9?3*;uXm>m zfqVS*lGXRaC7DLLIdjn*ZjX3&LDR@$E2#x+BBq~N9~*E%dE$ZGxD9wc0?VcGcAs;G z!6yE()eBk3ebe(t>8InJu6yI?o|i4s=QTKh z)Gw3K>siB!00l5&wQYdB1eN5NU*1HeLz?aM9{-dv7FLq6|s?;4~5bTrRXIW#h1)bhZQ-% zYWPd{TmPoj*Oiye3_|oBTY_aCEg|s(v<-A&Hgjkn#?veK324*$Fa~!JpMt<%You^N z0Gs&oJ`O({P0IAIc?e)m$K~MHTdq~@^nL*WB-p^J#=rYN=L5XA(~UP2e_)hNt_7m+ z<}$-Do7olq$f)6)UT(pY8SxY3(>ntOXv%lw5st<8$m9kPs~LF=v_9bv8g)KdE{msx zQ?-qj^h$^Y{2>e zXN5{a83hv`7$3x?Sdzr{X+_Y?Y%ob>)I#xV?CKri&tO#HhCY(N}jD$ecISA`bjo-W{Y>%%2l-*($h*)HNyri|gMM{1Q>*@+|m@oATlG(Oa9D zl%0q9eW{ziLMTRAAPp2_wZ&o)>>dzrvhcmHyQVIv#OVsIjA=91La(xm)a@F0#cv!M z11yVMLvNfL68|q3;PBgelnUXj<0QWw*XK-0tec=o{N~DgDwG6gQCa9+j(|Z!gAe8t z$A~tx&X89~7f-G57CKP=itP_r0`vpdpThy6so*mIBliHSR|13n_I0BU5FETvuf z?ZX?UMN;9Tfx?*TTRJ(zl(0+e2pm6j?uu{?sT&m^Ki>k&Q~Ovmxw_Fk$Dfg(~-iHy56~47|!^>#{IB2H{P3XRlhgQ zNG1LM0f)eeK%I0t*R)&)IWD|Ap!VmUA}l$Hf9CB$N42v?vaCHlyni+b_2@NY8@%*T zUoxd~bC`q=8{^p=FJVUzCHWy`fqeg87}=}Ai^`!Iqr&rKx^pBsrNHx}L9ea=<*k@` z^ALvX4i6P%KX2p3KM5UEr-ej1_KdfOusB z^Y~UWy&f18Km0yFbmJ>C*jzUD>&}|iz3j28R`QB$`~+!MiePWPJhMQiVd-{LK!FSaKYAZUY8<3Bz^W)b{cpso$LvXI<98$xEjjWh{ z4RgT)R7{u2`Sb&ALdXN|M}Sq&!{rd!t1m^x(3H?SGLWf;4A_*kN-oDh_@`Ji^^Kaa zLhr{?KVM#4%=Q2rpI8=TM_zNFPQq9AEe699Y8G+IeqG42Sp^K>7p2dv>bHrk z8wtp5VnmiPp6QnpG=3j3%Kh^rl{PRNjzR`hixf>w=kcC1G4iFcH(ihU?m4^a49TUL3^r@T~@DbFiBSmC?L7ry>bVBt@@(WVHMfKo+)3AU4KXo%s$R}>@ z1>B&NHmX`2?R;&V%Fbt=LEp%*ge<>`a5XMx@d~%(hh`e>F7Dy7q=|tG6Hqs>EI-FT zB~V`j)<;YPDc3;9GZTHF>3)d)i2h{8j||1%+A7|Zlt=Fjq-^I^eT_z)qHjPMQ=i0{ z{=q|V47hYROQ_b=Xj>OvR=GoLMjl9#RZNYH7OjH+;iVQrpf~`WbsWyvQl@W>J zRA>pj$)?Jnj)?oH`)7wz({7;Bc*RaWVU4n-iV{!KDWG~9JZ!<(yxhzZby183UyqH+ z@%z8&y>=6N7N{_G$cK=ab_tOqGng`7OmO-0UzcYomOQ*%E6si9{! zJdg3C=eu4`*V<`~fkUkjaqS9OjS#UDca9@>7GNV#vut}&qrJUl9Q)rh=l6;QXemRq zsttgt&~Rr6_}GmT+RSw5>>=xXMDw{{`|k04h8wnn@!Us>cFnWi?i&T5{Qp|yB}-CZ zz+X8@n>i1x+&tYP00SbJmD4?@Ki@W@+6_m4CZI-!sa76mU$KCsXJc`je)o{aFDYKo zrKpTF*DN?&Z=7UL^Bl80LueJC=Y&8VXONnw#8Mg_IT~e>E%`!+0m;g5%jIq7Zj=>$d@U^4yfFB(ZQ+X zh3X4O|B{UkCOKfia`PNx$trNFIFwX3hLGlH_l3eVDVp@F&+if&He43geQz3>K&b_- z((FFx2Jyos;YzAd5eRwoAF|jjTVOGyydbPmzhsUM0|#_9ADtXH;T)lqbw4neFu`+h z_>BZK7#y73yV3w6CqZHqweYJ}5yH$ZNFPvp^H%Fkj{ro|}HBOCj+KN^=IwZZrG zAWosKDmQ(x;*Vn)YIg;eGn_-G;LUE%AcSldxqrWGrDa+B25C3ZxuJsyZ@0jEzr_jD zBn6D2vm!A=>OH)>#5LK~oTlbWTn^k|ky+jv_PO`GD|EY%JSLaBxZo^>a+^M9-hadE zs`S4BJw0BB+Y`>#SltG9;XOO;DJ;B=bE4bxkCpPk8K)+K$Mzr^-5LwAeuDhd22=?A z2N+0>$-4wq%q401(X6>sDk&P}Jqnrzb62s|Q-wS2`z=~d4(9nQq=h1G!o)+{ZU<2< z#nYHeOhkq-w`px`7PaIPbxBYmFmKJD6Vmhix>$U(1Aq0IxnvW9kNF{<}0}X45a_sT1F|FVOb0F zXD^rP)Mh$XUv|P*lj>tKKaYsVSCT9jKwe^v*5@&xEeWaYIP*}%FIZvvSSL@whoF6q z=1t;Eb*z79l0z5xH2y^gEBi$rW={a7syQqX79Qa^dn0#~;hM~b2`(sL4;#j0xm#CX zqh^piLKIskw3RV|Ho+sqtL6&=6t-VSb1R&D%rF+=T^q?2lho8oF^N08HW4K<&5z-W zFHxgh&&{!3q<KbG7`I??HEjXccQRgb$*Q0BU1E1J9~zK^X{nP4CM}jOu^?(pc~+w$;GsS zTjOd}{v5i-d&e2GNy8$im?pe_o`WOp>2U93LKfR#$NEaB8`dBc#DO~p%-xQ?d^TwF zn7!Snpc=n(;F8j~w{>{ErkdwBAi=|8)+eOVq=zr|++h0~7sTF^fhG=hf_~fJ45DzN zN4);-QTdg5_w)jocj;9DG}_CPB^R2Go9EXr$LV*rP&r>vvy09TKLff*g!d!Mx2K2q z!#<;0?Yw^d4&B=_lAVygH?2r49~!adevC>XuYlRXpF1ohReEI~NX_l){Rg^-7Qc1M z41t;rhP(yh2PI)`g+cFP9<+4^ygBGX5pr;3W(IMRe8~4w79v+i){~tbORixwH0@8E zm1Zq)bSF+nq~x?`N;#_#RqsGsptm9nCj1ddeE|&J%SA|m3?O65@CvIUBAO%tFHJWe zsoxvtR0z=HWa3b?e!4Rh$^GP_wnVgv@~Z#5RYgDUhsw}^{&_Mi)Z(rH_0?4Zw+a+p zE-rhtdu`^y!1A-g$nf7hWus;7x4>(AR)5;GQb?1X&;GEUG2UFGpA=%OO(m@7xhAWf znQ%HaH3cyQsLWGO+CMi^&**5DRpl*?vT1%GsC}-CQ+NO4VS}?Ava1~S=u;(u*3n!h z3+03@5k3Rs?GW$p?HzULQL(pWjDPgh(%Gr`&P7`cL@t)V-T}%#DKY`Ayf|A;INfFD znr72_qZU2uT6vxi6TKra#wu<=_{f%HDap>vxxN{ghmP$jEG+CElQV%O`}?>}E?Z z*H|8i9@@yct3}a%5TEeYeYLn2&Q&1W6Kg z&#N|rgf$i})K>qw*aR*AE&Tvi*x|kkA?t`+8Nk2CI_EGLN&X7&V!f%g$)ic;1JgZ>0( zv4gd2vH!aVIp}&L7kXeleHriO#d*~bk)2aX$RF+Ph*;XrGnqFGDN^Vt$;N+8|JZA+ zq4o%6)Hs%fe}Qz)UGcSv$lVr&9JDl;;h#rvpuT`Q&yChPb{h~_hSJP5mGa%%9pJ>J?IWF!%@&GVwfBMD{1fK`O3E*I}Dk~GspavR*OGgL?ikkYO zYXkfv6hM)GJnSL(4=QM_asnPBa)gV6KUAD*+UpK zG`W~}0A2(lKY>T;b1g6}dV2ms{(DC%UlWx$0{rSt5B}|=Bcw^5*VoUU_`;ts5qxgE ze2L@WQ~u6~ssAOuW3n{iH=cFoCN`xfuZKI|&FEqI*dW3j!49zi`)()`semqHBI2^PYpdKX)5Ya*S zmB;wO)!R4gg;isatKS#7_CmI$OcFa-djc;_p`^LJz2Cay>RI&P)IMVV6iVGmFn}c5 zH-*`2y{O9QA@+e*Di_I>*OI9b=QBA*+xtDZ=Y3N*zcSw~g~XEAu3`72!KunUAKxy{kjpgu##mQXQ4**3Cm{wm9g zdu{}CkN|J{rO?}{KRF-i2j@z4;`pJ>z!aUc zuUj7M=P=$LvS##m$nSHlL#_7qQoW_uyWE-udn1qywh_;0Y*)w%sfXgui)Z|Rx<*BD z>dI?etNp-hT+qUggH-1L82_8DZV2U7ec14b_(LiqL6fhLPnKZCVIl+ z7xF377`AtUi2v6CXYHZknkCV&+60gY$c;DKnuI3k923B9F*={mXaGhGsg#DsI@&`a z=#x##pKrmy0Ar?8OjAK8;b88^t*gK)3-&Bv6KR?ZzeyLf=&^OdA+%0R)!0{4rQ2Jp9%L!4mhE!H_Os? z&e=U`zbtZY&{Yb`nDBeK#uzjOm5nE4qt=k3n^OR6Iy{_jf$5j?VzI)E!4y=m(PVJO z)byqO(|G)Bd5t(Qur1d{*_PfOjVR`cW|>dW=y$5q8I;I|(?R5A$foqy$O*85Zx@Jy zeoqL+lYits@ydkHUed!>rHFg7r9YrHil9fPQY?{d_*|256K5c;Aok?qbK^nrA_STCB(m}@Vqu0?Xd!YqFwgzjTm&+l1 zQzT1BglCMbyD}AI+W6 zZwiMpVKxvTe||>Jh`2K%)?u-x*OYI#<%cW!x=jDsBLe)&T@W zzeNpbLUEOF>WHtnQ29#J=6NGVEZw`iMT(7pM^rx$FK8*i8K`GAj~XUMGT3kLrt_n@ zwN+JUrL4^L0Y=1u2lw*T_vz+WRaX~tamB@5iO@$tR}|!$h4$7)_=!86US%0BkHffy z_v`WMHNkhlfmD!;<>0=}k+hIwaP#U)wR&N;LtkRfPYPRcHTyk>XX{@>6*!iv8hD>eqePyHCwxZU!pR#)5=(h+kHr?4w zTPJ%c{R>T>AFlT)oiT+8oS%yMPMiDwc8f#Sg6lZ;6P|SQ3(5x-x(1^2DW>7_vs~0^ z3(b|uz~k!SFZl2=gE7^W1wWsVidD0azz!9R{+$ zmBZ9uU;Z#J5_2<+@zg2pZmcXkw0FCartu3o_{6e??tlfLm)VVMk3IR7wj*r=UMpNW9I^WfJs>f>Qx zTsUsP&Hhi7r}uN?{J4Luj-EZ0LGE$|px287CIDxRpK4aE6=mGOo9tY%Kc~mqcZpdX z7$Y&;*5>6{&_>s*k5!}8N2z9$p)E~pIc=zAq*4e@J*bgK2a_^4LGT}ExDu$rxHT}$ z5@pQ`aNp3iD;9`oSZp~Hs})MV0BaQ89waY`xgZhIN_ob??_Nmr8mC2tF6M23LWw3B@Hr5`MfKV~9>Fd^CV)I~uqm+?U!J-`*p#zf z5c=Rsal5GkSZ5v%+|TC}CstBOcePK}YTjYT~622e+Bj2~eWHOBu&R?>E|q|By*T zLl2U(=RYCNLTk?JK^}bq*cDtI7$QYa%jpUHo^BXA-=1uMYiO6Jyi3coE7J3uT>)4; zT>?1c5ifEdx>BwmBu>yP^e4R|aLg`5qrrp6GPrjqb4&}h1Dq7$IA8}2sXX9*Sy^{z zt~&^~b3M;|@=3}0v48RfAn;+0!M zt%U{rSjp1S<&P54oX63K)2Fu>!I&=PvV?{0LIK4xB5nLRI22~;2d=6#5;e^KI4Diy zAGfw@?i+QC%XyL?CHd4Rx_uIa)EWkg!&m8I3Nu+P*wVjEj_OKe82+r&;LxX=<8}Wh zLw@>*U^}Tmt0t~eh#%p?_U{LeU<7Ei8}4_y7#!_AvaY*I<)A5ZenHTfw862DIn2=QADDVvRE9rY-w%hPv>(5lxUYB+QSazR5{tAK{Q zovdcgH{D4j?U9NEB%K)Ug1WGM8;rsGd31kl>F$2IUBUuG<4C|($DZW4ReT+^mC@>r+fZ`;2J8yr7&@Q){qDwrTFvf>ff>!rP%jSfxhv)8j#} zNyRIfN4&-&>pZt%*pq3g9JgWc&#KKUWacTBlahy<9kj~>>riyqt3E={Mk!1wz~CtW z2Tja|3Ca{BgtB7~y$CSj2ReZNdeVu^Cc^Hc*1>wqso&+P`vf!UwCbwP;=24;fA~K; z@}FJq#8qEhuxK&N7_s!9``v#w!P@DgIw5 zE;Ebl^hHc1IH4Gb=Z=SJ5cb>x^|(xlER>Gdt?I*W&=APk;~NFha-2dWDW|pw?FPm8 zDC$J$D;99e#RCIX9%avueB}%yf&f+!yE#%bz3Aoh9STVhH1Sam;)G|>T zjI$C&2Pi25T zE`tjGz+_I~8sm$#%YF&YZ`W#C8T!WFH1HcpM6iPq zs}wkU5E?z+4V=JGmBxY9`oxjs(}Kk0k>UP%;nP_+pf_pF2Lmqlg{BllV8 zoAA1)9s r{DMdOe^g!KA(XrUq|qbv(#D<>H0ul>5D32TJ0OQ+x5s$3dTL>_m&!1 z{J4Y8q%?^>7h;VllR?{LQfC=h-u(U7IlCT~qvUmM_$DCLp7)*4Z=}Q z5w^Gvlr(dgDp}@Qh&H0H=1Yz2;xs$;;zTng{$RInB|LbYc%)m{xMqMS9CPRzIN}jr z#`x#_7FcL^$ZaedHO4m)%%zf1O@Y)K6%|%*oSW8a ze|!5SM&g@f4|Lb4nfpA}TBhuz#sCo5sb|ENO+NJ@<&^dpvbtXN!f+i{=uQG7CPHG8 zh9NeNdmA)d5C-7Q5<7&9hnI@bhj4t0l&uJ56VO@=n~1DYNM`~K!{N?ZqE;Nk4niWP zk%?|{*dQM(Os5-gILr)@4Cs<%W+q3VdE>ulqFmBW>}WnVkE0V$z+T$^B?#nei4fCy zygUGG3Easo$7FAOMceA@Kxu`QA1*s`ZyQat+0TnEr~Wa#j^-ezLJ=vtNG@EG zM2R5Ajh}2DqW0qhXfLzKT!Z4Y(9v=6>3Laqho~12s7mSJY_fcgSeUF{gBt9X`xj7N z{_)nFj*1X6c+V-;_SiDL8f4qWf_&2on)xP|gk4nzwo&E@+qr}xg2P7+4NP}cJdii))mbt#gxgsm5qt#%ewl!0BLJ!DOIDpq!`BAjEk$pDsiLM)W`u_d7 zKC~o2r96)lf8JmNj%_685=-ztUVsl$8*s7kz@Hnjt9Y)9jGKI!&f#@v6k$$kjufiEBd|W=fL-+8X9Bs)(OTAgp zyHcyAjBlT%K*$4;AA6mx**YqFF)IX2C($Y9gwymxg9Y=cnZqp35O=V`LIART?S5J| zwIJXF<}eS;wB>V{Iyp9_c+o!{%=0AML-3w;v&9c!v{;{S31?!PaCsFngipU$^> zj1J}kDSBD1+)`?i3+M+;Sfz;R(k6--T`cQEd6+UsZINkYD!i{Qo9~~i*_k6LweIMq zgg`gX`VM^!w_i9#HO65A1k?;h8)|{MsBC_ll;T+d*+vYQOo0ZjQXl9d`Y|QXDtnCb z?!4ki*NocCP3iB)Pf-CeVhN+^8N3}Vl2DR@`&rSA*WS|;O~e0NVpp2jSQE32M#a`Y zW19u)esLmzc*&}4_nJWv3DRL=kg5NOm#rKc)vxt>DFhZ!vRuc!}|}U?5*2Jp;2cf!a_$aE|quqE~KI3*MScL|K6eP}}6uDo}-8aB$> z%&GrD=|B=Bb#n@bUinRhjR&IT7vaK=&Z6lXCcS-r)87QeJuc-SP;D5lvbBfr1W%^) zhq*oI+xl#(?mvtcuY{D)DS{p-VhxWv9g83Z{1GVZ5zoC$LJa$y)lG-4H^Q#xqmMUm zzKh-4uDst=Xw|sJez=8FXAkYjB=KDSw0f}w8i8-@y@#&7eSJY^h%j9|@gqDX(c(Et z_DxYiO_K-r-lLFBfuT*Q4NkU+C5}#@QRm_C^&!+Wi2*jjXpOjDFE?SPKPlgARoPWT zCxzwEwdaed<7RFJfaQEQenEtD^#Z)Y14EFp7FVQ+AvS)rq}aKY+e~k=Ewk*1m0aR} zx-RT+gB=o&CmI7a4Em&R549M<(el>TRu7uZQ5G2Mrl{aW4YGy_Bz7GoP$T*(Da;*; z5r$F>?$mabSU0c}#7K5|IL^MlelmEyP)(PA^+S90Gpwe-vJ5P>{Q;g1jvrtTfEmoF zW2!Z%W+g_|pp=*c>nNP4C;2M>2=Tgy6@eTd1L&pic&c1h9aaU35juIeiR%n$G>S4G zSZ3rU$@|O2iJO({$ht|UZ|fZQ3+SQ zA9|L}%dZfQ&DTD^P6duy7`wezOOZwpqhNIzqj}sCH$shd`b2*Z)Y^<`-Y?LBsr~lo#U}W91)%*Jna% zV?#WfRy2$vA1M|DHQ*#vj5ynXbc5-@TBeW0adg$c%O>xb6>EineI>KjGD7l>LcI4y z08$uWcR%^VeCz&Sg8!O!DuEsk{H)?3l|G{$J@kxm%x1dGT5b%;Dv+ zD3>h7mK-_G(&E`)d*lED2jAM(BIO6sB<6D3Mu~AxoV3h;mPrKU zFdQz-6*!>zeUOI6_FTCTP^&}&=E}-0w!)PDoVs6}t$j^4FM9rvnHmjkS6+MfWFhvq z45{xY>pf=IHApeVE&v5xJBVARJ72cJg+3C~Tmw;9Z$Y%4A(*v!uEyn9^IPe z(<8pkv<%5Da_eF-&SAWFNNB~!bx@^b6iQVJTH_N#H8s4_f)xm)5q17=O_iuVj^qEL>a2q5>Y^lk zad(2dySo#d;10pv9fG^NyL)h#1Sfc~;O_43Fz27Dd6+5+9(bUNI`{0gdwt#Q7Kh3i zwvL?Vdj(4@;2Scnwp4>HqDK-%Nn)q*ZEoy^-^-zt=vP;*eS1!hb{b{tD&ennWPn%w z-m@%reEZ)=Eyv~P@%6}^pHFX2CmN6%0oJ5v(dG)+roBDwqC^x8gB zc%T>f)gej{EivT&JFum9+fiIE9avpJf{?_MNL-B&lNqamTX|aYppc`5Hkcu8cX%X+ ze|US=X7HS$c)vSfnKMv%#H)7q2O^()w{}edpaVdNZAu^S0*&ToVXyBB(QrYQ3_Cyz z=KOprUcmSZi%>@$N8qlj2`f~*l6t>i;TNz)4SW$YmT@4x7|M{N&zQs^I~8KuxO(w) z7l6qEZ7%9|pmI+=4V`;!7EkXv0yody=@Jh)x7yk{`ZFDMqOHlACBPzMkt2?|4`Bm|DxuX>WIn{q4+!0sN+Mu z;5RPG&tjU9Mw-@bs`m!JB2H00;w!-Kw*ZZBKk=V?tvha1)bLWk6dS|% z=$)wp((Z|*&2PFAzcMg;b1>hcDdz7n;s-WbOcHJe7)KC;BLfA z;_jf+KP`I?L|T->>KmIUEkU&+{-F&1Q^*V^x#{O^4>6B*{GVx(t`PO=>igmQh$;6f zi>Ymptbo`Bm?~_$_MIb-T`Q}HB#Ve>mHOM!!$`vh3fW{l5M`32<@g9ty;4CgQbCn> zLT0)~#TIRw#~@Lieo%kRntfZPE-*p^t1g{_Mo%gAK7bbm#w-tkK0_AqJPVvy$qybv z;H=8?=L&~~y(KDAM>46ZfZt)KLd1`7jsf?9Us_Z*jDICtWHL(=;5zsdv%Y2mC*1%x zDwvGO$TeyCQ{qw+Ys55JA28$qS^GeWPY^}`Nrj|&@m|9BF7qKAT?2#NmzNjj3&Bfa z;MK%<2)vrS2-MX{W5`m}OREoip)FeArzpWPfaT_;l%c4WGE#9SXuy%f@p=8f5vHsM<2 zu;G4T_~#W^p22H&ZcX4jo6wL4`hsgo7Th*+oBW7^bnoc|_{epQc?hh<;#vq65kXzp z9$iZe_D%g+<}velfgRN4N!+aO0s3{(e*OUr{GOxEwH*K?Ad*CJh9?Gj;3@@~vU=p8dv)2=m9`|Q~lyOL5v$W*>_bW?c;|GpYc2jbd z=D*yi;FNeOlhx7Bb&po%o#d(gTY?w?9`HBbmvyGf#*_+lNMmB`2yy<1ub{#ORtwhp z)Z1BqY*cR$Pk0y16>WMMe2OR8q8_lVnL7NHo}@R?72(NO$9+3-fX6kFRh*xs|67Mq z8)R9-Mu6-cEy1C}DX~R%RllTiPawfo z^eyZa=2GxEkAjt>i5oUT$oB;ku%*vPlB$1MBL=H*1MTwo>US&(0f%2ak>Jb!7fJ`; zz#iK!eGZ>0qVw4B4#i(&I|O_k+IfNV@_ZWI2bjBHgHb(6Lk0P7<*xoIMD2=Zn5Rh0 zO^EQ(5y18$m7o6{W*+^0^WU#qPeU+di-DN2Q z3h>)t38Y=R0w$nI_vCKyRRh>D7y>GSQecma4hA{WMz{e8{ zN+!uFd+`zV2J&>-!@T=pODG%vUhnPDNsa?#$IFg6IeBW6fJhO{K^*~L;U1zKk_kf$ zR`A!w)H5#fvY8D{&DsHwRPg{fBn`(|mpFz(U_R5Y3!k?xMO16VTJiph z8Zvff$R<*DX526x5)iz-l$s}3hU)UD!k^q(o8-eG2d(X`LXt2ceu{<#Zj1QeSY^{{ zmJFIJB8wse7X1piN(^f>rzSy|65!ydY6l;ZSkRd|jf6bYJ&{oKQ-WrmKrgR)?Z17aXJx`{)!kzIzc(iwd;a)Q4u`!6 zj!`#bSrTfvSLcvs=GeV;^6;zwuFfXH!lw3g&y}wd@xnvExJ$oH>sN!U@~yxy@JDKE ziMGr0H+DRDNEK9EfB9yR+zhN{`I6o-fESa{>PW|f zzMWMP{n@&`vBH5-Ao9~fdO-nfYXy6RWk+2nmGUbn5lZPIv2KIJU8=+i^3W6&Ys-<} zU?*dKDOWaS19`iX1cN`TRw1pH!tX`O*FEpP@$JkaPYeuqsxETK7BuvnI1uLiLxfRB zfPMt`MyaMTbY-HI3zqH>E7t8NbKZW(hee)?^z7aHt4iI>@*{`El*rby%+Sd-7*cjd zU1}jm61{-u4UW^_p?RzY=x)a|;FWFIwn`tI50cJ;H-U1D*!`nel_sg)v-udRbKxua zqkh2>Bf?woa(xNq#PF@af7!VM5Gqv+lf`btIn|0P;B^7EMZv?#sc`esmG7skV$`&_ zXx0NS1uE8X!LEF)pia zYpo;u{2s^Ho6Rk3BtS$SXF?IVr<*;2H-w`OtEB(851XMAS93|4Z0YZlq9oO=sVvRq z#l_?fJW0nVAa(#!QWy$?PNUFsCb9op!-mc0@9;UgN00X35^0B7+6R~WhEj6Rv#XWHdIWj zamxAeH0-cVx0~tl6~3cA!$_z{6J_2Va1qgbvUAY}PE+OJw5T^p;@L3>9_tZ8FD&jG zGpa5kOK2C|CA~D(Dgz6VU9@FdDX8$VQODtG8YPWX2N$+gC-j9rQssZsEkircO%_Lw zzbeMRW)*1Q6%0W}%wig0Myn@6@T})G#2MNt@9Aekz4ObM^%w`|75rMtBuFikNr;=B z&L6^8!8c2g#LfX40SWg|V^AA5+5BDyGS!c5Uf#Q3 zKH9<+nbW^@T}qdbJdJNkDMzf^122MZ`h2l3jNzNg*Mqp&c4fTT0;Ua(+w&Yn`2AqZ zH=Pz*VpqNuG~Ga{GG-(c?xg`8ACySzi%-&8g>7^ZRayN*5?(BXZT3oB-rl<(@#Ev; zFJ=Q>-6K}T^4TWR_)a3*S{A>LB%RQB1JQp5#QxWSIc#T}sA~UfvY<%}I9-xsLj)t| z2*915?>Nqa3iST@^~Cpk3pLpEF_pV0I1oU0^TZ9_4*d9Kl{A$dnBqibnlgVgWR4x7 zrv#!CF3nM;YI478K^!~lbmb#NgoZfp21jom8bD)WW}d#zb(;m}9#xv*VhriC+|Kg9 z*&gQo0vTmT>#sqg_My7Os{zsk_et;%w_pL|)Kv#}i{*%PV#VK{xrbsZH<6Qs0B(_5 znkGGZ#S93DFTQeNgR3L+7~(GEEqdO1$+ltgaH z%8Tx)DnMn6)t>a%gDY;wjZ*h!pOXzx*}UGLQYI)^JvQbz0_6Rz8{?=^)0p9S;@#_A zDUXLUT%nIAsQ-=zpX+Sq>p_R^|DuDu-*$yR$Up84J{8|idp_ttj`Kfo4gBAMcAh(S z;58>+tD5ik8|on(0(m%?+wu{SgU8e}Oo4jl>j-aoup^Bb*xprU##J}%7T!yU`W==MPstC~D0(Npj&tjz7*F zO3*Nm%v9Te!Bt(oYE+m%{jC-~M)BwoCZb5otcW3E17s6)9-I z2@AZuewI_$ApYY3YAXLxgjUme@jrSA3VcGLW0@eP-Fn+ixfkkbj@@gGs=T;PEat5 ztYNVhg>{^qA8iukRWez?62|axizv4lXvMq&9Jh$Tcn?HaB(~t0txhJ-xx1W)RSy=# zlCZShXhQ0DW>Lht)4U+#o4g}sV6$1+?W`gSK(VW z2Ae6)Aj8bp-iY{|TltzsIy77o4&;kw(S|MwV_8@JNLYp-P_27=eqCaE?}JuB#pD#& zn;Q!Vc)D=lx5V9Ga5FCREsnTtn`HJkCl>|k5_>jkuRkFz!DpZ9IS(g`6Hd%tH@Zr; z__ku^B`XEOLmNmXD~BnEJtyU?yT3JY(|sHD=ROqv7a(DO%9jsz-ojNnz#^U{38a^2RsX)}}Ea!}dY74IAore5u9M{Ka3Lrqhf>#+L z_OTJcASfLy-n9r3Wd{nbEe^0uAKw9fe?sBG9HIOed7mDNNcFI;RXb%&UcOvR31z@m zt|1D=1%7zj(MSUnAI}L*+0|D}`0RVDtCwOywY9YYS^$9D$c*RnHaj(FZJnIRo}&xB z92GZlJ{kzdux4xu8+PeDxy;R>$NXT((0&7K45Ow+1#T|CXUK&$f5YgLn`CXr{)L0x zxE3-LOSF-y{d_{itY7dzAJOkaMCPeE!ShD>fS6tjXY&VVGJOS~E-Q3FmdQE+Ab;FO zso`B#s@(=I_>MSOI`J z+~fU)69_W!7R>j|+XYU>e4iU|02LlXKH#gVT$ySbQPOa(th(j z|FXO{FQ>)#&5_!&_H!&iMi~Fsu1J{6+{UtxWlHfd#k?Mio*?V+S>>L)CSsUe$>2 z8Vw`G!&you^Tt}M8NWHE>d7OFg;)XZB95xZ=PXxDFy8EcZKn(E5Fnt`XZO>P$6=uzMV_UB5gRQn(WvxIKO8#)=y| zeNGY44+67RGebVL=6Px3A>Q(7FhkrbN3`0G$zs5SIR%~WL-!-5js_0FJwa>swc|mj z!tB#Q4v{t@7mLEg*P7!zsQNg%#Ac5pq&%aQ&k|K2+yU7(DgkPmsS(An!Fd$Y)XW_X zLq$wBYr<>fQRIvqUhhJUol5m`o!up;w>SGJzrcW!H#fIXAfb6rBJL0VHiQytaJKm_ zr|J$cyRJI)NGPXl-QC9L2@W(_5cliQRP=_}|6T_wsZRcgA8v7Pfs`=;L%JaVgbNTE z^AYYEa}C&X0aoL|!9f5cz;5qszxw3r8yv*Mo~5NqMx)wAV;Um=TV?`8?(51?|Ho+O zOgOqZ1y+p%B4~I2zHL-hG=i>y{?5$(7keT-;Mqqb67C*Krsf7tN-=;vm3lfVK76`s z0#wv=gPk@5zrfA+hqkBe%}=C{hts<2*Ufh%zsJ?hopI*wUd^6&_@3tpY`}Rrbv<*7 z{j?Q~;^gTWIcj>6>1v!~pn+Vj8a5yb{v{9}i%vqh|7Wul;zKcwnntvAqqErz*!0iD z-3CNKlcL@-@MT2cVR-~&lcjMox!O2)KOvQSg@oDiNIJx@+`VR#DQja91gb$urd-TQ zRD>u)Wq^|KAnT!~=_Crl-}%~C4G|^WdG&hSj02(zWEg!-wEZdC&IlTi}?&EtqbuOw-s?`e%Fz(@xqMq1qrhm`1nT0|wN z2vdGem^ZQKlPhG|{)o5g>E#r)qEGG{A0IbhX!|_Aw|To7czp2*`mOs-z#hwkp}Spy zM?2$GYy^=LFsU_iwF~{yyH2-bZ(Fg+g!(=9;gbXGkmw*T%kK@m&t{Qa)Q76jep=h`JKeI zDep@J;V@u=73EMxpBHBOAh*~Na3j3}J|?A0q6A6Ke-DoFMStFXqE)RLresl)zE0WP z{)pv}-}8A6j64tq!`QS~pu0Nvw`8X~{#<;j;XKT9ET+cvCiw-ncrS3}wTy+4!W<;b z9Yt2`cCqILtdB)eHh&wHW<5@NHZ5!gYC`OS^J2p%(Mi5Gz5cGH^ix{cICT>YKqa|j zn3%DQuy3<+pK%|?@z5xn`I;_*u)JrsjJUtG3B*nAYBQxQwU+xP|D1ZwI?Wm+(xzLt zhtWVaz|5?43O?IMMYl6NU#mre)M>KIPrqE=OX7@Cqn zH5kaU+pb2PD+kepBdbdJ*H{aXZmqP(cK(|Y?VtfZAc?kj_2Z*D^{Km4$PSt{UrJ>6 z)8uj@ZSPmDsp#gb9BVu;DOd!_piHGro9z7J%7tB%-wE5P!DYDL&!i|a=>$wTQ?kPh z^2yFuBRhjbNLsf@v-^mGQZ#APA;&PzC+A1X=q$E79TEOZiv`vgb|>`LL#BG&n#AT8 zArTPLh6|n5V+npY*L20?lizAEnDzP|EEH8W=tbS(7W zWj#HZ<|{$;{7PZV+qc`iI?C#6c-#o;V{9ODV0M-_<|k?hmNEgk%r9v^-=CNLIN(WH z3)9cZHdzFU6ZT2;?$#zA}O_a2rw63>8-eXroZ3=7(N;y z^)#ze59lujNRDGn(HE#1J(hl+OY@hbRvB#$nM@K46%xWx$3V;;-wn9GqQrl$gtL;h z^}HNQ^-SpQVQA;kzlP6(@Zi{=(R*##*=1rk?b`s5JEC~ECh5*{hstZ?2@({Oj)iV$ zC@O|UlOH~7OJxnx5lLE6=z#yZ0jWR2WSn&J^wT!0Ohx=TNE(lw_A6ZLkW+~MKhd7e zK_9-M3T9^?8-gua95qLE=`(cH;5mE;IS=@74TpXm9k$?9y zaVI)fBJaO?KESiaqESmc1_o!_5^ae^0h+^)PI3cR&G8E}0%CN)^MI7;mH-CUrF5hV z7=V+$dxeN)w-wK_at-BCNV)DO3mfFphO!ls=!bw5jrisMD?}vVEl`VCZHJd8fPB*> z;9Wn8kd>C3M^I2XU+aYs&Bqi&0p!-DZ^A=BWak941=ii|Pzm)!952N~pb{HyDgpLS zi81{f;SMUp!GiRL4J14q9-H5dkm;<%5XSUV3z|^PD}8|Gz*$|4bMQyOINJ#F~8)V8?&nV{C4fCi#B|539D(At}6TlCSY$qpV`40Xo1nJ1(w2= zAe$919FwhTQ0)ytjg6=xHa1XEnSHVS_BOX!Oj#)#*XP$0%Bpc%$r95mza&z#rSCn! z9hk|Z;2KbaRKQv(@J}lXn@`OmdH8m^d-K(gcJln3F{S~>lM?E!qbz*clnpHXRO#zP zStFy#p5QkLC=kk%n-k9&nnZ&Gi&)nK5DPTqKbGrB*y2lPH482h4HXE8U`0eQJofc{qv3(#0{7FC${w{gW2=C z(|gV)HHfzFzPQ7Q$j33%30GdXj+_SuA+UGiAd+!sNREN}1ruQ0m$ zIRnrl|ISGODwSGqi6sb*p&H3ZuHaoeyJ6I(odID^9je!WI#3jo^P|bm->34xT9K{j zvhtp|dBo+clQMO$s0$tEDE{x_JMXKIJjx16#7k`?3PCLh$y_wd$-5jbKY8kv~Y(21QKI?Oz(%B!@Zc3LWNEzf3EgdjO1KaNGnNJGCPkBGL$iE5`#jalyr zHcAq#=o+BQxeHSCB~FZc#V#OZPe@M5Yo}Ezy^*wiUOh4U0>Ja_2Ojt3rd1G(BPQe$ zk4xhie#GpXdxAsnpvcdSoRb#nAh{ewRCRS3LlnG#W*XVtp*NqPWn`f{QcArX(I~h) z3{tift?EXQgJNY2D?HVpQ%R_L66|c%oywlTIKcm~WXG}KA+zA3ux7_ipAJcXg;1kR z>Lr0k)CIP7-wK$vPv9lH#J{yyf^;bvROVnIf>}Vnlq2-1hg=2z0LM&IGOfa}n9tn~ z`0O=E##Z?NH%eg8gF{4p4{+}&po6uD9raOwGoa56(Y&G8R5B>PP9#H@89jq*dD8}5 zi)bcdN9^FdcFAq)1Egp6M8l6WYy%%KnDRrI0IU~=+Evwhpg$9U#Yp7Y9S7clH36WE zrdoW3kAU{?YDm}*26dEr&3Xj%`u9lw1ckalvgM5Jc8rwN(xb3&#nxRjFezc4(s_83 z@M!j_myUFdo6}R*@hcpTH-1%rHreijOpJ64gijYAP4mv!m4CEjra45ID;}-3Fd4Nu zRJv3}A;I>9euARkVf`w5drw%#}rsi(JSti5ga2ssI;Pu>ZtiaI8a z8C%u{cnkk>4!W%X!K;@Rmr=LCNG^azc8kD~$24!0V$c$&F~Rb!3bx;Q<=6TJORj=z z1O77EMDya2xlXSqOFBdDP(uYwNxOg**+40MM|Bo7KNO2XI`xkcX@PUW;g&D{P#j zlzTG+8EHc|Et%s2^cOf|-a}Nap3c!>^iN1xs6DDR^KG$jLJlLkfB=6lj;{1i+$pbytBn%NrHnU$8{f^~XRvfu5lck52GN$^QodRR z+2XLf(n9H}NCQ8{k&r1JM-Zae<`5Q$Q9&Ygv!Yvppi`YOWR6~H1cx3C*|=C6ACo{6 zrDn$Dluf9ZpZ5gXHt*Y4(KT{Sv3bL*TBq}OWrekLO><9W?e|a~TiSk8p208>r!#JB zvav!i9vU5cGX|=YecveXQ8hkx?tV;rAqfGRGw}^9D$SM}ptN5brikfr+uAn>{d{}0 zA#}tDNhzeC^9ywcfC8A%sdCdXlyI@L2Y#qC9ucyuv6X49=y#*|ZOaG+>b~`NL3m~i zbGeFB9qa)Xe`Se20#TA=B=-He*sc^{*#NENZTM~H+;Dof5M>GqH^=sERK$3eI!1GO zjDevTvQdQm4*f}_?Zvrb(T~~G2i+2*{@cy0al_p18X{bFSxNyFzAMw^o|0A5GR+7T ziCi@Z9NYDZ{U!(FY$sSh7f=$jG{+kM0K=j`JVjTBU-;_kV?Z((556-vD^PDZe!;Kv z2r<#>tS>A;WtR|T&7DW>hjs9!(s1N$Po&OQ-?gFCKew`Sjz7Cjbb(HW%x)aFo60-2 zvihw+SlLQ|(c6Q_>a^FNdSDD1?AJ%BbE zN5aX_*HYKx7yG^)z=F!cDPvq0M;C8>gt|jdFR0$IfDS}SAY7lJZBYn3%y7SOD+qSSRz=^}i1&bD(Hplyv+ z!u$-XZA z{^5PepD0Ar8-($Qu#;eS;XYgxvF+Z2S?YoZs;rWHcocP zu^w3*2Js?U9ha%_;vVJ#bmzwseFE6(Q0h|EbW}_*iE@e88Td%M>rykMBsmP!#U>eZqXY5sE8P5U|i; zkTBODx$*PxXYTH}#yz`+T-S$N02a3$kQ3!`(k zLF2c)`ucghJElQ?)PJI*RdezuS&t}=9{C*A;dbf%`0*<0rAp62n9tIJ+tjaKsI5>W z^My+bo6KOES|*)4cg&e^62+H#A~953VBEuyIhD$toSfiYZuTr1PwGSiF@pqvWz#B) zE?HB1)USVPkN$9Ao7w*v0V^75M>;F1ufC3iHd+xb0BYehl?^kFvRW<;wR%GS^@CZJlBBvjH65*7*kIshXxdXvhkFtRg@LEG81u{A?R4hQi-B_Yhq z?$qV!R1I$jG=U{!Sx5lcNHfG+a7RL0XMvUG#u$xo@(bJt&A3KXJ@tr!H71Z)4sxrJ zOaa3GLYZ83k_kGvZ>H7A-aJ>KoNm!v*D_|B{>&X*7G3(t6+KsO@_>DA^5-EC{V*RE z#`gUFQJ|lc1Nx5d@%fV)XV>Rijm+W8c}|#YOr>%f6g0%ME;o0Z$Mw!L+N`)S0wrha zXHKB~4dsaRattPpiX)IFBKRXfGz%Ulw+seKW;GV4RR7LDxy&0Ok$oI{SuMtCVvl#G zth{y*CW3?vY!Q$^W8qX83<#Ed|jyjcXxCIrp8bRTv-a@xE~-&(-_W1mdWmQ`xN_2C?E#Q6>BlZfN& z_D)2FT1WYh4Yuseo&Sv61|aB-gz$~qv`NPwmTWagnlQUQP>oRgaS==)?oW4u1FBd& zUm?&>cc3Pn6O!CAiwz51I$CkIdJEkF8MB~!i( z(TqsNa|Q+a5DmE$`%@iR12r;k#lz!VAP)pYYMZ4*-^!_t9DXnz(x&QW^_|)|p zIDarz;yauhzXh@maCv8!5mV#k?RqOWFKu>*HU;_lXWv?MnPwh^;s8^?Zd$3#Hf}&Q z!fFirLLdlpdiyG@T3QwZ?5MHm-Ya-~{E#L}H`{-xj4K&7fbGu1t~FJ`*$(XeL!_nz zmSW^^?WayTQUze3Z0&h^xJ;xV94Sz)Ha@bVMf5Y;Y*B|c)82W1eT0{6y4Xpg(xGf1 zvV7f@FIP1aVUuht&5m(f&;h*7T|_{?oXGre9h6L6-NtrVs^*FYJKz>{V(3oo|8-_v zy<51?H;rdi6rlloBlH*L~-Bb#pGc!Vq9pTPNQO z?ApjD{uT56WaMpGC|W(GWBJ-jaf#clscoqPw1u4t>U79@)3SZnW>1(Od?k${Q~O{? zkJtwPf_yT{L{-JD#2~yQzr~zjxL&9XScrAi z;ybLXOu@x}*INYEf-P*&W{Jy?KoM1k)|Zr0Vgaz<>l&{MczN1*IFu0p-WLym(h@il zELebr^Y$4tKy}dg70+CkM>9sviL8otx0h3!W7%54%983;vA}3^jssMfRNzM z!GVUc@NF)}VE=~0k55V^o2(oPJ~Tjt0V)q3+kGB%Z>Sh#g^0-@MPo?rI8_<%6}&CN zgF(v@w0R{h#bou8ZS=B(MI+hzl<5+qX0(TLI4O-3EK>;T0ZG1cT>E}K*arH{i&V;F z<0`SYcZz9&;i5@TovcJAK$kefw?USp_ixcK=xsQ=6>*RS`W-&PX4bVYLhpC8J-;=#cOj%-wy(K?)2>>RUbpLACh?t% zJXt6>I^g z*3Lqs-U=o{eW8qL#Fa}rk!3f}5C^jC8{Zr1XN9e{aCF*BOi~_a`!YQIq zwSatull#=e%rR$>p-?{YXu&Sc*ZtrppazLle%?PcFd;uW?8a_67VUVO-X_=uXm~$1<<@BXF-_CV z6lq67NK72$SH4p6BWXpcM%KYiWq7B{rj(;#N{E1ii#_iiJo~B&X-9t1A~|Z z9=%P$p7{-drFB5}`F;NSQHg=E=o!KZA&sJm6CHjSJ);lrwb{)vjdZW}a&V3wnhR7>6m%~TgSw)C=djqh*g zE2_-3^$n5w>7W+49gp#9d8Ffz$c*$?K+%JEr@mn<$HffRB^~t_S?zS!h;br7mYA)c z_kuaZLu;KGuMcu+l`?;?cB0O&O0cy3D&BNZ+u~{JCLeO^H43GrRdpVDlC&q`$o0eV zA8j-D)(bk%sfFU~1kz3BODRu#C~QNJ$+p~pT;s+t=F270?HsOE#A^4iJ4!-in2afl zF?hQSLNv+ZhDt&YqO7UCgu~DSiAuOehT-k$KY0V&0lnPjYLrSkBl`j=y|V*20We*% z83l>1&W`=R;)TC05Z>ZzKS2@}S46IN!oVI}dH-)m0J!O6y(gu|d>WgJq~=%k1%-LHw5;9s!*+F;02!jOJzAyB{98jwH=Md*HIzJd~gYZgAUbO?s;=#`x13 z&`F?EbN4j85c-_Ez*W7dy?VU~_kb2rB$o{t@+qgU&5Ygd^{AoFrBjr2UU{PeKnUz>>!0)X-#XcRuZ^UuEgwDR*EOB zCxvs-)vYx3JKMed_)WM&F*G_F>9y7(Ge_L+FpdDk^T~Mu@U)SNY zz*hE+kQuRG<@LIJSc>4Enz7%65k9DHVWs6vWQC-*44PVOiUl*_Zf6HKsu5E6+q)rn zh!mF~V@p1V@-T^&-ZMa&2#AJ>=a3+7gAj+wTiy`fITz=cCC?dLNr)h&a74XfhuWty z{&)xaiVY9{zlDCO2Pg^%10onTU*$XdOW_q_vX2>u5s<#lyh5A+gK=U9aIy$dI0 ztn~#U28sAqkH8Dq(`1d_0;JzpX0+srqW@z7#-0B}DxLh!MYf(>Ixo4>t<@N5l-r+i z*zl>E@X${60PHJ%x7nKk_`R!j>^O)@i!BQ8o1(Bkv1NNs=XkIG8O7EK`qCHgSrPtkO8YQ>~)B z+yR_y$%l}!GnEpZgnuke)OOArvK=c`GHWA4_=w$~*%X9)EsmLgfk?=Lm!@pIGq+z` zOV=>?yUL%1mOzalvS47a^4%ye52bQ!!~?_}4*~JE)!9gPklC7&&c?B8J>ck#60a|qFfNp8(h8*DE3}8GjM+ZV7_$kBWyux~s{6f;3_QWR47*!EXwJvQ zaW(6X%lmA+KUkY%s|i2#oB(l*laIe{+{}Fd57@ST-6pvC*RBs99xVo}ZYPX=G%Nxk6r7hFM8JD6cgRBmT?JXSWNQuGd;l zKqIkZ{|2cg04)Jk>$V297s&I>{ss0X2Yh;7NW<%zXKO!RT^-hC2IORD)W~@<&#Buj zre1RN=yl_>(BHRnZ56AhQN*29L_>e}_}vVAmVQ!)*PgKFdKI@k@jL4GM(OOST|!viB0)}KgS5X) zB?-uK(m2loX}uN-mM?zTWP;vwFUd`&Dg_8<+I&0UuF1Ih`~)%?J3Ri(|88sam|NTt zuvpNc#HcsNg2v=vPEn^62lq#Q;#~!y1!DL)bm)>Hn@lJ}s$}qc)WZGa;SrSVT!=;E z`f&o|+)1=l#qxP>z+u?u$}`b%eCT7 z;vY9$?Yn|>KF^@?$WPUZhz|N4W<~?JjKb*sWXt>xQqnChW;`kr7A zCSoB*kQgHgHMN9voAEsQpOb(_trmJmUtx3k%mj(MFy+J$o!BHWU`R5?7;ZjOId=;K z^}1vLn)aaV8W5jq%ZdJ4H{SZMxtflLr^U1AS4xLin03FjxdKH)R2RGqZuRr%9YtcH zo#&tl!~2}tW%{UTl)zM+@scCYoPMY{HkiB#Wnc>&b+xCWg2MG(GssSGj}z$0V8KK3 zpCP}>uoE1uT0KAMA{++(eKqJ~8JbJvEW$Tl=5_tMQakuAn5q6Tqkl6gm>iEryn_!j z5M7V6UwV$zN5VdjisL^n^h4uONRGpYH+_J8m-j7E_B?tE3JHUGRpZyT#d%|H8FX3} z0T0=q5X&lT6ZU0g$V$C^IKiSlC@+6NN~i_1$GsjW!of1DJ&}WOqFh{&UHaG!`3cVG zQ*e9;f?iCiW`)TJAjZ*Dj#Y*Wo*E<4{vC(_=pnzJI>`?o|C~Px<*G>fD$Q_Lvb}+Q zGE{n`8v5q+wvCtolPsYRc!g}PhedE8NsDNv2MG|T?~<$))p$GsJ>yoTIv5-XF4(%h zzNV?T{gFbew3m^e17z6!=MOM%Qtv7E|9q?~>3|heE0yc-e%e7$lASc|TDIl5LPskl1=%rsjl2?_ZVo zUWuky#}oiPY(=(lj%P4N6NUQxngf@#dHMLtN3rb5%W=8AZeNam%Q0?fJ1gDbm_U29 z5$v9ruLBJ`5H={9fQ1?f75;@F3ssALJgjuYI51gt2$?I*G+vegRk5(uGzs*RrEE*I z3k;Z6?d$hm$y^c_kzmBt)qgUA?ZODA0-a8Id1=6jE0s3_oI=s{t^O|AU1H0){)gAs z%Hd)RH#kieO_^SSGh87EbFk>s@o|@li@iQVi???+6bwT+Yn$uFzjf$#^FtHHc6}h; zUHHG~3wx#&yEkqpp^Q>qRLpE!9JnzpM$Uwib`oU>d(^N`HeGS$$@sBl8#OH(cIbOU zdkpY24}sLfULPHt{MZJcmvR5O#=pCV0|`&PR2h>8^~x|@m}wZe!DLM7hlbUar+9&> zZ-tE79=dVEdd8`p)L>e<<)KR~SJhWs{Ed;x^6XT-cEN#odd-mciZ&u#CL;uP zy}<0Qk8<(J(3|zvqs_AyT-V998EvtqW=0Ci+T6;{z?(lH;_?>HwNqB-4GS)W`3{j% zI-`jskR0wyx$P2gC%z$nNv}iLB3n`@pr)(Jvsny&E1yRF>J%)5IPS`O&ojbhALkYW1|Vp<#z2 z{yjE&blJ2VlKhAZP=T4Yh-K(`aI6+ICC3ljGJL&sW9;w{$m_*fww~O_2DdHEn$i|V zGvo)9Mf0QqQ*ad&6h*wnr9FGW*BVCJ!v+)mZO8O9Rba1GsRnX{T*%GI0Y1$}e7RAZ z?G{M9ha8K}5yOv)59F!lqNs0lpFAdr7xwn`x&l`E%eGwb(&&f|D5063o*$z^#cCLq zIK6I^X#{U?ZtG73Y3iOS4kK~6=lTrclJd>=2MkO^rLN?35pG}Nmjl$RyD zA6e8#GWIdb1w_yh{YRD=%dKi8*|CPCue9CVE3*l_V|-$@v*5W3&aNL78rz)g0P;I1 znNZnUwnn!pTS zl#9H1E1-&6!9X9Y{rOV&d6HR@7%vL(cJXKc-XfOt2QR+lvVt{FLD|dGRe5j3W%+-Y zI?J#syQo`lHr?GwcSuS}cS(v8(jYC3lypdUcSuWzbT>$cAl)V1b=Lb`*LTkO3qRPv z^Q^h%oMYTWmy-ys`cuW(zvZ{zp{)IVeW}s#@K)21JcO~+&@~FDaEat30O%CE=+Us- zmB3WLO{0rRmy~A-hMoOf!6f#>JQLwV!8L}MKAx6maNXADJ+K8;FvX4){3&N1r~kzd<$cZ^BEyFB z+n_prLKwA+&?`Ur5#5EIpJ63vo!b_6N%!MgI6{033&ZMR_Au1WymDS+cFwzFR!~*Q zrse*jsHi9{zxWxi-<+asRtH92#}w;gt($J;rIlexfG&(0nBIhhge*SU4wPJZL|$At z9TV>-D*X`+sT^e*r4v$NU|d?s08$25v za}3g8q;Hc$)Vx&$hhqo;<2M(O`NJ+a8aJ}XwQ-iTWGNoGukwVB8yfnG(`kB9{CdUZDTlId(Brq2@1T(PHNm&XiG*~^n4@vOgKq7LEA2Wd~Pskhd zk7GteB|7;S_Sqrqjd(57RM=k?FDhg~1&7Hh*(P``-|sbyRjU+LI&1(r7UiqPm8GFS$tq1P3fOWWL6h*eug{yp z^Tam3#Sg+!AN-08Rc{opL18A?9qLNr#~(Q<-LRhpP;%FZ5NkP{R8p(#;5vSVsrJ)f}&=$b6W3 z`+Dvt`-i@NR1?O-MEP6}ylkdFWYhwur!^8Au^Epy9q1+Tj;J*W6fgI8kwmuGFS9YGzfb1l`^ z3Ir}>0~`>E7ZO$|vQ?uKN@~jEUo||i2{vh20XRWe-qUxAzFgx~+H6=MoqhkK1_cfU zFna0Ow5%5|;_ExQL^GNRK$nD(njGx$EmY(3<L^ClJT8`WG*&u?1ooxbR%iwrs(M z+ve__M6hH%EOvFjWF5>QiE89~Waqlp zoFwRKNzxb3Kev2%%PiCG7u5-VgH6L2jjaHKD2+k-nVpDemp#7>UY|ZTlr_05|E5!> zeJrIQa7yRDC@!!90t+mlZ?H{E4Y3&L?qUz|EdLpa{RTEW`VE67CLE~&An2EEUxT-k zWYzo0e5M{)aID#&;rPXJ8$>1MOATf@?>p;+jV%f1_MHvCJ&lO?de@bk{fWW7h0776 zxZs(9bi?H#lQfFEKo)VakQPo{PkV(x;2wMhVAeg8hxC?mEFE)_L|+ocxS)$^YXx*c z+VoWj|6(Q3wWJ86wtaQa=neQ))QMY3e60Yqk$!a7pB^JXi6=6wU16*arer#)Y_3QU zA90&p*%@0*%hA%C_4o&77S7B{t(^leAcybzAiudn*iGl2JgL1x9rnN3U^@YJ{gxY7 z_shM(3t|JQ8uL4P+%sczNgF=Wqiav+2ff6PwW}G*eRg-N&&SdBzjNmgLGm40KSX+H z`yGGH%f=N%w$dtpUdix}Cr9$FXaFo5GluD}LD6s=WdcV2&8ND|fHLOy#hUKw)4EGA z+8+$t{^XXY-3(fX?4}8f>0ri*cm@w+#`1jqBX)vX=ID7Jlb*klRW6%l@NxFp>3i>E z)#?zWqqIurHIOIZf1>3Ka78~_9y~BRq8AV8rEJy7(Qo&Kfh`rBOCv3Sdzxw7`_WLaT!YoV;KrLM%7&C9Q|M17*n$FrW61^&Ob3?!t5 z+{~ZMbbJqj3&8OMNaK(iMtgp;sI;+OZt}9yZhM|7iCACcu8J;0`>hg5`y5uq+~s-Y z(X?-zW8Gor>LQHC=4aA6!eTO?3;XE918QQ>k283tH56%?OYRdOs!8HWW@$5j3NG&W ze8|sE!o%-#MH&I@hCCD+z&l+^>@OllWj@=`*A@^ zHU*0^?iJ=QM?7K!-X1W|W7@e8P*xdt;1cZ{8Y14g&=~#fq*SP($HPN}21XhH$?V|B z)#K&uzwgX!_*Hg+Jpb(d4=HB7E_PHPp@bLv2~$l1A+x%?{|5L@eZQ25HP{S?aPX;0}`YJOm8?DU;;YhNIl>9i;+YO%j0UzqKiqV3T{Fx z*>=~&zrxV0wt-k0EZ4)$P2qDPkT}5}Teu(VwJcBs8{NQ1@JGtjI_A%?JWo;kZ$;I9 z6Qj5I(td!R$u|1ySKj=g5lHqtJA>)T9c=tDxbJ?K-*b1DdXG~7NBMG(8ka9hn#2*L z-so2btlO`N!yh)9?m!}j^%tia!QHB@h#?-iqM`y1%cAz<9=nvKnrAh%s4F85FcH`g zhP<}13YRCIN$B^%C#zU#>+|lImWU9L{w*7?QCg}lPicZYj!oLsKT@yFFH=ZpB8vsL zV8gdYuZ_Wa+ea02yTnWCn3*ihJEa@GOSmgni*}gli%o6xwKxolfS{SW8MFPXy{#wu zq{4pC?`#Y2BAz=XMx@+^w;;7xXl*9~mtz|8dl<^krQ~Mt0DBj{x#(+0u6h*-knH`K zF}}R~^on65u6vx4y^FzS3i55Offr*bLO=S+kn12Bh;K=+^SCbFC2|n6ckS`Bxq%;yvQTBoodA*B1=$mZJ}oJO_rL?Rnt#= zT&VEN81fA|$E6$Zi|N&>`Ff#p0&%%=A} z_OvlvNUX0x`tpY#!=@rou2BK41v)lfo+&*=&{$U3r0Zv1DEU{ z-*{ru;Mgq8*P7HO79!aXCPp0TW4+eyg3?9tV4{K?KSU%gjxYuR%EQ{J*I@rur2-K{t3n)q{v_1-GK!?)~ShehNe1$|t`7g+_^Ffc3! zh`-J-C9it@d}hT_<(^|c5^;0H}0`vaFc8HCmYZ@3*@) zm&G6CtDhNsxMQgDEO#AfCIxf&O2)aV`)+Q6>$^AV#wJjIzY+MElqPwtAn;r$;*R!97*k$Q^HvMaY-(pqP>N_fR|lHkcHC;)7c z?{<^oB@j5HR?l`G_&_Ej#p%_d-RbdHyZ=a`YfF5q>xc6On<@t1f^JUiK>SK0c_7}l zoM#g@BEgZ9o65Pc;?Gy55*+U|M879J1c;^=mb``|iIiC^tE+r@@{R^va)0l1Qw4o} zedg1_Tq;NhUa9&lrjvfh>P5teSmH_^61xkb`4r70x-4PO!ZwAaMJ28D8*d2B zaA#Le(MbA#Uxk$~g;+Gn+Naz&Cz-7j$~dx!%lE%-r*Bi!M$E{}T;Jc9Keh#j*`=3i zeHTebrbfy@C{w*HsvJ}?4h|&Kn_b(o?#*8^dwKnjK5_@7Hr&jA)DjZ5SeH7X<8rk~ z&?N|BZzc(N>{*9cN6@?ZW20#SeWx8Q0gEr(?U$l5b=MlSHBxo1Mt*TK6BUU6Q6)$a zvHt0g#p()B8K9lmOxDp{crXr|RwroBkf_~TEawyCv{H;f=C7h8LqiyjF~;tO^!R?5 ze}m>*THz%&T(umA#wu_8j_7Y;+UL}?%>P8nUrFC5@|^UnPmBcaRYDVQ)bqMSr%bsf z4f}nScc7~*$#2iRKsJeUi(dIhYc>qb6^iZseQXD^_3e?>oKgkgF*dOO_U&hA570h} zJdAqc{#YUX9Nl9So;OI9{+MQll0al&&@nJJ#+Ju8^LZ~`#T#|k3ed-l?8Fvux!e(? zrdHv)3bAkW3);mXYjoG9!Muu+&fEn*{*rTu=k&>T%zq44FN!zhCkG=P0FN~WzJDQd zBOziV9ugBFauX1FY$`HfI1%y&<~*;{JG(~!W}$Fepn197yodIgWsZsL&kr@)zK=xG zdpChUj|>xjc+lov-Mm{DmS5L`Xaa4~(6Kxdh4(fc&H$^coq;4`Sz?= zfsX^+cTKOONWgyqVVkEB#xIiq(^Qrtb(%dI)^EskgP6y2aN`FNP@w_gC}Oe}zI5)i zQmjRv+;o7Qa?9Wauyqmu8B4KniWjh~H&@L1B+QXQcz98`MKua#vqmm7u7_^K{-AG8 zdUp(f?LD;5^t0pC@MdQ&4xeM3fKnN}e|&df3|k)HCwQwBPSuHMlwxJLx%npWj)=z@&x=#rG>6qLUzuqQNwZrTB)7f zi_W4e!!%riT+YZ{Q_U{I?nw3;DM5>~->pL?Hj~C#IHOPquA6{Bn+oz`$>9z=WQyKf zVJ4wbv(YR2yAm3 z`39r7CNZ9LP!E-?+U(wCFcF6A?d>d!*Imo%dfx@eXZ8*SH4o$_!X%WUn5n^F+@6QC zpDnFE6O3nz4wQY&UITj4zM^dJFj{QLxcfxom+CWj)kuN%9a4@IrB7~V0XJds6z3h* zZE27(r-l?!+fH2=v*{}TB{6QlkGnrfBk<*)&K_#-%@W!cy~bZ@!|-cK)(2@6M$;sY z`FQW9O8lPLb8Y4q5Wqg!IL5HApEDZS)-f9%wQPOyCs@)7u5P;NILcW~h7k-AG@YAl z4lc)r+S>GLhT5%Tu1K_CZIEAdP+1Djf%d0-s{33$zgZ5mO^Mb!v78{o7iJaAH8 z!pDFxeT&$H3+YjIGS?g+bIR<*Bot=Dm?-q}3Ml~y7fk+IbYd#Zm9yg`KMq4W#FV8twm;}O~(hBZh;Cy~JM z3-IrpCMmu4uN9ixoCIomI0%m&uFZCn{4|~#5jZ~%4HIk(uT_N*K$^WMQC{$+Q2ZYy z);B^HI6C3fVCjW%cFAZOF=9R*<8+2c=FcJZZ-{da0ZeB2+;qyl##o;IQaqoI51ymd z4ueiUow+Zy-E&qdYgfybmyrd=G1K8#-~e0f zAfxBM=QEkz;J{@cGQLNs%T?x*F|AYgjY9sL{$5N?IrCA2u8`1*CyqiWu$#)X%|30K0Y6Wi8?)%c?QL;&yf0&-TKNdL04b}eoLyeRS^s?PYP*CKm(iyc zXO`NJWKB0OXT$ES&1UvMTO_R(xNiR)&_y7T2B$#8;velmcK1XXbWK90>d3CBhW8); z3P^y!x1c|~j$A$29Zqset;**mh)iC(#VLmH&fmVJ>rj0so|7{20xABXoeq)h#;!&q z*YL0;lm^FW-W&2+{3FeU`KPpu?g7M@%bra;kqB&+sq~u@)ucpvx2Ycjsl;dqAey2d z;l716SWw@i$8=C4KUX${airhk(-ZVifiNTnU!EQTk{DfeYo>-G=KwCK93+u&gN%V} zHA^G!1j#VyV(v;zx4SfyP2^X1J?UB4{kyf!1n@l^d|tuAZ%= z#Fjqe@+<1&)hlUiK|M>jJPw(?_zwE}<{6n*#;pZ50#s1cG2OnpL>Bd-jBMk4{P^*9 z#NavaJd!`kOFg$B9z-%?u#7U9OdMWoqNpcyz{#(NSLQLQdh+tBK0w=JC5~KmXI$1J zhjI-C5aCTFf$Bhr-4HDSTSK!ZbK1=nGaTvudh|0lq|>TiLM=h|+?MypCq^-LrbWpr zMtY=vV?T7II9i}Dy@+)C@Aq|=k+i+Q z6kn-m+JIH~z*Smjfn4Zxbt!1Xf=5C-iFpj5hZ4TlYHvP1N;K;8K6@#r7Cw3Rd@;=z zbLT{qGB-D0%)zoL$OuwG$EeL?R38#1O#}mUFg^h<#g(P84TGc)SL&lx%;obl0pI+` z4vTXlMR!&=3~ino?9H1}g)J-Xxr|N5Fg!7{E~WsYAx&V@>Hp4d>B)qQXiP0kVwF31 z`|HzdFgEYAwr!NflGE2=|2PT|^kB{V&1NUr5KWQ%dbVH-SUKjysem5lrbe06uDQWN z4`?iUK2p11kax$om(xe)5?O6Ip_84xZ{%+lu9JNTc9_!qavXBReZ6Gv+;_EAvb30U z8mo&Bp&;CNbBM@+ESHr9h_0Pmgs*H1p3qO;K*-(x9(dB`6j0VgtH7x+*5}hr8dvi- zf8GQG)ezYTDyWC4wj-8tgxW+<7;()O2$uUjK3>;ks!ydgLPq6cSU!*}MgUU`N*qW; zlTs^gw}g@_WNcb1D76mEl*xOvWqG^ymu@@mJH6*#qnx;Te)0@7DsF!;eZiKaE2Dp> zk&%&M^=e?VpX57vxmTqN8@boW53~Xp7*uw4_Gm5P{_oImeJ7y~(|t!R*_s}!`u{xG zfaAg>LRmjx!z-zc(sQ~QE&BZD>Y))R%7y-}tY7bt{N~<3TATP?#^$qoSWU3gl*>mc zt`D<^qcy&=E!3elHdn2lb-5#y47YU= z5s~4m!zbcC4+e?K)f;Bw5W9{i3>B4Vk9Yq)7Jy{6pCw&t8i$Bq}`(PfVG=QFh@MWJW4cOC7nJ| zS*>xys5&O;B3 ziVAA$w;KY{r%PONimZu!S|U$UR1CyDyN*x8ViGg?Tob69at6_`D2o|bm-*Y|$fRU= zSS*0n-2)tsZtsM0gq_#hq%`3-Wm_;>T3a9g%-w7ZddIXqgCtUbJmm?Vkcg-*n?F2M z9b4>2iDV81bBsuH%~{rJn%9*2%OI$aG$T{5cq;rG!Hd!Z*N*Aj4QK|eV8J=!0D!b` zgv=lX{-+KQ>%6Y>)cyH^@j5NMQgOVDSXdG8bxrB!So#C)=H*HMpgN&)bHQNr3~b*b z0Gb2v?v-ZZ8mXIrb7)OD7#Q3LCXUtMP4Awnt#_ix2+s}=Kq%jou z*N(7aU6>uhp2qL>d{;WGo1TruW|)gv>K;a)u+- z7zotwG$Bj=G4^qC%0CH3^CaNzC%UqtJ~RXI4FKFN5l8EGcW!prei!XD48r>UeOWz} zV61U~>{W$V=X}F(9B(%g{~XZ;X4w2uk5j)Y`oDQRs}U#;F^SvkP*p3G)RznnTq>9sKhPy7Tzu zxn#Qk)}vOX#yrD0`|pET$n4*19*6vn)j`7UU7tw4VZ0#NgtbO7iRecu^(e;T=(kwz zUq?LDta*s6Cc;2$7Q*!Hw}zxKApPQ0{tn&ILG%LJt4dnPD;{-!tt2{trQ}VI#K9k1`@4ZIS3x@xBk~VU4N#!_8`=@Sf!VuQTzD~nSK>!}dwE8f-dDPSJ@MqddSo4C zflEa$7T8VbTd0T!Z2>T7ITOcoL^mJc{{B1U)S$%*um@-0hHw@0;7<0S3k2%m0ovSo z!k>~n(6&i5=M#9ZSuzh#$k~8z^k|GLl0L>0-53ovqBa%r0iVA5+3l4quDOiCFc5|} z9QPJ?YmB$?2VcF&B%*c^v@>uCBRAkA>^51ktZ5lwKQ7;GbB{Wx;UTAg?HK6l;DfRr zEftF}jo@S!_5%=wxgtHDdVvWb4glOb!@%~)X(qNI z)x+vDYQJRW4pj4%^iZu)$TG__nt3k5PJ5JY*@uBwks(PG$k{_&Ii<%o6yRL?^Y?=f(7Z z40q^MJgL96$L17~yvE(QAfvZNnFf)UlwtTX2b=N!8~^V1l_v80H>Hb~6lx#vOBZv? zU!B)zNT6$yB9I+l!@K0OHIl^|}TZn=lCD&o7@-ALA{12?JU5$v*)2=R@`L!H1D|U+bneZtHw9p3^fO$ z&;!x(V~V+ZwBv2pUxj+omsj@9cu{RAY$Yig3+bm$anFlz>Ws%EGP`Dl{{l-yP_S}xYFUQBMz>vQNU`c zi0OUwcqgz&8|656U5)CGCHi;@`=RUyd98OxNVKSTP`S&i*pi{n-Glz{nUu~E*}&ZW z!89&(++bhUXohIN`tAv2C`*=T77Sj{7_YW+x!W=4Bsb?QXy%IGF&^;5@r>I37&mE| z_zbEh&{+*`xwidTyT2#VPV&qVnha%xEQ?qgu9b`P?f;hu)|FeFi6>+shL4!T41~(a zyMEXn!ZK>bM-Ws)!AuLkVYZ-zx2F%S&pjNyfDh-d@LK@vEZ~W6J<&>M}kh*9~T zF-+i-IjjFrOD5Q;DI6|}h#aqDhvTog?IZjte)3i!j$AsH(MEt@u=7r?dyi?M!7j;u8zfHh&vfhGEf7qaqNClxkGjle2m@dy(q zIt~uWn23}*?Csv={r9)8IxGf8(w>CJ%;0dUeqjvc$GH5o`MQlw!mHGsWcX!kEuaS? za*z$1iQer#vsV{AU|{mPZoJINHkieSfO0w$!kn5Akq`HLyIXixW@z|$S|g#Y$tA>% zF(=?0PZZsFa%T5(@)B@m=#|xw>&pQaIb+gie3Y z1n7PpAC~tsi4%V4a$i-4E}i$|X`w@h{Mx)JfaorVga++J^m?W2T@=j-j?fNsx1=mH zqd%Nn4C{yR{p8G!iI-*r*DTkEr3&VnVk!;D;ON9~{c%sd(=v``2Gei8=@0k-$fjF(~W@n!r&V5{p4pZZ@3)k5|F}Vd#L2a^i3@N@Zn^2>5GqxL)5nMKi{ZN zPbj*t-B;-_lD~C528zTx8p91(nl~jsM)6sBW9U`%2rJwX?nwOQgX0Yl6GXnfcOc6z z*6~e(u=sfze4!uVnti6JT|~qXKvRd%WZ$`}Qpladnnc&I){}nkeDjUrt>CZ9T2@Iz z=&}#oEBEL}{s2m$8+fM-#;^%R&oqjlTr`P|UBcCge^gNVR#`a1{o3Ivd7)pov|-fF zt=(Rl2}BqITMbjS*l-cY%+4)L4e75u^oAnaU(RH~pNfzj<=53J@RbJfe=$dYuNm2A z90aNl$O(fcC)=G(tB3;78`*evM=y{SoIc&GZmRg)<5pAz!gY=Rweo2YX=XDWzR~8f z-SQcJEYPzPz$Fnbc1}T#kP9UKxRxi#d)&c&@=hRY-z%el-7CT)!y2p&^X7OKP_tA%jktnau1(n@*5cm%ESw-eQJ)4OZ%SHurz3r ze^*wl5J`|ffB;Y@e4MUFBimkA$ST>+4At0+_y1I(0?Aw1~K5 zhD6_Mn(A^*(k)oRM6?|+V-~e0mBSDt@(9}G7hP1Ax^B=hEMg)^+H=uB%zkBNW-^6` zubR*LG<~u{71eG1MLuI|l_pc@#5H)i@XiK34|}&0AES->B6oe{e71Dmf7nXSflSiL#fMG!X8D_>p%z`W~<+BKH^DNobZ7Q;nlo>2^X;uNX7u* z8lf-ZAN)T-@GN*`v?@+k+NOJvIKb^ddhwl+QN3P@Ca-l6de6|L5s|nK{Hp*In>UKS&+a%R8QvGPm1 zmKslhcf!HL)xR#;>g`XZuH-?jhJfZSTj@$oi&iZ&9#;cW@agb`!~dB6er>5-Y{Gp8Dt)L?aLNy zTI+-~)8={e-X{W{$|M58aXd?S+Vd{@HsPxs``P2X!Gt{Rcb(VC!}q40=wigrzKV4L zSo9ps6k?se5u6C#amDjoQUeW(8Q$kECo96}x2BW|h2FjFIzuNUdX>DX;e8A;$o`Do zR<((T+%Ps+lt?sMusjV2w<+>2Q_HXTxoGs$zIE&(@(+r{ME;#eYV|p>4 zE<$zYhyrE8*t{JjJlU-;MLWJeKisZ{v34tbQZ!|>n2sJxyF9NOf*`?Vi?Ij+n-t- z!n9m=340IM+D7MDGJm*!yQLNXclq6-eR##Jb*iHVbl9*9u#NX2}5rXwmt8+P2;rq2E>Pt>` zlO-!c06Dp+cSLwNYOB{3iqGAM!6|6TUe-IF4?9jT*gMw7()rxJJtLf~whgr0oSa@S zzx~wK)(sk@u$ly;PZcyOVx43z(~yR%NZYd*kMyWJ`IibMRW1(QwHciq-rxE?EUpq^ zx+rmiUezUfLhnB^mXT=6cgqGe$NqI{)210gJ#M~ekxhtMUwN6#m;EZH-rwj8B75}T zwvZm^h)8bLPtLmp-FZa;HQnR+$T*m*1eI&B!J0}(Fxqjd{^Cj7al-oB#LP()TQqFZpsI^ z2OhUZdN>&JTH%+LpQ3pG;SvZj)_32|Ca+WT0@pN8^5!GVz1lt2BJ6NzRZhR~5H(sT z^;A&e0UGiFH}0Sr8UWjXRfWs4yt+wjyhu>HpCR{lR~^eQ%aBHZ#s;F3u`Ykg&i(z8 z9fi^T+j}FT=Za53(b1Iq0|Q|7#;G-G4i-m#KVcaLKg-8OHKf!Yd(`Vt?bCkGzg2EQ z)YX)OVHisvVq+QLQTD=M0wcE-%K_?zo)1dxgaJfTOMXfHDkjp$!pa6^ha^BnBOUOR zRMBHpnda<#{d~w>yzeZiqir4omBZ=mQAS9DBX2?|LDK>n`G#s7Ez=*_N-zl2YDC6| zfuT=u0TIkK2t-vlS{wIMVi#AY#SuhrDnudheRoZ7Go$K;XWn=`0cQi68eV>SA^$Ha zxR|i}i{1ay&@Y>T#oavnTUeKB@JFx@0}~;bIUbg`1II@NOt+cVJ;35s5 zx54lF(EQHV6iY0(i#Ju=h{!58#IS}F!Q4FW=U1Q)8p1w?|Dym!v8_XC)nc{x@F-P6 zLlB&aN0m(78&bFei*1kH@+bCh!$$-s6;=-&o&T!^c&+(1+B2~s>?T&nOypvSU5Int zw2VbOsz)5fM31j6!;glz81BPRV4kq4x?C#qhdpF5`)q`$JGpe)hy|2~Wn~1)6f9}I zd@H0F1y3?@j;hzNM$T{+T`U#YT@4MkQOIE~p)w;_X!##@Cy9)Bf+?qa-F!cI`lJjh zQZco{LVy50Sp2R_GBxkn)4h`Ih`?NS`AsN+CHjHIhcCl+IIRSc^~ZKni^an+WR#A+nx)}Lm5(4(O6Ql)?K2|SeEf|) zzuiffsd_?PABzm@9c%pa`J%lL~*hGJ|Bo$0J9s&U>j zF)9^$EnkunsG6Q?{&67biH{3H$YjJ+te0~b`M!rf1bIdv7m7m;!+g)Viv$qs#;Xw` z9qeotg=Ji8IKQNP#sisIisARJ;a?blcJpU#3HDT7(GY=O{mscL6QlHpI=qsNw~}+s z%N2{?VIxDgA#??`0DVPUU^~nv{@^tld#32(EHH?Rf)SUXp zMlK=-#g!)AMAEs3d6tNQQx#J?4hA@6KQKR4&VQvvK>A$$oe0j4ei)LFDY=FTiHeR^ zO~Q|(4OUuNvGB_h!`2Ql({8?1dZeBYgl}LBvv+k32Gi}OC0%&r4K0M%HGQ#SbmJs0 zHN3#C9>4G}#s*AtBzifQoq;Py&gED{8! zq_nxK(dP*R04B*ubn)n3zkYo>-{Bo%0MHgEm8$?OMuh|`?d2Z9`%Uh`Rr?qbsL z!iK3G{gKtfLUGLxjHNi5n)$5E37SE9<*IWtVartGOMb!>`ZOIM=iiVEx%mR9;inU} z3sxgU*VsZmb6M#7caeF64*aHoQ4N9wJ8xEfqD5csQ~>)A9)L1qTk=qsst@0ePVmkX zV<5Uc-r@om%ij(k3N^fa4!Re?rr$M%T+;2O)~!A-hTFVpi?=PPZ_9a7eXn4iN}K$&zv==Rzj9S$3YvCAKxg{w_I z!O+j5Wx4bSVbeg=Add$>b=UL{f*;xjOBhsER@RUY-5}l#PFz1bQiW|zxhUVA@S8SK zFp52pHui-t!~%~2(Bsc|zt{XB`c_!DjV4jzlWCiNSsl$q;%a=^=^6HaP1qQ){}B?} z0rUC_U0|$L;{-MrOyW>%J=f5}=ZaYoF_vC5EN%4q4}s&Umq7gjqKbpf8kd+fV%8YS z*vfU{Bk@~+fWBAE_ej&=ZD}d96gju=s0I|deI?QVt29-!Y{8RTyJ#t%v^)LAt zKUgU`qc2PNG|784%bBw(9p_~vl4z=*a8h4!mGkP(0E-t3+4)~hHC_7|y%;!gh}8hE z_vH{xL@$m%kzDg-l$?#RR%WCK@6Td$SOUPjjFpzUzT&hQF1B z&vu)GSd7s6d}J=@R``2zQ@Z{+ViGzEl0u@QqBw|Dt!UzdejPNz+zVT$u?_Zwfo zML4x~qbb_-7dnSL+Zb8p;6U7$Ee3jzzw#M z36TzzOp2t?BA8s?kAAT2{5jv}D8)t~Mh=KE6?F$-W(S=`uFo(X4zI!!f&* z&E5p(W*MxKpXrwhpFsqlANj=JTW9_*#q4i(saio5c&ouj;1GwjR9|9rh%>NBMNmuH z>V5@{Ew0Ticl_Jp<1d@-MUDLH!V(hW+`Q-d*5Ux+sSDE51LH7iIZmy2-h;^|H=MGW zZr83xvCG~6p{(Aw;0LMU{Cf*kR7t+IwoT(-?0#s*IEHV<D<*N={@Q8lxK z=qJ9c710mGKDdLXw&6956JPsitRwv+r*N`ch^ntR&9vXPiJVQEzN)rImCOBpxN(TK zt8es$D>IK-k?h(tqDaH}(`52Fqmqa=BzH&frny~Z!fF{7x^ZV7@W3zvr?fFX__*%9 zp`VYAkmL9cPW2n<+f=1G-0$V&S=|20tiL&a)AxkHGJCypuW=v<2i_hPBeuGHuyx-A zKoFQU${5~b+E}TKYL>T@TNb)cqo#V*zoh%)D11;kTIYS@nR*wJ^#~IxsGYdw<5t-= z9UaaP8s|?=7U*!{zJ3O(KqT$9G{j#}N`nzZ8biM?i<)!nPWTY!Xw`ZAsAv^ai&YPF z$fEy9TW2c>3_*q^`-#A(T?Tj1^zrFhtKSU76<|piNaqAKAxyY#W6#hzCCvA{vGAMx z^uw(wZ02O zo1LLtbl#LN=esYq*lcSuIr9dJyB1?cRa$({;x_u#g#Z4Hp_w#S;i??W7uU7{p*a zmw>6MDOH_y9JihR6~#3`;^MiY10(#ip6jxzx;P!hg>LH28<;7D=l7aHHTI&FR_`^z z)MPzocPcYBd2j^9U3>W9WBv3KE02sx#^sIJl;_RAb)XTmQc2C`jYLZpCc^;w*I%uz zy+ADx2Gl7m?GOLndOaKiRbuq&Cg=*4b?-FOJfL@?6aSO1aQSwc1UQC zCU$OFeHPImi%k+QVoTi@z19Vy8#?D`@GI^{e&Ly=YBR2hanb_WBNNP>dxy6LxJE$@ z3+N%k#3l(+lAiIq#Gs5iI69(PlO_(gG^GOR`@tIxg}xKV?T`JsHv2bDZ&w2Nqh>|! zd#YSpGVe)#Tjy5(K!b)djG~Kh$%~3SM~g6gSpC;UA#x0Dqz>c8&Q$!2|s z9!JR&H^li(fG(&=o(GB)B_p2?*+>lKro{yh*-SVM>P!y)sTt*Pn0=C2aXNyZ;vid2 zk0BB-63y|y7~<3~uQkfk3n#}1#AVCZ9y)0$`<+^r^U4+A=qCbxEAT+j|7!gR&69K1 zB^z<>SSmw^qfkLj8HfFhOb1ClNG73EdeSxu`_?4#E7(FZ~P;{u}^Z>?AH1@CdDIy>u2 zp}8Nw#m`|QGn%r`Eq*r8q`USc=IAGgX^ru`zY#<5r#OEi85m&T7Z8c%C8di;-is}S zEm+R7O1tl*G-xr43$x%8PvplAmTa7sCPKg%wOiVBFML!G32^mUwm>W`ZP%b(8^4=P zo-TeB-e76pn0ra1dA`OA}8F z3;NA>uT$V|r*ZG@+}o5Ch`m6b;7^-c<`F;izqL@55h)dVB{W_}bg@Fz__NYD7$qCq z@H`|S@h$!HHht_9wK3K}=m$^tw({GlIWfi`@6+IX$c)RtnriOTJ)T!$glsv$p3ZNRSdQh@_8ov z58Peg$xpTs?emzwD6q(Z+}#MIv|nElbRSf|gXOWURv<2rxJsy>1iPwOE)Qhi<_|Yw z^C|6b*T(#5{F({Aei!8ye;Y9=YTc0NuqHgwrAj_AJa3MTb?b|7>WqsLb0X%6D@I(D zR(B!zN_FYv=4^-|8jC0=y|B1cLf2)J|Lmx2b|VCD5);K+j`Pig5uX>9@4CJzOkxhz zCPlxr=}>hFHLpwlkwT3=BcbHm?mz)KAmtNTzr=WqH6s0|GsUPp@AH;Zn)G) zhWTQSF#bs zO1cq{?vhfvySwvS-kI;-J9FmDnK|bV5A40xdY|`seowe_gT`0s)>?JO+i}MFQ^|ko z4K^=KvcsG+CEJ2*Xv^_U`cU?S9Ih0HiJQV&vTM$Sf=6!|9X5|CBXNN+qg;-`D@b!v zdX)lij;K{kKpFV#4E1s=de`eWfck)Xjil@v><1A@?b9!>0l~4v54!;+%vEXTEU2i5 zAMXmXiZv}MgK?QieXgca5;ep3F7C>xR%;;#~U-iZyo`GxTBK;{g!T^ zZ3j_#UE{Uh-?FeR>4A;C`6EI_+-P%Daj(`KlSHx<+pKelFqve`wxWpVH7?Hc`CbF| zu75TP=F{EZyJ6;x2r=7VE;m4>$VYC)(#M#sqhNa{m(kTRE0-`Y{YxgDY5uD=lJEWm zzL8!i1Wmo>Ebe6y9J>WfwQs4!1iQBggz~X+N@IR$E(V>FT9;L+D+G%49XVL0N~5r$ z{m51(e|sm(t|>so%Px(q2bdyV_P#Uwm%r_pZe?x-H@RV{4K{Q(?7y!zFr~l8c&Tsl zgFV+)@2H3@Mrd3dXYaX)WbzJ)f~ z*Mh%nA*&=P1ssWuxhA#Rg35Uv8yiG=&0q4UrL+>=PS?>QL5M5m`K znmX*yOR>-4YPdwvl4^9c(DH66Xiol*F-<)2kt)Q~lIY8XqPJ>1An5RC4Z$;!q!#wk z&X@%ZT0&mus0@VdjsuW3nCyhexD&(@>t*k+hhrLX$8XDps@#H&j7y`A%8LxSCeY`<|2DB>zQ^C*OxK{}zV2QznPc;LUFuu^ zbJDIF4mo_5HaAbt60|%eQ)jt2NPtJKg+@w&*B}Q5j)GI4+llxaG~BwEh^u=M<7}tR z)3Xjh)Bza5i!Y^r-R7v79ZaWF0 zN8+F$T1PBUIauK!k;%8owNW9^kZbItCOg!W9{YcwWWimoaolraoU3id(7yem(-G{- z0+CTyJI1!#iAM}Zi@v31_7OHM*}l_8lEXU04m>>)URh#7Hz<*6S$Z*o!&HSBdJk`8 zTX32qQ`Blt7R$uIFlNaf7?X#lKaXH1y*xR?Su$)+{Wc-@XHvxd6!vv@YLe3+r_53{ z4|64SEs`^ruZsl}5!_x-kj+5%1T@iqmPF-1r~0|SZ&gS@Na+@BM+CoZ1EZoWDkwzgA5m0y~srGl<1z%Y( zi6g9n3aAO-f(nbM?Y(0FlB!e`Zb-h*{1?$-+NkO=F^+e-%>h{s{hzn+8bDP7!e z?c$Rt4(SwEE3+*-`q{TV#Vt4nK`>+Wme(lgc=5DNldr{M@MI&DI4^fzFf&U0NEI46 z*(t~>S|fZ@GfED639}H#RQawalD(_!wWTKe`5z_0&zE=#%g-;uDy$w%_myxno)~U&4_a^= z=myB?BMs*dTvUhyc2&>j@vNwqWtr)Boj5gCwv4GfzBisePbc0_IRDJ; zUaf3n+_kgv7zGDAp~>u-OF{>uKUC$6KJh=0`C=U-zZzAJj)_HGfeF5}3> z!>V2on3`{@7Y(Xs467H68gxOF8xYfs!C$SS2Gw)Mu6-4P6csc36>|qb) zE-PMInS^KjyFDAKD+}0cuV51K%>hpDS=gEQ)#W*VSl&he>)8ub%*`{>RZY7PAo5<# zsym`>b}M#1JkKfm?0K?Js-*Ovm^wXVSZ#YRhv{w1Gw>zd?m`=Q|GS#d*QYU7_#?kT zW*Z~pEEkI5Ab*$y9ZJPrf|bXi51m}PHQV2oV+wZH?AG%Gf-tHfwfj}12ezh{$$Pf- zIzpb;qjI^d?X+zAQFW=ENp6ud9Ae(X9`6<`Z|OFzYG}^$YLMv6M!l-m3@bGY6<3?r zovZhfku=Nb&q{Kbyz2j3S$iRSdvfv*yu7IQ(a6Q4l%X2!{8G0o=_*G>v4CE>>-&nONpg;>YS0~v9G-whCJp`4xgsWtQOp=YZZx)cp}G_-{vrY&i!1{MG4jcm8i}GwF{safFg<~MRVzakfvy${Fg_s#cgMjQ*y;= z5Ug4Eef!=qdY;kTeup~L5$XMC)Mmj>US`T-)bAHbFyRCdgcYdDAzCJ4i;Y%d;X6|Q zznU@B;G<-?K=NaI!0X5P?Bk+)oTSF$(c{CN+wt)?bzXXRo(j~_J)D^Qjzeo6Ih~4H zQ_(~?`EPnTOFt!<Pz}Ntp{y-ogD8*(^9qo3sOQDR-#^-9Zn>Rr<3T`t;GO7edLaOHP_M9vD(v5vM?1bv*|+8;f8(F4 z{8h;JyTUJl3~cZdKE6I#b9s716xmpqW0_z4HMJaR77|kYTJ-cy_Zu+`8HKuj8x~#8 zev}l0pa%r^vD??gNld~WVxgC6mvI0C-3b6q>dnPPAa?U%fk6zu+xZ9~2$G_K9$cW?T z?;IQiRCpW+i1@gqk!c#>DZD?Lu`9pZljIC=>FWJz-+MN4a=A-!Hg`2`I~iH}GP}H1 zj0BI)7M|acO<>F|Yq*OaXNXf@52nZyWP4WDnWD0j<90+K*hwCG0?V`##djvh6RZrj z#KC~;qQDO-9@pR)2Nm>rZHoUqice>vFBCmWb;A(*J(`~{{&J51jYC^mm0>0=rEHA0 z(PM)1oR%A(Zuj3)i)FXUu>TdMLRLpMg|jLn3?cfinZO0SDmWml4-$8d+Zru0#X-d* zC=_nx>1N!MIYpMLdg&@tJXW{{0?*gBw`D_RYrCv%7k`P91iIa8a?_m&^?J2R>@rA& zc~?gAJNj3#Rwj?sW~8GfFX45GiT$6Pxv){shCykBTko2ZMyEK^Ub_uz~WLOMu zAi0b7S@R2?)YjG2-Trz?`l=>_B5>u|jCs^eX1t(bmAr>chAhKqO}_%QPQ=gWAV^|2 z%{lv^gfJ^#S02}9P^#t&3DW^#{i&HGiat&RZz>@-h}b>)T*Z!#X8iXN;|?H`9Ab`s z!^yKQ@Djps+*dUiQk?Vl^t^B4kz3OHxO};(P2ZC2f2I)j`p}?Nbekt;7*@Zv^Lzy5pEed?C}oH@k=?v*9c-J`Lo%7@ImE4#i~-EQ9Lqf68dh@52Bi;r{* zHbsq8FQvEGUU!1sq#lXZaSPp!t|R zI5%w&p|B3m9bbf7+ukGWcKrOM(IcfttIa&!7sH}NHTqasK*?W2@95vP2iTxYAno9{ zB9^{kt(I}EwsG?!K)wPWyitp$L5sFwGoZ)L8M^ZERh+{YXgUq+9bt%u?YGqISG-{e zum^Xldz38l2JtxjsOyi8*55ReI^92fuH zoz5q}Oulx^l-bHAmdKa7%Z{%N7(2#oo&i?i2w6du>ja@aq2WfGb5Equks?^wV$l6g z%C-2ysIhX?b`S&HA*LTW%g^bN_@fgPT#3b}vG96NGQKInX5;8?$SL0&p^Ah}WEr>V z0zyisZos1kvU&ek5=>-lmOeWNhrkD~a<9=N5*l_7-~)hImvsnrp!j_CZWFgRd5k;X z$g=#cK^@p-18e;&8fgpyjQ4C=9lbKq=WA>KT5W!Ldjt%Iy>Z3=BwBGYBjuEn#hu#oG5sW(G1}I(;T7xn-4YdFK7Q4hPzl z?%%Tq%Wf-PIyEhIwl47Ck;Keoz8xWEAR|I9RcJHN&Mqx_Su&N=KC|Nz-4&v4Pr?Kp zrOp(`@Z-Z~n>o4~(7SNf*g9)K{V8w!zg~c11Jlpu{WcdmzHT_++}lmg0EC^0_XTq* zfkCfbY@y#@iK-CNqUJU8jmU#$=@NAo@J7~+F!`wAc6|&iWjC0nS^`@yxNnC)AsUB| zA9nZ4Sq{()M!S4SZ*7Q1b1_5>Lv~hM0p^|5K3#qNCUPWAQzl0$L_*=DN#{Lnd>TYP zZHiT;@&6ckkhGadc_K7O8gPU5I@r9A0Ed@idqeSYk`ckIEW9_LsZ~U z4wUJnxeO9M?OYHSH_?ul+PTyy%ceTQn=9B(*W#dm5m%x#mat!ZjxrTeg*88?AR@{d z2q6Yb|DZk=)h~(n)LHvIU?z*x=f@4%O38{Uan(baYr2`)Yn*iKQh!Lfb{jIV#w7JG~fjRNhZZ5NcoM1|3yY&ROc7?Ig;9I<0SLzwJuiwy$>5!ttof z?5V*^=iuzTSVbov@}m|Sc^ZM%rS;~OhR@t3*}A+XRfNUdOb5H9*YwKGh^PTiYtL9= zP}~k~ZyZ9XXAq!1)8UhoNz%mfi5sw{()RvLTE@}$3N``?V2AYycLxnH4jh z!>G$;Z^$KM2&)UF02gb~5`w-R-Cd?2x>cQQP$||;BXREPRUbo@b(88zu`k}#qb}AH z37|#d;(CY}S0>n1AKo@Pt4~`^?pDLh%ao@|FKd<}``43Pgi-zJdB`HT6LaET_qRCu+Ub<*d9po?;7k+so%L_onHkvjh0kQ$#Prn%{e zCO7>cmy5xZSF6laZQDeBo<&i(${5_1r<<8kTsiJ!02pQtOE(DZV%*lN*1h1_XOyKY-*5e@n>r-@(Ou5HP%0FoW zx4Qr)VnmE5^2I_2b4}da-7vbcHVfS);Z9abnD}z?&x0Wp1X-jZ!hE;6Nj8Xw-+@a+ zRSCdg9A6#?;#BaI-I)giROHHDd8@Pv;k!UoUtFM?gD*9PhF#jrxHw8#K#8!DVU#C? zS986p++8*~)Ep|1WzCi~ zXm4!$2zJM50CK)r7}Q?Wm=~npmVP(!d9T41N;~zAWZRNJ%+ykJF7w*+NvyJ? z<3~KZSj@98l-vSNP%A11(=1E^ujf@AOybKLk^ni`UW<0+(E%}8mN@nqLZ^b4y(}2s z-F{rK(TJEc=WhJIu~jdVWV!?2z?MWQ2|ICfGK(fIme6u(b6~!@SZwzAd`~*fPQqxe zfSXLs8YgK<4iopM+cBurTu##W8uJHg=06BEF!9=37eR|`>IH$SOISwsvPVQ(3q&>o z`v&I`_)v5|Hmjj%6CwfFcPFqf=35iZ)~(L!W?Mt8!!RhTIm8T1N0A{5_36rk4^%K{ zEdD$(g!VjLBG1~@`IVnA8OHuq3Zg!y0ts*w&Df}@)iTsPYP}Fdm4+`?Pki{tW!=tW z&S94X$Mf9IH^A*pyTtA0U=2^RnNfF75LS`fsQn?S5%T4S;zvX7=k1!*Av0boYun~U zA85Kk&hFvzKqt4EEw&6(R#1e0(os-2^{4uwY6kw5Xn8;?=e%oxWr`U@zF_ev+bF23*6xpU-m9R_6=kic`R}G$FD)|=6AQhinhlktH)by8w#=hEFQre@Uv~#zIUoO_fh$fe1_&FZRRu0vP3&*6z&WT-=RK65i>kA(P@BK zxC){D=}s=FK66nNg7HUPY>5y5!0<8HWeA!IS4R2$-zaL0R;}F7RAJEUJGyN~4l%-z z|9}KYWV5KZTs-o8B}!kU+iAX2^y?Xs$k%(c0U;UCaC`TabdnI6z3wez#r5h$5MKsn zrMi(bs)_=Tc1*0>bROPJ-R2=4wY6He)aKM2`D>leQ zUs^S^1L>zUJ53ae2m;17KYg#8?wL#J(2w@vWrE+uw`;gTGq7*wL8;|Iqe$<yD)jK$mKZWOyxQTr@k~@PPq^1_PjZ!SZ%88+|MH1fn3~lID zQq^P>mFT1mnRn{33yYNsr{#>Pn8ChXG_ULp1q*jXw-xWiRgU#{(UQGHi~sJvJUu=L za)_>-Fonhs*MmN|82M!num&6InOYZCij^#vKt&Zy&m0i@U0q$hbfB?Wtuz12yTBtO zR%9~NMUSw1+o>^;%Nyk26GugmY|D1H=mzwo433VDC|!kN zPr68BZs+fqI#l;2o??@x0FzJrtQ~hjCZjA9k(hD){!P&yN)4r()yF7G$RL#dD_eQY zI-X0lWEor}Md9#TdGonRd5l8mb(lcYe$fldcn5NV9yd(87AXSH@14YpPw2(PB4kv^Vpi3*NOL{Ot93{lrgU>KJS((|Dv zbQ*R)RsOu(S?e|OE5^5H6|ry7Mx3l^W7766F6*di(IZVeZj=jGd!j{B*xu8;y4(F8 z@$`IAtgY>aQeq~-CAqXEu!*e|F)DnJPwAJ-5pNWC{;R%}y2+O#AM^uUgfAKoeZN1t zzkw%JW0l9;pJ2yHUQQLz!M`A^?U`S*#169%GDj%1c7YZ z^8GMB0Kp6tjj6}8O`4Up3(M?Of&ZP-J!xYaNrwd8HEV22+LL{W2!mBj7*c=m`podz z+XMU)?Agz&9P+(R8_}AZFHQUg;3b&gzEc$ymm?lhj3kV|;ZM!)`CKdh zaVY_brtYnfZ-58{NJ%lVRkEKARk}vhWP5TRXo?db!`#WVO2KJ^Aq1KyLB=w8jRcs` z!DO?NA$%Dn^uLR=p5@bfXt};f5E3xX<}bhSfjuWykBYzu9H<&Us{Uf{==kC`7Yq|+ zz7lpLwpaoJ0`DtEQIzKrCzKJPRiTA~T`sHw76M&=)ZT#nZFU58NiC!Fj+omYcCmGo$G|VZcpc#G8h8ArkXV~VFAeKaLjKjs{O9E zOC7uilD2g}*`uFF^)|8r>>!r$#2>cnSE?wX@z;qKqkgrcbR8t$zetsQ!9qq%&&=G_ zKH?QTzsmBshm;p{#}uCs0Dw6a*ZZ$($J=6cyTuM2Uku?+SF*>XVLt z$+5qhx&Y$UYS!aUR3zz)c>SEr_`$acMZDe+;|wS*x;{&FsCZ({hAJmL{$%Ygs-32K zED4=`IQKz=p=5*l8~WvPPywhig#`c|fowDzU(n)gQBx!_d)x4`BOy&3`KC7m*5a*G zGAj(9$RLKeMokOZNte--*r++UlNnbRpMd=*9;wfu^(c@E*f~&eo);Q3n!n@anIQu< zkVtF8n$vz>Z)6>-W;19zFJYAepfdoJSjg}vKj8SmRLE8osoIBwGfqttib%*{mTg;# z38k^D1?eWxs7$8m+$8MO^kX);y4phtJ$nyd*xW$^*NHccMh^e)i+o9FiWn^NQ*{b* zq$k@P|4eE}b)P}Fl{d6vAM<+2@LpF>_g}0iI7c?l$h(R?4+0)?U4ec%<~TFzXW(@L zxb~Pq5(yp#MheG#BaTSJgH@)GAVZMXFXc^8NK-06B=H+pYr1I$T&-WGZ@bW4wG!FC ziEB;%M!7WDBfINtm$QMfNBam*nxf?}?pWbNhP~qLQLlu)*J1SZ;b!1Ws%aG|dBi`) z$T9fc_xOCbR@t=iy;x};=lvkk+ce_k`@%zc-Ql->)^`FPH_s=M?|R|)72Ph?T^b{q z2%s}f)6mJupFMO`l}O>^avVx8s&xRL6+7vb;lC>4)%|l=*bPOwe)C(xzzTMzLG=H! zynOndLK};4duej$q)A`{^Tr)w>K|jBK-1F6*@)=g7eETIZMl)=L6Z57x2eQZKM~_* z+Ccbe;LEG!>o3*PDv5A3Wx_~PyMUJ?vB6%zMFnB4Lp!-?cD7Hz`vr#ZJIogg_@-y1KgIr z_d~*V$Q!IxO?;Bw24{hfrpaT8Y)SGF0VDuuTxl=_MS%#p9k&sQqsN>2fJcuVu6}Ch zM>=^9ObGZUt!r)eC}qDaO?BsGUDN4>khj|q+|bV>Z{;v)2^si|ESa7qy0cn({) zR&+q4mVPTJ$1RV7+;FrhKL8#O6V4Ec4eu-{wN0rv=Kp#T(KX`b;DFxta&K>;$?|V8 z6?UGV%;byiW)Cw>wxptyX>J}DK^KEy!U=HCUdoldATTG+nvQ*U90g~Byb`&7)o}j9 zvlLvm2}A35S1wGtKwf?};vLBGk6N8;Y|*NRZ3PW zc$Y(+Ek{1^O`MUjcUd`u9kY$bwCUkF;?-=Oh0`Mf#MGa2%$7%pTv;$3liQcjMDvU_ zdPBiIi(9e#l6=R-D2c-PmINgxxGjej65b0yS7(ByKY%HnY%eaL-%*P&z@`8C%sLCotSYjVqR{ zD?p^$sWEvZX<665XXC~B)-B3&gJ~NpBnvHty#KQQyDYMbefl}&h`)_(L2uB16SyE<9}%O5^L!OpQUJiS)07pKHNo+5MH zpr_Z((JONJQy6==u9*~y3Wag4-d+ko2l*GUzfE?ROj?3kfyp8itd4G@WZ3~SLW>o)?_s^gg* zx`D?}L5W6G&VJzhG^g<^mspbZc#}4)P3bL@eBy|$HvwwKd{tYQrko8?KpJJ}4?E`H zd~)MIqSZ~uSL=Z73N`JVG4H5O zHBE~xGvkC5>Me(cKQ7A1se|26aCw%8K_)-dc69An4R1MONox9_WRqo^s(o(S2jg*- zF&Y{BD9u{fUuLu(E)B!}nh0q)l_BByPcAJQW6WqsWWp9W|NoM`LuL=rDxWIyt95PV zB8y0;@PPy^c|SGFbDD_to%C~v-0gpWOd>238=5O82JCXs+lLo1<1yl$(n_ew1qdGG z@rjB8whX2r;pe8wwcad4;GhFa4emF$B}mn)JRemra?N(uF(v#u?GR#IxYC?YenqAY zv(FzfL_fXqJ+V}T+lS}*G9QM_FhB;17WGE}VjBsFDhz)Lswz6Bx)K+480@(7?VYdwJLS(;I+OT zQ8Lo-7(PE3$gMjn1Gu1JuB$4k^!l;wG~o4+UNY!WPWH^bblJ345EP zRLFE4*s+tIkk3?ACBpJOB(KVjbz?(J!pCycvnjR8z4lN@)s zWwhFC#FAB|^~&Da-3N3KH4^_onH7cXe&~?(b*<9<*#j%xw95DTNJ}5AB1X5uKB`fswongW;Kc$U4JFJC5Xi^)+!8~31X4tW(8VJhQZPzvh5@+b z>ytH{*5wiJM{K|j4 z^b%++#SzZwogvBU^)=|p)IXqZPs(8e?|VP+$OGdHx1t}|CDF;P8l@(ZcGX?A8!Y!h zpsM4~D%@n3<6V-G%zTZlL`y7{f=0%Ut`5_ATGdirKGkaTCw`L0Hn39228FHPigNov z{Yy-~@KoswBw!W~0TE!UdUC~q9~iIY0Aykv{M79!8feY4A#c8-J&-=URUrf?`UkP( zgMB)UYb)I>3nHnQs-PW>lG@g}a@J>#zdSthqy~1JLi^o(i%JY$aWl|3CX2uyW33Ou zU+oZ(mQO4qDyNO;2HYi8AwZRon5r;8zBwJjarv zJ)~AQ_i8uarYViWPSFUhNu*APCMEh?&jU9FHqWyY$8_K|%*yD(Am)LXE2$>t^-!;! zOcPP)Jcuny^r-x~Gu@YfT!M{oATfWb1MxM4CL3rQl-QlW9JW?R!C~nYT*-jZ2?{DQ z0=~t~&Cn`(OgH>IH5cdxOnbf7FA+sHJT9hLZ*EBws3Aq-as5nr(!1rrlL=ugDCn!E z_=ff`DEC?&Zm;luo-+LU>arfeAcJb_aZ{sn5_`*02Wyv@>%zGh@u7ibT$_Cy&S5xc zjs?APjQaRFkHCkwFN(|GpSB^EMvSF7<2R1H2m`0#;m6zy0xIceR6XRZ?Cm#xvz5kL zm}N!i05kP;Y5Npd-g1kc7U5*ifqkN1Z{N5+4%IKDoAPRP9LM3`tR@=eeyfZIl{5?& zdi_u0{pEQkZ8X%6m)|Q>ScFWBki+-Zd$hNIhZ&T`moN1$g03=49*uALPu<-}CAF@a z<1m$m-l(WNd0TKCiu?aW7996nCB}HEi<8N`#K<8-6HVtzGRzHqS*BiqB>lf`=zI_n1ntG*}hEnU|Z5H6GW~)xjf1f+Ghd?}= zFBzCpe%6k)w?~3U@^EZ$XY|X;ls+yFWewOfaG0EnQQ0|fK*eccx}%vqv7d7tN_9ru zxh?Wftweyw0yAxq3m)PuuvhbtH7zL3r66P<#d<^A!0;WBSzb@Z=xTA^@rW?4SM){8 zlZ~fE^W=Gi^t4R?-T?E7)o@Xowo{~TK$0AEt`+ErpVcTSDSx!D@`PUM6}@WLoudXn z3S}bmptlcznTu_QC*$cP)D3VpDpN$KLK5XkjTZzifgH#Yh?gDgVxZ&i%PYhtlKF?* z!Sd8)VyO^-CYFg30jb>xh|X^n0@O8CGotiXV~SGLI04~$h)qjql`XL~fEn;b{^C`2o?c{{xU!S9-A)R%6)gWFV z-YTCjJU^%5%CPC{T3b>P)2M2dH`yHZAcmwNyk<^3w#)qUo+fjG??X~jQiZyc38|;L zX+XPO@VKI(X&Ubc_EIa;J7=$0ihQPYPvp5q*Sn0*E0qc1Xj3jt1Pu}S?Xzl9KMZ*& zu>ZQCCaTr@T!P2N^5o&EbiHw!a9_XRWJ z%7+*884t>PO)GbALB_;8ME~ zXMlRJz7lQ7PN-j#{JJLkEirD2YP^aeRH`j)8B^Tk&~~;PoDSn0MKY#7LsKUM))!H_gRDOKFA^*$k zjLdd1eeHC&RA_6MA5^PU=$2E9NX;ItNw%f%S zPj?4$QbfRs2~?mlCa)>6J4Pw7gLa>6ZEU!`VE$?Y&hI|Rjm{u-{Kg>O@+$uqtBAVz z{B2xj-wneT67=xgVpdJ-*^`JJdx>cOLX^8Z&dfpEbjpIH!lC9JIj%HcdDx}6{0H(tWtM{w|zD{NumI?Ei8o^SX$`L~5+v^|Fh)o<;T=5Bta#W>cPo zSPWUN@~NjOCNe>i7z2S=^W`J37Owb;9D@&(;4*~CBMYgsDn31PJpl)VKYzBgsApM( zR}7@ARc5~<=5G?vOuhqUOJ0tx50n4Tf66wp1a3r~()<(Zz{BI`RhSD(D27Z2F0csm z5;x76$M)sOzX~?$&;a*Lmcl;j1aVY9L|=SvK9q8Yj+ecFop^}-+|P#LU5O^S@#s-Q zXil^I9ZL58J7kvgPg`EOh?YpfIzFmj}w685ETZHGExhfzQ?FLtv1|(eaMP69O(y<%D zSImQ%LO;BArhOJ6@cH_W47A;fW;>lfsbAGGFsa1i8RiyHlgb8R%iDv zPVR3Ut$1He6ZCRC7x4@Rh3c$EzTs6tv;BddxSZ^DNT_ciqXUIwVsEHr$zZgFwz?Qz zxNtsbdwZui{z4U#O1(-nqSQJ#!=g=ZGPo{RTGm8F1q3?48Y_ZNNm-+|QxZ%elfo04 zV;L{xf0o9QTG!Xt2G?t-g*38_DH>THSy}n9zl)~(2--HmYZ2x%wk#T%cc6!?#3L&Z z)1+TnjTGS(!+d>;R@G1aeHZI3bQ6upZb-UUinhp)v&$$b)5Dkb4 zr$q+Ox(wh$F39*+Xd!Ew>##tHa!n{!2~z+~NUQ?MC%hn>cUlloeBSFMpq3xAH2L4% zM*SdyvVqd?Q2UT+@gpuBInT)lP~AlBCr)sMLy!ri2n0!rUhn~$g!_0Gv`hnC2*7(x zI8_9@LwV!Kk(IoZFE*0&AK7|FZqlZHdR?g_zVTf)B>7hKj?%x2F5D$rB*6OUz6ECW zgLp<^x{9SkcG~;=nFx!2I3Z`}^e&j3TyDs=n0zXhgbu6LoV1kekX|_kGU-j{^`Q$JK zr`sW8Hf?jUw++EKviY-i1AaCo?R#RRst05_k`C^iZc2ZSQvrC$2h1JH}eQpar3Oab<$rps{`Qa=e{^n9{`ti>0fBY^Dn z_e%iyhZ`fG?)PGUhI!+*l88ccz&|01PHTt?~NL39xgFh3lNt<+hS8yze zMJlzTwye&p8bQjMaY7Y}5G(y6`-aOztDM<722{SEFUI*;kXk!|x^MUN=)n{Q1+ev^ zcMDs6=!P+!!t8^bwbzDRtfA{)Q>`RhwwtG9+T{Vr>o>4i!Xf>nxDk4L*tyg~4oRV9v*U~n# zqhozo*@rC=5y8aq6*SaWAM!bSE+T`GflV<9H+_FiDUF>N;Vj)X_Uz36v7w{)i{GW-vL^m`KTxlo+a_v%$ z?lZ8ESiRjP(@2{7`4j&%@Fd)0kK*MP5yh#@5(0YK6WI%n`TLYDezcY)4%BIj&;5yu z5QU|L`mhDHv#Wb4H7#K!V>nYJE;5WJ#q8AMp_&q2<)xU#a&3H0@}uwJWTAEC>bDkx zU-pW6aLU3G`??BSS_+Pq6Sw(jB(}13%uVv?CDr z6-#m$r|WXFyqo}0W=WW)nf=K6JP9;@KCVBLG411OVCTgJ7MPx@9<^{{*gM1%6_Hs; z^XBCd+ycGONtM)fXgG0bcfxboc%km4{n(}-xFd}LP_sxNsTSRGXkuc5GQmKFaKMw1 zKYu4|p!pu4>~D*W(Wyk?xuQaktDudqILr}T?-4GDB*{*}F-!5=a-9*OJ!c9Ovc;c_ zy4L-UB%Wx^C7Tr%zxgUf-se9$9MFb%6`mNz%01*_xBithhrU46oDnXyvV zGL(Jy>_?jcHT(}KphDp}E`J$jQ||{fu`b2}ONhGgYyJ{yObHq-_s#Eg>Bwg{_hBGK|HOd21@wWz`k56Hn$?-^=~ZP zz?dTk%10I1Qe$6>rIJ~& zv>%*LdNf+s+E>)q7x)A(JnEH~E8rp1Y27(^cR=jZ4Gx0RD*0)>`1w!YAO2Ux{u3Fs z4&7i;WfMVM_V7i#45x*G!zgR`j2k2y3BBpN6-9I&pt(CA#GF9H=$REA9b>qZDrT%I zT3d0%#6BGIoFf`({A@@P*dk2cbE0zxpW2rMYwkdcUrIx>;bLC7$TmeGZMq*~_3wx9 zpU369zvh$!D9ziHos}t8FYQudkbk*v4xRb;3A(=w;3Pn0>$QhgQKp8_Al!kGFaq~b zc=+m1@@jT~j=`=;+jCy`E?n>fB)g-LUJ`Ts=g8{4hDRwl~xZQiM4hs4>z2ay4#8g5- z+E##Klju;R zy>!w+5U{}9OL04J!7$V;X8c*kq~>w9i3Rl?QwyN-J_dgrwkm~WG>SyoXy0K8U!%DL zV*Rfd30ZGnLE2VUXflP|po_l)fLen)p2~%+Xz!GS4k}Q zF`MiADutU6QIE=S9OwIWC~8eMIXy;UArjTVzsW1#kc2jz_QWu(Tb&8>g=9;Jx?e5L zpF33_chQZ-Ns-B(CDb0o99qT)>}JVXi6>ML?%eLs)D+E4si))V2eCnuN@I-l$Eoc>~3HT zXYB2%+;I|Q8|&$*5p7mC^ms$aT&LMBtAe$b&)TmCe)+5`mbO?MN8J6ZN4iPPn7Q*_(F>u zlA7SmRQe%7fgo`Xfmxh^ewS}v)fHB2l>12DPvj!5Tpzc``(#@h$7cfVe~s$&cKUk) z;&R_lY}|mD9$c|N4LOQ6ar$vPAG#WRO2RG>t;ma9k(TCMzFi zx&*=!iOy#aoMu~Wq93ZY;_%ql$)fMY{*)B|{am2FGRinxTyZ1)mZTi#$|@F1y_o(> zb4&d^!LLsuS;g;tu$~(cmt@Ii(=d_4+LaDu$q^2l{~6TSuC?b2_|B8=prj>T?k)e7 zcJ$&<@8CqWUW0bU{c}QFy{}>OT=;3@r*w*yCwin}A3Zs?s~vFzY4Ec!A+eZT97f-U z(|DC=6}gj@W05*+=zRnkqQsSPtPI9Mo1FAo41;@oBI0P7pg1Z6(%uDGh6}l+z9-j7 zm?y{EY=3fypD0B5lTySdj^E-cJtPkv12WSqnrs>aHRjM(1+N??^*RbsF2PJ8?5bx> zfBUO2A8e@HV_4vd0s=mR8=v#23AM;!RhO5SE^wxk*F;NP#2`i-w1x-d*JY%btd@i0 zjimpG4D5b`o8#Y8V{!V6AM2c(0fBk#?3ZwHLh2FpSNL7zAD#m&cX4^EIxjUwlv2Uv zHD}$YPcbS+!pH9di3C$t#nJr(F-5LTe7uk11SO;+Ac*Y9h7f;L$$VQ+Vv|?8Qsr#| zT9pY>Dv6q9Q`0v5Lq)S%mThdE4z{-8pamXQ$}P2%qQF`=Q&WM>^y^nRJjllfBRfD{ zEipB|RGnog9}w#ZK$dIe@)E#=TYG>;_0N6yul4NqRvY2RhS86VN4`iyN=CdZ01T}h zuG6+N(E^*AQmX_8_TH5b4)d{01#(4}tdYhrhPF>lz##MiH@d}Hankqt-QR8mgx9H# zT!yWUjpHUs4o*rF^yC@ihntNr3J2Q;9@dYKae?dr_;dSdduih7m~p_&TEWlHKlTt1 zf_{YwEw-m9rr;TL=(5ilx2cjcRaVCVr9KgQ&N1;L_Z>V`NY`dGQCg z3S)4ZDJeEKwo9PX@lP~fV7|c&>O7)15_(TdCr`f?~nd*#@O3;z3X|d`?>=tMAu|Q z-CrbSBZ_>Vs+wpv+j{rrJTfh&Y%uQf70(F1LKXDGvMa(fxQR94uoQoasoRJ%+BfyH z=kX}ShTQ`uCZqx{;#=={RAQcVQ#KSK-r<*#oTW1vo8M?4NXu+vG((=hdK_`1gF$Kg z#gF2hAyd>nX%VY&@tR^)u4O35qMME^meYhef8wCypWKP8v1gX@uns*6~p0t zu28_Ts_8lG+w|5`22GOI4-o(1{t2|1;5w)4JD&D$H)FJa2Q=`fs_x{Tuf@=t{Vv|4 zXYdDHk_ElF-Z6s8sZ?Py0Z=Enm^fp0cADDql6Yp`Vv==={w6J!Rw{r7DQGFaw+6o_4QgR~a zNd@TDNz)@KA-_V=^uKWcdiritQn3hekVL`jNAWUCHEJ z;dJb0m-g*e?Zy7P2#2zgGz8VIcOfi<(pQ6f<|Y-Hisr*STV%txW8+;}sV*=8G6df# zrvW-Qdmwf&Mdtj1Gzi_fwnldU^n4S;tXsarxe~b_bSDYwWvf!AI?o@>5@-;+MMbm> zQK)iD-fwnH9WsrM#8i#YsU5HW5HFC#fVF(z)B2U~Yt%0tEILH5i{`nxKovj%$yqcl z|2*%plC)1~kglGG6M8~w$I#1@t5`p^5N_6c{l>uXgc>zo+$nYMjBf8UjS{;i7dk@T zsAIeBbYQmU8{)J_QZe*8`5t!lU5wLoy3*cT%I=8^E9jBlwR?sYR{}+%81@T!fn^VfZary6k4qUR6#|d>bmf#>=a8jT7RF z{i{OE?j=IFYF6zeGdD0-a`u&%&vvt*`RL`)0==i3e`2DE*WXaLUZEss9K2IJV3!okm=W%=5`y7?Z4O^rtuM*ZUjoK&KlFP%?PnegH_hPtxWZ7G{5SnC9!ce44xIp%1$xV}EGm+gtY*b^WWrJj9u^7LXL-N|eiu2w42d~I9 zl#KG2Zlr!mV2(K>hnO*jxpX>?Wq^IsJN7t0k}0S!X5-}L2h`&(W%Hm!)e&Tz&YA{u zG@Gcfk!moM%6@{R)9QUcvg~(230)%dTa8-uYTv#dxS=gfAQp&?M2XNWuY^*rHyIYs z-9W@PqGNK;>ABx9@WAlzg#Y#%R_(UEXA>iG7qY78D$QR%+BhsuoklXiF-0SGP>l<9 ztXtb60~G?rBc?@1DJboiOY(a$Ys-iR+JZlObA;^$8^oFjg&q(PZh<8({`SCAHj5&{ z@-GW?=(S~KA6{F-LiC|aOZ$WCw;|W^WTx4iIvF=5MHhP{tXIF4>x-fs5J>_BkmsP@ zEQg}xXFT=%AWJ8biTiA;;y&bQ!8$y}lxJEgX~C*l9INCTbCDyR(08)a*bk1$zR0L z?n=TM%TJQQoNVg+l06TaEy2e;5*YBpzvn6x;PqWzBi+^&$}UpP^LFX*pfj9*Eg|0Z zW-(nT-E33*qzfo=5xEmuy+}QT)^^hhOv59W7Jk{BU&K|e0SKp@N>D&CaW6)8{m#9e zt)$Coomv_AIKt~$YCw0Lbvx3@)P5=wBR0CefNo+9W-nti?EN4HrOdr|`qzDPJ7_nM zEuh!Uz2auYL)4z;3|3XDJJ0;(!D;TkUSp+X?^loZqd}g#nz6#siVk4f~ zeMy6bo#$&%Hz#C9cHDmTc#?F%F3bw?#jHU&vvrHs6PGEkej&Br?GespR^ny1>Ena0 zIO-rHo1UH!1)EG2bl#|Kf`6@YpeVjShBxN?_S_`NOz8Yey-s;aHB?~o`Un6kgUh;{ zC%Y#C(-ovpUaC!TlIb$~ovbJlC7{>a6i2s`HkfB2Uiwd2_jb4S?1+LN5E>xeHSvRx zT6l@_x_6tA^mRJmzKVwS_k5#E;y(`@5F@$;^}Y^{URxy==AiFVdLXoB?Vc6|#+s+0 zx7i|GJhs-S1L2%Kw2WYiy9+qRbMXIM!iTNr;(Ym1pJS*+5TcK}ISb_ukHA12E2-18 z+-F=n(J<~68kkI=m6q#ZXg0l_focp9fc=5^+up!V?)jEqVHWp^fzUH;pw3^(FTy&% zATA#y$?iVo)}(p}8O=dB*%R^5T1AE)P1Z(v`>lv2M_9$i_T56f(?7Rl`hX(FC3Kv< zI2`3mR5#3Bwj#oDBZ@2KAkWQn8!XR)*XH%7*1dab#-Mp|%OFvwb5|iG**pq{Zm*yl zzEh!QJjHEdC^%THa@+)Nl_A0Pj-gT-46(e-PUJ52y!dx#mN464`raO?Rftxo$ctx!2Tymzt_|yL##y zi_c~%n#ck9Tz`|GCo9)3f|AVw3`lkLKkY z;ig~;%ZR!P?Rb-i?Y~#s8q6w5s3pZ7WYVMrRWkIiz#p&@{6Hi?Jo|htz<$d@@9exOWweLN3!9#*9ykXO6^L^)Ov1Lp+}TC~vntYRG6ai^oxQ|8|? zar6;XG_^R8%Vy_T9T;U$_vd1IV3){6akFV zbQ=HF=&2-qZt9ahy6JckN*O8ApP$S@v0bv}3F{ujpFq;B#ChA)#DHuhS}{+I0x$7Z zb}KysiHA5IlOx{i{)!PQlHnETD||Pl>w!dqEQ^;IXK0n}H7i)^(HV{eDJ_^G2%?*q zhsrGsF7ii$VH6JZs65lh68(O1HPk?r=)_9#ZIN_lhQ$&os$rQ_(B~2R>Zedr(d-ST z-48@|cs$VqU=~M0t{bGu(Mra7pNv4&BuvQ?p%*D_?oaV5o~{-`l&@sJ5Dt25f3!FE zj?A-x5r~!7!vz3V+ymwO!||e!ytYMmXfK;@GqG@J5~m0PxfN>Mk9RKr#{#TXm?_H} zf`9iQLNkcNd6F?YI>a1tZ zNXSV^8Q-g8#k>NKhhf9il<+8&cM-U}NIe+;+*&MaYimpo{)TMG26CG}e3j{tWVYNu zQ|bV$4CTakVoKzq`9ntL_F2n+y;uD}!T>{>(>2t?a+ZmTGOTy!4pRGILjqU^ZWWlk zx)ea==}Z@5k_mZycZzz^kavIhi>kQZ8p2UZxal5KXH?w@NsuH)-LS~*d@Uq|iez6a zD>cL_LJqAV$Dm{H=t~C^>L`te^(Y*J4Zbr*&ALY0-p^o4&XYlaoy8*fE`V;hJ>84| zHAI`W7%(BceEfc_ax9w6>P3>J6|T3a14@C{ogYLurU+!0qW9kt6n1`_`%H$h3u`8v z;i+(`%eyc5kW|OpqfjHJe8mK<9AO^Z_Xp~SYRt5*J1HBVlYMC!#H>~_#|DEi5}k}} z`(% zX9H^`R)2^wjfpt{uCZ#1i?QwP{N+nDxLdm$Dn=~QE9C$(mvS5#N^wyq!3j}${_qR# z(d5>|I-7<@1k1$!J3&{LAG^)%4C-{B&$5LKx)cc-yeOALUZ${@dG`&fh4Bc+C{e6Z zI9Rd@ODvJh;X1#YF}mxSd0Qt@zMHDBG_ms~cRg9_^91}keJuHQ$I}-6?Xtl$mQs#a z0H|l?p$kGTWg0jISq}b6yb4yzwft{QSql;bA%8B%T4^JC%ax#{wr~1U%xf?RSnb{1 z@~kv=8k>1CwQ-0#>(3xyRet>mhJYfRmhPjT-tBfuA~h5K&_`e(zZcW}ux|zHjMU0r z)$35vp2fnnC}@nG%|db_23qax?Ci|9IJOb#&v+2vRK#=lIR{n!I+4LAO^qnNvZh$G z`iUUAzh=(8*()53$R9AFMspVl3}NKOoO2VgH+FR?r_I64VC5b}EsPlW=D{J6K-0Ck znGeak(%pSth0WvZ1bp0aFD_34*xrF>=6B4$XPZ5z_*(iM-HQjyq)-b>{PdP!aCK`? zJttso4*8>64y!xBj=yNVlf|RqU>!w7uC<_UWNmVpc=KsfNNMqLnfUa$CJlsIHjrRe zTHM&qJsjNdD{DTlE4vAN{h6QnnM|T649TlfLr1;Q_Uxj)C>X}c279K*Ewe!yNAgeZ za9h0mmf$!DFz!esl+U-`aOtz)X|v!nM5^NQn+BcNr|3gVGQS}cAvR>q?TJ_DCyKV_ z+b5}j!8?5OFWmBYa+7PqpGg@-m821VXYGII6<)w#wec02<&_`x`Ps>;3E-coM%Xiz zT5nv!?~EB$uNYBdD}w+g%Qpjk5n#_{b^XD#f z$Z$u64DhYTD8v+E7)Nf_Q?4Bc4l6YBPzkPNq@)Li;^&uNbnO6uc(Ar^S!4;#pg&!Q zpbs2H`s)=M1u}a)aka85AruTIyf@R}tbbYiRY?UW){OA?!8@AKx;I{uS@>)oh($P% zIfoD3Q9pZ;sa!amZ2@6pbie}V!?$@H& zpRM3%PTh2j6X;|T)RF0jKX=^!QA!)fm)U}4@BGYiaZYnSwZ;4Q0-;3R9U5B_o>I~@ zj7GLW)L{(l8=%&`E>VZ;IwvRN?;%)ucLVkclI-R z9?otzHpKUHzpdUwRhs2$Xyh}&(XhU1cCivUf;_Kr_@fvw4P&{-Q;&09UmM+MItwaJ zQBfZe%W5h*xVs~Xw&o>pPmYncc!3_JMT8alv`(j`{PVy9Lln)CB1Hmvn1&&JLX@vz zw8YNbM4JGNP0vV#u;6dR$8Y4vw_ZAM;HHWrAiX>5% zDN4d)c~azyAem?EdJ0k5CGU?@htVLTFo0Shn-TuO2+7ygBrtIvgb^rCDo)gC2Hj|6 zu|}1Brkq`d?8;K8;|Q^_55|e8Fkvg_z=J!+$Lg%jtx%$N%|H|__1mRoy(O)!`DgEl zT`qMDwV4@ww43;bN`;6e4~6%`0>Sn(gZw2~K<8(yfx{81vZ256#adO*)e4O;x#Mo# z)w6Pc&CqtHKZPNL{Yl$W*4%>2qT@(-_xH-BJmq!c6i%Rzk{^j3%r=U;-06m)9+X5M zPu}`_GPa3tS~LE;2o3J=sw5YirZ89I_@Cf$-R##+X9%>l^J}{)CXB~C9x&N%ZVWgV z2D52OEWD5<|fDDr5%S@RVB z+mH-x7bO#3gqYaB=_c6y{7lxrO$qOvZk*GL+0B~-?fb0HPQlm56;vsMKNRK9Rrbj* zA)-~Ova*^M`Q6!m&Glj2q$TTct6#Ys9F`=fg%N~8mg=iT6xf<{8TxhQ#cs+74-5^F zt~5I#kb9j$`&=Xr+%B4n^nfgb)8m!7Z=jO!6OM?-i}y;KE4nAbgUoazgmL+}zutAn zr=d|i;hlChes@7Q)tVv5lriC(1_u60^02I({iKa;xbs9OAD08Mf?fSlo%pe1u>x2H z@7w%6GTsu>{mMinQn?rubO1sw!8HjS$$zvG{F`|}Cy9ov3rW7qw|li<4S`~M2mA}* zQF*XW96RtTjd6$~0-&BaZi!MJ0br+oTeoU!Z*L#eWf;Vs^z90=rPDT^zK%se6SjQp zl6*HD(9H7Qrix3Ly^5V}#kR>3xkfi!2xk`Wmr?2K4KjJ<$bFzD9XV@Y?*+%@o_D3@ z`=Xui9)Da~+|D+-ZX%fHg{v@nHJEctQwllf5^69#PK~fw2c-%Pn7WK05QRg0A7Q3! z#P12Xa5L?LUc%K%^_ob57}>TZwp)CmEBlYo#~fY~AvYAePu52l3+~5=G`!}nN8@!Y z5+p+$X6}vKkt38!SEReO^_rXB%j!FE-Ye=$wSSFP``-){e|MU=q57~4+wca?3Rkz( z-YzcWUiGrBfMMcXf+5qvi#^WB(oAP_w_NLX)b8aiFfbq!)UGdBH>Qp5{XDrMbJF+T zdlzt$#Z4R>pSlI?Rs?7d3=t^y@QDZV+d-Fke}VcO`uX|vg$zVb)}ToX8T!H42sZAT zPvGWd?{Y_4@g{EX>GV(L#|%@kiMViL@5*BD_ZWy1(xN=W)7U&wdDWbUDDpuJ2YQoD}yA6eZ!_e zBK>``D%B1NbWH}Td6Wu_t4WlL2LZ~$$5q=V{``znF~j`ym3nGLcl=$m?^+vD15Rq1 zMMSpJvU*$+TiT}6i|}B*j|);vTQvUlXn|cAQ3*?AZM^^$>L~%5V@n=Xd`3 zk>;6Q{=6#R)k`3=;>aFl&mIFrNBsT=fTYziDJQ{2aE1or zT$@=4Z7>gDQi$p#Y5&6e7f}RnU7H)=sYfiFiM(;2E)QinEN-HUlrlQD zR?#RLuKQ}$(L`N|kmtxIhhJU>N+B!P9yr76PR1P1;L>N3Dq)oAC|gpF^qiC+dHNuY z&e#$si7Mp(_Xa%)bEqI)loy#hfGc4T_Giuz-tN750oCeN%zZKEBvqKbw|8_|*>{5d zhk7e7U}P|4?Lr6`Rlxx#u4SlXkNE!Y--y8Gz%YV!+IB;Bvewp;$orhivHKT3b>CdL zcxGyV0&xaER@O74I8BkB$;1QSdjE}MmFh%dC;X#NmvOA2n_7GCL*jh=emE*^z*7TG zOOBp`3zI)A-FMSlP`o8e)pn{nozm5rzkW&?BeAnMH)1B#vWf)z=gRA6e~13uo`cFZ zraA&u*_v@LK4(qqYqYt*bW^jMtEskuS$%WZkIC9yP2ch6e9;Igc3$WZAJ?@PI3<#+ zF*6{A`o!obq=oaZR6Y?W>BPh!G}bAEG&X5&ESaf}2UN4Xf9DWoTOC+lZq@2`4(Si_ zix_H$vd2sZp?6YiGsU6!88n{)*;cI{TOMB7!Neno4{?$}KPfmU=^@D`k>3k4_ z7bQ>;`TET~{ECAhii0SIoeZ_MsVVgQbJ(PPSlc9Gj~IE6K6#rhdYdi6sv<(RCb0z; zB@%US{%r%jLl{jIsFU4d5Xb71p?Y~>kRp-VI?SQ@Owa19%j*2W2F1f0h^$aDv_t*qqr~ExHfcqa}WE}%wZSbK-LtpKi24)X<+t-wI ze$W}lxdkAeDt|0EXPMmn&I8=BFF!)`9&^S`U}7B-&;8~@2EZj8ZohXw8g&A6l!CVc z&GO(TyY-W!NZ3_gnL-P$PTu~2o8#psC_ivX-U1NIPoI~vACBOecd1q}pGg{5SH{%Q zhzu9!UU`5!T1;exn`hh4adP%-J;yY~9!J$aYg>4A$MtlLio(D8Q`5+6gUGT$SG!V+ z3Bl~LZuOuOYOqdkoOoQsKgAW-1uS#;Be`X->x(VQ{MckstY60^iNSN&AY2Ga69h2~ zi&u6cIwy+t!^4aDK(J{d&V&m%qa_Rr8N{2GRn7uk5Uj>sXt|R4pyquwG=6^<@L+Qo zH*CA861T5k-G~(N@wdwn>9K6XB#ux$2?S1UDz-l|^MfBP^}j-SCIv(iF+rl@Yfj zL~u|Li_Y`s-~Dm=95vtosAmw*)cd$<*z&P(+F~0NQzId*dbNqcy z!*${bUje~f-fFcjeMpGai5NHbi3>mk*=bm?{t2VNcf98TtPTPXue}x5qZw~bRv*f( zaD@vx?$ZHq>3gSL{dVvI#XW^l4Mb~8rS%RH7wcFg=^#fkZ!<)w!v?=bb$vgu>r$jk zl&uT+u~A+&r4ZyuWNQy1jUaaSd&#G)%o$VaM|1o624czQ*O;(V@g!)WAg|Ni*VpHo zV2cFYYBkClxbQuI3>B|)`ehM$gyBT##AVF+h5*Gm5deJa96!ucL+e?gdAyjM7qW#tjX927G94|R;~9z(1dkG_jW3c{WSHfp!BL_ zD>0cyMvyB`?aQXW#D0t1mF3VSNpi5;BwRoGPJHzJ{hwF$eR_H>@}*FOyRO}hGD05^ z_-nNjU?LfeUFR7habVHDfA~!CEtkDS9t!p~7U7SZ0}h^`HxOOzZSLY0D0{pb_9fbD zSZ4Gje%=orcI3YwUiFkN#wQQBwhSt>89=*N)IdF*I#Xu7?+bqbY&?8jctme2od!*Z zJzldf^>Lp#*omT(%)aYa3l+|O(;}FMq6nA7ksMCjh(qCtVSs4{wM+mP1c3PPVdivZ zG$zl<^>su04LDsnnY6>ew}(_Trtc8M4}rVE0eGN~JnG*4kOrFHrzdaVkAM6vEg}xg zZZ0i-*#fTIlmY9wDMVaS>xnvEO=0*w85e40iA&|JXTMj#nvaL_-dO||QjjowH>}2 znKntqkv?{&`BQr#M~5>oje0k-R1~&ZG>+w^j#NiW3=6*4ya+64H8ez>I3ZR-mb*;NCys%*hFwpAUW+ zzWpVXi859!LX{~(BL0pznMT%LpiNRo2i6LD2^}3hnQ&Oj3Vh$N9JahbQzv)bq8R)4 zSxX~3J0+czm2#J3RVJGn0+V-)n_Wg|sT32_)_%B>`B0`fl0eqLFX+^u3s5bo$X%C~ zVB4nH@^WGgWbl<@#aL|JY~Ft7%tOj(K|^qTlBdDRzkJ;2BPA!f`?Q=voG3e3aNiY( zu=I{!SXh$^Zo81f*i51vhvx>V)u9t!toig(+ingdF_O*cbeMBWWD^+J71!nJEWT_t z$G+(&Xqy92t>2_)WDt5CX}VUEfX$B1>zrTDf>^g{mF6;<;XI}US|B)4%mvL01}pYp znE(Zn*X|v$pn?!T<`tdNd2^xqppKJ32j>AlYk3iwGfYl>Cb? zf;|qssB2mgJz&C;`rgJ%S_RhJO5@exYaR-BVI8MQ`nWvD-$RTfXWbysl;l%nZA&j3 zK*h$sMtsP(xde94Ix2aYU;Vz^-Y+@{dj3VVHCGEV3gQi~)vc=4{x#b;()oT`!}wz& zC2x()-$vC;H>KQXq+?CwMkWAJ0#XbwBp%^~?Hs6P{{i6FZ$c$Yrh_@QM&*rzzB5k_ z&blIDRap6d{F07-E_{lY5X~huORa3+Sc}6YY`0IL+xeDjNPm}uSGXyC;EoViY7DMR z!K$*C)hfs>0Ln~OG>Sz7nPP_8r@Bt_&ZtYdf zipscR4j)kUzGe6FH#Ll^d0sU)Qzd*S>vjPs9LQqNU43s{Z$ZxbKY!3jw)Qic*MSsq zg^ekqcea&trg1#g=;5$>)#JG$J2kXZ}7A&2jZAv{0Bj zy#Yr#GSt7mn@{zV@EE`!_3M-Top8geGnhoMxO~|(it3uZBh+uZ$5SCNVkcmLiOTk$ zK+vM|HkDBQ`BRUDeQkM}@!j2$Dec9cnYaWG85C+3>@@`Yvw6y@vWr~-14J-6Q+4Lr z1J(QxsYtIBirXSfp6>U}1JiV#a{v_0qA9n;*dv=92mQ{FhWyxCek3`T?TWSA}y#2D=BH~A`qC={FPn!RPS%4 z{D`Fe)=UiLL>?zSh>KAFb!sU?I0x0be)T+Pzur&tOo891Y4Y_0%O9W?rHa5-FY4Q! z#RXEJaM0(s1q@mP_`n4N3LIaJ=Lq%m-N97>ZI!oo;DK|(O__c@J){(h7{K-5OZgYD8bjd|Og^c@C!W+rdjQjOST3RRtafd_0RLn8!ebnDt z#%BXaXc^1qu5s|LWpn|{j*}?={+uRaAR_Q-4}hs~9jiv2U%Rq0;>J z(VmRZe4MU>Yk8+s#8g)!EzQmT9PkJT2n)7Nf8Gq=)N8gLfS34^gj8_Yw&|}VUJ7b$ z_{n4HA{-qbgN+2jdZa8<-5|bYVdvp6l@KDN!V7EB^hH?%Z0D0|e^v3fjGHRf=9vXX zh&YWM%Ojf6XLt&T(f1?r8~}mp{gaOb8FHJ!!UD|KAJm7X3A#2nP3N!LzZURH+b4_IEO-!u_8C8sUk|aD#Jig<)Wxq6Z z##aV{=)d0$OODDI-oxgzBjyNs##FMs9_5 zVW@`;D{4GgC>`4x^&RfeTYym_@gc;}P%Q%gR;an1ZUq|}G9b)x)5ux}-1|iw{Kt)G z%||W*zi(OyP{7#b9{l+G+Jhh({`Za9hH^`G-n7D`Z3!8HLL3cd0?h?Q>CvX&Wv69P zw4~9Ij(X9xf@m{!M4f1SGJ|*FXd09lj%>V5D;p_nDQXXtf8wEL@|R!GGzM~01c%qd zFjYk_t(2O~=ijY8Cb3xvqeBF&#ru)>JgrTYImg6fQ3ZK;79N57vYb}Yc$FFHiaiC> zkV;!7F6&q3o?mfs2i+`)G&97>+9&Y6-tKL&{#jN=G@APQ=PDXrWD!Jb)VP-Lp|o=& zhwjfY-fslI}MJiHQ0n2C;(lIPi3T)-HCF8{Hc9Z@o zn}U~2^UFVN9gD_nOq7oS!CG!C2c{-t1jrzJWvTv8&|zRCdW zsnt^g2?F!<^@#aAH?!WE@Bd=~lBQ$)n$@ODvLuWM%IjFvK3M>|HoqEV`!YlIoM3MS zj(NI61{iKE0t$^ARK9ulxCz25qdVvSjNySDiVV7Tsyj(`v<{1Rv74xSu5@5hWnDIY-qHv+#yE9H$&!Rguv z@aFG7n^zjkKN<9S5MKxBC1nsEc35hb)bO~IY5Sg0%BwcVe11eVC`3XVZX^As-tmk} z__KdrQCP9-t#5jy8*RjSZU2%S0s-=&RtOpvvEgftW&W!(k>`OI+Up{%C_G7j3Y4}2 znG6SO!7!U}H+F&>zy_CqDrTYU+ z6>LPo=Lqy#fODvf_RDaVDuA?=4P_P2=DU^LI6tx5e&HvLj$O%>2{I<7fcXxmOfy-y zeEfOEW{xR}v?89j!~Yd>+4a=-BHw|>sKB4$K+GQY^z=l^HU-R&sMK-~l?~wK?T72> zn&Od}uwntS6C~%QnC%Iik04U}@<%r~mRxj-oXq!}GHD;_^_U_@wj#9XTf+T6jCl%k zv`>*g{OvigW=zk%c6qCLyqD#xX@Tb0B#0f*zWZkFWrK!m8~|XDNMMKV>5(v_fx3;+ zB43Xk0F6~u;gV{QUj?a|esXM&rjat$KKP~g43eLj1NN3)P~ih(7H({M z8B07(f}q`7;&?5hbBHyB7ot!6wGt=4WZYaQge_ON&#`&RkS>R3NwIRl%PLsdt%+{joXKmEom46xPv0ZvKFt_ z&E~T8*7>*znGr_~}1=j6~SkdS10hL|T!}PweQZ}?cL6R!@3?vb%rhm*- z3hJmj)~%hg2k%~sEDpg0ELfxIuNDPxp1;LDU?XlgJ9$Urv*m2Z z8a!f-0}45HUTdM^Efe8bqSiF17EG< z4?n(Yer2J{_0io+K^6%c?|#F9pRQ#&$%ubH$>v=O%8k4t9UZ~&d?6e{q%EBVEG}aS zN&pnO_toSLM0UTPaZG95m?O6b`d(KsG>YDO1zazWE9wo4iXheG(3;T4)Wf}(LkMbJ1+^9Q<8p1s5 zdp`Wd0mVo*ZfS(AFV7FdpOYcQ(X$@WL&wK425C;+gQhSs^g&I+CV?DTRCbuRmkdzF zH#Dm%u-Z?}UvMjmT04Ro)RlH>8b3qj6s?d)zX)jEyhxNY`~755PKpNKn0eR=?Ns2vlZT~(LX#q zU>GbDv#K7{%I^83*oeI+>4!U^g-tgVS!P;>v;TA2e`BIA-xgx;U znfgKg8V{M(ZD^(>A<&b5Tkdj&o#%~?eC8-T=rJ94)zA=tDMxg~ge6CT|CcE7qFF!| z^_PPXMioXe!_M}upASU8x%Ty`(QFnJ=sPy0qVO!=6{83p^(dUr`Gaz=dvW?rsvs-# zFsJdgwVV@Ms7UCq{Y62zJcnQfl@n(0+hp5H<2nEc-3oVYo<3Gk($49;O zP>zysXCJCHeOO_da|uP07l8SZ9LuGYMWvsXCj-VVypt}tcV>yGa@xYAWi+XaG=vf_ z2X5f8*uA4cmsOj5Ih{-9nbrmK*DgU|Iz8uUsSVv%pG|(*f7*b;I^1^eJFJeEEp!l) zOSCcxdg94etkt)}N#Z6eq9%~bBr1dbimM}{6^0=WTeBv-dA^;yk?Q-EU2nuPnSRI!#4<<)q#=OCL4M>8ecse_4*)_|7EoE77d%? z?3Xt7jDjE>w~DVVdGFPW0+#qCfi?_sS7E-YRfVi@$H4##+xR$T1WtBD%Vo9N)f@pK zmRUB8S7L%gGzSgJAE&;X#D=AROpgV4Z7h|@@H+4dsf~;>sF@Zigwt} zZ1SO@qo1#NqN`tw{+Owt&fNb-H-#aw_vNmtgX#3(^77wpm;}sGz!uE)B#VJLarFK} zu2Y=47>oZtz8?=70sewB%|X=EmuJ??H4omubJ$GmWnj_`iTh(gIrTvG$Lsyet?GB1csB{`J@MszP72bQm%WnLj8@pqcrjy_gDP0Fdn zC+5J=2F;SiOp4C#hr(_G9JBCW50pAqPwM@8MdB;g;N-l4*R={DgXN@c+>K1E+xTjb zuKeE5@7F)j;7cRmKm46KFU`km^;qKj8M`TZjhj1Dm0qyd+r9ipMx0nuoz#m4jeGp2 zw_uKi_&L)^LIvzgC3fHTkd)67MfRz7?E*o@F^^hJv@AO|9FjdWBnT^snJqdr*&;Vt zQsd6(y+-g9m%ZG0_ois!u*avE7k8Cmr;%X~DSQ9cI1|>gSCTsUb+~hftb36n<1{wU zBb`^z52v6K4$26JO5ww>^^uEbMkhdJ0Tvv&4{A?FN|es;_B#eneP8$h&rb|4f5x?X zuMqWdI42i|^CXrZp#U!&)o%LO2E_*BQ;znIf-Sv=-G$!Uw!dy2lk*e0 z<#}u+F+?UaQvMq#i_emj64~9Id8=|0hu`CD-ZEUs?+rsEB5LzTLP1wx4rQ}*A?6LA zx)Pi$?C)~x981%U8JORD=c+aQ?q)(e>RxDtPq;U4zT0iWzm~S{ z_*J$d@)KyV8YQYK!+?k0;+@(fBGhvrF%cv~p5}_iOaq^}Tu({Dq09FC6|m#HW~;{N z`__MnF7l{+S}C|(I)DBAtW8X<0Obj)So$LI{n$c)-UZCGL4Tt%4lsU>|FgI!7gb^B zAh?r@9!W1movDgzcfbc}V4Y>ay(y#7pN86AUy#kIXrt#qZ)|7P{KziK%~lJE_i79&>weoC0iQVIUY<$;HJ6Dy zMROf>vxMxjO{i|oY5$TeH1N$@DWW!bJy1fvgsay9cHa+3I)SCMb+E0QQbH%0AVw-| z3$gwV#alZM#_@|;Wz5mtRt=~WR*B~!8!-#C zVM@=7i|L#J1X{PvLrIzPbi=}CJrSr@a&*n~P9osi30i=3QvL~?-GDh@P@k4vR_Dr| zS6vcXY;VyTK97#P22<7^&yOcco2H&OSDtQRd3o9iC^;KM$$*EtwKb>#?_cZn5Al9< zgUCGQw!X!yuazSpUkG(naoE9AWj&7!D||}7uxQz!j8_CXheZa#!Ge~>y3t4%UR_c(?5MnSMcU) znT@8fzd&H_XOLC!o47!zcEP>gx8o`0w9jV)B3lR3B9u3$wE#cz6zKA54=NpjT?wh% zw%Yh|^IV2dKRh0Mpnd1*GI6>+-|_tBIoJ30jp9ibg{&F~_x#(V0*(;;XVJ}M#d89U zzMu^E8_q2lcS)!0|IB6bFBC)D+WuHv{7eGN2m>eIfbR>Jthk7i$(DOf%LTU_q5vFDCE?2nO>{&;8g%0or% z=Qz;|SQ!hXFo=$BpaqB?GM_N2PbU~Leyu~1?Aqp7^0RI-6KVInsq*kb3zblUCkB1Q zlql3BBw=5ooz%DKme?s7{Tk#jW_m1|UEknhMM+1MU(wPL1A!mI$Q77hm0{5sg~-t? z5nZg*`VV+tfTx!jhF5jk|If`Y+vRR689bNB*&wpWnb!yUbj12}oRA>PFk}-W;*}Rno_}@@nW-x1z58s`Gt_UY%c0{m z_KhShTxPn}y;;w)BvAE>OBDeNqT$4N_57(xyEa2&3Jd(}Pj&p6{rm3vFak+lwbT$3 z`wLi0UX7X-(m53(Q*rhxw?EAbKF z2)C|7ac2a&NVy}T@>wj-zSxR-*tc)zIT;(KyEZ3laT?yfb-Uk9wG{7IwC(d`Q3(D9 zSw>`Pk395Ze>3LkdB3hx-lbYqk7K!f48Lp>L&b)hhqY0sDvSH=fxCRn2|D`yI%$LO zVcgB%U<-;h8>~Bsdd$GKvO29CddBd(TZp?(0SnVkGfi}+O^5=WtcQNe)!McowMxntY>8KgOHDJK76~78pVug()jDkX-CmxgLHwn+t>tFY_6v|kGG0`O zVg&gm=4;z`e*%kSQ)x$5VYf4=tN2ZfOqUk$auL=iJ}3Otk`Xwnot2=`ZzPTK-P*_A zk)tgJkoOsd>uYPqwc2jEUBSakxB6E&)P_T^8Ic+9f3y43wqW>i;z0xdGF1$) zHtkiu=(gqX*OznD#+X`89zxFK`A)QHg`wB{^Cv|41MNRgX`Lho(>pwD|vtd2JgL2O8%;4`5TD9fVJTHgMM`hT$R(BRzejpbPv;4sgPJX zRU!ppRLEe}jvzunFrNCWY?RXg*(?7qGRAq?{R`yLXKSn2N6{V(jm*9N679MuT@LXkuWV$*jUERhFI)%%JTYG;2atJ%8leN+usQLcYHF#5Pb@wcz zFi0^2gaxI~RUx@pt2im(&>*Jv)L7~&Ueu}1&-}6Qw`h>;%3M#elWHfZ- z27gG5y2G>x{oh4WlrCQPyX8%<--sE0#r)iAEyRr&rDn*D=tprS!3^0J(}Y$W+WJDq zf(r4Fde}s&x{9vK*p=?zb75|uYhI^M(|TugluSfP;y0|RZ+nUX|3&_L^7WiUPBiJD z6SHnB)V=HWIii?hoO?sJGyl1}T3Js3a7oW!L01vae6w@8rr;cal2mcGf5q^gkm+-j znD4|*U&i#_qch!Tsv!Nef@xcV$QSlZ1+iF1kEU9Ocb!Qa-fHawL(Nep*^1Jcx=DrD zG<9=Kk%{^x{3`=oVtwZ0zl8_9Biy@y&TkJx1IwBL1g1el^_^Ef#p3n#8({I=!(u5o zU1=_KxCZN{Y()fM4|%0orvs8)SGpM7c{?q9V%aRpC&?>`NRVmdtUg8)!DCon>m<=L za9iXdNjI5x*?78Hf6;f?y)L&qpUurVLAlFh+he#8KTHKrNU(zNe0}M2(x-6BU&dZm zrfQhpEM%jDc$=`>NB24tFKMFQU23C22Ut!@I9{{o>}EW)HqPht2G_u|rUyv`Jg&d---B?Rqk{K(?;msS@D(iSx&rgRRxSp&`wq;Ww5Wo7B&RNZ% zSE;%6?WpT@f_>Ue{EX3)&zx<;#L0KDmTDS>^NVY%$Bvgn-_5NH)yr>S^D|^x+?=r@ zfOUgI5u`mpK>dmn`>2j86NG&+2?7UVMfydaz##`jBlp581XSZ@Z2W*B07EGrAV0+Aetr>*r?@<=z9D|mI{uz< zM)B}qez$`e?q#uP2j2{^f=Y9A7#ahp5 z5#`UxF;U!x!*cnkqnT|@dKU(#_#~p7^w}01?q9Qa+ZbN}9WVio&0O9AtD;`!*{Ww% z?2sm2-cIo@^QVMC%jVqDinrfBev7p^gn<2G&C5*Bs&Hn7ANH*psSLA$Q_DNT$PaMU z?^i^-;#FHCFFgUQF*fyh?>XP|%Bx43B>aiW?|6ZJ?7cN=?k;QdH+c=6@=)er=8roG z19oI%rEc>b=S^UaWi#pN8!@GV2Z0NvR_C#niO{XhJ&wHp{yrYDo_==63aRE}wc_^r z#wQP$F!2|hTl1=APf5#CJQ?_c;1OJw;`~$A_n6U9OWfIe_n!-xV_p$qMPr6aVPqSJ z0zFQHn-ao{+*)0S>RBU4uh$2gBz9>Xhet$qnZn2w@_#(`p*ON2^b?8272eldNJ(r% z;$!uT_!KHFr1DJ|UzihYD$ZN)1j3p{mTjaO_1VDeCTJM+zbO89f0%CmspV}xZ)Ek% z9tfXjx!v7^mJKp#jPUjeLtEWXl2=kV?e%eDDRdLOb6X-2Bxo6(M^@EoN?QUW;OMfC zB}<|op4>uC*&w51qlb^{K7L6O^8^HL18{W4^C6VK_%u8Px)@mCnEaZTonPDOX=T|0 z=(W(OcvolVJMj`+V5dxxRiv_nH=~G9FKt{r)IMS$=P2RE3WWd&3V?Jy_Z9QQs19XQ zKN%=wH3YK$wE?{?h}ZeJDRyD<`+?VU@Y2?{26}<3^rO< z1Mgpx#~e?x=n<2cnN(f^x1g<1(Ef5@S*{lw4yvx+b`@Lm=n1a+*IG>BNQ-{P^tuu% zye@U&4|G|KpFaGQFZIx2Z8og?P_T20(%lRlb|WDk;TE-WeVs!Kb6@sWUbva%E&-%4 zFeczB^N|408{c2dW+V3b|Kcva`TnaRDkMT0O%nTWmDr{{*})IeDH`sAhKMMDDe0nF zf6I!NKN@~3#S%c{_~O>xPBFISgks+Qj3Uq?L^LcO= z235!yuFLFvt=+B#(_|#0v6nfooM*-(a&D|2Re%uh)zRh4q#4p5+goFUzIloW z%auTBg)u4=&Qcof*38>}oD4VSv_niPhBCPbkazmu!tY-WhZH9fulgN}-E_zIk3+s) zi=nKEe9_i$cIRYxFD&y%J<;QD*U_I+Qy5$xa$|6)vWA@iwv+~pUFiZNpbTy`{dWW# zucE^4xiBabh@wG_Mp`<>veQIrbJvD6yh*+kGeV-q__edWA3SR|O)LPsweg_p|Hg@t zZM)F*TD2|VzktmcHXQtu(7-AzH$f!NMNH2Q%oU&emrPxk&3&}>1Z^aIIp5!Xl}+fJ zu`e{Ovk=b%l0}jHX?sk)x;Z!yPyY-;FDfcR(7{CcZ>AG3qJYCE5m^JdZ>dmahuq;S zxH($@`f(VfzJmk=AZ-Kj8ZDG1_I3^W%)ty8YH&EfvKy-VO-oioh}7dHc>H?pTS9kz zp7kDJ(*@e@yJ&a)k#!OeVzI?DV`Lu0Kj0$*=mE$2mSrKBPy)eE=jkx{NdOgi{lN73 zxp?|is6IsK@NLqjXyp6vM4#|9J z?W){?)<_W8*z(2ijC{5?{!z4Uk{{|!tHILAvIJ18QLEZ`VIJ1fKbbyL7R4MQQoKNP z#~Ja%3BE$^oFg#;GmvJz3STHbqz-<)Iz;Fl@Y-0GKxM+!>t<5t zyg+)Nzu>sGV-s_#?@M@Ukkba&sPn@|h@#Rr%~31#7*v>F+uJqQK6ep3scIr{6VDz1 z*D}Ze5oKtTW48sYu`xi35(cKNcu~Q>`jJ*WaM^<*PK?pqwhZXN{#$B$5PJ;}}d zdamu1uaZcTNQ#WMN#<1O=1qom+7|?-;+8E?_h*PykJDYpd3hs?Fz> z@7!7JVB9qFPGG>lq1U||NO}A1TZRFI(w_av#O3R|N@Iw64yE2x0z2>sWFN4HPv!(w zo-RT8T_**z>A0r`$xkb9K{JXwbQ12%HKi6pl!DIjJ9=W+{&s+C8lX&rzqhCBquH#PABcgTM| zUVCZ3OiaeU+H5X3YpfruvJC zeIQx0ri+d|jsA9aX(-@*-gy#O)XK`PxF^nSN?0-p<8hVc9?pD$@%h4zdGRjN`Q#M93n|Ub;satH#U*Zc}ZF#^Z8px&8uN+mXi8D zM^&!oB~8vY*#kK&GEqIwo0Fwqj0kz=EW{Ez&>Lh*QL}mBzacjH?yEp$0g{&%-vXNG zES^s;4Qy~zjj|Lk+qxQ=V$=a0Y8Nr-8(Y$p4YK0rYrUA=qp8tw5XIHKRh>B}so3Gr zh_7oVHH7$)Ye*b(E!vE2vsI>k9UEIVU>nJA4oV^KQ#mkDA%@f)SV|J1;+`bYynh*D zr6EA3(rkF)+H~Y|mVKcwU?iBu{x%4g)mC8}JAIlxUCH{Ij||g#Zlqyw#-^#FP5JXC zOXI;02W@*rpT{_E5v>5R=AeShlRb5d}mG^`#!XAL0PP zo^jgQC@fkPtT1ahDTU~6;DRSwWcV?bH&UaTyF$Ethf{}5IErsOW;o>$2DG4ny`>)U z*IQJ#zaRYbii#&{@6DStcqxO`>(e5t2YHX-)nq-6?`G>~|7JoY3U|kby+Su*UhCL^ z&?dcz9iRfWb~?}zsxM+dw33^VNTq&7YE1v1ylJ9oIKoz+dA{ch3lcCnrS$%}a;PJp z@X`L)Vhod2Y(`6Y#A80T)z{8nK4=J)JQjglV&C4z&wXr*8OPrdvbZT#RHX@)8Gh+U zIBpZmt;n&y!8uFDgR@L^Q!SW{`3r!cVx;O8hwK?(tn6ssCP49e)gdN+KSg|Vp%#>6 z3S)144#%6cStEKkcCKBj-~vY?h=}Jp{kf9<_ia3-{C5V4r?d2)L6^XDa>42fX?|^3>e?Q~$zI zio}S}T4QGX_%)mKEFjxuOcV<+E04XaxzfHf*3qxJd-F12Fms4E7fYiuzYso}x%;wP zc1)GAO14P@1X+=)s;Rm9i}nLi=PB&zpAiLSWTOmQYG&O^xkJo`&+@U=O>QLMsT$V6 zeY|`7#}iW>S7skwvbrv9V!KZ~RJE+A@rDcVetYjycMIvuw7=)HpzPM)UCtbXPw#zq zL2hhn`WKRWNfU)e9}6`oh1j&{EgXIUU-}P2i_2Re;+A|Bjx zLdbT-!s{0o)0nA4blEbPvqRcg39eF668HVALIw<+5TSXf8iU-7eeeT!q%DBayf8L1 zWEf679PfL5N}W_JkF_p#BklYDuh|^{gUgke39?de&=n}uaR1LPT%L@dGFl1J@dR!&-dV92E87u2hE^Cud1*Fdv z4Ut%@LJ#q5Yk2zfo6~dk8Yi<&{j=SDb0hb&9E4|W5VDqa@oR~1t`fNWks}&fb*t>?`~lt;1fGG`B1VqRiQ<+Yk+LSW#LLljEIR-gQv-42MRGIDrz`Qpr@!7i9bO#>dh3XoZ<^ov1xh18hIxs+6@VnUeUidEyN_x8 zrCxutE!jq&%&?Kdp@j@gE`NV@6u?V%&w8~#+U_8|AOPv|^go6&L~&|MlMW;I+O$UQ z7Rw00QuwdeVtEm}`+nv}Mqb0zu@MjpLR3K33JL-A)__1j)uof%JNB6 zI`M6=$~qw_?P@*|*+qv+Hb%$SAkkipo>+^XsN^C_`+|7d*q`>(4WHE#OZ}QNF$o0T z>_Khe1EFZYPI7tWsvXb>=Br!dbaGkmX(o85Db{4ZxTfLCjOCQbMsPmC(wYoLjy~=AsI{ zVuQlH^fj^2|GiYGQ5R-f2Az&duXnuP?hR}7^l?Ub3E?$uxZS{U+O}8Si2z@?msv3y zL>C42i(0llJ8n|!0b$I>8e!zCL>^4XNist~N8-|VvzICJKw+57l$^(4FEWRoJ99D( zYnOCHRzzf)tgXE`>^MX^h=(S+-?GaT{yUv+Z>Hoq+@^PCDKHfL-Gl`dnK6lNG_noY zxBN052&&q_rBq9Glg+ToELDs#5A#1>5d+WM^rDLU_ z;qHCF2ZWZuQ+m=}7)pmB4O|(vrWQf6uU`BPC$-|rf~6G58zHWERX?;Z*B%hMjtqnp z4UXb<7ND#J_N0g8T7@K^X4sJ0YkZ(rd3KL`pRrB#`I0F1$RtIy5H)n<8So}%$iF8; zp)Mf*=RrbEerWYUMR`9IhyVp+t&Yw<=TH78G{4ajK@jmVv zArZ0j#TyAG7g91Ir-Muku?`vR9Z z>wVt)$z=&^6G^3P=?$zpwaeAe{1`z_v+hCr762<`7~XV~ZPV56l)bhm9T0u9Pqcvt zbSj7WG2FG3j_TJtfDADi_&of=Q7b z>I!i&`5ZXc{RdC%x4!IL)`fQXlVo>+-2JQ0OA=j&Vya(NCzoXO0S|X8>DXT7C6iPvGzk7q(X3U_ zcP~3f2L|O2A#Tfo;*JeGp6qfYCu5?tQz;=Sn7$e*i>wAXzkcNYk`EmQ8ytOa4#)`& zeS$KTY@>LaPn@_Mn`(%A!?#%l;}>YS%m8O|cRpBF&$Q;0OXnKRy*DFoCKoCIxwsxy z4V7=}c5JV5z-OFmESky?B9ffzrFKiQTTL!O!$?!eERT5rwxtg(;lI`gdbM_<+}za@ zS$W>4P5d|S*w_$o0-^}F+UzvRK}<%QF~SMoj}>cZT2e~VCf#K+OV*4cx10KB$oKhw z^-Rm0fXQF_i_jvapx&$|owasgKv zT5{pi98OVoe2d~}%aR?;2mA}%U}my&9{y;|Xq<@h1)PK+=O_!vkDfc!iEa4qvZB&>j1tY$vv6-U{bE#6?gOe}Y}*~($Lk;(E&ZXstpG!19=m^U%{7D#Q&p2x zYc$SWOD!$o{kJ=Cg#H=_lQ#@1UnIC6`!ZaqZlA(MqvaH@=5M%X!E}Qi@z3f2$>8Cj zPCP#mSN7;HasdUrXPFb3*5m91N!WhXtLz@%0<%18(qHs_AeI@`eP;i=;i>v1f?1>? zq7+G08-+!SF>AeX)l9;6#`tgHw%YL#lH;lo4!KJcq-*ayZmfDc0GKrVkZi}KQZ#5m zG!LEl;TwkZGAo)3tzq>L7rEd(aS2St!Q@t^Sup3c z<~=`@g{{i9_eBF8Q{?i+C0DO~nlz^ib1it?-8nGKb2TYa5)vIOsKUi!LU0nc%f@TA|U4{J{ zsQ+1u2K`(KQMl^tkuY3W$omPt&kFn~h8ASRK1awoje9H;gV6~}?xDSNBD53kd|9yw zy@uaUzi;PY)aXu$9ShsHwBO^~O)zmEiaEr8^?HWv6S`mJ!G8ijQ+Rmmes~sw8yS>i4f+(*nJIq0xmzzQ z6}>4%VN-`&KDi-(@g6aF;`Xxs-iw1#G?)kcZgG_#eVcskb=l?FVe&FNsisMv?c%!W zXUV_72L19~mUFbMEoZ%md>xo_cX}l;ONQn%1B!A2bb!va-`(5-Yp+@S@EhG1>bUBF zqK|w5u3SeqZCkN0pIDGk%%2ifmrJ1j+TuYrNbQQVdaMFcFoQit+)Qb~X=~A05WI->0(!_~e)XeHT^x}( z1&YVl_ayI$2lT2^%aMW+Zi8-f171G<+HaovQ#fPaf9*dnI&%2#6KBuetH+x$CX(0N z(JiwEv24@$&4_RKeG3sKWdn4Mq`p?^zH)$C5DKjMSQ=cc_(}ZNv>;hS)Q055?`^7J zIhxIm9wjJ6J+V{W0^mw;fQ9+t*1tkYC>A$Egiw#7S^M}LApzfdL9Hcr*N0ho{fra~ zA|G1Fphk$&l>lFO6pzx&tj;0ZMTD`{okZK*A8~I~bQPzsI{Gonxj8FiGc%BVGU;U_WfT z!ro7^xCk)nHnuQ7=hq}J8iC}o)Y^}ZQUdzOf%(d00&!3b*CZ($>lTCM<13tC6^N{6 zi?9Je^0O+Hlp#qC|Lw=l&nD9qv_CJfERe~-LMP(LUK?ba;GuW^kAX6qD4cydI>B9< z=mVmN@MT$NvP4#2y~ypQsMdG(%yD+Exe)cOC|@Fe;7H9H;syRMf{fc_Xd zDUWBvAGly^;u;=s6bKtXY&*Qhk{_oH(@b$sG7>2Jciac9b7xCMm^!YbbZALRq*_la zmt-9Naua7~r$NDof|9&}reF1TI3?UfLo%A}uKjGkXWvWv$)p#GuEa^_6$7~l#I2ug z-x!_h|G4|nG5A4TibM`f@ZW%I3lN~>NFqRMkMjyyT0#u&q6bKV!5AJ7NOwS7LBCT= zyO0Pd-P(q1-^K6|!hW+&Odm(bVlWNHFr_5^w2JISf0~dXj{scQZUiCG)}IYgY)aT9 zdpfAJAv%gp8J%M!8`r3tT#{WY+SFQ|Tv}pv{X}X@1cI9N*R}6K%8*PFJ=!o2mJV^N z8|%1DGSbVu_v2yuB#x~{PL1>Qy6F}zi%vlQE%vta?cSzR8X{=})C70_7I>h09;*Fe z;HCq)Rp6$p7#a9VN8L#90}h~3v|(c+6#bULRB@6o8kiZjE>dvuj#v=ZS(~ zTq*t}$Z+oI`*Zs(iiMTBf|70i+!H+0*@;$1Kx`^H8`E0OFzWYD9ofF0#C88mw6SA+1}xM;Eir;?c+W?Jr0BP>)lLtAu=L{4k@Ifx04)?#-Dh)SU9$kEnQj?wS}oQF=1 z8oj;dt@uH(sbqZNxCLdaS^E~(U2K#|-46B%>b-li2)M7VtSXv(hAMo2&nQ}cvlDy) zjkC^=@ciG)yY?VB?(qQy4Y9$FK03TDq%Dn~3XW7!AkjxJQ!RVVDF?P%1+uY(HY#Dt4FkIQ)69gteMX*LY*r0}o56PZ!zuXd@b zR^8!mtko}aB~dWb#UiXqx)p`->++asl8sReE-4CVf}juCA&F{10Q(*2$-1MA`3pj7?Kzx$n`)>FyrdsGmXMFC5Zk)g*pSJ_qG9AQ3R>fp zuUG(Mx$mZ*HT&p1;fSAgYGdi2>w8H4l>~6T277>B(>lPZ)d;XOs&!w1rR1}`?B+Z@ zs4rTtPMv@VIO4NnDKPwiSrB(0FvU~c-}x)N^-Cq9D2P5@S4;=45R7e zO5)x4d!3mOVC{Z3HwS08>*}HOoWnvZO@q|>=<#wRz|USanG(|rRPoNv&Y&a3)~J#dd54lOoX`b7^VNTL;q9m->13k6+BSQi?MZd25XG31D~g6ReP^I!EY`=P6Dj{493+;w*h_h*>1n~xiZRz`br z_6In!$x_GW2m*s}_8;y%2CCN`CW(UVyXez}WEjD^P2rdB;Q(a|q!G(xD$=HqyIxdt zvR9+KK9&?cAOvuA1Vx#Z=gWrvmrTl+m`by8=WT`1*hxD=_4SMNU*xLYEF<*fNo=&J z*?8IhY6AIX3ZcF=aSye8)n(9ViLfaGvXZH{A7Va;PW

>?X_yqgME3h03MOP#lR_X_1s~K5);V{_Aw`(@6u;Ne3NNbRGPlH=yv}(+1pXuY27Aqn)g-0COG^ zszENKl365kW0@YtG!5ZpRIbx|bE;-d7JwY$IW?tfd-WH%D%P?YZxp~~;^^Z?2WOXX zm~~UNn^GDgPKlAkV5&(JPdKAe>>5$zCN4(}v@Ec_2j0a9+puaW4A#b*R*&hXr03B6 zEo|`WJw6xWNb+%?FI@-6yIP?P{HAT&5>9)VV{$>bXed-opYKu0b@W^~v@(iorbch_ z6?j}9i|MXC-Cg-k@Bh7Sa`TGm6F`4Rmqzk8B6L`HF7Yqu`j%dnRd1WJXL*ZW@OvOj8a=V2ZhgZZ!K`+JDu-Z+j#wXW|G|f#0?)7Gs0sH<3>2 zyWx|1$KHU-N$Zz8awqgrlF9c@%Xrs6N@iGjwLZO8jcT$)o;|!0!k2a*-2tQ}CZwcS zhXT;a=i@y7$0(LH#-O?MY`cfOEQCY-*>Q$NlHT6q6{kbeHo=wRdlm{Na@~`p5tqiw zqmdgAb#*WiT>1EP;t4!6+yAOiAd+`;^Al5%74yEJdz{02J zYp`d)6M=Nj0Bxq-y^yJGyo4M*`Z+a05+Zk@)5?BG&b3n3w{K|JS{guYM(lGp--=@s zT@+y9r4GFA{uVpEHdkpTiIhX7^cL|h`rk`z)Lwzej&VarU3p9Q;o-MtzNqz{tswZg zhojG}@4LGl_z^SUlc47ZpUvWhJ7uAUI77ynlswM~OutvkO&q$`gv;?_s|(qiSXFBB zyX(xy8}s>`2!EtNxVOc}r9J*6_^X^D5v>J$aRhQ7u#0FG>*{%9r-`sQSeyqmtK*%{ zo!-KcCCzn#jt)+DeAjcHhDk86(83S1Jy$;$HNkd+iMkcw4LPr)XXHcT^59oKm<6+J zujGeRvLEM;diHwDN)wuV$B-OVNRvlx5t~AeQdgTk;n-?k6<5a;G)+v|&+Wf3RgRXS zd97O572w*KA8i`&+QH8k4kI`W9>JDZ2j47)F=lMn^;5LRZw}&-bNqvK3!@UcY^hBw z5&gyU=&RV{#-a@m1QqeYlKY`y6qvJU9~rE(bY0uHP2dc9jA`=097rcN zK)nx2A>ty7i8JF`h!zmCUD$JNw5-u_tM_g5svLdA>fVvV@Y8FnK(76Me)i>D6qW42 z#Y3gG^u2V3%ulb8$E-`0XdiwzfDa;+sscnHh>N0{oJr`>M zcTBfT<1F7}h56j%Xt-H+A9cwDBB&f(gRag2kNu%mNzc))4XZ-y;Hsm_UAB`S$4hm= zKoL(ky!-FAInCtd1urKi;&WmY)!xWgetNV>dN}jJ3|Q|XG&twplA*b4rOf>_EGyMyrLnE1&hAZ8{v*?w+BFvku2CfkLK z&LpFXNEF!o%}J>u7KZM@1V;Z01P&rL2`!o|DwCrzz)B!P7P6x`zz3K1oe|&5bXz#W z7_};|1FTv=Anb5Bn)RsE(N(D+UNPJ2=1k%K@YolOwP-f1iYQ+tGSJ)nhkjoZe+TM$ z1&J@=2mMaG4Dz`T$mFogSKYY|wfyAZR8SY{kr*4b|FW*-49caOP13$%(}|c)bwWA~ zwWg7~1S2+-1LT0IGFm@9?g4WUyP(doq2FSmC%z`) zcl$^}5H+@udAD>PHPD(NfjMrs>B4}KO3C=J3}&cY0ezng@%;OL4bq#!CvK0!ZM}9n z;)eCqv)y>Z^!(|m4B=Gqxw6A3SsQzxdkF^`=tX!Zdsl!$I<@y>%D%1|Z+I0O9Icw= zeA@L0ZTJ~6+_o>wDhXR{#)EoX7~&d(vacnhX+44ZQ|KmL`;Mf&$6_Gr%Js^Dkw zThyTca__aEz#?DYtL4{NqMWIxxaJcv63dB9NO*j5bZCR|X+C@`CTbL^5e@S_I3Lq3 z#EB3srE%bu(=A^Nvb~IujEv%sDA|-NnSSe6CIV2tQJhS4YulT1W|DpMgp`gpzy;5Z zoD==QOlwXAXBWGJ67`cC1@UV|rhV-{7;4W>ZUH!+FDd>qHU>Px4E;fK%qGMW~{aD7P}G62*_;=ikI1)S-`o zwn68gGw!pk4q)yBZk+{-4*b=S6TJD2!WCeb2oY!9pCh`yd_r^Z5N(7YQoFHwyS0RV zFM1vRZo2P`?BCIRk-~dftUkXIXZefvha&w2#D)lwW-Xy&Q4AAlY^SqrNY}M2I;{7ABPF07+gvITLcilF*E^ zCyGc?+zJM)c~%9rnnT^REw?+ar0kzslwrDh1fm(3Q6Hq^ZM+rN{1q_Q1Ug6hrUijl zi@RMN`3$<^$>6|P--A84DQ|-{B^@)?^nhDIgQtd+%Xqv3$c&z4oKJigIJt8 zRI6>L#1Z1!hn63uXg$s&oldK%r3?d^#$i`rC5jxnRrJXGQLZpsf&m3R{jhQ~I z)atO!JFt%J7j1Xohzrk2c5?+qdzPVJMR5Ws$bpPn_&g1un>=Ipd4>UP00!pFUB&{v z#tq_nQbOsfv=bSv*K5xAXJ5p6|5`@O1qkGu<(;KZx|H^;#u7^=eP&X~Wx|o6I#Wb{ zhHT~P>)w`PX7<1k7?`6A{t+Lbc!9_cwgsYz&GW}t_+Fxdf*nBcN`O)>S3WHk*B!^& zWtx@EbsJ(kd7wUZBE0j;7gp^jy+Jf@pzX*;KkqH#&(^CfXlUK-X z;ur!GZLQ{nMr|e+%MV~qO7JQT6z$)Et1V!S>*w_TE09$pPz2LNkJf+e`Obr#ae5%L zSzBF|Nc-NzCtN4s7e@Iy#cVCt-2ad<;smrZ&lou6%GudZZyUw--2qTRc%5oEZ#2C5$ zPQAH8;=k1{AFEDAi;+lp5o9iGA3a!n@000pW#$AsH0mhHpd2@gW}kDC;tTYazVT9k2Cx(F|e&7`KHL&*w~X|g9r3~93V$8FIxEs9x3ZI6F;}xVE@>R zeNt2Rg5%s9ot|53yrjhGW&5dA#R7f-QRK9jf$i8G^8NvOcizSrF_OgC5Vf`b2j#6E zkl4>O0Oqyhs>aU?^&Qh&+H~vnea^OaaQf{qKF{7o*|0_Oqaql^Prm|SAAF>7aSr5y%b-oW z4Aho48b++s<2*K*;^0{`oF=NPzcyL?L9_hBFLt-%T_iVG*AOuPlNw0R&~_+bL|<53 z%qg=;ru#LqcJt^?p3p8u%-C)zzHuXLu)Fvh8PQq&_A9WXrm$6i{kgBbnFD@aq#=SiHSLF)UeI-t?h2Jlg7ys&QXZ%%(52jgrvsyGO|EwU6$6 z=xrUVnu3nw!;jMjUq2j=QSj(@3a?LP)cDxLa~l!muz<}K-Zv!(s>%jDKgdKLyW_u# zveIrv^5UovzD|=|-HAIPhF+J-hWVa3EnIjh?Lx(#qht1N~Zj{!JMMmgbnOPn1PMYvV`3JW7;lD@_x2x4T#5}z6w6((-+=zpV*Ei8h zfvc%70;f^=@|zS3^fnLPQ#cZAW>olRqAUaMDmW#Mc#z#Vd5O3qyxoE?bTH~^gz+oy zBz5kUUXeVsma*2Da4Ws(ur~8C3e%CY2FIO#|46p#jB|W7}A_x&a|AI_gL4nQi z$WV}?grUvXlK2Ix^i?P3}DW(hqg4zMOJ0$OM3$y!?dHlIjv+b&z zBOO**ROI03n1jUKXqtrCP=e?FM|NT%Adhb0YmOXS3w!yKX2O%y$V1Mw69wDO9#{AE zM{GnezTj5;fp z+Py?4jNkl@CpEhq&-$|RY}3WwiLG0qXKXZ?)@yT?RBZ09fi_csWcAVI?1H zIcA3RHxC*!vn#08W@iU&hEDDG8V?*EKDRF~hZDzZ0+hWm2U`Tn1(gN8?@Bq9hr#=ujRz&D4DdO)Rd_CDr7@*&Kf4^UTI=}q*O!V%6Tkh{UwBJ6KXSP%7 z*)qhD>^qa0W-r_9>eAbvo9@!caX)Q{w+*3t@`m7h3>@i>K96ACo&TwEad*y!wmoO- znXM+wkTPyyL?-1G#v6i_rZQb++XM$eCf{Who}J zc{C2e;mxc-Pi_vY{1>Jl;1Cp)$h7v?FSme8!<8P>bXO7W6_JF*$z%0+G8t%gjgtor zxeat}pEvLt*3G{V9uY@Y=Sl44%Xl?+7*e@?m&wX+Q$7E}?o!r%4BU=u_gNt-IV{X9 zDGCDH>zHdAz@)LkG~E#=Wk=lds(pVTeq(ydfFraLn(O;G@zgUs{ETsUoAW#x@w7p3TrT?}&U?}$5@(RUGAhdZj z_W&nKnUV@`9U2Tbn;Ifr;YVH#y3daIIemw5U{B0_!w;2$hIVGL)U`G=bQ~Tg^Qd<~ ziYL(zU3+2eUKcbLx<8tcwW^H?DI0c81;^INEJ@mF1y2;uy^BR(qT5a-VEloM(~k9M z{8${Ts)s9lb|x&PnnW@WS}B;v@k9vokiS@>%p-zK4(Vj{uZt%&G>D(*+kf*YC0DeM zbl->9NRjmmdMxN-1wi_JVn^pl;fAvbTYR@@5ofG|c`}Bvd$|_E#6_kN;fgu%U;0Fo z0RKqCgJ2BFD-? zlxG%jiBvTTM=K6=r+7v@jw)9j!pcm_!Cth-84}ikT3X9d0rHjR=fqJ6D^*lfrU4?r zFjh_P7|!?)z{jx9_Mw4caH>j)Z`mr3Gloa07J-65xJ-4X!se2~K&nkW@Rz+;^5z}I z6{k0N@MntoMjW~px3NtUmLzYV3j~NGyPn=QxWGe3P2P)EZD^YkJF#=P0`K(V+usnF zU|Q_r($b!wcKL_fyP@TtsjAfJj1~T46z`Zt?Eub!Vd)8;?#0D#M|C$|Wq7M{=n>!h zrkMP3Dl-j@0mrEM-O&={%6wJ*DPHDZEsSx`vzrx zUw|d*g&Ezve=rxHP~xNTi0YR!^2TqNFdiu_fEr?q-x9ef^)^VRn|ttcIpzub+ZqQHLjInRVZNC;rkmyA?Q>zRil*d)6M~>PQFx@W zuy*o}U~Dv8yp7Ny8Q%@#WW$qs1W*&fCAN^hHt zuA2C5n_L!R6p};GpZYt!*|J8~=p(x3)zO)-4qXvOE9XVXV>vU1|75^mPHpye3`?pK zh1teL$VAXQ&eZ@ETXgUgW+9+P!c7UI<=wv^0jukQkdmTzp%{N$N&}U_BoW{d!0d_{ zAY|rUcz(I+B3r4e*Ecpw0Rn|96GUkgO|#1}sDA^sadC;DFGq<{Y7o1x1{M5?iH)0` z9U^rzmikv6!^5oOJW{Pn$ip=bCS)PM2XaOn`=c?27puUoum&zu|a z%|u=nNVEX7C2E^0-*oA=b#ZaI(~TSylTI9b%N4O8Oub)>UUGXYAEa-mafq)m%GjBW zv=FYW8qsrYnzAF=CQwG0xcNZVJqKb~isdE7vpTLDnp?UqHc=qRK1A6QhsH*vk`L`| z@cu|=Jk#8X-&}gIUrKi2w$)kikIDvIKe=b-vY_W_q2pceeEJ1uc#h06#fvz~6+E2- zJv^?HH!A&f)^O6$3gxSvE0i!DR$8k7j+h{&b$82d*6UjAHSLYZjdTWnVhr*I%q%l4n zm^N9{`^SwA`p(IW@Ts6QuZ`B3--u@r;IJfsms|3;&ZfZNl$nGeRCr91p~G!!aV1uk zRVHNec?Pl`%*UfEQisv3=^EAJA$ofOT}l+S)#dMs25tFl9gO0>qf$g++k1wiAKJbs zRZyZ2X5XEFHZ?b2)k*?JJ6KT{ zB~>|a8lO)rEY@aTC5_#OUBwXx3MytXr*3}}Lu@NF8t8Ip2x4!$ozT`X93U8bDr_T? zV)osI^1Sa6yVwTcTZW(2vl9i*@SD8FMf8VaMo9`8RzxzQKR+?EhgcmKxtAGxyjY8W`Zk4X}q=)55 zL^XS?`sF!H&6?}a^MnV?#kVMTiED?Y@Ec?=CYpKDggptKn{k`M%4}E&FrvXe^hxt>@`_`(j9+9vj6f|&|I=ka=;tiv^l${V?=5T7!QwDM*gbFzK5bLp`bkvO26q^F)gfFUl~QC$596j=c~%{ zF;+F^rntsdNKcomq0*ZTRRrtTXO@7_;z$9)+VTPuo69m5HdR>{H`JKAK zhjTeC9vvUE;yL^2mjhXoFUL^qfy&gnt^&Y<7zIQy^9mOFS=Y_aL0-i6qN7(?b!g#{ z1$2K+6u3V;WZnDKb8{mAde%L3Q_gB3!b987PAH^{NXquLOR5e;uY|F#u&~m(@x&-w zXfJ&I-Zln)FX5;WofhLQI5|b5efWFb9?FS)ywuX(dOw)Ovoft73@bX}$atCYgV9N? z;giaabL!Fi?6P>%U4I~b2jAFle-!_*FOZMautW;CxM5r(lGBu&1(1L?ARcZw>d~w|3L)Xa67b-?kP%Q8}#4jisvVB)y zd%!qgj#kepfI~Uic7<>#>|OygVxG6^<_rmh^HN^&ZJd;x=1K=Yr&Z5k{LilAnyG5) z!G}Jf`mLcPQ#PR~NRFg|`mu+ShmVBP{$us=FY7ZYOzVE~#lrVh>MIO10#byF2zFtP zBUj^65=y)aQ7`Aw(Gky$iE*3hH$66xeA6md4fHWxiv>t!HCNlHP<{eKPm9JVle-3w zW^&N?nq%b9GBY&I#-8)B#|sRR8`zIGi{6GJL^9Vr5s@Y#ZLdq+aO!M_w)FOza9o&V zv$Xm;IYs2=hAYiLFFlRI!D!jqXaph?G60rO+NHdgcU|zKun*4ra9+N?Km2w9#jD^U z9#)?v>`vXLkx8S(dd*Fa;5X3RFYA!Dn$(^kLJNhJ5{#1lm1%Pj&0;?H9~a|-CDOJ( zJT$Xvm<1SPzqYIs>VqwCy`TnW*1;`2b4q{h_&~Ne+6FTN*;W2;{LQEisor0&qAe=2Tn-1ey*hTvU!wGcYYE~W;=6@Y;(2MDJ5WPtgUJy zM(us2;4T8E>AJkHO`8tHx9vW4Z}cXKpdrBPkUItpettO3J`~^VQN95(ga+x0L0cR# z6$*DP#?doA-*Y}OIeTBnQ_QEc)+Yme>6Zj_;Iqc$_;ljOGKd}I53TOw`gWZnSt3BZ6ff8r*B6vcERug7LGD@$zOG20;BoTo`K`uV;rx}U7BN#LX{VGeI z72g6Z&V2X}_S|TGTXdP*gQ5cpa12Ru*AG+*N3+M7cgq%Dy!v`fcC;DVnY7)f?LLT5 zVKd3SD=NRD?HhDkiWd|{JmgdrH*fw?RX`ZGN3&F84!>X+fPjJ0bV@i9uXnakuT%qM z{;E}#e!g_>1`7^A&>MZjCHJ~U>Inwk0o`#MOwaw$iznY5UzyX8&+OMgfA4+DThU`7 zC@hlH@&N_50-u;vPBk5X zjo2!OQ&zb!(V?DR1qZ%&0fWi6zzq6Tj+=! z{4?}Q?+-48L`YHN00mQz0$e-5mI8vfv*rC`GKQ1fDPw(0tH4hO8<8;*UR~W1(|`a; z@G|rE@*&8mu=0~=#w?r?IhW@m?KFUeNhYa>o3?@|7SGYF@IkeZW!>CKG(#;?%BOfj zq>y!-qH#>58p_Re&yIbWG_eOMVjD10BRgO)&dDD5_z6}>Gp93eod1G(aQSd_Cu%>MHqtaSfQMOYW}?Fg_|LOD>7M!?q|^)sW_eo3 zSZ!{?8rZ@S)KFWzxUA@U_>2iKdieg@=safm;ixWa<1&l<$pysCQi=sM2D|-BY8LHH ztea`IOc8yuLxb>-5@v4w%NNCVFOz1D@$yr+Z%%~KtXPwqyGHmK&_~f=t%DH z1QjmwYsD?M>-tP?puTZr)@UHdlY_5hshvs7_UA}bI7on0lsEQ1bRyKw55pmZEmD&+ zf~*Co*ItUBAKV>fFUC~ref;#^*~F6om9_LEP9zq62@4O=$_H?H67F^5`X8FkGOEh% z>-y(V(%sS=5D+OT=`LwRLb{}+yCkH$OFE=ey1Q<=LApUoKpNid^N#;V8OT7-b?v>@ zTyxEzsA-olho*Z~!QYF(92i4U4(>!r#pPpsj(8Ax%iNpc@7}2l zN>?;TdKOM@qIUt&B}^*nbrl4zg8@gLveCFg!~zoaRMYHQ*r+{Dp}$ru!E78+4$zT+ zxfWcrSH7HpFLSrVks31e_r@DJ}<%YRb?*}Ge(-oLMPtG3S9 z)~|1QC<5O7ACgT+P&Pcb*Q~bBthQbOLdlWX^x3Zo&LV9wcU4U}V#piBuYzjl?h*P& zpjI|5c*gyzvd7-c*&T=<7Bsh3#5j85c@&^3zT7`t*aehD_2#1 zh8k?fnWl2|v9Pj2AxfDtadq0|Wmtx$!R12|79QG31zvh<*Z^tFFZL(59Sjh*ib-T%z`HN zA{JcdNe++gs(}gJ637&IfeS7niF&s6)Xwgv<)h7~6R11OswfCi0w`|~zXJUBUFkfw z_Rh|c%juuI?hgr8+uAxyHP$v)TF_cMZhS#>$)$(j!JKW$;6ecHWlhqO_9clTcL1P zFMfzGBOhmc>P?;wwx#p7ZnP^3Vn<3pCiJ7+ClRNjMTe89kKyCvb68-SLT(04yG4V> z;N$e48?Rzw7QZiZttjGMnib<^d?~l0+gk2PsQAExX5K+R};a~{3 z#ID^U9~fIQZt(B@+j;}>zEjuGiBq0Fo&Hx_R9RTG5I4s_N!4+&){w@k-6(t_P24JC8)c}C)RHdLkn^XrocjF~9Xu#t>Gv}PrOe|ys!N6R} zCYbfw0b+V(QzjKQ?O{p)y+2Z zD`ZbHbB_^LUD@d6-?XVIP`o`ZAObw0so0ArhAK%=2b;YIk^%~W7t-TLCm>VtgmFFM` z6a?mFuTid3K5d+)Up>%n4qLt(aA2R`q>Ral1pgZ;ZOdR-=gWZK_837`+1K&-7s!> z7G%b1%+mN#P$F!ni_yc39&1)?5`7J<6+0ahD&NaCLt~a6U42}lwhlf#6B^gLA)Q>E zR=00>t~dV!DKYGY)%f}aMn?p-?namK6o$vcj(D1@`$ zphJoC1y#$1z4f~Yc5YSk@4P=R_z+~VhDb8!88pB79kwf)hQ8{$HcAB%p0|JK!08$T z^UMg|z*Sy4j-sm(X}d&J3c(q$UZ2^&_T&}*YV?L~AtI?!^a?_NnKy~8G830JiK`D{ zi|ONs{Df=J?d1{=hH`R%Dw1Zbr>A$=G}0V(?O*u`9}%30D)U^K0yw7FFWMYd*!2xF zR<}8!+Hasdm6esVaFOFXX|BQQLIVFm25((}7h(Z{st(l==Alr#G2+)=mVuJ+r=4B# zEo-_w{b9y%TXzZv8RqOo%8>&v*}oaMrD@&ral)vlm(w>Y^nYFosxMke48yp(XkzhR zbvos2>ErgEp5a)@9FX lF)8H@+Hc-of*>Yn%Tbw3C&24$w%=rmY~?Um-)iu>vUZ2A)- z_)`j;nW6@dXEn^z`RU|6$2MP;za37H(3V9GL-RHFRptI$A4EXlN|+nBd4WepAHm#x zu(Iv(C^OLJDx&h4Ct4RwvhsXL+E4SC0KoS>1kQj|=FfWwqb#mzA?F{}SeoiVTDxsR zx}#A-Noo`)^LUGch5X!G9AkXU5t=#fuV}xVhxy0$*CTdWM?TN&zK1@i z#`g(`HGA$io8hc>E-p4}mFNWfPD@LoNtk-R2bahJT@#8QI0>DUI77l-6;*`?zGIR# zES;6oRa^Qc|J~`;{Dq)O2`D#b64HI?0+?Ek$-*uHG_v@6KvuMa`05eJzqk)VdF3Zf zIJ(*KI-bH}a~!7btCcXXpe8s~ zS7m?8jEv4@;4I#_osoHpPM8$?s6-q@e0h(&MeI595z=eYUK3HD%V6i|8J^30{`Bbi z->xHAz5RC%Cc-u!J^!gNfOXry?0RZve-5o|_Y4GgCpe|nK@NoL^>t%gOAqjrd$jd= z)QYCXG*PQHMVi9?*#Vz#u)ap4@}6-$M79{ebzk`ABx-V^}id1X63q_1)C>qK&Wb(40QSrdwFDVg_??eh~$NnYoIwbMDQ7#KAyZoag##Y0i6bz2XAPA zpU0{2VM#KG&=2|i{>ukS1j#?l)7}JtxyWNd#qaX;vzVaYKv29^$^;*G>D z*fh+k_G(zXg#IWgIXhWt381GACr{R5779?cR?X>zyE66+iXLF{A7B?Xj=gXB{0RG`D;ZxI}{2DuQ@Jq3a%~_`b#E>#R*?R z$oa%y(?HUW?0B&q<3LGcJ>HMi#y1$h|5`eA4KUfbPT2M=tY3W z!Fynf9UR=ctbrAkjk7hx{%3VZsL1}r;eEJY@1{Ez9+b8#>eS2ajw1)~z;2v(V0`>^ z01`Hok}&_WPmN9PqOKAO(s_WUFWj{I<|Ww#a}_c^q6nKg8|G>BVX z2UUNrK7GNK8ND|y+yhXn&o_FCSK^?NU;#Q@AAhmBm#C#OA>!Q%g|>afqYc`Ohzd7+ zEMEp@vmg}eCO8cv_=H-@wt2?GG5^x`lYZNc4BNU8Rh7DUO0KDjLB}%6R%r#k6ZqY? z=%KRx@ioj`LdsCpj|%cz?lp_nP6~g#K`lvLWD+Q+rxky0Tit%J=-IJiQ>|r--N)|b z>D@~s`@7?Y??YKklk`L{aR3!Mw)R~5o;$-ITp$Az4D37eiRcI)%I<8DSJ2UwK!2|Br*4`I?S*Ck4)xrzd0;^&`PFUOblC}6&bG8=TSQ`%)#cv zQdw~cTt7lcuJREbL}uD-J(<%8^VPB=IX2Z!OmB2w=C1xOexziGH~mckd&1v~cU~$= zC)x1rckR*RLY^QVq}m7}?o$u0B}`F)9`EvgGy?uyW%U!~c2eDic20>U|FrlAr}B?4 zE-wiZzi-=uA@<|bdUm_9aaxajQ)c6wEJbd?xMf}UzvnKPibaIGec5FFZefY!wN8ub za=mEfAD<3e!34oCLS^%x%JW8QJ~-nHVZyXPgD;;*6>2UZ4ZgD~{_iI+E%U&v`ACh~ zQyYCBmLjdL4oGxMBA`^&F16c#J?>vplEB>U7=VxndWdyH?w+erjHid=hQ_LMz{(Ue z8g6lQd)|O=_k1Kx*3h^)dlCeR_V$jh;V+KTN2zU08Q)IL9t8Rfu!u54syv<5z5gfl8*Z4-)k)o5Yen zGbI|;@RLUV3-2P=X+Lq}?R69A@97DkpH66NA!o-FSh8s#gv8a*R{O;TCpj&X3Uff@ zqOakfI~y~)c*1BDFc(E#QpJDw4ts9SNS?!tl07&{i#dO?I|B^kD9Q=^Jq zo&8%fvg7^0Dk_%)w$bI18Lf=|sLqR31KVoK=$@Oay&v#u9-lR6PrZ5DpFMqK`RD5F z%y-5m4~42`>m3=U`le{M0e6;o3gM<>FH0SWjRA99&C*$L*w10|Lid_&3el(65`u+B z^R=khJBeu}r+qr+4Y3_M1S1C2t~eRP;N0ItY=cvD$SDkHVIZ)XoC!>f5;EfU7DfFS z^?76w<}v-==~23Sb;vyWa7?;QHO)Nja#1LSTepv6mfj2fGV-e&5j#5{N5(|?G;B~S z8?(n1)KksDzjVwE>c?KqRZKc<77e~48T1jf*LW7C*LYoWgcjfBSvxHv)6+k_Ua>8X z@bAo$i(qDuT%+ee-p`Z#NZ)4C^zr8Qj}ARMhdZ#J|2tUXOe%4)2nE34_1@bbqz>aQ zoNE$GTcmA1-lMg8-Kw@E!O0I#5YwAl_kYjG$N^+&$5b7)Oj)EJn+Blm2Hu!euxAYO zy$Oc{MS7Z-t}YLiAT;$~e$L9u2IzMMU$-?iHg*E~iDcCD5p~U8j*Qf6Q_^D>{si^F z5`oKEr}+^4PWh1XD`~Qx360?p^cHR|xpcS5yqc2N+ZMU^aQz0K$D>Y7=f7^K?7oXL zv2D4h;9h>Cx>puX6UykfM>|q*@9pVX>Hw=T9h%!oL+~9k@h>ech3_}i!zadk0kn-_ zffE;gu+=e9QR8>B9|&D459-^x7XpDfaRo)KavjnW;n`NY^M{Mu_Y`sR4=esuBEM{? z>p!oWwSfl|ev@}9Wne+vH{~~8COLwX85WkqT*D{i$!=gOd|}19F?{HrHMGgr52+LV z!jwAv1`UD~$-4D|Ceg2O)u-e zl}9UIIDni-{QMaGwfA`C4F!c6@OY>%vZ-B`U1HR&Zmz*XTZwoohV!XR=#=O77P>|qL!xT~22}s**gOLNN|I~=2nSMN> z1?!NVNa2T_ONDGkkvX_sULXZbL$uI#&k+O!FuCjz}jah{dap{;?g*cCyqe)Ob5+G`} zPM)CsH)jz)Fo=>PZ+T2*>fFhcpb0fiM{Nn8LK+QxejC0gUhGq*+ zboKt;^YIBhz}DP7qoa`?531TtAhnd)AY!t6I`OpSC=F524=$x&pTM`~A%eZgQpDpw z1-W5 z+j})ySM!HqLr6%de{vEBXj|1FveH;b2rMiz<9r)++Jng|=LGHX^tcX}_*d_Vs&nkU<#c2Ikt_qUc}=J5J|gejNRqsPmf*zjpUxR(Q|+8 zp}-rV;ETD1jTL3@;!-HD++XJMOKQzy{=K8O!Ms}3@CC42fBX2lA4q?C9X^q@(`u#k z!`K6=j<@~N3rEyd7=!;dQ&Q1;e$n3t+>g+skrY^GLngEXlN2)dK&)HwvmL(VKhq8O zX@Osx6fsf}lLaOl3!YAaR|@;LI$EuDi!@8?7y-4EuK1x#k-8Yu;`ZnRCx37ffJFyu z4J)v(s$y))*xW_|1meJdq@?*@dCcMPb2NT3JlvdXpEEY$aw%!QaOykie=RGt$QWK9|>Sj^d6_6m=|ib0odQ%+BIRI>`BJuYpcb3_1%kn+_R)>;zdEPVEv-2 zkw!G}mmz9dyC*XvV@QOhWevH$iAfeNi;Pby9FhB3N8fP{E3SoPfDm!`LtAU>hux~y zcFq*{{@Qn@5!Ly4lTkAj6u#@ zdAFM<7_op-G7_PL5cIvy<7e_&^7NoQuC3Nj3taQQCKvL$$<{k>r)w=1`;Wt#aYF;w zzd|rziHym(QE1&Ad25hc-m(+7z<~60wHf%ccGbS1uohtqm-KqHY=k{mQzLf1in*NL z5_Tu%*D=PH9^^1YYX=1)RuPzenly-a%)9QNe@Ude41z}_VxlymwSDWLuMrh+YNM05a?twoht=8sO$#83V& ziEUG?u|i}CY%y=-ViKm`_7RyBK7{~4Qu?S=!Q^ zOHdW{8Rg8UPdhC75iA-DfOgpnBk{$2xrcvl`**B2TM_g&&l zAWwdQDuGKj`&+vULY^jiqiSD|#P_(kXlE6Yn~qcXo9cN>AI!!8u3x>I29>F&Upp%7 z&z2rMqtVQ-g?appUU=1N<*iW`l~n+v&jNBM{Wd|bu#AA<^08*T$@m4=4H(WNrY|3J z1BJvM6e`SUghM)>2#hJps?9z?Y{*7}Z$=jksnTR-BaL*D%Vn#-Lv@M4aRT3Jo&6|O zZAC4nMY!*BZ(g_kHm+C!yM6iCfRl86ceh`*9uXPYA6u(lBM9jwgjKIq*#%!=3@SU9 z8UjDzXv9VgEaICdPZY&h?~kuN%D$<4#KMiS#C=$^=>7OxwkP# z<3a-vWVp3EKXUqR9qBj`5#O#>5tMW1-R9U1wOpq;@_6p`2}PRP$lR5xB*ZUxa zTb*?18;4q9-?x9sB5z);Z6?l-y#ZvEe+wnrmgnyaUR-^kPk7o)? zTl*a`FB1>59Ja;?7oe}bw5vN@q2AkFpZvj0`ru&2(r3SfoblA(#DYF`F#x%ckA z8b2G@t9gl~V;0pS+~l&-zqHk#es5>&`&rOT;Y&FIF{}I=YZc=T-6r;uIf1Y_2d*?f z6`RR7^TmcfJ(!;SLPGUaok&~f#DIVCZyp8p(iu^K`D|{TFTnjbwLp(8`H7;TGgo6D zxF&b8myZ>*ddQ?UO#*@G&GZqhWA8Zl!DO$l!19m(E9M|Xs>U0 zk6r`nuoJ)TwpNg7X5REMO^tmZ%oip*adeH-puJFGT4b1p7VBrgYjxCRu)lCEq{F)lZXh}AUz5`jEn zr#pPbX!;T2Tbge5>(?rieb74#vSF(7KCh@r^Ka*F%<)a}fImod@16Vk(y~rfic?T} z@q6m187izP$zoH~{To2x@yoju!N+bkn!X7CTmIRmEYg+dG$#>pasE3-*HZj8=3Mmk z^>x~SG66{tP8_UfcJ>N7Vgtz0Rp@IVsA?VtDGMIv=LB%aDDs=l&zkPiKQX}mu#z?Ih&k1 zue+2s!l4g8w>Q^*Foh-g7!sG1$Bk@nbAe$8idgNU{E^`t6Ntv_F{A`KKB)IfN{sZx zIf%5zTOKjTGlix*fargvT~MF81^4`G3rwTHzgUx*a7iRD?F%3*9^Ro+M4M7!igGNTYvt^X6HWQ3TySHyi3CmZEaCiBB@aT ztx~sgGmd~$@<@Tr-J{KmwTtT7gk$3os;1WFZZ}S`(v@x-`X>=}EkoNyV}v$`Px$Qn zHry}45P2cAVDqb_3quRcgyxSj0^kSBmQ0Z%Y0G&Nff^!xw2Si?EFfxEuw_QDlZIt& zKK2MM%_+fTac9)udf#4N;xFpO)!NmGo!rFEAt)S@R-3-FcI8LE^FByPrc<5|S^fgv z3WS`SBsNj_v<-53#lmUY#5lHvGmnW{3|~xn8a!Xbf!fdGGx<%kHpZU|;K2Q+P21TXi_Bg1 zi-15jNq$hui0X#h&HwxcLJlXm9M1h+6 zsvqn#Ono~C%w~)RM#;~r$9EF4Y9;}CN|2&HBm2$?C+}=cHb9lfOr>}okf6B&fH{yDk?P~mz)>EIIHHRn+ zR>}JIY*csnm4)!$RVezpcDjusS8sz;os-T|L ze(fY61^mAqN~$@N=4I&C77P=Qs{@<2B+uuR9ikmd*MlByVBFb%KOoI{_((hTgi5eh z>8#uHht0paqN(U-n%wZV#k&YDJNsNO&Vg|{oLAX}0SS!Q;^-nP2yiW}^Eob;9!|EZ zaiRvV{Sk@XuG&qH#0>DJ<%0CN;n2AF}Sm$JD8Tk0|8jMniAe5xfOljuE2j zb<>0JUkB*j64a0QoAfH39e$Q=FpoId$egoELz(MWZFHSiG+n*-N^~f*YGaoD$dD5*3*&f$u_2yg!@>(-o9^je?;Pj^n38u ztDdcvT1x!g!Ir6uapN(G@Dcy+q{rRvkXPy(Oo#hpCnKx#KQff3vdv<~^rEs880|kwepmLbg6!IFGd5eBTgG{sQW^WcBbQfscge ztF-f?t?-DxN&aSh8Mxt|oN$`;1d=#XJviAM1I?x+Z%Z|;Ih!%a*q^+HmL~7-U!++J zU$&lHR2uixCHg}@=^;=I&e~vJYKF_bWgD*U_x+0-DGT=H!?u!f)r_1m?VDnft9`S> z`}|36ya%hseLB_{C5ls-r!+_eXgdqolmd%sM)Q<}ZV{G`2`PoVl%tQf&Wrvm_;dv8 zvG$xdel9d9P9pi4qy*j!jZ@P4N`xh3Tak)GZpfti@A45FpE5TP0mh9AQ;!me~pIfdI~< zDb2&UPAgbAc1d_I%@I-MYwyI0Ld*Oun|U>tft?hiE|#@N z-o|DZl`SNz%;RG+0rw7}x|Z@60=P{Eu^td5Gga_EFF^d8@vr+Aq(mZxrKD)o26cMI z6Gv9YdH0{efTt{9)?Pw=mMmJbSR>Dn`xPT9CUInt2D=tM4xDA%?Ka*`vtPBz4vo)p zUqR>bXgORtC`sSH{m$|k>^hh}K$Ve-G_gZA&w-e(T}o{HA=C|w2xlz=`!=<*SgY02 z?qqS{&-jQLN6b0gmt#Cb-?6(WVMS*j--;Fzj4Y<>b928QL z8U*+YN|?x^J%6nUuWxKX0SZ}`bYw^MWx0})l8M$pJ>nEPmOz7e{`M4Af@lCozNY50 zMVdwVl=_gMkWdW)>CUT*Ta0-of=%9T@L^@@vk_1D?yuMk73MVjJcEqC0e3s@YWLYOc2Y6cR3lB=?XSdZ# zOPl}Ri4!_fL$1Ek6hegk^MxtCZXbId3&X)+X8E;~ zHNKY;`J*TdF7I3hzUU?pY#19U<4d&JGDY)op3$$XCe6e~;vG6*1rPcUY&i61&r9P< z14QSK3le$CAfy0zy6Q{3b zqZ|n(RW=U}LU&^5q6Pw7nwy`Z_byUXMMyjzg)r|0fzc=$NIa(8a;gj&yoQ#c|9xzB z`g3E=-8T@e^h+>ek`p#sUEPx{+-r`1L>jwJkC;`~RFTC{c~dI#RKw6_hR_Cytf2T| zl7)+18XAILc4r(hg>5MlD{hTBLcU>j`}{up1LPT;Zny-7aA;Ju%g1M6{N#1L;tK2v zH@D+oG55@ykI&uA`fYp0zj#Xl-gHG?6?$4>7tnGmA83GY$xT_RqFq039mPtqIa3uK zjjBVh^8BH7y~0aBD+`7~7#?`{KD6})ER~~~zU}b7Cu{-WM=b^hy?Mm`Er4X-KpFVl zTitW()oCedkS>E|@kn6D0;f>P>NbeS^(L%FY%8=_JpmCLj*Lhk^4c8EPj*bFw#uKq zs#-k31XWwAI)Fzi9>o_DWdOkwkTsbsF)yB|VjKH&kEqDZU_qrND>CgqZh+ynl`1)t zZNm`y;;WwBpWiQ|n=P;pgThP|Q+zuqCS&O%=d?SO9TKiM{`-6(%wOns8Y-KvkNqxq z;B<9kV-}vihn*$)Eiif83;o2+u^ITpOtGzpCso3^oXh($D76MXmpJcSGkzdku%}8; zUIiaGD6o;ekNrnwfRR~zwe^QYIK1C0I4;ft33XcNuRkv(1#UQr@uz-{ci z{*tr3ckQ{M1IXXfUKcC;y$@}rHDatI|3VpXzdp|EQ^^|rcIj;fkk6%|Csc1`2AzZf!K!j41J{?X2V6Au4n3TBKA)=+>wtFv;! z$X-Pzng|Z{z+!P{$rdHoYuojE@u%%^u6^$}J*OvcJd~in-;pLT$|1@@)aie|Iz#Fa zVI*LrchiiqjzpGzI=tF(gzxnE3hq=1ae7YCdNARf}%!sF-v%Cu_%y37x`Qj-vq~lDA7V7;-=W)zx zUwS><;DCEpRxG-F{$;*J5QE&=MvrvF04=e&XZL|q_i{rPcsEIYs70mUzQG&-whneO zMP&^xnj^Nh^htxt9-OgWRxvNrl}oRMFI10Nrx-- zzE{x8JHMp1Mj&#z{GTF0nG_Ir7p+ zWQF9<{|UdVK!{7jL=ta=^}C*~{j*&yW=Gdlu)U0~68^m*rX1}(q$Ih6gq3gOXk3`hK28=}T;{nA|!*=&@S1tJO%EJR+zbKu34EC!Z&$(BfWi zLp*Em-*MQ?iGBO~x)&+_7Z}WaYes4vupc0lRL9VtO;IQ`VYSO`bTFY$bptTEs9Ue7 zA-9N&orwEoenD0^fpC*W9;iyfx&x!K24~Ek*VyD~{C`h&ybe!m=3nRxSZ<~1fziu( zh3d0%9k2d^|A-+QaqO#`gOEk9LZ2x~mCou>RKI?S|FF9QoC)`)wRWz%dy^WeJV8wO z;k`RAnP%a4i*jl7^SAISBvT2$y8&|0xhNXFCbr87Y~~PXcbg<$kJX?LY~ftol7Y(< z`k@9#lO_r;<7lGB=KaIT$lAty#}gONrp(hv@t6guVxzry?Ofe>%_aAdkoQ`wK2t5}jjxkGA$D%Ma=WZtx-s1z?;}>@U&!jQH@+AF%IWi}JRn zqF9TmP7WC?N2~7sSa^cwb84|96IT($a*7K*KRAL%x6dfB!B)8I+)Yf^6FnG@p4tsa zA2ZH)(oXnKTh+8piFJ#I~POB%;I& z9;U$+&S3E@;y;tt#2T5!_0EiVwW0yls9%2b?YvPFh|P}hkfp`MgHSkh87T7;9d21^ z33!pkk_xN(X`*Nn1Gp6eU{UsEvU1E3ug){@hCKAPi7}*q`z6(4MRgr`bx)|yU%T;b z9>20JuKh5zs|km`>7m2oK2Tboh)r*gJ`$nNgg-YNmI$i=$Lw+(71gv(pQ~gXdA2EI zl$0?#62%M-R7JU z9cw*XTX~q*xSjp)!uR&*C@8ZGBD(&WhI%$aVAN(>4OPh}9ernoq~=g&u5PtlpRSillD%@f*sbHHc(uijjy{~*OV_dP#n;1Ugg*r{V5nlb zkEz)gt;gIt$9_Ho?y=}_M3&a^Un{Gd$sG??50^iLXCJ=^Wo>N@d@lR=+UxJ)XH+sF zVc}Ak8d8I7EV>Ato2MQ;Tn&mcwPZw<;I>b4n{2PcS?UwnX{Qz9T77pMbTq1I^LZo%n$!zC*%O`&MQZtMARDc`m$Xcd7jCqH$zY~uJ(=e$%d8xY-9>BI8kRjP9ljfG3&gsht^hjL) z(Vz-tpJS|ziy#v)I^Xc$ugl^XhM0bs<%H3Ws`la>+lClxKDEY%W4|r>QXaqs^NYws zX0d#)y!a!6oo``#JoNRKa))jMfo^M|jvA93fefvX-~dc=yuz;y7IaMq=A2@&dkfaw zOaql}XYs8S*l;Gtito7Jd%Z*tE*cJNgB2SdOknQ5?Pn_zn^T1m)DK>uLB`tye`bMU z#psW1^FvaSQ%BXx1k+I7Fz4}jsi_^W!Y-pIl0Q17Zl@rN0F&shLQIvHEXpz%CX%Q5 zLFW%z4X4`cx2G?LDW13Em9WK>PbHyg*l=UXXqzxepCLx>pdKewHu^2(u;((u(jNOVgDRApKUc zB2bYSe)=keS1t0Fy6M!!#lHv*fPvtuwdMjG=_2ek;4=r+oWq}Qt}3}$oD#_p^zgFh zI5$z2x^;gBV#h2#rDL-`%sK{Q!!|-T>wPO${4CJrNWuw~`)0?F_NGrEU*6D-AJoXu z)q}-Dd3svCx0fxsEWBixnk+u!}+wyVCz7^2js zysKPTJqlr{IcpcqOooshHj|qbS;47h5m&si$O`#xY%k**Nk(IZ(iuV1X>UAtHX(9E z#rzDRv7}Pwe@#qULh?<^GD7dYmiSLX#yM)Y8xc9b3Rs5?sZ6a9Rd#W)4fSinp`O-F zLRHGo7X9orRDV?0q(W%JVH<8>S!d=iY>kJ_?}=&xyNYv^@90TM*at!OtH9Gb&bzcU z4fQ&DS7%+?VQt$1h7q>?t7>7g87mCP6mw5Zyj!ee_YTj6Qcnz>*x!u~Sl{+7#gA1!Koq%y9CFM8X>BDoczD`%e|u^qijH z)-H8V1mfVMlTU1qOM8)e2Mp_}NN3EW%CiJzIij%bU@?aq@RBALk{C~Xh`j3x)zN>D zg$>0RU=Og%dX%O`?0X;GGp)QbWF5k$LwN$Glw-8s8GTe!l0sU)CodsmzKp{JEfN=y zl6HQ1nUCwPg{9h?Rq8nIl?G~Id2P={Y) z>+j#ca&eAAS#?{>iB*GXZj3zcLrXJJr5^}cy?hYzvo|$;G~mKJ7ox@`?3c? zl~4y+6pPeI;Ub)wVqMAdG0Y(`96kbch)}9j%2(*>TDirb)J#M;S`SU@WR9h+XZ9yV zekClN)En$_*f3fI!t`Lvv5p~|-r$a`MA)e*v#Sk56<1aL@x$@}uzam4|m9S?o}6n_hIp;nCsY z>YH~sNy4fhM!Xpugw7RM!r*>vp|DN#6N-tj9@B<~7XLlGdJRy;s9>oik??~Fii2P$ zpdSX!cjWjJlxyJo4PaWtWm_|NS4T(x*t;A%Xb(hXQoxxBGP}0I+PCf>%@zW3B-fm(Y6;4xax{7w zJvt0~h{lxTP)46mp)fHOD=KH=yuc)J-eFZ)a!#4tOiNIz9j3ZE(*dF{cMb?Qc&Zxk z5(;2PKpnoX`1tw{*&cOsa1TyfR3(pF2l)Jhz2qM1=8ObLk3Pq@Nq4G--hW{+sn%rv znG~xnc}P~=2I4wFIKrI0YAMhT{#}IPgX^9Bo)WQL$Hy2zA3}nUd;7kXC>=os3C@k$ zl?Rm&e!n+ZYQCKP*!SJ3Ab1w+hgfC!G8-T_jw2GDX_`vHZM#l0XSSite@L3Skal2i zIxUW!1w6Fwe@0I$WqT_5bg)=FuYU28S#>1GV%(i`^C?_J=J@8;qyvEfNP1>w=4ETS zn;Tt5Kz4pMAY&wX_iUsb^&+cF{*?e*&}pjlJld|JEt63qWDlOr^|NU+UG~iO zDhRKw*7~Y&Fo+VH2Ra$5tQvhdKbjG1rZ7xBauXYRd6Xo#q6=G2eE2C$#I;=J)M*mN zScj`@SzlCgq@AcnjqRyE7sQoBU?Fw7%&Fk^96B2{YVjWoF02lHA8sc9BGW3DlzQTE zZicI*u%da;zvT1AT8vt#YB`Q9;#Qgn(kTG)*&`UM3aen{-c>4f=`iuDNbxzml_ zDb7?gte;OT{aU&|rw=~-kPC~gcRN9TEg{laQc_1HL=g>!(cpN{pz6{t)fG23w;KoE zJSV1zt)f;OtpaAV#o@myi=# zY6exK6FE2!APB1A+tRqzeMV5LH^2n!uZ_@-pO#&ZUYea9>|4iL5G~RWQ>WouNciNC zLO7EE%TG^`IbVK!v>B)ynXo{M{QK6)H06tZ1f|>P(KyS>yV%{;wKc~r8r2v#zKqS? zpu#U^T7?mlFj-K9&(waHt8^Q44#%oi#y;|AF?IzA%!xPGKXe@9gz3&QAAZR+J9pj6 zQ~1ott{Jzi7}hRQDRdlgLfbdj_;X8!OC9&Ws}<7UGQp{Q-@kQ;4KU=#f_sZm<`_Z) zXvVRHB(CxnM!Dh0_;i~;_KI6DN(%k<#t+&+{6kR*uDaI5^E^RGSm#78bI9U_xY zx5~4@HjVM7w8bCPZbnJ{C~>f$YC>6DLtg4R88V!SnWJj}OvaJ?$?fyEHtT%pak`~; z??MvVHTVutKIP>Y%_SXJFvzsv;jB@P%J}i+Q}*36kDT-lcGYM!4%p~oXF)Dcw{~zd zJ<3(V^mg3iH845@P>Oh(DQXk|pQ`hqBYERX79TAWlXQyeeZ23Xu=q~naM^@`PSE+F z^GCXjQ)s9OXsoqnj=MXn zf163OJ#9X_oC;^atKM8;@CM`oMKd^T6V1kGZ+aDOIzAmj+kB!^N4fOBLT8qY&<bXB{I(liD zxR$u8#7HJ}50N=#{cki)>XIOkJ@(C{7^WCS8| zy`&k7-Q+B=GDNTb6HiQtq@bI_?C`-ka8SyQTWUoaz8nRr4!&gdLBX&2eE7fO5?smH zJcAAo6;Wd1Ke1K##(lspUT)X=7y~ce&R-W zBVXKU)3#3fQHUzWgoCX`V8e?ejOMZizfGvR{JZl%GAerV<1-NLH$9J@qR9uQQKZd6 z(9~-A&DBXsWyxrVIC{y{#%>WMWzh}RI76lpwhr*s)i-svL*j_-rQGF68!Xu@PG;51 zv!8)U!K1GGu_vI0jC_DM)Re=`22fUdg0Y4<1jsPc_V}dtOu<55XKslVFA-2sjW|i| zANXixjT(C`YS|Uk$Wxf)xhz~Lqou!Lvt^A}t)9f}5q)7p&L;K}*6KW%e>a~lCt@Hn{Fd-IoR{oHl`7$B0aMkIq~b) zAqH>vN*9j^?9g_{wO2WVx1M@sXFD2e>p!v{5$2?LvmAe|V%od9j>9($PP?!X+pok- z^DWsJ0(YD@#Ph1=n0p=35&Lg3n<(8=xFjwFalK`AXEXBkC|>m;usHEjM1wl==I*Ex z8?M3uLZUgxtypZh7>DoAT@>kz9P}nP1&7gErTN)IrY7N3)`H<3uXH2@9nVa{o(8)0 z)IB%TXVwd{y2_1o- zMCa$&s~owBJSLeIjct`UPd-RGNSwVvOoY9zzOuJ`HRc@O-zdV(#W?S1PiD-SihYr= z*cZ?R=@G)&@@NzKN05GA=X*3Bh^9J-9-tK1go#$pYmB!aIHB4lKf7&&9*IVH0*t?u2J$<_Dt`GU@FLGquv_A;&=759*07o(Lj|-!xE}I9!oH3?2mq#fKWk z4p!(V?)Pw<%ir{H;f;v2Giq26Ta^!#e#9ej9lB|omc$L{mrr#-0uH=_E^hPV7ZJS@ zOpqWYxgtG7-v@1AHzPl7V{_kk!^g~rr9_OJq8Pjh^sQp$S;ny0<*^&vbolZ4oZx?6 z0O~CdXk)|grg>AMC@ES2Vd2*)zc6}%2MVb6T1h1sP-kdz+V}U;x~S^Fk)~db66sqF zv1`KT!r`?fs~JfhDK)Qir0TBbAu`dqx$anY z>oosm^wvUFn~3wTRbbF_(P|0C`A`aPIoOnU#j2{nWJYKBNbRff#FG6JKXy#Zj9mgS zJJES#I^ya+rt))ib`$5JoH{hkIMT&gK@aE_kFGt7nBp8Lqh2WBemo*TN56ZdU`f^q z{)RJ1kiZDsHAGKkozAZ^g*v9k7@#i&iKpq)K~8~DP;3=+6D9>Bk?q*A=r_iU$YRmy zuthWz=->j95!^l&UEt38`8Jd=554?hqdZF&mHf7(c{7U9RX<&d{|6jCih(h+0!QJu zf$ZeVD*-;Mp`6HYTc|~7;*#DcE$YZ?woFZVXO(OVHw@y#D%=1WR1G7Xx*_5O_KX5X zq<|a_ZqG*wtYq4?A>exC4UK`}tcAZR<#w9W`bThVYt#1pI=n#>%&TbE^jn3Um?1K4 zWXGZJ4A1NbtOza&ZsJkl1aOkV0hALljI$TAe@1Eb|9Cpfpt!oOX%8+L+}&M=0Kwe` z*8~Xe8l2z~+#Q0u2Djku5Ind`&>MFN-^p9`eE+GUrsm8(d-dwRnw1(jc8b2VfzPl? zB0a7n?POm{GXV*!uBX&t)1+taXb_unoQqwrT!-?ib$nmKC^w(_!_h6K%Y<{W#yC8Y z%}1@2A!(iG*`=dz;#@~xxiYCmb1#!rHg`&MeM9|UfBNq}|7`l)y5ilUQ@c@ldE)=} zRdJYx)*2Qkpn@4o7T;l`qXd3Yx-65}+<@Bh!itNCC8%P2ujtwzt?{y6suo{Mvi|J# zZ$L*SK#qzOYIwN5^@4lVk2rxf%9*kRTS`oC1r|lpLVF6TYV?4Sev52`RdtdvLPl*rFGf1*nPq9m!Gn! zw~+Mcx>YhxQuMmb^CnMbi1kEQ$PNN4NR3q1%N~Idhch(v3#qoWrcs@?Nu4%h8MB>x zgp&S+W`<6^!KwxQmR`{>uY;^_8fwXu&X67MK&VN;uKdC{Fpkw3vML>f@B}n*r+fhA zbmj`bH=z9pAV$X@qfIpOSmo#40!u2iL;q95hxbd>`eo*tVcMa)trpo15C_*6}S-+${l@vf38%gx4^7GEEB z1!`b`ivZ+`ew$tZ-SNkQY_y>I_s8W*(~pW1rbNWrivX{6;YGY>Ad;Km3s32fiO#3K_lph2VC;TIZ2kE6I`eF4%*za&g6* z50NB1#RE#9l1ELb9^S;LKb9O8P@=N5@nfPej0=y1yR9_TbdreYeUEB|=o~ zN5ige7xaUUf10`=E%ckpMu+-G(Q^4%n@ndRa!9&je2H*pGeAB91mBJ}a**q~!Wqi~ z_J%i*60vWoS+oVI+7gUy3t4?vtBTfIR@oz-w=<@bB3*vB|B4tCm?#4<+!HMVqP8nT zqDCEf71VE@^r8^27GvzCSk*!18Zu;p0Ot(_V|H5QasXm$UyjQK$?f#Ky=To z!tN^cMoB5rJMY#i&0EmKL?L7P=?vqE5H0M6@L*kMK{9oQ9D5M*0htW0sc}L5uED=` z;VpSrHvVRK7lXVHxf2NO=X7S6HDIR)KeQloz9$4@%0eXc)wef}nxVBo%_p!Ui`qVN zjoh{>>*b$vNm)gGkX4*Wa(^FIn1Ig>+YwnQAqHqVB@r%j+#X(D>Y~^%4CcE(PM&On zs+be|2t390<1pu+i-r@)U@U_$9Q6(rkmRuY5B9N@G*}*(={M`^fRU0VRDL<==0x@$ONF6wH15?PK1I+LmCT#@Wn=j}{~EmqiSq3tJ#KB+x=)hu>#}wncC| zJxA|5BiMrFE!Om&8F?l^=-lhsy!aYg{piTv!IEk$ z;;F&nkd!G~*5CaJz&too5WaU3A&pHZw-ZjAn96`~{RYR)Cs`sL8C~~Wme9|g^~yUn_+c7G9NqrbONER5!;vkBii(TKZ9Vtx=Su`+DND8SD@;5(6uaO&Ev zmvG94#?M8VS|2!0l3p*uC||`v{z8KceXnD|`5}q?32vn0{Pv4w}$g@PK?XCYg8bWkR|9>a3C$Vku~WHz!Ur= zBqFlo!|zguEASi>pdaXy0ls*62;Y3U`}y#r`w7+&wt|r8 z2cad}%1y)<(8baqxXS&_zT^+6hS{)g!lFfM{<1AZ924&3(bdy)=!WMOv`4WXno@>e z^!VhW z8bQnL>*UfiIo%b^TDpo8Ify$a;nV0L@oTEY(S2n!TRl!R4n3{d?}c{vn5)A#8L~hB zc-LM=l1x{p@gqZcp#ss|4fv%y@sT@@zEj809AKV^B280>tzezTP2mzja0i0D`4*=c zrp6h4t;p6{J;cP(1hQBKe4#Nq+1RXL)=_$UP)j%l@h32>&=%V$)i^QU`$zax@&VA?1#*bN8mCT^a4C+Z;lT_H|_~10YNw zu9Xl5bUKul#sOYhd9QeHfhiZ*Qz9QU@=t#0h+>13@jeT?31TJJ`-(Xg3GIz7r3d<96{?W*5 z6*DFD_OP*hwF-llT;Uf}08kJ`Slc=NsOXMzb>7#-U~!Rfx0K;*p(c;qph8#-d+K?v zg#cjIaCO$(X>&c7lf9SuUa1PCpM3|S<}W<>mtPfr#&*S(vcH*Qv{%rzAlA$o<{ zHheiM52gNpEu|)b;HSz~=P;lR0t~gYq^(Y3hJ z#+3f&etw`zDU=nkwW)kCqx0cq*U~r_wT)E5S;%^Z{$z0zw@?i-%)uOyIn=4}5{>y> zt*-6JM}VqZ?>p8CWleaN)2K_bG>joqlWLt+7~D^d!&Y(p_dP^{>e+OfqIA}t{O>8W_%hLSUblUsn^7DgnEq3&GvtnhqJAQSf>(jZW_*!- zJCOM81p>t`=zzH0(%Jbt_Q0Y6=xx??H(NZ_Gh>4NHpWR0MI8v&_wi^`tPtXeFG0x| zvaNR(F?4L*`~IthFm70zeNj zPF}aictFgSjJKWb@iRTjXu3`XS!o11d*bMUniRrWAcJ>g#M8KmW@0b}vmA z#fesgjiEqQN>p6pBOY;|>R;Z1WVX!uEP9!>p!QtzP11MPvke$AMPR1IxcnBI65yYa z#@7UU-?bi@Gll9zj@-B&$#AZBcWs#rD?@tjLd+zbJKr=@E;MN~{ zIDw4Igf@X2K#dIBX%a!R&TJKg?fUag=LbD?|t$*aymIe&#~q zfnwu=^F}$}C5)gns1tM6J0LSMOGm7|gSCK80JQ5`wP1tpQfb-6fbJAb$$Q=dQlK@h zKJWRp>x_>2Bu!Z2PU}&zPfiM1t{&HkxF4wpK5>4Qvj`S=C*0qEWnM>zY0;Zp!Nqi} zW<-?&GkyRE0IaB+C*c=>mqYfq=Iv6H@FiyctLD;Wqv4F_rBcv8A}4TQ4X&z)h#M{Y z%*`{7%Xgpn@b+7A(lS*L{lHIQO&GK#q0gutI`vq zm#d97<%`h9#S1FxjIiKi? zu{wiAAZ0?4lY=RX(!sDVODbKKL9Df$cRQSH(qz%37POTgbd*J9A*^_Et0-+9Z726^ zn3d3xt-VVF)+VEUjH->W68?~-A+t8k9$q*4*DtIeWt9z*DktBn5n-mK#p+~9A(oIB zB{YphTn10WAT`Q8+3LxVV8Xw#H>T zezlwfX4|wOWSEn3UHEKe1}&lAZZV@CV0eq_VF>jJKutp1_!d@ULwwd~KxG=Q8jy1R z2zyS_^l-63<5)#)250?8Vd9WWdB5SEq`}gRmQJ}k-7jofoo^M@5HluraP6vH-Rc)e zck7G*P~k_z;k-6cB2SsO7Kg}yE<>X`H)+yP?8~Q&ouwiR4wWKfYm<*pFZFa+2o zE*sC$Fb27SvO3^F9Dei>*TL6z;026MKpsM_o*Z9@TT{rWctL(gI}8$Gt_|3djVdwu zi(=dL*uN_dd0~9g8oV^_=^FirB2b_V3V5_b47k#ZJOUP&MD>+5G3}$lh>`~EX)M<5 z0drS=RPerMfaUr1Rd_>G#H49?mUD;O920km;*KwegD`f8bCODF#Oqhvo!8ubwQJ1J zJd+|%nV%L%%&%?taq~nsEfWGQ8=Ku2IjE}c`lTbl>YSl_k_=B|{c218?`h!oJicu%0!Z;4PSY)KP?tvVV_ps97>-PcTg@WSU!%eQOGC@^g&% z))ICd-I&p|Y#&@fA)gE|Gl*oH@SV~aQ%>=juvu8664sN_Vh0A+H6mUquzcPmkJYaF z)RHx|bp92{Bk^UkmsOBz;i-D%0sMKoRfg$^z=IblD84g!HceDKpG+!ND7ELuQz>Hx zjX(Ux2j@0ottFTgpjy}LWJfBH`SRgy5X`i(SM#Gxi|#vpY-Q}vH{RAiP8Cd6RLJ&y z0ok?T2sdaOq=svI{ds9Nu`uCV1g@Ki#~rkk5Ds&OmNKteA$ZL8KWoZhI%|4oa$+;p zVp%hgyVpa53F-xn+|%x*Y%Fbrled2uMjXY(%L^F9{3~9Hds2O(L}O1nu-B?A>ei7D zFe;Lh8&FMg=-vSLafEl)&XjI?Vf|DH7mqRS@lqy7)L-|1(}NqL@2D})#n8=k zwzjJMDJA4oIEe5e(9pJR%mli<91Yl~4^ZNE-qWlv%^ejf${(?lVaT$M#Q~Vnvdq*+ z`I|e$pVxx7mpZKY^XnG;`JnC(KYxzNqrecxA+7M^e4GQMJ2NivRCD051n^S-X5ZE& zpvrv?N9iRMJrmwO1GhzUlZJ^kIDro5KorO=X#Q5GqcUfTMw8c+TKEfWt!}-l)_1QT zqk*Xr_%Hwm!aN^UyH2+XU@35BPwI-6wuM6Gg;T{T0UD9Cn$^8Btw7=g*89A;gTeQ+ ztkPQQ#-izpoP_8%*KT1*DE(55_gpcmpuT3t6p71cF4@Or*c|Gh`w0oG+D7yAE}xjR z2n0GFa{YMCo`SO(B~=4?D+78)U{9wZh^PYxqD$+#WRttw5rjolqEVdscqhg+3Ke{a z_VpS(p^L>)`m)PS7lme_f?|qbrTT{-NC7CH;3*?K2BaW(?%}49dM4NopF4}-6c#Yv z2)gRDsNaOkW<{C8+Ez)=GPI-0M`ytfb0Y^$HNY8#>l}z%8LuV$3B^=RL8wr!UnHAw zUUzc9K}|>x&km-AcV0*6Nk*^WBmk0*GHb}dO=x#J;G8T`q@7X140^oNLNlHg4blUN zaN9HR!1sJWF5?;H%ywhzaWG;*8ox^KnJP@%i*+Bb`G=O1Y zpM+Q53TZXDi2ZJ52W3%>uH}VJ^S;d zzCH;>4+1Qn?!PD9I~KhCwYm9>&cyVltf7Tiq5Xl%&|9>?LN@Q~R<}w=UHLfa%q` zOZsMBB{MKncfXP&uMFYq{YSF??dpDzl*y+ZWZmws0gT0W#rn~9*z5KNk>royD_yRO znE=G7#@x}uih!E#zr<0u8EihNBcCw~a|8Onz~I4G88i8dO&d#1>X->%7EE9=K=cxO zWYBfuUfzPCP=0*qUy}nP&uQE`S^2C-avXY&a#MLA$cV@xKi?#-|4G0x@$NBH9NMTz zAa-xwx|!v2c+a&G_ISQ0X|rtk%YB}D;CRMmc#A{Kh)(IbI2U_Px-A-0cbPwTv06Ii z#eaOv`ra>sE%mkVxijbKPZWkp2L0i^hQQBbPfN^U6c%i=m{}33YzU5SYOGI98+$nv z4zAbnTmE+=I3B^lA#s_|z-DAv0y=bs`2<4qa&gNphW}o7!yo|Vyw@4(4ld|B_S!(z z(DMn~*NbEZGDPHD@dNx}>#-d(VXrWWjD2;Cn61cj5T0$z2BI$xU&<1k^NfADv~ogw z6;)G1(64bm7VniMW=3{D13-+Y*D*_66=^s|Z`YrzFnOJ-8S+k~g%!3pNWNJrmS9;) zyN|Y2TES3XKJts3OB$JpV_axe*%$yxoAw|E{oJtQtjA|kI6o;7H^2ojRWK4_T8o@7 z{D3xlMJ=nZ_TIT+xreay+1i1#XKpyoQ7sqoxs)1C>MkkZJ$>`zj#PRDXD~k}qtqKwIyiy1^PfE2EQ< zHcm7I;)E%Zvylt=_=QkzyM^wKIg*>*MDHia)T;nv#`vOjAr z;ZCu@pBSeBq6szA&mWoM%SQL`n{;Ak#uef`@e$ee5lB#Hj33)_9v$8MSy9ISd%iY5 zRD7B$vX3iq4appgeQiQ8(*Y|6P@G|QAV$u@CXwR5|?`8o$Q*j7-I zQJhr0SZd8|U!Nc`bKT@v%R9>>>5o+TK3p$a^#7Mt8)s1I~MOnmG^FO}) zzxOIq+`2{7;Prcx60x}<(ODyXT!cu;kWtrfp>*W42)60Lg4{8Sl(Z8A0B|7X>>Z;! zzu`sQQ#c^%g4K`8vUhL*vzGV-QX=N&#s)KudRq*(kdz6H^SgjAeo&FI`T?)bkADK; zN4S+#Q`LrZWlG4f;nYHx<$7s*PWD~<{C)yb+H|!EP<_JRz198|F#iwwh~2Pwb7<%PgL zPAIwdq}UnlFwxG5wu1>0sv61j|I5QQMu<57@$fEIM)DSE&5ljl3^WN%sF*UFJ>C*&xgh4&}o3>c7Ny6n$vekD}zS&Razgb z@VzPlc4)f06^xj1Z}^K0>M$=#(*$N}b?3GPG){1q`$6ud)$G5>N|o=*nvSv)Juz5= z3Ci`2h-D}0z4lWFYYzb><&^kZpGFzWevo}9w^2Nyun9@W^~ejWEKS_ABTvq&ylAxMUz5p2K=~*Op>|H~KX~pOMvvDYhtr{zS6}(kAi|>D<1V#O?!0 z)|6$+IvOI}o@eaAf#rn7dq6t{viSR*C;z5AYDDlLTF~PQ;w1n2TQmgKYdm@Lw~ZU! zkJO_w>x_zfLMZq%jVF_Y^p5WzD!-&l!rg7msDonO6!s1W9;L#;f{}hRuS>wc43L-r zUgr9LYyf!6@9~GBN$0XjtDbfKl6?iE7=ciknCdI(v()kFRP$YW%d`;%x}iPt3gB}?+)AK$86 zTL31cq~EC82fVB(%?c)^@!iYtU^+7nadnu|_U9zrjK0`}XB`l6tHoj+Y_=`a1Qvg= z@RG;^n?*Y~XIhO3B(9@7Ut|^ad4-ML_5SE7v9A{ceyGCYjbx`*rQEB7qLF(ICnQdd=Fh{XNek-^`;*F9HiUWUp4j zYIiZAyZNn$p>pr zYMz5p0XVQW7Y>wC<%yhmM?Gf_+ZdHj!xml{(QJ zpc)=i8bTZ|uS6I&TSkx=a*Du_c^Ng>aHg_5^Bpw)3m?#I?{Nh_Y03iEDlI3pCpa@- zYB1jcaATqDH{Rv@*T6cEqmXRpJcSWPbGNF`7{ncEk`j_cHi*u2o(4=TIWDGZE8!_A zODMpMaie~POm_3kxj@a~Tz@*o0g#x1QQ*m!*76NN5n~NQ0LQDv=`(QSZp3O?|8fbe z7Jx&m{~0m!mUz?enGJZsLJsd$C4u86k#UDlW=QN9z@vWWIMG~sJ>Tpewh|f&U~4b( zv$jovJU7n@H|VkddsRj*G~t7ap-@Hyg-F(HI6z?!;(gWcj1=X zfRc-3>A1eZ9H309kuMqvM;Xy>;&e z$2e(Q)7oQNnoC+g4$pLME)a5@kS^D>K}tWjzhLr9qAw4FtT&)*)+p%fi*R`cZSa2) zxZT8dUF<#JRO8?8JPlsua{r1ij)0As6lmdtEs`oM+WdFk-TZXj+FIe0Kv2}E!~}oXrPUIb4^7xo{p^^wwrnaLkYGGe2o$Pu z`(QUpP_<{sTHJOZPrR{iJO7KW&4sj$7cKFf+wPTzkl9JH+%C$XTm{rBPb;v|P zLjuMdRnyo{0+`=;G2DE|PF@-QXPlKnL6b=^E2*%>6*4jr$pzAITb@mt^l~+e8Y+sH z7@h4jQ~m#(hj4#l%|fW)Q#kb436z+N;!&s^4=@3}br5*G3K-Q>ry~Rfc4C;;wU}ay z1F(j6{JKAR{*+?`%+X_4#gss@c0q^RtRK0(pZmx*>)w*OOHiQD9kEwJ( zHpy#2xm1Jsj)NeWvjx_(^ZvL=cG0^AbPsIk0jklqzAXF4_BoaD3ffV^@r#TSC0g_U z!hHj2N2urSHdu^iyig&9RN)MVZi{$UFo?$RD4$DxJ31}fBBVY9KKN$qdPW+@E7DbR z#8SZ8!|36y4FOG4aKt{8b~p+s(#e7X3}i2UQ5KPq;N zW#CBzHy7(pNkW(SxYC7VY4}VNVy%^QF`wyUkx4Z%)4GFjivq>@pxE%*X>JVOu^^fu z!dDUX^y0o%`sHpA*t&^CazE^S$}I4AL0$m7V*_B`d}OINGBnS@ak z5+W7xW?q-(#c@>8i1|BbLbzwHNs@$_lRh}3{2<*HIi67Pw%aSRMq~SgtB$j{Ex&cb zBF5I}&{ixv9sBm+`74twDIKjTS5;-SHU$!3BV`mch|CN|@*lwzxpcNYCI(13(^P~F z%ix5lWG$0uV@bcDU8f)SW81D$phvCEwY9SUg161Q8gzbi6X7Kar(BOyf)ctYFp#uU z|5Hek>G=4$Te1)?uq~%zAV=7^PS1oly=M>$eHboOG6(q!7yy=5b(I0@C%~)#Ku-=` z=6aql94tB2S6>?M)*s(&8!Vr>kKakV zBfQ^ni@~qF@;3StahiS8H9%WDwS?aVeBk~gsdw{yP$P)|1#BtyZ$HJfJ|XupqU~vY z{Dj8-i)egsC$gME$a6^lDl5ZIT0A7q!HNMe47P?ZK)`xt)+>AmJ_+OTwA`Q|5Zo0> zN@(#ORDY}0{Iy|9H(q;5j|s7Dv7F@7o|ARPsN0jsmb_&;XiBs5^zi)<>8CPKX)g{O z9fg!yG(gthc3d*{)zwE@Z<2WTW2Ryb-Uj`nR{87!@8U&=L9jXE$TZLLcom*U(i;gF z1Ku`D1&w3+XYolfOo8yqx8II5?1x?0-?B;Eey4pexc=kA!?N>k|Lg^d2k*6I8&ClGM`yaxIp7b9obp#baxC}H6PE99 zZ`1On3$!t3d%ygga|0HQH8yw=E=&g_07!-QSZ_C4pn(v+<@D*`v#pa5*>)yke=p{c z4zUPNb^)_>&zg$JtEMepg#W>{j+O;Lz%lfH<@pz?&r)UpUN5_Vb7<^t?fhQ5Dix4n z3t_4kj9YcLe2!?$L(`kEVuw3nnYHwdxw89ofTeUz&Okraaw`zvN$F5v1Cp%?B}@w^ zJOKYSV8&`I#z#M%!z&^QO`ehKg1$ny8y6|(8UYh_74bY_Z>mP4T#MjHyS84xR zKaR=+>=WZVS8y)4cK_9C1yNt2o>+gifS-pihk1TjmnRg9u~p?%=DludRl~?tmRo)~ zlR?|Z&k8lrpiCC)=s*bExY{7!3`S8}wqRJnNW7({fJmmrQf1o1&sTDwbQBIeSciRL zg&i{-`G-9IxVeN^YzOO+2_u(<) zqXId^A@}xwuhF8Q^YwKypg)M6oqf8Q?O(UU__)IFRHiElv=NJj{7{nf%|dHpg!gmc zOxGS9BS}9mm7Sx+!P|`n1IyUzliy|go+W{C$(e#DMlL^g)?tsE?V|wyCD2c@K%9^L z24HvBHaE5#rbJBdPSIf~^^*#ET;=J${kxU{|M*`V;N|RVcTf|$x%KY{)Oh~%foB$;YxM$@F_-V2$W#bI0VTL)17;d>1IR7=3{uNy` zpqcgFcoOJZ1Qgxhaw$E`yiT>6h~uDdc8O?FZ!} z2`hk!>&N7dPZ{*>G_Z|`<$g_=U48YN;)2^XqWQIujYMsRN$oM{S;;^aQQGWMOD#a% zcO&0m8+T9QPfz^kCX4RDZUtX|vyh~0d9d8t$)?rSmypwOYq7y1&El@3w`cbNmvWEQ z{tqXcyk7MJ{1?Py%`>hu+QaZc>=u=X-5zG)sjgDx%M09Ocgd-Vc`9D#i+Sk}2m%_l z0%!(<;z@4eW45C+Sw>t;JC>j^Zb1bl2IsS5D}8n5zSGG95M_**^Y`Fw$xy+K_crVj zJ=jOGG0XY~_o}hBjkqoo;MCV*8VEnx%N)bLGCBCgSw=@8|G@w;A!w^7IY{li7@i?J z>(aY;{v+tv!$3q?)xB#M;@2^U#Rmv3YBa&U-iocHoCrm<;m7R;|TGqBsaQf@{SHXW8=O9o>fd%Vk`eDdX zX0vYc8sLWlSy!Opr)yfhr~7H2tz z`clL1;W4Jn=kzys9V@r7j96=Rt84XGo%rSt+ea>v&T&Hj{Qix1MnP@_(lanHXq`^Ae0%fS6_VT|T`6=+wS(G1sX@qm4KDxmv)8sx*e$qn0`!F7sWd zZ-Dxh)j1*CcV$ZHw%a@mB=;9c6o{-`F z@NmSa;1fCYdrWuGX_WLl3EtfcKb-$G4@gc-6p{SNSZwv456bksRj%>OnP=YIg<+66 z*D3~+1V0VX>J7N8JuIYSfmwNfpRTB|inhT_8Awg-KV>Msn}>XozoTZU*Yanl|4PzH zFb^7|frnOKB4;DKnS7#8g4N+2G^x|Pkm^ws(}u_>WDG9GyJ^HGA=V}cv$>1HZWdXR z6G>2SQeRVVtTqfVfxjhFAbQzX!Dq`&rr5y;BAJZKiHvx^vlZUb;o%WL6q@pZEsI3A z)}u&F=A8V=H?^}lI61>Ny(zwZBcRs!{`C+=e zBNh|@po@vSM;^n;ZE_A)W;#vdIa1)_r8YR@&(48o=9V7|D& zNZ;!Jk8Q)xBaWl{MV+Y384M-WH!z@vKR*A5IoZy1=z;+$j$waZs7t$b2XMH#$t^i* z*TQf{4La20&U*U#yT3Bev0&@Cw~^NL4Ag<*x1b>n-_1fq7(c+IX`eEHmFxePfAm}v zZTD@;3MNG|o{#>*2uvF98_t5p~{p z&4f^5#{u!iH%RCnT;ZudWy-~1qkxl6?VCC*6+1tyyhyBc%+SoV?(jmMI2Gy7t}rl% z=3*9$)1q((#((&;y1Dz|?WqR2KcM=2+O4SYsPloA7M-px%w>LlSUYM$$L=FbGQtNf z^MY`N(+JS9SPv!fWQ09gC`>N~=LMlay%Q$y%QTG(c`Ho>2h-|ToG3*(>{RWp0BH-j z6|cA-zp))Q{dzz_zkEUlO(tE8`4T#GWQSX~rL-^Zj(y+Q5hjY>h!1(*EF)!)Q# zVs&x@c@7b7aNj7);^g=_m<>Pl((@t^25rk|Mhcm7E zSWARxv1}%ZeJ2!Cu+C|DhZb-QLWnaWUB#i;e2Yk)RiQj8{jV@n2%uQQT?zG@bcwCH zXX)E&`74d-6lGliUwUs80f+YPf8hZ7*c2d|{P`mTmr#)RWfiDUMh?6g0Yzurdz_mR zTvzl3i;EvUFrFp>DiXjJ2lD3?LDZXc6B?$`sCH44`a}CWCKr;(09GX?HC)a!ns2qC z2yE6w{Yo>+*X@5DJO2FfSZ;HDJ-=E7p8Ep>u1+l6$!&PfG*CYX{1D6oFp$h+BZU*L z;xO~jH+*(I=q*h-4?gB7oDux34})9i0sV_AjH z`4xR$4Kn&zwsz_QSuL0HbKH&##_j99&oD}J1=coh6&oF%h33s0vj6e4y@?S&jF3iy zg5V)$ghLZq9>P;8tD*?*k@)34{$4E*IUWm=;^nRR1ka@}mw)d*o`+F{o12iO%vpNM zeB1PdX~&eYjGZud9I~dYs8ryU!nR7H`Ge~Bv zoA1mpset?hE;dhyh2cmq6+3-ki`gzC3V|ic6|Wh5hnFAdKe z)BYIJB6Wb5DekroR5L(~@w<|ZB0Ccw54d3GZ4f5P#KR`cQH=0z%s!?kCydv1zwEqQ z%k(~V7X%vK7@x2H{w3F6-1XqIxf&r1x<3~!BR|P~UC!NUKkw>4?|S@T{#(RgmyvTs zFZP4O=B|VP>(__Ox2q4e3sg5*V2OY_ZbPB>li?P2j%CVa%JZuBo^`?Za6AbalaSnB zb(<8Lwt8kd!TN4Oam9$T`Kd3FFoeH-Go%B>;4nS`aX(In5B&8 z#&=+YO#GQCkmM775vUAge??mA9~U@2H_K5T!&R9{MQFIjfndA;sBHhsW1Tq2-4y>4 zc$d>4+ZE3NYF*_Z?Kp&`)bTx%Bj%@M1TM)GcoUTYj))WadF*#E#~PTn%#0&=!y%wL znu<1_gYXwgGY* zb7WPrH{2an5bFgMo0hO42TnN|Nz;i;mw31+pBX~5+B3F<$tO&OgYp(gYTsOIy*OvN zFMMV3X8Ka(|VfAmkdMzhi-FST~nT5JaRDhgxj#|i>=i;_t-w3~Xs*P!@s0+&N!NE5*9+@ zHSNQvsMQhnELFKWs#y@BolhucK*iLF(707G*Vdl3*edV*K=nvnhjzYQ`LZf9tv*+- zl2fIMcFlrS`$u~ZEiHMgbVYhyGAig`^MBiVp(WNc&GR5lP^}AZJ7`daZbc*h{Sem- zeKuSX6XDb0kv!;wG19PQc9Pr91?;J%2-)0-lN6$gm>pF2(GL_Fm~npb#5xr)7XH0# zDyvnIZeVYGc4@@>3;13Az5SfnjUZgj_C^vfx3RC8Mipcvi;m5XB?S##M|ou_{dPo8 zEJq_nGX20&$4E(CMG3_>;1bb((}-(xOZ2VuEqw488zA-Vn|+&*{%sLKR2bJ|RIo&- zBWd1g-Y&j4Yf30!gH71eDP=;fxkGxqPi(3e%5IEv6&6|@YNtE>OjO{jIvOhVhbjXN z5n3E8X4VF)RYcX5+9H`TIO}Am9*?O_{;MbM57uiVRnOI5`Z_@>cUQGatD`bSsU$Y=nl+DLt=sawx7nhlEH_qvGT~%69A;b?}ymtw&T_xr6PSVK5{2F zPkvaDxM3PVBcB(Cj;l{D`|B@ShmByu{;N!Z$uPs>;NZ}5Idr8?a4>!>is2i`$EKmr zFtuOp(VhL_4K%cN{e80ihfMJ!bo6zJxj)}f+e*hl@T=3?($->3SJTzP15PzOWIRjB zfWVUzTQ}0#SuEIM6`Ko0QN}2lp1~69`TX{K-uUnsP8;y&t#j;13gpCPy0*zEQY&sB$pSkjfMAg=YC>bP z8@e=B(_&;6{BL8h8=&8)aeZFbEj{3vOo?vdbl_8oH9mxZ$?3r}c}O6zNMsmRkIZX2 zB&{9JT@e=PMmLnb3<7ePOibzRaqO`ZYMJ8>YC6q=!hVdUqAVh%g~uQqkBtZm6gEAj zO#cw!V#HRYrZT23?{*C@m2myr$RKF(`aIqR*Yn#U+WIcnv3^A1;g3rA)^`?x4zEw`sqKW+_22ylw#f_zVly(bp}c|1w;NgQu=u zd++cW=J^$!iV(Prc6}wP12FGX@RJ`&CxD@KvtGZ(QGn;L4PQM{f05^SE@FuweCmu7 z^YbimLUEp3;eUd`M!#b@>3I>`b3kpgMFg+WXvwo%5jnyr>U5Zq5tz${LCCf;n;gw7 zXKCL)md7OS&i<@iw6*ss6Qd$wg^{-gYyZ^9`#`aH&~>h=CHuM_Ch{#8HWlH}*7!8R zE|?B6fvO$C32bg{C(fpk{(qk}+_Dklz9s+|z8M?=>$lo!GSCF+1=OcWFbiQ>pC6|Ha;rh!Db z{_{UG3`TbE8+K7v_#-{eJ4um|i3n3$$wDq6q>a4Ra%8tIn%QoR?X~wV{RYV4rfoZy*p z;UkA+PjN#R?>k`&AxFkb3}iC<4S?~jA3*PCf3Z;((8{Z^C%OF{Qp~uC1*;_x{^hG0 z?$Y`Fm}*t5tR5@=!_|+Pe@m4{rJ&3c5}7F)uyaUeIn3AocgwCuyT_+>c)-!oK6^Z4$RruJI^vZ zAQgX35Nkth;XLXxcAq?2^jFQ^o)||MDbDwp4;iSrmobug?0&@0@V28rcao4J*r+Ii zr&LI28^V}*e~-8goTCc3`#;>F(7rbMy1FbBR5Qa9T3DrIrDuXT`Lb=$F8)m*fdv8N z1qkMBDbcdetGd%3Jio7VY?tl(L*iZ=C@3)IZS2lcq6mCQHL7 zqR`lH5l22H*|7RKP8R5#3smFplIMtcsF)ZWJp=!9k9*R5kGY+|AEvRo_4h0gR)Z2z zp+BIxkY04d`|L~>>i}~Jr7pF>8YH%R3^qqJcf#GJ&=Hh*A5P<*2Om883MGr156sIg z$DtNy>a?s1yT3zPv~>DLTc7YcHO1B$>k{_or3oazll3(`ef0XY!fbx()-fxY`|5Qh zOH$_#qrSL!9fWZlHfb~&PSb`IXdZxMD)F1<^b0UQkLZQ6;*gQ?&absV|0MB{BFnBN z1X-}xZMPGIqT6#&A{MNRlGwuaXFHDu#J&U%RB>9oIE~tcGN2RFeouM*CIQWg!0Y4@ zNZe3ip%=XHHz1)Pl9H*1p~i`jv_}c0(@t|yRN-(F%FSRnPDn*=`(AfY^$D@VW>>MgWiwOiZJGf4a!o8-^@44qe%uz4 zUS+u^aMXTRWB?i^?tfBDBhCKEn6w}iGrz1)g~qe|@;+``m>ujGfn;jvyqIwXLS)9N zvw@>44jJ^7{Z~8ze_Lo`5RiqS3RXLCLy;)HQD??+W`|3=>K`-_=MCX$H5Vk0TM0PU z)H+@m!oN`Wapir-W*K)l_S{`!Aq# z0?nSkf769_N!H>^BIB;JhY8RY)@-4nx>j6R7;xfEYt z_Oznec1DXq`@oTp+(sfxlkp;LDcq6p8cQK@=SzMwOOG zswq3!5R+1nPdicn(v?SE-xSUhAg3BdG^Tea8#Q6%L$X+ckE_0KJHuHG{o@X5K$I+4 zH7_HvyC7Fm*ut*-%P6BjWHSm4yYr{p?f3%0k3 z4k+2}5fHhaRUA8fBr)ZN6f335JWau2wvbJ$jO{0Vvd-2AC~1-Kj@y4 zgl!H99B0k?1+cAZ&DL*N3*j>x@I4IxmRidiByZ%df0j=h5uUMC2F48(7#CEV`T&;9 zJI3>>8j__PX*v6hsXAWC6eQNmOEKb{F*zH+9L{=52FEz90AS6r{>!L5ztVNE2g$fo zJE}5&w}4HS;Y`8tTI+%LQn^_WTQam^=sjQ%E9Y+zbY2;v1PcuhEFi$pk~?5o5j~qT z$-${6rKzCSPJ)0&{r~n#p zf+-TX0DeuMmd-(&PKi0*?~|5?FL_$FT)9#~x~I!MXe{L&sZY4^?k-a`&`EIyTVl(U6T0OS&Z@fG zhTFeoqnYy9Z%s?oOcy1t;lBgxaoExXE)S+}A|Lp#9i&p?rr}cls5^}a3~_%A-te8~ zS@z<;ONlZ;mc7nMWMizzpE00&Le%Jo*u{)#VFT~csiPlBEA&1{I=V2zG0D4R;Da8$ z3!~)Q<5q^5b(tKfoJ&#^tg*H=Jr+3XCp@26RG`l2v^ae&uiD)L-2KLmbI_-Ha8VOU zy=WmfooL~35E=yt0qdbaQcZIn{{@TwzFs2s?{sJ48M5;SNz#Hc@2nFB&QD1W` zQCyC4fiiiq)Zh;dM@i$VE^o6&!seVlGwDs6@w}YFquT&l#{TQ=bNMC=LL&Z1TB+_k z)y!zoGUwt__`+nLRdaG@=X1l${tf&QflAQNIz|PSm|>F|)K*<5eju_Zppr$PZZ=@s7Fr7xXjd%$g>(b$FiwiAM*r!C>?AqdyI$ixt&}=(5EwY15O3uO z_x`akJlTQ=+noRV>`)L4+z~1&m{0OOmM)r4iUj?fP`U2(@4ZCbxDihjlg#Ipn)Gm7 z9!rblbWK4YE=WAMBqG_4A2=V|yuB0Qa{d%t7O8W^1iEZRRX-EKP%eGS6z1XWPJbL% zyPok%T{zRCbhE_#(u?fyVo-b{<5Lz$~2!XHgP!K0>1pzwu%WPmC> z0VThloHl?8zIgP?PDv(5PJ7Abm`QImkx-XMT6!B~c{*r>OnL7Jfp;fi=e)?4Q+nGa z8P((06g}F$UFZF;aiF~ORDl=l0% zB7dy{1b`#hN_hzmgMUq-)A2dX=#e+RC@eZataM{vv=2@dn9Ld^ECodYE$KVWMx2!{ zgp;>S81kxxK&G`q8@BOrdgWs2z(#?U#=g- z$Qs2QYvX35wsDzvyuNY#yh(HV_Gu(kF-56hH`oWpOSWGQf3WH&M8;WBO&Z(zjMUx@ z6X%}$>woN7Z~DswjYeE0(1t7%`{!q`+Jk^5*V39lEskW;n3%dvt`)IVG}xkcm^i(~ zpSuR2k&UQJ;OUx5~?t}M`(j6~r+F8kf zx7j{cX}a11sB@Eor@V_~X=YZhr_YA*BaO)y(%^4qWiz~9F=vt@Ls2%yMWJf&m;7k7 zuPuP^I-vhmuBAYl7nAt7d2-~L>wL({X9$fm4}65VeB!^(DtwgBB~>t#j#+DKduW20b;qZ+xBN!bj<{fql<1LkV$mm3Q}HG>ms z3Mm8Ii)kw^5kqh>ZRsL&3V~XYo~7P@HH`pb9boP%nrp{1Bm97L0l;T`8ZtUPGSrPp zuSV7xF9B|#;rjJxCaPeY6M2&v8q|UNBMkP_4Lm8rm4yXT961iO>&|3i(qQ}agQ45m zq*6c8iwrn~1Nax7ys^2KT0`eVZghDhr2X9Su39aJ6`~0l5A~Ij1M-W<;@H&Rff-tK zuMDK=u~L^+nPdm4Z!C1`PoK;ERbqes z4A;EU>Y2WZ8IGtUraugM)Ks8(cg(sn2oOmFI zzDvjWfqEWdWMqM!tDF{?#pVHbc0iIHRtJfLtC7c$?fDi*!8NgDi|gNoXkSVD{OE6c zh0^)dU&OElNw8$F*!h8}jQLjN$!0YpF}8bM=Cw5nz+7-V>@}n@lz^Id-BO}KG%tou zA?i%{#?oprOKELBS6sOqV&OGk%&Infse)6+LlbSOy`dW}Jyl}-6^I~GTE-jjI)m?REHe|& zfks3hv#OAU=Gjxdi{Y}qaMg<}Ab+)*lA`*8o4bngEoJF!59wEZwiT3OP)!{_N(`}w z!J>w4B3pphbeT-}TT567P~tSZIiI%J>is?o7p|+yw!r;U9357VYnuZIPSwowfL{uC z8Ng}~JG?t*wdVY26@DA^>8JF;WfVM46j*E+$H=5{Oom@@uHX_;pOk!RCf`dqGwLi1 z;L-d8F#p{k*OjVO=@W49LaBA8VFpi)g#+E;Pg1i5=Ow&;>M8V({92#!y|o5+-=PhJ z!0-r&4HBSp?E-hpft!bxO*b4aWpVWNCa_)n!RwFA$&j^eNSX1BC+&UqW3nhdq5AN0 z5o*0P8WUfj`q?e9{tm}xw}6kwICAX8xsWIEHswe|A5h!wR8y6hG_rWh$(xhf7hdNhZtG;TC16@!(n=`Rb@W^=`R8P9hi#F9X-T?&JA}w0bHX~icLhuYf{L1UxlMa zCD3}s6XGo1GzCM$@H@4M6+Q9PV-qsl#O?fsNp<2Zt!i?UO_%u+vyVJt0xFGqYKx6{ zhs?x=y?$N1P~`>_1qJ+8OuRHowX6YXP=bQAC@6=&1|{*d^@PIen31T(#-;lAJaQO> zLS`(43Xq73k4$XU0RjHYRRxWBJkv&Kvxz0(fM{cwe|}t(XyAOE$AFRCyIE{D3iOw_ zDE_*k^P8(UAN3<9jTg8l{}B}TQ;mB{fW;M)=}HZ%oZ3y;QIma>x9K6g51p$qV2AI#QjWMOX_dwynPA;%(aW7n?SiVMPryJDUdkgLA}PihBaraR|H7T+kyBW zhf`fviXQ&F`0;oG{?-+W?4)VyJ?0O|B#T&ox_W#1=Z+AV8a{K>_&DT}njM4X_)vj) z{J{YQpqFWD+t;uCGvarP1$0`Vk&}z5J3qqmUekiuZKbb^ z2GagjEJDDpIEy6pQ6aOQ7yjce=f4$>^@8 z%TS{TffO?W*b-zu2CM#$oi~pCx;Jj(@C3`zltbrp(@SpU-XEIY)9UD2l>-Syy%Ej1^Hv+PIoBkT(%@7E}$S8asI7lVo!LD7ma*% zZ$`iNrxf*-+V_}_N@o)#79u32IPurNq8*ZlZ!u2gQ$Mo7*sm_{kGl{z-2i8w^u>!8 zJW;tbK#DuJs(!lCx{9oc|Hy+iA&YEX(~}mE@4YSVR!n-1AMzGy5x;ZgcUy(eA?x_s&AikWHsh79F^6s zztROOGF!(4yR_kk?2 z{D}jHcRu#QpNc*&BJu4l`>gx#+rZP<(s0LySlS;B2xV*f6r7ur zO=N)2!RN#n$oW%#_LD#*1Jf2U(q5;>4kuDvMR z_voD$yYm@v97v$AyH@QGzF zq<1_WQgHfHcL3Ry%>sb8Vi01NZ6@%-t_h{V2my%egF4MEPinntjdimFXfB^fqMW&p~v zR_wV!lZTeTAe%>dyqYaxy*e29K|YaqgGpzbAGC+(syNYe(##f_pZ^V1Lco)vr#i97 z0t>L<8TbXNd2Pd(tXY7Hqgl$&%w!G{>#p9uDC~@WE{9% ze@eD!ISy3MIr3jTsy7-<$wJv*!{r*`$r-DYqOAM*1Lh+D|9k*c$M*mg)m(-g8rmcZ zv0-E-NP`#*%?F|=8cdUUnkp!^M;`2gn(37KOhkZwKejSUqx z<&E#I0D3B%iP;Bx1;Z7cVGf`clpS!Zt53`PVpSpTN2m|8G;%80QK@HE32|k3Qydjy zNu8V*qGl78;U)_viGD~bS~zbOXYLs+jFGIp4m-l8QrotJ5DTLjGfZaGs?)m?=G@v~ z^)vHw#2k+nJq&T5WQE>l@hEnRO)=qse!+PB=3Q+I_IrA-gJ&7HXchle)zt4@SA4S) z9}gr)wr)^z&VaZQ+c4AGY}^lZ#wGGQ{J!15uo1L!mtZ+#)NUrvAh-7Jh`-Wep*~_h z%)^gxg2&UA!h2@&L;@vz$!4jR)DC|q2ILD^UBpHr@x64SX!RJ!Ld?Lw=|nt&xcwb z&8;vR*jD{O=W?mz8$b)It(_7Q+^^Pc6{Dj{X}zu+U}%h*H?xaT+@q8}qF&)TYQQx< zci2zX%1XAxR~x`7K36^>z7fT_B}N`0f>>|le=3NAfzHzI{zV=?J+5y=Q@_Z1g+9Q$ zsJu>rQ{Tf7*v(H03JRy5cFPRHLVdMoJ*36JY`{htaN^M0*W_`g-J`YJ{yI7H$W5Py z>f7elQfZpQ1AnlT_-U-Ym2e6vdbhA-X7(PM)^_yw|L@UzgZZDB2sr;OT20^WQDm$F z#T^zEy9wmh#M0?@$|YEIWc=2ZE3|_4v{!$C`PRp>XndZWbk-5s>(X~wxB$Crq?~Dz zGRizp1_RkgD6eN(H*Bci>XV|Zs0b#-AHdg_6zJvk6q&t(?tH>|( zpQw>(qL=lutD9zdz83Q(1(}qgOnyDUjP8}8VxBxbD^9tqxQ{?~sc|3f-fY-FW3*%%wlFB=|vx>C_QCn3=4TaZ#!T z_Ju5oZ9Buxx8_rMLk-x*h3Da93a5JZVGXzNNK3>bfd{&!b}0*-I_{&=B%9A6lb5PB zdsuY(ISVH?h81yo%%P#DdZc5X=qp6ezuWgkNm2n$7)TfrQwdlU)JsWCx?%av zJlY~3Nql3FLd|=Shjl-m+VxyPv;_`@KT5Zo7OlF2-%Nac@{hmK6QYq%ik713Zs+Er zxUE9dXA!Tn_9i7pZP_vGv^_}TEqdp6gh)S^ZN!iPR2~zCjB^O9K!LEDNCv>!ed4jF(9Wu;$ zeW3w%rKu%{=-s~Ge_#K~&*;YVsA=SkHNYr_{J=29)C%L^ zmn5VWT8@GHYE8aFmcxdog|{l#j&WpHcjArw=(}a6v5Yd}t6$e}Cyo={`XsviF7c>OM>Pe=A|vQMli zY=)62ydUV7@oh5@s(`)jmA+f2KT<#}vZLpWVi&AXr;yO3z0>_&1lV3BUKytQ%X%7` z>=A>99P+{km=%-1!cxpqM95q$Xt-V9DI>^`n%MBauH#Pg4Dxx@XtY`g=M2o5kS*ac z9vawx@?|6BEW41j2GvDhM}!QRq!PwDf6iYyk3B;WlC#B-r&$U7;_kcRxEa2; zwHg6+qqP)-$f^_NE4Em@`Sq&a^(@ndcYuSh3r?O^s?Gp^vYR|Am zyTnFNCenrzTC*)1v+^8yML_iXZ%J#w9*LI00f|uNg6Zykay;O$@*Q6t+l}^TiG^ikM-VKV> zTKWIwkNkBUN@D>7;j#A9MEuNIai9*_O89e6d?#CbMAYOk#=aDLpmGK`4gxz^eE zOXCi2N&Mdpc+^``69{~XVR`z4T(~-oxa{uS>1oe_mC}a&><_w9O2xPi$`{27=1ojs zlcEkt(X`C~40#>83U-O?t81*U6Ph{ZJ^+3CKQ911ON1z=-g{%NFB|c#YTaV`Jg)yU9Jy6L4O)W6agG2GdJq3rV67BccU9nCjm4@?HFB0V z2*^46uJ{NW>JGRYeQ*4AwAQgq?3gRp(zNab)4MdCSb!EJ`$X^E9Trwx-)@V%g!4Q>6 z3=C3R#Ym$T>K@Z?aE&fGBklO($r)$$+3C6Bsow5HZ||7{@`>-o>ugW7j%PA5WY#>n zBZzas$3(+yRS;|y z@$2T!x`xm0@q^z0J{xo7_HDw8VmQIGStnYL*Bm+cJ(u=7rU`y^gx+X55%3EbC0)2k zvnR?y;#YVyC!1p&O=GdSv{MO;Yd+2!d{c=nb;WM`VGi9vsdPyG0$ar7BncWOJgo#N z8THe|L}p3M`Bvgg8C;gMV(iv#1yo~VWb}plLF;UtPRE)3BOQ>W&TC|ourJG%+Y$FoWL zT=N*T_6(K2liP4qM-_Kf3wOwr3|y7s#Dz$Pl@+znEJhVV^NC$hfkft!K)cD;rd2AK zo%UzrWE=U+9>z#$xew5nbzg$Yl1G`3h3nJPSAy%&P@!t=RXy zVZ&?p=3>?E?*pOMI_k{OpVR{)7p`c~h&`9663$II>7GA3;BN1h;xoYm{B9SW1JHrT z^9f8vL}uZ-a-S3kM~`q8gYbV0QAJh}1-~Z^Wx`g+6`&Ueqfj9^`=+c}b}0F>R*ukk zud&p7Ag_C&$rIsc&vS>tq3ziCz9YhQs%ph-Z`cu4#h4TcoD&<^C~~R1C=_x-F-jh3 zc|yW&1GE}17cEO_iV$Z}4krUB4P|Hf!-i#Tp57&Z)R_hQ z(z|3;Ao_++QLA3;lT2HXCZz%nG+c=%QCbmJ%j@BYhE^d!Oc}%s*Fx^Dz*g9Q5JqS( z2tMu6JcC=YZq9b>VN5!nmLqq4odgWhl;MN>r*xi~vM~cf;z9yZh}RItujbD;;yXX_ z5h2MiL8>mB_*v^4FtYu0Fq0o6zD1ek9m6Z$8tYz)(AP?91Jc4s2uts0SVh4N;)!`Z zRPuPbXwM%r`FRl|Ajo2;u(ijME-59S876k zP;2pDgVAt>Gxa!}v)`qAqM|IY1y-=C-heesz=kOKXitQ~XTFkhtS4KBVho0?x74-a zhA5VzvwrRtQNn>?XSCRl|1wgN;b7z1)<8xpPy(+GEZx4+V2AVTPhp7B7m(F-z3 z_(bcpQK5X~vf&luT)bPYC=|P>P?a205XbPtk#=o)roqoRZO=&Y*b*s+X`-qowBCfy z49_RQdNRB_a&UUPZLqMRvvML;_#h0K$MjB_llauxs{g|(MMGGF zRkTIZxktdbH{OmZPMKtm4r7Zb>N=ONHoj z($dG1o1lJ{$Wf%f0}-^`3HUJ^g|DQqW9+t( zyC=5xbM_coQq2;4`|PpU zc)D1DV~J}+VJD`fLGjOU5+rGZIU~+Yz;q3_?ys3Zj;~+-WcDxNT3Sa_yFu}NW|}xw ze2+^#qtvwapYr2MmFno8=oK;7n%A%1P+p@QUIotjpd7b0t>T@W2+!dJ{FB$B8tPr5 z+`N(dTbOcdG24Rw<5eBa%PkUNf&uuDGl0s7AEsRXP!xK zf~u=&XyfRq#5;`hw2|Hdxl9B$q0S%Ki;LJ#ie$72TZCgz8*GwvE4&_;3c0IkHaTFy zpE$`MaqHh&v9#0B;(%<~_)%F$Jl}q3sv=^n-L_=BE{tK9yddu4^?<5dxm#`Lw6h2$ z_Gkkr#FNGvBF&*<>9HiEg0ew=V*e-=W1#d70E$?M3gTfG0SwDR3W>yvb& zSDEEY=gv7bD+*0T`=)UWJKF2TdKIA{7i)M(@XvYZQAYRo?4)3G9Q&I<0kVvmD#uWC zC|!g$=?p3@&xy-oc@(YFlEm-OXUqYTMbj=AUS<(W?IORSHFrXuc*H-KnZ5jkP8Mqt zC~XD;V(wrI~_e0q!~IwSJmUr7^K-%yV(*uGP=x*aUSgxWShS z{@*FSPA}HUlWa-_T-FUpeu9gW9rv`%nD2nUKA8%1W1gvXeb<9zz zih_JOOIB_yEg7uOp1@#?czvWdbw(KlzMr8!xFysh<>Ve_`}fan6S)pZ2xVDhN354H z{+)gWM1y_GzcP93U0os904E(1xN_74rl;N<0Rh}6Fl1q%hce=eUscDjfAsr;eNSnTG(q8 zr>hpZdz0g}?NC*JA(B`j=GAt^=uQKxN9Z*;^!lLd!~K`He@3{?K?Tu>RDW8Y_jA9L$5Pk}Be>)N&<|UDL~nIfB+58#gzn}St-Lm`=-GmYpIkg~oK#&~iP!G&6AKq>QhmHw9fvcZ zP%%!z{TxCsGWqjTbLF)$u3UuRRdiqNZ#!!S37j^1*QkW(K=VL%AH)tbmfFE=0qCQv zW?H`PXb@-97R0V56`m6`&9oFMU~P*A>A(Z#i85Ssxc@GinwM~5adI2}=(qZ7+xi(Nfg^Zd+*P+&IU^6+P^DI_ftKJf$8eH z724vaVW24GjBL0NaG;)1CaU4;ySLOcXsKlME6MAbv)HVCxyl$)0=A^ z7UV@Z2ueQ5EP))3X)q2%Eg?+CcZht5a=Bo{JS>m@x$VL2enYu@Pa=>pua^w3TgW=5Q zrYXOcC(^E98Zva}(;;wP%AGcG`i+-1%h<7RzVH=Y3aVMX$p#y(cH(J$_sg|Htby_8 zr`b+~^NC&tjiW&fUs*?}_df(&;yEvo$CFnKwy5{(PrS-q*_biJ7+f!<3Uk!CRRhQRaf0$Z(U8U7hQr z7~wGdbXGpbX(EE%bbI!>9A*{4k#16OV?9`J{krlC15)^vDs7v}wfbUo558Y^D|YZg zPbO3Th`y!+6m^!x$^yVJ97ikhGTd$#e$tX(8?(55SfqhX4M-?2`r9y6Au)_lo{a(l z6C>wjd$NywaF^6l&Uf2nJR@FEM0R%{oEmj;k}X@@0)|mWvu_-c_D9QjVuuA@#>^+* zT9H3c{AWVffOKU6K-`MNLQ82OU;XMbOWlGMSQ5_ao3_7H(!A#Yq6VrjgWtABA2BjVGB6{>>?d2OuI?rNo}>J%MND5)g3bGr+cdk4(VY3)LmtV0qs?KJ z)Oc<%D_x=wrn?lR(+{{5=qY03=kO7N?8ZOQh~Fi~Yp=im>F0OM+pUM+Jsu&i@NiJ!%?=Uh+9`Kud2M5B+s(`5IsnYJ)m2mLR#W<|+Wk}msfmxM zG#{31yNGGW7KPQ`?~6}};FbnI-4;DzgaTH6spWNBT-Sv?iL_H}x`t?U;UoP6p3Lo} zk;&2-Hq^ev@Ez97vA8w@v}sI%VK`4;pGy9sH`Wkz@VMbK>M>;{f97K2_wUCic+V%! zHcQ;~=4QptCO7yS!DtksHvWkvgO)C+xgJp)dd?|1*aMJ@m}!(hK?CP0@5Ikg!)fdZ zXDm*F0@+~!?A@a4*ZvHmPySDL)^L$m?NWAPT`XE_rAa7%5ut(X#i8trTI*6p$TY}k zg?BaPBT56(iKnbFkAuyRlbHw+F78*9b(%l&xgF%9fqMu5R*-mZ`njKoftmO*5Do{t z7vbd3Yikl4Bivox0l~4=)j0}^2j-b1MqgQ{G7x0(pWIFXUe&=IW&{iBPtf~;$)D>! zR8r^Z>i7TJfJ0mIJkxX?h0&J)3&pmYtVCDUv>ILuii}fJ@1y~L$PLcdkcAC}b%L_z z%0#vV3C9v%;o+2OSgNQ+ zvLC4V2(5b;L#jSIjw%=_T0pLxp|C8^Q}C_fY4XxI({*v zLt1_EN7xNDN(f>Pw_bsFBi`8xq7K5?qPJk~ipcau?ZQFAL~On*-hXq``N2{2h7Q5# zJ3y-d-g+k-!W;x@KP@w`SHY@32=I1A%R>2qe{`t)(Z>7bJ6G(#Upj=}s^PHe+-LXu zbv{*qc9KvGi;y5ickRp2E94L0bn30v=39|B9#3Q%AVx65ZE{flwz%ij-RbFc_lmf2 zXLjO>7a~xSYtKjAeqsWiJ6{5q?8S3cNU`oPXNZLHaeInWZt^#91WRq4onZn_JD!2f zq^Di`n}2N!0F56YEM;pVD!%|%-UOZYzsL^~>j_k~8$~d+qy0T+3ct=)XJJojUi+u4 zm-pDdRHGeA3c4F-7{Q8^Hdz9&*smt-%7I{#>kqxakyG?+`R-W$W1Uwxw<|&G1|v}V zXu2(Tt5HJiyH18cc){8&kW{3qr;wl(Qm`s4G%jzTjtmu)JB zU^6!~y2cx<*=K{C(UtSkiPS5IwBrerMN+xbF3k}rD`_RHiXoqGa-}Eh4}K;F-G@l8 zzgJF^Y0#8cbS&R`^>)5I^Aqo(tr=Nk?_I34U-D*^syqR+j(OYh~y69p=5z;!&^vEb~B3_R#r$ zGJjr0}CEPd(0gNlRXq|H(HDPW*^_MLq!jTY3}*%C6=Aw@QM`P6NQ-y>POKHt4`@hs=^>ERqvr1G3;xKdEG0v|tk zSkwv*4KQ~+v??S^qiGEOfBV21E*x{^i266OkH%Pd`3zu#CcC^MG>{&stHqA+EQ4|^go81CNmun^M3+7l4=1IDn92qnuI z2NqMH4_&wI!)?;w(B=*BdtRED+y zJ*@bhrjrYqM@c=$EC@Y@Emy$%H}NWoLhXQQxCEvJ|1`MS(~>z#X9C=s9_dFFh{7IG z=ler|8Dv~&*woy7Wem1p37P~rXREu!chcF3VfnXz#;eEgT5h11>j zxu+z}G4V#wu;)W|Z`#w76w=2+cOQe&YE3BW#-=3}C|g~16oIw6E_D)MbMo|v2DJwC znK4nX&<><7iWeORxGnVTrT?5;^0#%E5a6H@-Lyd_~Y$q48 zt1dIannK9qJ^h1V@C@m^A8BMKA1TyYTT_+ug<6f_i@`Xgae|u;Q%>bO*ioTZ->m0+ zm0Nbrr@|45>C1?>lX%8GOxoc+8=pPXA(xZ(XYU#Z-miE3`WAA@f$}`863bVL83&9M zm%O9e2Q5H{zJcDs6@=i^B{8&TY({@Jne@eE0oD=`+G910GE?bcRJB+Bc8^QPymbPY ze8bm%jJ=fsZasklU*V_376d?X&#fd~_Y!Wa;K?Vt0-@0GYm{aeAyPRW^a1c0UY}w~ zw_af>v2sXzp-S-`Z?YB*G+rvO)4cHcVKMh99VgK3DCwHtxT`9{VjBJL?Z!z}^HnrV zACz>Ved$GMQE@EMoQSo{P{RnRl=77f(Q-u~e4j+uxXsq5A^W$2&jQYJ*X@obKwX3P z8f^cE!peUkG?&-^{1fVag#L&g;cLG+WJ-LN3Ur_6RLRVb4i2#z8f{yz{#|a5Iul_G zmN6YwCc5R)2}r@_dw4r#Q=;>0QaR@agbYFNE9RA0n`>Tw$?f zlcKG3@-pT*IUjwj`#DuV9OV7wT2yl4EkD(uApfqu`Ieh0k+_oEE1^Jaqw5lw@iKC7 z*Dt_^R{M>6GWq1o%nUyOByr9uAsrn+!VIOclu*vg z!CM?XeM1t@&#{`!;%YPS9TKPw6}dm^^5vo?+5-i`DZ0OgoD#|y`4I#nex(4uOjY=& z?!^X^CG-l=nyi0sJ^7*$@0?q`_$b87_rKM4z`YhqhHUHou&9d&DL!-V8VAW-tEJ z8diI$St0S}T375ZAw@7j8v8mZ5W$!}^W z(|g3U@n7vjEBd?XK_sSE)hE@NB?DV!xQ!?23|~;{b=OS76_5lLC91!C?DGs`ra=OE z<|wN}cV2VX`tn=-Vqw7NHfe8Q%+Xa$gvd*D*dj5}CNT_H zy7$^w%hE{Y?0`(vs|F1~?=1U6UeUr-(Sbl?@WR&m1KzU)z*CHvZGuL{hdzfs7D1!H z2n5Tb8y06+TB|B_rU9y_0csJPPYDkq{f^2Q*Q82sA|LNlvpQDyi}#{3|%(*TW3Jj^Fz@y67ci*eRsvMrihQh-i$_nQYabf z#i?SRj6TYTdYRtQX?^DQf|gx6zoO$jIK838-l{{*HQv?O zDbU5s8^x?4Ur<^YZSO-|-{s2^Vh(Yij;6amZ7fK?2sT}Rcln1}g;vyWgmc(?ASYO# za7{ie-sDX#3s8leM9}z6x2F@FqVlNG5Y%{|!@p(lyECMXlRiFR!0`$6dOJd^IeC)I#HOxh4=hb#O)?l04B>%d! zh_jLC*e!LNCe>3x6Uw=1q#KboLsYa5e0RBA6rTWOsGIN4D_#BPS==^Vkw3T0^UsCu zUpLlIkVGxZK!al>jP_G%i^)RX?q1eB!}>88Ri&dM&m9AZ^TS4vyN#`ub&%>==XDhQ zvNO*>)D!})$YrEVa*e33EC!#9z6KbX8l-gKI%bSL6DG8*Z?~eBV`t){M0dM6)*eX! zrAhDEo-_A9Zt8*@m)nS=&wtXp8}C0)-v@Kc5jtd}a9FlJ&P+Hh6+&hwI;4SX4L4?g zbkrW>+k-+v3y!aoRGgyGtjs!p;e~i4=<>O_GYzc`?d3!=DO;`i_&h@HJ-eU2Zolzc zbd#}Y`r6n0^rh>`IX$)C)f}PAGmP6?_j-rYbjl%bgxH}Z9wmOgOi}zZW2YCYv!a9H zL`k%Tg8O`Ix%`@QstlHyt?(})pN8yFU?|ig(f7ynRIRvzwKA4TK{%s@S$09dVMRaf zTQSP#$XY$~X-piJaKD>NiJu`K%J(+y*uBV51i!RXnS_&Blj*c9;Z-y+|KqTgPAGDZ z4Haz?O~kh7FxkAj!vt=A?d0Ko#!2cqR(@f@pR;|;io67Nry-IoK5k}YyUV&s0V#PX zT;i$?Eo+Y9k+eU{PP9T!L<{X}s&z$&crZ8YUM%+8lhk9HEMxU+v(W`Z-^B`n)n5uL%?Z||pV%@nAYpeh2$$#bVVq}b93;TgE zQ{JS zXI$$1G*Tf%D3gKTGaJq+ZAwb9QcI0~{9$AUYbFiF zf=UW|27(@dix+4C#;CQK`C3utW0~tL4S9euJ%*WR42z`^{@g{Cz%8}c|32C?B>}tD zPL8j|=c>CIifZlg0pW(JQ8Sq*G*5-7sYtsmT-J*7;j3%NuKVo1c5e1iaZu(olb#uk z{%t66$_MTVqeFiG9q%_aQL?Hf_Lg}@(=CkWDmZCoM$hv*D@tn&VPJ>(C)YF^veg<- zV0Q*^GWi9C!$YM%>n_Y#{+(bbE7M&ivc9?Qr3TWq#YoD&GU}Xu?B|%ZJX^$&WnsQA zBn2k2&{F+|*BKDEONLO2$AVb1Z2k{AU>?9wxLsOt^U$a@{uc~9z3r=!Qa zcjcaA4B?hY(P}PFCKcc-fq6`dO*=EGPMenvSN(IiY-rDlpwF8 zt^$7|>Y?5S^}(SjRkHU=mQ>VIOL_cTOdg`|8=Lyvymo%IlnOl*DXBh+J=lcehrHb>pV?H>4C_i7+zbYvob7O|u08hl zslI9G=<0ub?1+%_(7C<}II+$Agi8F`O{bx6k`8D;6Ot~siHo)uiL>&8Dn3eDjrOlK zc-1{5T}Tg<=AgTs1!1m&#qqdF+BY__*hqtK`BdOwDfGwZL5Bjx5;IXWin zbN`AXhgIv^cNlNJ=(_nZ3@Y=yQ+zEg?y>_CK@gDY?r3{_J14$=UC?;jp7IUPe||o> z-=LtSeLQcKV(+^C$o=$y{%Z>FS5;FFStrBYg{%!v0Bxf`i4Q8&QAOiP7KxZ`)~j(4 z6L9@vX_gxRL#LpL4f`qo{cn@xlU?Z1JE}LhTYR72c=fMR#*eKxmgNV%NQxz0^|DR5 zjgeRTcJtf6t?aF>?z45b$Gd_}w6Xf9#cv9d{TVM_K1!m^sBQ7NueAO3b)@|LeNpC8 z*bZ>X5kBv9Jy2mUu80He2^)YPt8Hx@KEGQ3@|&zFgW;dBrmu5zPW*cjRMbldPpKay zj%sr|SquPDAB(^ScPR#Tg^KCu1dnhrCw;KT+ zitFzk-u(C16 ztsD0fkcnEr=N&R@aRdPei01yXDZhRlQk0_}r{gp4*gN<>Fkq77=IhL&XbP?K4fZr4 zD2*&qZ^7(SS{}qN2JN}c9Q8@jjzOePXUzAMR$lMeicq_hixHy0bvQbOH zfsVG2)*#sOnk6-m!qK&O8}Wb%%#l;NKlyG&*_s#LSMeE7edcm-mjNN2Idj>%J27kOl}0 zh_~9hn&xvWY9FS$cHvEhiEY+l4~MCWHC~Pkau_N}R?UI8DsV&YrFj3Dc5z?o!p4ZZ{jGe=qgFmc2|uu}-A0<_pL&Ig)$WFwS?V)Bm-Tq#Uba1zgL8#sE=-6=;MYDy0f^M zxQc(x+|~saFed5Qg-gWPNA@sk^I&P~}ULV-xi?+WMJB*qY&epiP zT_8$x6d!2$&1M1_u#Yvj4~GRzmcR$q#+FjsmL1su13{dX$XD4L$uC*@&a|9Jj8>0N z+UZ~wp0j~TE&p0tFM0)?c}HU^-fEGPOoZCf95#Zcs7WvH9M{%L!YQqvSeB}@WtilLu5iv3 z|0hz7JW4t0jhfj*7bo{o1sM(+%3i#f)k={)IU$a?cI z0Kj#2^$hv+V)VH9pF}!_sI$$$HtWjCP-VllGFV{1F7sU`zX+}NDj+&#gW|G$?fmSV4QmwX#UjvuDXX5${E>Mi<~5J|N3QLyTe*L2a*=z zjMubtvu$h9v1Q!hKM)HLPkII>rmzBX^_dVzld!}_Ki0{aJxDClfMps>?;H28pCN{u zB-cHSWX^-BU6QkH=f_7#od~RPtKx_FCay7aP!EV4spsgNM2e+nXo%ad(q^$GKkB!freQb% zQ$ESjw@Zj$ljwF!>wW7YjolG+I2xF^`-G(ND3)WLIHZndc*&GK-3$Szp74~8%VNzG z%1y$<96lstMv+&}S%*9nbGJvCS2I35dv}ZECM+)949R9pL6ZNAytl$0M+SJ0(33zA z#`#DRL-QW7oJgU~_z^_e9ZzutQ}EMjkWQ=0VK6=3P2l8%lC#!IH!5m0Ac0oI6&0n@ zm$8YPm&d?fBhoE(+!vV!7lI5`G-2$qkOlxJ*;4ioaTxQMG3d&Ua5#nQVn(W<{GU=> z9`+pUCh5Ox_<(jMbrynF-GQTe)WS97zdv9>zBPrg#QMwMZj9O|iNg;v;H3KB?lmnz z?AGHow#m~`R~|Q}3=7<~a6(N$8%!Z4ar%$7y-GDcd=nwsCm@#Z2_3FUE;6Mb0IW+tEd5RvHDvt7>by-TB^c^PTrEpzq65e9!q&1W608)4d9>(np_~17gMNP z4|BgeQw?Q^*PdvTka~Q*t=_UIKe%JM-yfs*41c`h5C~NJ=KlH8$qult0pm%xJ0I`9 zi-O-OQ*$>`Cge_JkwIG9v>mfdfM^+jtjh|07|BtsVE*y0OKe6|_V#8v4eEI522hkY zuIN4^M}i<=A_hhL)T7tx0Bn-vtMV)MX!-ny^GN_%>SZNspruicBRTFwxViMzGDe)P z!Lkxk^G?7zmRiVMAhxSN7IJ}W?K$p<>S)X)dn%`#Kx`v3jt?+*ty_!6k)W9%dUzsk zxK7Fba_e2nL&JU4XY{MIU2I$fph~&8H;eSMWd#n*dIwLB#Z0Ya{7xy@t)Q@ymB&C% zk@dh})14!o8DqHSE`R-bPtWt*I#{&xXQ>?rF&cxQ7)DV#GHU_vUtH0oA+4BnSVSh4 zpiYm-5wE*zmQk$C_y9(E^LOrVGT_X?LqCW(xo47+>e|8BiiG6b-mP~33uv4{2?z+1 z9`;>%;e01Q3s9(#6}rNH>6A7_2-2b`gr-CkY$1w-;!f)^#=MNdxyp=jF|ow5Qz5Hi z2a-(rHc?4E?eL&Dtf-<@mNy_@s6D}@eiePPYL#sjLC?*j{xLEp(90kR>n*<%#Xdxq zgr;I2B<^g$F5D!VR_V+rI+8TWFVKb;1BsVSQ!7Y5i|vh6X)*(+BSXN&KQO|#m7v6N z)EXnQ#p(zid)S&G_F3#?Q+cg7NFQ7q`k|Awm=k7Jw`?DAKyEM z&9j`jTU5bszDjJfH8^B-NE_daER}jIBKuMzpnn0Zs6Xz>Wq@TGV4HLV70?k&@>Eqs zD%7f9HlQ0F(Z~cxTW8TtYsH(aDa)UC!s^pd7TB)m2re9FX)3j5(5*v}282J1V@65# zw|7K~1{Y|Z+bn0|g>AZ_ZuKc7wAcCh9`o zphD>bBj49U+UU(TzLxLPQJc1DbbGdTPu>`Sd_ip?0{%$ikvo z$hE%)!GXgzH*oREEB7R3YK!V_#Ff6mM68eYW!yT(;zGiyWq^H?`AFBi$t~T!VE%`; zIedeSJBn(z2N3C3#TOI=#gkgh^z|)4kRrL1yH2@7xjuMlp4@dQm@X!H>VEXnmvVqt z>bT^af(m)2dXU$@Om|F~iYRmNp0g%^NuVppX8dP({i#ZoN_Q*47^K(2L-f|HnKW|c ztfxHoi8QZ{S54lgK&4+^)P5UaSOMn)}E(f8IF8K>bwm$oJ zWruyN`j#fSDG6INMMi7|6S&#WOntt2BU)lJ{>O39FEb$U3^S4M)vQb*_qP_Wk{O|8 zsn0d(~Nw;v~pU7G@N6$Kxr@t8-)yJOaG#;J9T_JbP(-bp4de%URv$*@7=**OBsB=;=nF}Dh-*ggi@20HQzMN^Y6rg zy$0`xync0pZZM|H?l?}{wY_013%+XJ`yDLEh9v@s>NB7VEp3)2xR4RN`1=C5rdq9N z;XEZVo<%M9Hbht2vEM@tP4{!8Y%Ce3GD3x@rPjj2BUQwH8Rz*4;^4Cq(}^U_l2WIi z{HTdI@!Iyx@`?PcH?7nVLQlJsKEr8_ctOeyk^8RuI^ANZ->PT+Fmq@A`O_Y*LUxhk zdu@On@cw4&8IY_CsrDAwDZgF*RzQ=#jl)6v^D&QGPhGxB<}H+0iE6U(mNeYoDE0R~ z#64Z-$O@dwKQg~a3U!V*xn$tJdgfJcqK0-cSU0K&Kt)<{(ygJ$BF$nV>0JHb?o5ii zIB*ZJ#h`1|6PHs}^YRLecHDEs9K#zf+8Ab0fw{#V&C1*3T#~u!x4@#1l7{Ci#J4&o%8mL>%Tk!lBp6DmR34)8pvc*&O1HP%`86)! z=jKLzyt}u8wbn2?i>!H=SaaGzTd_@=baWADYRS2!*k??A3DXm@)*~h`S?1ugdk`{d zx4DGwiXIx%7K#RUzVPXanz@9< zMeU@K-8fy$FdeSWz!cc1&;VrdKb%fltROLP`5`i0uXub*>`+=~8x_*Q!Br8r>J_ar zCvc22WKrr3MBg-K$l$iF&JPI)Hnt!t82TlJc;0Gkgb$nQ-#XGL<$x+x&p@xp@JXwF z4F(A%CvD-}+G(q8DY3$$%&=Y~tMd)liS`ty3~mh_9Q??jMQv)(ya`DuNrL)!c)jj{ zkMWP_)aOYM?*MQ7fjP5|ToDH`kua913Hy`g37TkF4phTH8F58=94hyng{N*d?8te* zJ`9R<7+Q1*RZ<1f^4KDpwS21D8&NB*2HLGaI^SWe;48?UKwv`uXKgF{ zNPRF4{`R~zEv2gnqpfS{bpX6e0T+&kFj^G}Xmh39AP{`N%RuhdO`I|`#or@)0a4L} zm!4V@eLoY}N`J_8U!$;E8lP)hcGo~|AV=E_59H!6wMuHlMlX3?^LfQ{XGjywQ(FO7 z!2>_efCJF>U5B`lUN^pZsrUdkI7Q>|vud@&(0Evqci~SnjEYc7r#FT7jwEDA;&0|n zU({lGb_h2T5bF@$*4;cavkp*>0qZ8{J~6fQCYi{u0Yo?xZaP%NV4ozD>!?#=qYLsw z?<4v#PCK~Kt|rMX8Iln!UiY^D)*?8y0pTlTfOS}jJ^6w07DfEx+CQH5kpS8!hOBN^ z(6~B3F|Wul5+orliMN4peqOrZPbNBS!Sy$%mj)z71Y`SuHjqKm+r2~BWxn%uyjOA4 zLTP{O22|*fvEgg@!u%MG?=#~A{}8l-QlHdc+N$p!?=ZdP(OPMUsZcI9;3_Y-Z+_V0 zWq5=>Lm?0~P_QsN8Px;e<$)*P<#(T=or&>Y5F!t8U}avuy!>oaT) z^d{mGqmrgBE;rLm#N2tP)|?CHASPWqlBkzVzt>u-32VP$)mN9Pzs)`NnQBBg7nl|` z?_%wSisImyIx&QU-2X1DV*7sO_l_gyK~c8uYOmKx?9QryksT+DH#auqHcYikxULHrN`zM5g~j8cZzI|=EoFwdBANKNVyb**A)?E z$M|eZq!_P<@p&oty83c~KLVzGLPdl;bOQh)|dT;2x;WW;FoIF%v zOeK0d_+{P;OTQQM>EMvqY4nb75|Ncf2(1)J*VCe73#FoHT(JMCP&OGSk{URr(L<7R zRz_DS?_$GrPTahT(Ro)7v0zp}Fb8l^gJ6Jc+?Qi;-)(v&`p*|R>L~~Qb|GA-C!)eb z5GV%2cj{C;SgqO!;c4yq1%Svcc$F<}IAaa+QQe{r4FaWv6G#b*AMT;o(ICfxEn>wV zB>d9?Qa_9gk>E9M>rfk_`Ei5WR3KvZ#t_CHn2OVPG~Zv{Gd5Li)tSPL6-3f6x|lQo z_giBFwJ)m>d6*fl7^xLo8!H7dg(lfO1n6hk3j_lbEcXP)nGz0l{=^~Kis#cZOn^_6 zYE_C~l#7`dTR3x(!f_EDj*wJsZFDhJeUa%lkNpKI`g>VD-3RMyQIT6-KYB+VRZ9e! zOel<_xat=x1uh<34Lwo{%4euq22$RaX@BLNY4z-B(~R~(P|tk9svL|LkX^sWty(uD z&=3oQSAv46g@KZ1`Qd5Wz;4?KY_Ds3r+=f7u-4AltBQude3qG(-JD>0)8--bQwh9q z#40=AecNGF>@K&j{r;JV&XZFy=+l-GW~|Z-#H(snqX`6c4U(ZFA5kMH@yA3 zZTM1%Q|}GKHIAeBeTKhL(xC_#%IBPa(bY6>6hYE~m*knKAFqjm>O!Ji==|aD@G&of zf@k><2trRvhIt;#KjvJro8i#E^hq2Fe{XM8h28TK1*)34;_Kh=gf!# zSv&W|d*JD)$?dubP1pI$lg>vEYRhAom|FL=(cmdE zFhwk$YB9l?KWgpy&7jFhP5@~1#l+x!-&hp-MZ;QsVd-dP+w53T0wz!t<|5zX4ig-K zOYLE{&54!oYPEirsPZM}xy@dwJ$dWrzkkuR%;e1~v8ky5_#`0YDhsx6yLGd!c{A_t zH^%!S8?^m$kuCUPZn6~LLdUawy#_Wwl&}fqYNDT>wYw<0Kl~r7tFRx`22@Tj&3n zmGj4Ob1P+G%1`D`g*)fJv2o{-;bA~JB7gf9psjaw4h)P1Bvt@oodK&klZ{xFM}X)= z@b%NxPC)~ZW=16jpweh+o^|>^K-jN?I{Z~4I+dxj^tK_EC%YHK++jRk`|_x=ZZ-m_ z+txkqoSYmM^Jo}K%?NyHV3Up?H{eUDOrTAWvt2j#(iwr2%(Xyr5d4=zTwTg(&}&Tb zt#Fd58U}@$kqme;aO1Ln#_-gH4p689sLVZ+km(iw-rIaFMM4B67rsh90K9kHJe`;4 zYl!}zds)BFqe7ogv!i7XBv_t={L>Sx`RIQB2*CvZLc!sMtPP$@=3iObpp18ay|MB^ z4R~yC4%y|BEk>aB+WeGK0;m!*9$H;LUnK*J7;sxUR8zOl=Y*&s4~%Af-C>QHEah90 zcR*Icpk4XNTF8(*a>yCZ>~n?4gr@+l{nzoY8%@9f2k^pKmaJEeUMPc@q~l`GJ+f&N z*>aZ>BPJyYvx3yPyneP52}QPQrAtLskft(+5$JR}bS6L!Cm|}K<~UHs=AFQspYUX7 zg=Ni#el~(oRQQR<8bsIe&`0xzVYnKJrlF#qInQVeVGxNBvhVCz1tX~u#0?dSE}M|J zpMXZS!BveB^QTc#n9Lo)WHaXz>hrj?AG#cYSq;Y7(v!jmv?rF8l&_UP$AyOgp!_%f zy_VYk7;VCETtKFtzwrNl;Ra ziMEhCu-7AZiCB@`1a)Yu8A-i{_LEqD5FcXM-+cDhcI`;k(AlT0vZb!6vIohS+4@l1 zLc*(jT9IS4!ng`Cpc(aIyO%$Gu`nX4K(qQRru?p>M`%I0MNHs!>Q)7Yg*1biGUedz zJvMmj<_9Lb?Hgmifsh;Np|Qr%-~=$J<s>7$dxPesIYYDyBjng%E#nvE3+H`^6!wjtU{LnxY<4jMD z@Rr?q_XLA{XfHZZrBb$8#jGoP_zAWZ_B6MMU5i=<$mT5Q5suN!HgR~A#=x08syd^L z%9orHQ1^*Ii{mZW4G?zKz0+5v5BAu`9>^L9VpH-`mOx1+gmG(2eyuqYZL{lvc{bA8 zv>BvlI%!B3*UOHg1vI?EnzB_UN~Wh3e^2rk3v_!F?UIIhqy`oSb$bdoZTb?Zt|{;$ z4$PBGY_bV{+3JWn0;qz1hs=vNxxef>I6kEyAXM_EFX-u=gnAISj&9*;LQNA zxd7e{#V_CZW?gUS*19LWR{#JU+;vukFjar*1y0B-!Iy>%7M9|32VwrbZ`^{^ul&NN zPJ35yOip*D>AN+Qa z2pWB&6>K&|XMq}+GPZ+RH;>6EYDToOE~u zV@mDa$2N})jmx>L{!aHKPjKms1E!Wj@%&4s)uP<-F*9)#tQ=8gcc>vN+csj9=zVl+=-$l0;fi)mk+vQSGQm*AJQ_|QSc z3cy$P=~+7T*G)PI|APdTT=0C}Miw4DKB8e_X1*S?s%P|hhjxEJZg20%fHb$V<`u|5 z^)y(gTUxAJlL6(0VMevJO=g@Pn7Qbs%YsZi{EqGk(?&S>)Jril9L{XcYL;@Ld+vom z>+yQ#MYHhxJ}M0Q6CgsnLxdCQ%eVCU`(+44F#BPOTOdo2bDSd8hb@>in0!SfWE#bS zk^O94mha!jnb*&UQR~g13ef*9)ElZJEY-=DyE;0B8uXvG`cCGq^hGqIG?kSn+Zwi{WloPwAOhA1 z=FlQ$8RJTXiof+B&NeCIl_*Y3;Qb6nbN))XpHGm>Z7h@ zw&+9zAZA!p9>n~Q!9#kygDZFRbvy#dhhxSAl!XB?g5OV#x2I3GS{sno@bl+cCJ`(KA6RatRSHjU{NT(4);I`b zH#^6~=$#eLO!?=7^tK+pzyN|dfI7vKiO1g&I!2`#iD~+${c7>$kY~;6u)94SOkCb} zO?b!=prrsjl4~2rPanZ*S9RVSW9Ag}r&X4Vh&3`#Ax{0N#Rt~TQL$vcwk?Q6Bq_Da_1;ry1tq8 z`&Yvey3&7lN#$BhciG-(AQ7)#3@R^#toCxLuB50}JPsi^^iF>m zS^ppxa1wx*neDU9iTa;necgG7)^nyypD+CDWi@YYcrl}>zZH(8emHZp6wnaBNY-2$ zy3sjpcwyF)iR++XQBsc~089Yw)=}oUIo2P%W8IFioSu08HYJQtl@YKs^Z`*!yTud4 z5eJRf)nJy5ImW`0RVmB z2ST+q`M-kuFom7N|;z}3v(SdA~JJ++Gw*|hgQ8_3h|_Hp~Qxe z`fbvER@DTFa*~UBd+btLaty)TzjwAgm6La!Ox=RFB<0y!BU@aJ#3gk^;1U)XKyAC$ zE-OV~9SHI{P%xO2;9wR_qtpgP%bHYDa_{S$rJj8 zxJ2wOP1D$uoSkzIVe2U-WU%Sv*B=#_oZsR|`Jk+~AA3Ip06VGR$0lRbt{s455^0Q- z$SniU&{(+t$@1TI@7dAe^?gWg(CY)38#{SBM=vk8k+oc=;EbWg(G|n#$d*7@cTWRV z{h~eNJK%Qr{l^8Kt)b z|0w~qpZEp3`cP2)P%_^GR=dg1{(ym#xar@lcQr_sQfkSQOq$h&q-#C>r8ZN>;qLrcm z)BFWZ?2Psg8oneh)}9 zi6pLmFOlZ&3_7hcFzU^V$JXB&p#zm_7&>LSm?EneO>#{zaTgtGIki_C;PencE^?;V z_a`_&B}OD*_@n^tfv7{OadGJ=5G) zuEU@U!uUZaB8EhPl8c2vB0=!HQRnly*ccd3nVFemR_h$m)wu@JnFB=fQ5U=T&CsZ+ z>wG)E><)){m9cPBe4j}9qMe%sO5_>Du3IP|@Ptnh_ghIrle8q(#ZA_mFbL;|#|t_` z`=-VgAtjL}fa&VRuW&Xz8!9Pb)s%d#+bz)l>;;ui!#}Y$7Is#I#>iQSJ9*W#l)~L4B+bi4;+cre9uY(;@lggUC}~JR-`jlJ5Ft?TOI6g3)OC!N3!&5G zlpCJ7s1e<08h~3cwF{Tg%z0F+6kD#AxeIe9S6zeGo{8n0+Mls{#d|4!vBWJ70*per zss704F@>h2@eLDuH3Kx@9EX3_tj7_8#oA&LuA&6xud9xSoPbUW zbH>`xr!O2mTVq~4UY%ut%15E^%u#Loz$ zn(3@x#?mJ;_ky*+GB*$IAZ!H(^fvLiGdbe!irEY$PfZGJMeMK<9aKh`1JXg*gM8_x!4ikWKgPHFfSC(p{8wRnx!&i(TaS7Ej83PHEkzX zL+hIFoqQH!JrFxdX=0p{gJJh!+-^0Zqu-cw2D-^jQCrKN^amra6^np*rOmKcaT}JY zJ=sq_C`jT>;egH?pDk{$)pGvs{zUeFRpb3VUdPKzXMg|jMP}pO=@V{Vq2XaG;U|#e zUeD0ZY`j)VL7{1@!O_7t0zj8DFs&IEuzGZVuhOHz4u#bp5LAUv+dI>hinth* z7z}wA-+9--e9vrlC^iE?Be8i8L7I#O2alH^SEq6)GP2vzMXf-297a?9aH)c)#2#?A zbaw;g-=m)L$Mp6`d||81mn`1nAc2K@tY?F%T?xP5{QtK-YSFS&{<_Z;954L(_Y=|# z;E3mcBFG1jiFBzr1_clKn1mnZ7S4S2MVaR^1-P3sk;e?laVV4;O+yDEqdM_NlQ`d` zs5;hQA>7VRHYhEjih~3pQys9CY*c_`NqVNc0^^|Lk}%;`>@>9n&E&40n<|iBF%tj6tjEA79lpabk1%_<(HS0*PDP{EJ7NVxi z*zfv1_^Ne%3lUJi%hQm8x;-%1_(it(?s0iVd~$BRd_>(qRpEhW!>@0yjnxcYK%Uq< z9HHF%t$;ZL7+pS?B#=KHt{MKBC=y?wMK$~b&*9mhh#Ho62LF$@`M?Olk5)l+T9szi+xAHFxt2gc2!Gv(LX63U+VcgNqgTZ&T; zm=s6QUO+8wcsDo=N@u^z%3abgTARE(Fi`yD><>o#Eq-O^XRLOPL)q8c_Nu59D@rJu zsg;HA~iBSS(p>Zr6=Z<5e1(@Go z$WM&v#;tY$GSZB zm692pcQ_-Lh3k(6L#Fy4=6(DRy_4XV8(g5zPfNkkpZCfi)(GRODV`Nj10fQ^)zj>{ zD!vdP6>_LfqC`08t6IO2Iy}3Zu*=Ik4lIABoFOugQ%R-Uq+{{gi}94W;Qn7opym7P4y5DEv8w*#89@D z%zLZjn4ufZBf!p=3R9YP0p~BQqMD_h>?7Hq3R?R`h}vu8`nJh`py*EI#?hg9@8-72 zS7>*de`pJA6;EVFW~=xkZ%fRHr(f$*+q;Qa@=?Jb{WGTt za1+2vm`N<%b7U|Ugwq4$`AW{}OWKWGNGvl@%X-nYje;p)#7INl5O+Mg?(y0xMBeUg zVZo4kf?)a-aA+1qXvf9_m4$vGg6~IyLml&lp+K|eQW^Iu*m`$Puq++Wr|nQyX?I8= zgKPe1@8{HJ;8m(ZS!xD#LF^!MD#2TI&s5Rnq8HBf$NEPBYQ)x|07j(W=iT`0A!0yW zVZa@#US6TJS6q{V)XNI+Uu`_zUPdS|G%%AbNYycOAb?fN#5_bfk?GV25SZS^3KT|k zE1rb&5(K@VVd*bn>0$BjZR0z3z4EHTUGAfOqpj4u#Zwu0SZ`kkWZ{9oJ?kzzp1?#! z5G&<%U+Pn=meHUP=MNofIcK4~KGh!twI)5%Dtyf| zokD$+vGUepXa8t=>}3QboINiZ_R*rP!L8TgD4l}|coSU*V^4Fh)=Vhu(0t|`gjFj& zNWy=$D@x0S9>~O8Wd(+sS}H+0Ic_br)8S;(4``J>7MZRx{#j&v&uilnyEW)hiRqL^ zu=HR&Eo_-zBc1tq{iefR*j>O(Z3ext=@;kO4R;y4dz~Fe4SB`Y3(Q*F%S5R-1yDMJ zoK^J{=rX^$^@bX@*nz%N*Id`B%I!#Vm~1;I%})0H8cm>fzK0T$58)W;(myVG)PlUY zh>04dr!O;t%-2s8E?>C6cer>bp8Sv`_~(1q6X$6=s`@Usby)bId59pAl~kR z^8cPpi=ODS-Y@4~t_??N;G&lWroI<_ zOjcF(&+<6PD$`Rvz}|$D`=?FmhScz5JD(moOM^$xn;|xyAK?>oT!nDRGNE0x#w}ow z4b^IkNIVD$P_mwIb`24ne-|ZDTpLGM8^hEKZQ1W?r>DYMp)~SDxX)|n!b;U91-y#M zuL)6?TeMLIRV{`MX29nI*772Uan2h@fCe}612WBc;2AJc*x57LNW|&(Q!=oNaRz{% z4ui=-tDS4q=bB!mKA`sDIF1Tc%#oO4)9LJ>sWZeuL{lx0tJMJ#P;wyq*xX#s&H%5F zfZjm?OD7Y*$Hj54w|nsWti|VeQ?0CR^kW<4xhaGA=GD;BMpi^1!HGxrw@Wx z|6@8u{$D)6kY!;&0;l8N;nggCL!n-%>|kw&V{#Q>-7Y%Uc)KX6xQKN7IqG`M{9mzs zbOH|Ocv4dpZx@#nnJ*;)zEO<-KIQxU=gSs=0;yDNxcyg2Xxgg%k(GO96mKaYAE!x| zz(i9}OORmf__~`A*+Db@hrO+yIK}5kP{W zAo*>f+FG#7?;4dv9ioQ@`}A5o>fxc11BJnq&{;IIr>4vINfo z@e6-J0~m`M1MXaVUY~V8PX#|AkDY-?iP=+(bq~L_wy_FYFu_lXLVkzPgUtR(ocd)~ zzroXtzHH#rjwPQTip z?~WJFdOtK^yzmBnNE&IypDV_YEi?x=hHGXbuF{>T%2jQBCnozCsT){IJfseDw8zs5 zg@ci@!NWZ9q8^afq}7gjUYhP8t2@%DQ*1u2@R)F@k!LlKr;9P9Oje>#Qsxr1M_o?n zug4~Z?;3v%8OT-K#y4s!Y004x7l1M0*UgW*W4+AUea+tRw+A4CIUcEc#KUt;`Sr>! zderSa>-OyZ71=&}-uV|HH?+tchTv_?do26C?xl5Nd3&>J@++WmRRg^K_oAe^1D1;z z?DC&N=?9BP$3KZ&4#}rXuJU6+I0K#vwWn+}A-U!Aci-jA{1r<1&z9L9V*>QOlUU$p+jpymwwzdf9JFYl?JEc*M_CI*? zaY&9&i9s-6Q*Hk1-$yP@U6N3xqIy!wBgPZ=LR35juJVulgmU&*(_r~P>VFuFk1&Lj z9C1byKt_Ze&cafJUB%^g@h4pQh|I`+)H0s3QI3gTAO4jnQ;Jpzji>_omz?PTYXP)D zo|vXLO%KlR9gkw2pu~kjj-iRvF?8=~fc9BTI<^ixIz|INh-4P7K-*tlusn6)KJY!d z>7hnH96l9M(5zeC4OmgLSZ9_DoyMqIXW`Hu`l4(X*Cgb)tU#bXa#&%gZxoP5ixgBK zVx|b>Q=15%y`Ijw1wK9_t^Qz?GtJG<0oW4pj)nfA4Lf1V>rYjNXKS&mAfQUwb7zbc~9|Q0$CTqrh z$fI-T<{1aPM{?IW0Z|tKC(z{5{PHq92d?y?w|789!$p#7aF~X@kST^DU(Mu|o(B+L zL@QYjNoKt?ec9$mbqk{$u$@cgEUwTob#oGq_x1BBd;`JtLY|?mUSNL2n@j$Ffs7^% zgFmNw6jlJV>PY|h+JtP@U@O+DYXNKEt_UNG#pfySt+?Zbr=Nqt|FTFVVX0SBPHH@; zrbJPo4=_QXkYHeh=~wDNJS>V0iP^+i&~<7cL27MF^ZAl)_Gs9UYDh9xTq~}=ztzHrBr3$pznoPrq!qm~@+ib! z1O^n6Dm5x^b~q!bE;?(3=^r}38lsq$%z=r`jwR{w?f6o(6>&QAmQ_TZp;k8sv&gqu z7fL_N{}LB2$f?L8$qf{0cQX~O;gtmqBDlEeBdY^*04X3`W&3#&nQ6w%WyT}p9;KN< zovyK!W|Ft7b40)v%F59CK4US){9xB;-x^uFO3uf zY)<}~>P5;nS5!V}{vPyZgUUF`+tgFd9KXl{aWg=8o9w~=c}017Jm5uq`NOPDV~{(Y z_TZB__VpJFDD_SM&&!Q!SmCQoU0!Iq2Ma|cU2=aDK2FM#W232r=%Y^C>Mi1X*plf9 zr`(VtGMyOpXDyRtXLNS{$aAHcUu1qG-UOwN_&sA4OeNFtGWu7PnTU+;6SOLxP9eQ) z+ky{7wJaZ|Q0S}_e>nkHRA%TBBZ(5JSA+72I|DX%B9mqE)2BJZWAuHDVe zty5rR%1My=_S5EpR7qHBJHe}h6EtWLI9&Q(cww!|&S^e5g>CaKf0Zq7g5Kk2%3IaT zm>*8XBtD15?~ktKjz|Dqr9mUbp|4O&bdK?#YH7 zdQFJ}ii(1{k*W|U5ZyPA;&Yw-IJf;R6Th0bLn(~y!JUP?yw7d}8yQWTdtxz@%w$U+ zG>XW?T2RABN^3*q@%=X0MK60s5Jj8U_dR;w_q(ni0F?cDoSLXCGq$-2E%0@W3eeyb z+w$t=>6bX-<~8`*IimJ`o#Og^9^+iNCw>iM^ap-meC!}p19M!!zc&bXoG-A!ujR5U ztl^eb2+x&vZqg#!rHm|`<*_dr-R7~GSKBj0kmZ96o51=0WhBC5iAIlItdQR511VD8 zOvJXA#d?16x|_XmT78n*(W!gE<%b(e;}DB6Z5jMH$2|Xo=xhDFt!Kdp#f$pQ@DC#6 z&9V0tyUjlXW~ePitTeZd>_`bGa&@IC{g z2(E%uB#xECN#}0E*gZhv&#$$&B)Zrt_LKB6FfZz?;Avr`v|r?xjam&%+YF2Wz~WYJ zK(qsRfu7*t6JP+r_j@drQgPvhUqz+?YvpJ(M*|pk4)L;>-dv(%>>iCs?xxQYzP`STLr)<$a%ytjL4%TOB%)zWxvO6 zdyo6Od*uBd!#H5K-=Pd6#40q4XH_D!NsMdI0Zd7aV5A}0EhZ@_Y+1eMPC$VV?(_ zo}c0J`Wnx_{T5BvN@7X?oZ096;r?EdDlwxujd6~v%wl-taNi>=mMQ-f9H6*CLDE2o|8q~kQ_qZ+&tjx z-#^3U#*6Z<*<)gaoLD64j6~M%$vIV5X*XKQzI*rN8fDDyHsA2KPo>PeJfRNBuaAF zz+z!rNG(rM4}KZa@1%wcGVK|OfLAZS#Wn+<{rIQoS8I&9xGX3JEQaJNPhR@`t`fxQ z`rRpqU7PaVcgZPp{&4tCUi>`Q5m;S|d}UVO_vNP_l%yZZJ4@msR-*tWNihH?2E|T& z;PQrVE-QY*K}tZ8KqRqe3fL`4Ss8vk5pl^tK_hAq@W8YZG#;i2Jn`hUu)7));0hsE z`mqT8a<2wtpZGwkM8FD+=W#zsfjw7nFcsFKB(*FEix6spShTu{64beJPo zbi{k-#m9lCwQ~jCqE|Tt&r5`9&XD8vB|+UkqbkSe!1XbrXu>&AEu3N-=O<0JCPo&E zpUca0{L6p-&%g}q_dDF*Kj8K2*Ld^hE$;5`@%HU4_PafX{T{ph7I*iza@w6U@-V7$ zQZ2bOey_ZrB>N>{ni-N3s1rukH4Rpq4W3+H;q3Gb7nc_}KRv_Kr%!Qqc8b1lv0AOr z_iHpwr(P4JSQ%+a#Iz6W&qSa``9wOh3a%p>OPph zf7xH2NfwdcOrs8A5BD@OuBd7P(vJ^NVmo)j~%*q8^wtnkjnpv5Kdg?*H z0V0+IIudY3$>N?_-|SV!hqzv2vEa4eL!+_ta zg<|7pd(zezBMRg-?wF6$q)n<;P%wFae~;aMj{?Rp?3LC``7s9o>vK(qW8@Y(wr0cr zUa}hhJ|*&j154d7?m1^!b8Uk{0(P4s$|sZDjQ>P>ZhNtm%9|n|p3}G5_o>2k?j11y z8+lrM#@-j#YqWZqXZ@{hsxn^XN4BL>SQm$5I+u^;RyK2M8&kU4a92g)T=x5ZC64Ek z@^db~&F^2jJ|FXm;^+wfJZM+w^rSuCgRcnwFiM(¥@qg@h%BOMr)+vFVn545zhZ zhuxELv(+A+Gah0bOaDhzLsQ@3s)B3|A%**G3u-GG65!2qTbcODC%* z(m9KJZHkXbEh~NULH7AIZ!1w|RnHLS5!;6y0HBNm9`0_i-R@BGi2M6HJZ$epd6q}y zJZiYpf`-TpZqX+~>g3R<@$mnek3#!g=SbUci5?vY2@hu0gJ0Xf(D78+(fK$4W?4T? zlIx`uG*CI$_Hv*btn*=x9AHT#RSF01E%iLJVRRNkzTcas!Rt4#arxvaPR}l}&q9+v z|KShu{KX60+}`43y+Pk~822N_afg%$Z(rX?A|wF&-4>hEjmyn0H`w}D+28ky@siA< zfDQYZ2x8gkb8LroDo@C!s2+DD>s8JY3i6nNoBs%c zN-6375MD5jdk?W@b7TpTS>-dK8+8{oDS?yl0mC5@FV}Pq)w8D*^^{7!Q{^}F5K818 zR3@dBAXnNt1|SELiO?j%_U0vSUu^L72R}vwiNERIeu?$`-t-_A*09m_G38&81w>wl znJz=C) zlaHalN+>2z>fFKzowY3{@-X25!sL*q87{3q5x7N$d(ZsTEE_*Z1-_5zfyp@P~i+Q=Fcj>ADeMo%86fD&x4r ze!p|!N-WoM=x1aqHK|h_FAkvfaNYR0DR+EK0lqYbb$;xg!wkpAi=B4Q6|5zI#VRnx zIzCYCkhPUT2r5(T&;8S{RPLKCZ=zjoi2Kek?3kWXowFqXVFoaQfBLO)c zk8wUm+TV&>mB*+D1B*3xqkN1}1VbmG?@6^mte}{g#Fdi-fEy@k2|&>{Qg&u#LZ>PD z8LS5 zcQ`Pt(`wJgzp*}!?V8nZ04yG8BG5k~a*JA1Xg3trm5vK@P^{X5kw(<08(e$K;3aQW#oR8MOq+olDpHJF0YxkU1+UH{m!}<>UY#~%CwUF!a{`k8* z8>e#Ko+&?suLVm6YBa*eu=14mwXUq=J}*mP_LzJXpII8~x$L(j3lh!t7%*8Q$7lgi z_t|$TasXB5rN(^LLl4=6)l1EW%amXc`d(tc^j=akR4NRhsAa101G%Tzx;Gv%_h2D) zIro2pB8rOo6qb>bI!GU4WCx~t7|U#4LZ%4KF0T`dRh(Okasp8+iWkZt0&*_G-$<~H zthpq-gGDjb5F}|5>w0B*2M-0~I3VYYhyS0wH*1n4InD$>HFNj4@~)$+s~Tt=Bmr_B zI4iq+!-&kz{@5Ae?!Q&UD;<90W*eNa_1bq~+%Zcyf}yrnuK zJ^ZjkP4!bXJyvThAMTO5J%`8dHyjopgXl|QWJ*cq31|qsnr}GS<|I5mc7f+W zJXRst1t}rwhHAzW33;ndXenve#NfoX%(5nRz9G28@`&tkAv6|sE-glxVgE($=Nfw7!YE_@zD{^PEYa2Kl}mP^#-%q3DdXKBTS}KwEI2Ub`S4e_Lj_;A?uz6|MTAtzT!@3DunDgEA!Hm38MQ^F3ePnc_{)B zdp20M+(v-qF?oOxL6ToR%6Rxp+iIlde_WrJimU;9TP`0~XxkR2$47{v#b(vPJHoW7 zF_|pTG!uAVq4EyiduU)gfoZ)<0WPv!?P7!%@5~T$ccD6*j!}ZFTjgQmp$sCp%A*S? z#!e)#okER)vPPX2^o3d2sjOe68_}-|))1RWo-+vU2;gFl0n59OI667O;5b{oshxI^t%#hI= zYZdG%r6|U%4-t%Z4JQYm?#ybS+%FJy$Tn2)sa8XJ*bX{pEIS1WwBXV%wV^&u8vAxDc|n26WXj?3lL>-^)|2zt?>lt6E#{LN^Z6o&dH}7NORZ$A z!qy7WA`JWV(9h?i0#~0oG;-j8&ia23m8qdZ)EAOvET0l|!-+3+#Y%NwA(ONOC<;#h z+1!b&Tv#Q-4cC#SnbJ1RO{iX|7w;D=^@^$QYpdSfA36i%i<@~t1TDi!Vev%l8OL(b$r=_uBijXmUFqG#* z+4Gpu?=jwL>Ab%N3YTUBuR|ICVt6R4jzmU@p<%EItk2Xg@jLaJKAua$6pQR0D!B*4 zV%}3^r@h|FzsHQjW6G_S!D9;U*qD!QfE!+9m1=8{D$heU3jB~GA!R;FBIs0K$+#CR z5=5aX_u9XeSE_gu9+ncgIyohzTpK~2hf*kq4HImfODRdd(^TYzI9?D9HW^bf)F!zF zA}ckloW)4Y@*5^9h`T6qgwzQ|!-4s|jvBrmk#kHE0p#JU34ltRRCpk|l-TGQ0*A-9 zdu-Ml>~>p(c8hMuq46;U_QDGtQtAMTXetLvy#C3vC!8ZqF_k!UILSImW_^G$HV;=6 z&pllT%wu94%&Ck^4%XB0PC@`E8|K-7P7b6p8=)7TtaLf7q@53wR!u37Z`9&6hCgru zQt@&H;{=hR`i>YAx{$D0Z}9f*w|M>f3)FRueP}_>;mw;jc>n%A5F(~cgSwgn;2fS+ zr%x1{XORMDJIPXp$qWd=QKb-f9-*Q6z!N0NK)Y?9Xl$E#L5BH7h>ROBBtw( z=O$azd965&j7;YJET*&HH&SB5vJrD6vK%7w9SEnVr#Lz~L0#1#N9-9YI5Zpnk}Su_ zd?2EDS5}or=sL8Kzx%4@brGUi6_6La;zXCz2XNCOAv=1(Iq?ED7+dTlBt=&W?>Bs2 za`k5VlAmmPje^As_9DR}yfM$kviG|UZa!Y&qMpJx6X9P3WoW9)7arZ0tz@P^WtmonMI0(n`JePf!4$X+5m9zABPf*}S&LL+3c^fp ziiS{5$6)Upd!JR7k};f(c`Wuq=LhY33WV$XGJqZEg~h0pK$1%+Qpet5q#@nn?VJcz z6>)U5z@%xg*=#^98#+U1#gmAOFm1OpkRx=VLn|Tq`+Y#W+2YF|{}@0*2%WTnl`?M1 zF#Uq|k!jNn3P>m*RD?e?hV-fwqWl(zsWiT0JjZg6*)~{(@Vk%VVWmbI2ROUk(<9>kS**za3BJlx@UF-Ki_gcRgDp*_j{g8C zFJ>8E6j@uKsqmbVU#!o||E&hnJicW4<~Yqn!AuFhH@;42ISCKs_8mU2z`yYgx3P9T zmV5az1K-%Wz5#Chw|+Z>F=ZL5vNpHOTvM(e!$MXbSw+4WwXD2`d7h4eeTKGmbhykI z3)SYfApiXo?iw0L#|)<57aR1);PLD1-(|fU@bH5Ui&+6Xhsq11jM2c#1&~JG3uaG! zT8>D$E&_Xy%6y7Bg4ZmesvLHk4c6NY=8GeEN3u~CI?H0!Kc%qPOtyI`NiOgNo=dGBpV)7t|#P-KwRN6py7I=F^EA>H~}= znD@sd1%f2}7}O8(wY)Cl9cgFzy^pb!n$$RiEWeEb)_LZG$?|%Su1mPPd*Hm6&SA6J zNQieU?{iphIK@{Yhs(?N`0~r2LaE{6;sT$)dWGwcA2FFu+1T6_S-W1XkO+vOa=!3frVDq>zz;U&qjGt1q>3g3SF7F`!H zn@wqm9CwV$45goI+6D zAZCLrIfyMnW`Na-%yW2bSe`^g+~0ga1n}b38~A2|F5}RCiY&`#3vKsxhCbia`)q28 zl*9TRmCeCI8|aT0`l)Y}_gXz$>EuN)N|c z-#Zv{U64;6eWgqR@vt5J!VzO(k!8K{r+|>$rf9&76Hu;gQ^SVloJt!112uy7^T3ul z(|2k6IlZyw_@pwIGR_Jp92N5t$bhTC`WiEGjs5-98XC*po7W%AJW=7xY4H5qmOle{ z7+jX0g(=WSF^nB>)MKyuW-tfyl!p@l?xzP7H@s1Bp=i z3SCIp@AqgLd)+ulv}5zs@u(5ejQ3MUshBttB+DM@a}wIoO;0sf=Xo{Xi=tY*ic~Jf zs5!fgr?Zlew2N&Tg}01>?NQpXeNu35nJg63Fdr&Ppn9@$^vYy1#qGl#{^7sHs!|VA?QhEcE_}6Yma(Ey#(ylQ=MO!GbDC1jp2GGT=4G6I zqSBG3B+lANa2wAd^A(5}>3AOMF*!Y?!N;yqdbH_%#=O3sGSWTvzJjf2aG#z_=C{nG z&EL^{*Y_0Jz~iX>k#k655ECAf@s+kfHw=dulAqBZKQ+YiIp>P3dWue-;8nRUXbI++1Jc_WC1E z&dww^C2xqtZVwXLh+Tm54N~mTc6;`=^TK0APa*NZ&iqLJMU=dq!a#v!`2ri7xJGWu z=Q+n|g|_XmS+B6!?a}VHi2FT4*J8ihBLz0NguvLf5<`;%7peitdUHUEE*pfD7pN>! z+(zU;8qS+^!%0&GFhA9Z2mXVE|4Y7e5RinwL)Xn=4&W@GWHZxyF=`1fb-u6HsDU=O z8)}h?g2%?4Mh<0U!4`F0p^H3rRaK$uTHN2?Ax4M&ZjXoM3X{nOP2J#O`2g=7rqd~$ z_o(X%XOk(8j*hY0?{WR{8n0i!K~psdu|rkY`26$NxW2x@-EzsP;Sf!z31D<1!{LB9u6k02>-bZ$+aV8sWy@GP$&#$8Ei!MGa`amo!>>JvBs=_JKgP8X4RL&~WJ6~87a zPOZjAtE(4UW!`O#?;wIF$2{F>f5rBY^%uU50Jta{v?RPJby(hAVlu69{_-`5Dj7zV z-G!DPD@<#@r^JzUQ8q^MnzfE1G9$e2Z@jCGys)}HN7eYe2759_48KF%uiu^IWo0`C zq8CnM>n<9i$_6JhF|RVG%9rOKEN0jRkNMae-z_R0VV4jP^Y zY}QMBc>gU{4>vf!ILFEH3^DA{g^)e<>V^|EBN9Tl!G6Et#Tq^8y5@xwWj8E?Ob(Hc z%9IFMN#flpR*aJ|5J(~tBu#WoK%$DnDPrP0A`GA4P{F$h#Mtxp(lJqEj4s|DXw+oU zM0qTg;R1bTMpSm8oG1+;1kS4|%!qf@DCbnl?I1{j6d<`IIb91Vv&_a(zl~P$>3N~b zoLUB|3g?*NR1I-Gf}+w#%ZzOq%QB@UcU%`8alsfG9TYwz87}0i}q<12;?M~hmvu6&K;gh*9 z-^*`B*;4wjiq!BJ8rt+6fl5IElsWi5Mwa3D5|vO(zzSvCrt+*2J6BK+o4gI zKWu0F%BEFfd&U$^X5I^B70-~E3{BWJ05(r*HWryRkrisAPcvB>1y&1xkb|XB0&>n@ z)A_;k4?UoI^gYUd`x_oTqn9cTBlm#NyGO^N>$)D)NM%!$*ttD0B8u$kKTitw06pWGZnAMY2IO4TJpLpp36SN7Vqj-H^0ZK6 zNr_NsIuG3dEN7mOlA$37-BeQAwD&w_NVGgoWlIjv$n>WM65$8dhy_Aj*SNjC!TaWx4RasIH>igFd&l(kSc_W)i0M0R|T>E*G$kB!A+bMn|ROqVcJ#>Wb8 zjVbDRE&drtS5)xRRc<109VY6G~-Jia} za&?Pm&z|ArWP#AKuEJ4i9h_{6z!9S8DvI|is=$UOFJmV-B(bs3t#w(>HUT$o( zaTcc=V<8b2E@EEE{L+c$n3CkkHjxyBLaQqKVX!#CtV5JJRX)#pPMP9N2Sfbt9FoW} z%^eORgv6Vid^xv44Su=~y|2)A9lAE4o;08s5n@7J*I2C{IFIPbDIQj9tX6BheE9;C zNrR6cui<@--ENPQ;}cA$GdS-snKqbCr>N^1ZD^qzVO`xN?dFT9Az1WcDgPibwDNFm7t=FS~<&xOP-U+ z$wg&Q#lS^8E=Y;SNCVbyI zP~@~bq~oa$4}^#otNUx5oSwr^Pk6J#;F&RbKgQ?vZ^eBw!h?HCA9Wq~dFZ%|*9jkD zktk8cn$l{l@T`y{8|bNwz8Xn~?a$uac=-%3pPyp0S)xl3b={z^2+{ z($o!nCBjpTpg|aB6o6Ece@h5mVkK0WlqOzI+Fn6bJ(u#NjNJh~WdWNa=P>b}a_+PP zWz>RpAQ#uj`98&a22d{&71*VkU@~A0iJ4)F;XoPAEi=knzoL1{`Bb1vsA-#?@7XCv zXvBG+iK6GJCRHzC7*`%cYbaAenELtFpzkzHZ(jTK=i0Ah@}Y9o^7!y_ra zqHg`Hpz@9$gN7u4k`)<#z9*pa3G3||4jt+Wh_OZ6?$GTWs>)-#PH^6#swy~NqiQCo zn+Yb2WBp?j75vKb+3lgUj1lFnf=&*-=7@E!X7Fzv#DaF%OT$Y*6J zEB*t(VCc?Lz6IsQuwmD@D9lhY6u{r>qZ&(8QKrlfZEK6cMc?JJl2Jl(sdqhqQVDnP zo9$=*8$}Tu(nj{X838PR?x7WiNtIzzUMusM=Q}qXf~?S|X#+q-Hf3-77e4H&z>!?-Q0l^P*)9mpb!vahy5Pd?^|@Cg?A2B)u3_}D|)1! zt~#C$go*)d&Q+@XMHEZuW?O%rv|kZ&t$^PsMi4CrfJ7kgSlLPJ`OkdQnR!+3J&_Fw z=+l0or?D_*UCY@^Le6*M5jo_qB>!2No`jb$m=y(Lz*Bk@9>KZcGz^nS0y-ipcKc;- zj)7d$jX@$cJ@aQw10&NDc%-*xrLA1lqX3))k^R}gC2~F`R8@t|c8mY|5C0Xv`{#c~ z~PUSoX0em{@}k33Juak*S! zx7lHOc8o5sQJ%X9#SQAYXz5SK?6H&}JkBW^h0hqghx}@&V2$za;d_RL(x(o~HWhd2 z-&V#bPuBBMi~11dC=XR?)ofJe63Fu@GSMdRwRz-{SufTotM{{$jTo2&JC5PaA7Ui6 zH1d6~9aC%%FyCP8$L1oX^k*rwij&w#Va8I$2atd7Pl1^evVBfm1U9j;FXlpC5zc#f z0@kY=++1Da;FpN{aMpM3?6r z)r!kyv!Rm$q7I31gX}^%=ivZ+{l|a7^5G7Z15ylJG&BS;GzHA3Gk79w*AJ-4p%Sl9 zFJ6|cNo3bpWbP-%d6x%~q=-$@tYwmlGiD8NzBmG1}wl}raAx36-Ji%B`|OVT`{;%&Lz?$EY-Os7+%l(61xv0SZib9009 z^K)!ATx;Ov%a@qW=IAc3@bIui7bEJrLI?qq$poK&{tBDT4i^^<=JR=vmvvphZnr~B z0d3nNM)s2H+JN1@#k;rP;)^$5pspLVp~G}G#hWkQV6$Ff(g1ZOyd;K#4KvLWD&?su zWy8MaYR#J$DA+SbLeaQ*t{n)@dqe^}@dmMTiji1n_1=S$L`@K(0)d>DHbJ~S3FMLA zHN@o^!;0)DU)E#g`#k(W&$G{gSMo*i1}1Iq)I{sKUU+uIv#w`*K}_<#@Z-{a)?1dGK2)5!$0$pi@zZRn6xuOx7>NH0ccsY9S{ z7rCu5<~C1CLKe z(oe^ehbrbJACd*usi%|?w6c2vx$+bP?D&Xkm;e9@Knz%~AF#T=!^7Qs>~|~7=L^i{ zb5wPW`-c_0uP~W3>>-*Qx;A3lbs!MxhJ{e&JrW`uc|4M#*WEQmJgMU`0L?0GAS?God!3tcJElN(o*nD(ZW5+{T!u z`9s1L4!u28fdl#m;+`=pE3{^ObaHer{b)P&E@YlNsu!;zBIRVYjcaS>EHryKiyv{240G#lIqq zQkg`ICZ!w;4pj+d!;Mv|I-mFLIK4WBnIlv1xPs(2=)Y*DcD`8?hwk7r-0 zwu++mudIP#Zr|bOn31n+7>p=&GUhQI(rv%L{c*DGEn(mN5HY4{9ME%roJ*d<@;u7- z0{wh_wohelk=Narv8YG?29Q|Vu)p=kpeUt3^hiX!fkoV`-P|IP+F za~*U#bkieZvtD8OaE-g0E9`e`OePNJ=g%;k&#+qFqpliEYWC_#F{14v+O7qX2dG9f znW1SKaE|HXDVg#(3NV!U)(}5tvAh8hEFF`|Bb7I%?V8d7F;~eYQrRPEUXlW8W57l+ z43=u7{o^r%(ePZsxrN>)lSyv7<&Q(UA}WS?9hGF{NuHiw!(@6C1m%W{oYH1k8qvSYyR@JBTVHOCeICr;pdZ8E*+6YQaHDy5f1`=- zweLDK^p$(l^P>f-NsZNN4etoeWQw|GUeI+dx-Rg>j`L`$Bh+d< zg+mOykrtzD9!ug*mNSx&Q1Ke6_atw|Y}PA$yu3u%tx;DT;_krtLPLy*U5C|ni@Ne? z>KcH0Q%c{rU}v2(FS%y$}#X!13`BoU71v9rkUD zcE3Z65%c*RyWJl5_xG4iCx|hksw-6FF{v94yKf_I?{4wp<>wO0Ot^UV3>W9;xVyeY zO|>|d=;mS)oyUx;M7cT5bD7hr#VpU+``Cn#iNP=D%yn9>nNUwAh%sQl+ag7v3muRW zrVSfPT~)IuDY1c7-;vj**3K~eLV0rL7lVRrJzVW{TegpziViIsc1dw1P*pWHn=QWi z=1-W;rg;7NYt&VRn~xvy)mPslc06al{N-QZ$3J?7$)o{N#BRI6-Q69Q%N1^J?@*D$ z(PECHlVi;0Gk9OiI^dkZT-u@(6HXy!UeuGt+IH;%iM=2@x#(K!ZxrY`#r&m^6EfCe z4`1N+<0ZOOG+N#Cc7{wFN^{jVLl6S7B46EhEyeje^Vo>gg;=9 z4x;nLrVrFuH@rGgWRRE)o1uMKsc21p0DTY!m8~%#nXFTKxxmkq) zSOBf#+c(5$Wp)KF7HCAnvhIuQvt1pu7r+rm-wpBQdH^e zJpuIoiApHE(0`u*U-CG+jUTZR{JXBng9;F&caAS z0wCVPj?nHl`1bABxVn6Y`Mg0F9Cq6+fP|{5(KI#cs)F+soU1?*`Vm8mL;;Q}G>u0} z0q@>@gZ26W&!4}~!rBO&q0w~E&!O^+ba-w|*|yIa3ejO= zaP@Z7kU$b;A3!e3LSzdw6;Donw#P7>R5xjg!Q4TMI~}wggd{ujV>_dE9dX8#mK*8#)V*&Y68UImdt%F_v?o$h(np8ZM46QwcB1d?Ay@Ol$79& zyyY?J%bf3fs26!c1jtK%Pko-av{-YPhuCqtmitRouElIp zi=zb+5n7QelgR`r0Nec@F+`4NXc|YBY+V?faSib|KM_^@RY6p36)eV)xU#h)o5=OR{_ zoCJ5VyfR*CVrJ9o??d^ad~Qg0dRQ6+(8seG8nG_oy=SjJzA(StfpB?sg~@b++nZaQ zo}S?0;Q`C#67%^S+ue@m+|_6%6U-M2v|Yg2*$JLMe+Gc?{KX5*=W}TTk7MXM)HU<| z&~^xcqb@evEq1#d0K(19EoSotyclL<2$(cA=Cdi9hTrGelY((;1b_}#SC_bW_EMZC z0_L+BUVZ)w54YE7+kok;0;0}IshI)UjDyNl35m~gIeYT5_iPaTl$?`@H_!5n*t@g~ z5xaJW_3auD4@*4UFOd@GM+bl(zxf=eiurBqL}z;-|* z7H!%Z8|9$<5mRCVb&UAxn{Tk&@9?vq{S5Q@3@Ju@@#aTZt@gOQxfb?s0$4k37a^YvSN^VQebZMQf+KEnU` zAO9nM_S2u@>goy)4=aEi>Sl_jo}j53Ny<%VV?vbB_Ye!S0)XTQ0mwo>idO;16~-$e z`KpYkn9A;aR!-HUqbS5g71XnYlvT;!AXW5>7bI{9^p%MY6~H0GC`>_iln<1htlQ=8 zGY&2H={tMR?fu%He=^r+P;2_2ZB}oi1OO&fOs{1ebI2H-FzaaALbgq$MmSblhPfGg zjM6AN#Y63J#p(dy>paM_kiZ5HL=FRy26~@BDPZ~VfDiA!!OhJjh&p)38=-z$qwRQ? zF|?6AZX73&cdi1tis`{u(CXb5tP;mCWrb^DWKA6t)ZsFT7F-r?b4gGn>Nul~cY@Qc6t1s?A1@o>KZCBkGn!E`!-cNN$} zreZ&CEv6%UT~l+21ysV}#kVsX_IX7U@$c%<$evB2lq!#w|8m-Uoj>6TGAyjX^mvu3 z{i1mIL*5D$L(q_}hXxrE#oIpD(x$$1j7EmfQ{euXCtIQKvfj)25?WPNRi=TV;ZCnT zph>b%gz#|m6#n7bPN{5!4P_KT3=@gqVkvw9B1CfVb%V-RGC0hCLx|Y#JA}X?*o>VZ zW6ih+a0o#|xxM^TqgKCKtgh){e)F-lsr|A%-12~7|Lv!~YwWs|#Cs|Nzy9_Ahxz;n zKmX~^5o0SG%&M5P2TjUF2dy;k%NBkI|6?9mjAXol?u{%dJjc?3r3W3Kf)R>wM>h>h zUkfH3;#y0iDvKV&ZcizG(&K}1w$JG+oc)~Yx<<zG9=rA_IvkUy%pZ|A-BZ5q`?XOI``#D>LMH|Gygs`e@~kwI zQsNNZj~@Yped@YGT~}z^gn#|^8~o`{-=N*^F`LctfBmQbgdctJ1#WI`v3%GA1WYG0 zOr~`n!;}a}o@IhFhIloykc>f|O9k~D&16Ymm+jbx#Y_~fprZ~a<-5o*iJQh0rr74vk&h zT;m8aqPxTxGX`*#$K~ZmTz$O8%g>(U?CcaV>=9$abUMLb{>4v04tV$OBX;|3-qc2l z=sJF;_nf12HlN|ut5?|VcDTE{!`ev3KaXu@nG9`IDao=0hW0{$9r?Bk8AO^iU$L>k9Mv z9Btc<0-%S72dq{r>~=f6d-o34*VowZ_gJsj*lafJ31_a~ZaJR|188QnF}45!UE5-{ zUZdT&sGAyuOFVo2230-7^~Y;Gd;T1=#XNhILbB-SbJW91GkPlX75)mK2y>TLYw>!6 z2zMevat!YgsEj_I_QTd5&p`=PykW(IF7|LRP(o3;5_vDw1>9Q z<|}zjF&G+q9{UYR3?FQrgzjT{?-9E#K74qKn`;i?^)4cYz~e7KiXFhzn~UwnF25@Z zSniNQVlOofp>qW15?0FxY&UCMJpT-5XU{+h==5RP8?$&(<%-L(-@i04s_9`pC`V}l z;|lsv(F2exIvyTnjpPC{P{UYXi7#!2tQET}sYVy2O+pT-rt+RF$fJ8W&OHhM96F{s z!<=|qNnx~@>wwS=+-gK2alpsc6ub_*gx)A+3Dt5>NS<8-|%KN|ki`Fc!|u}03v z?c0vE&foYL74K7(HTr)0eYh6J*RAFeS6Rzg zqRg>|*E2;9pQU}Xa>Xj3!+HEZ$52-MkZT`XW5d3e+=yUaHzJ3ANL%Zw#(aK^uIr#1 z4jE6Rh~>i)%jFF=n=RhIe~-JnJ8ZXGESC@1?e@lC&i8G%TWq&`mL;%JbqQ^|#lz|r zF#*%*3?Y2PtJnVmU(IoSbB$*g=Qut(hOcUF0|-&%KSeKL#WuB&8ctY;P;Yt}QOLkZ zxVrS$SGc*pLDxl`o}8jx-3WdbZ&9ww1f(cY5{0)YfACTVg0X$d^N`h^jM-DxfwH`i zg&t$s1md|Bu=N$$FWX$OFz2>Z*g&co+FNC^Ep2M{5AftTB8fR8O$jX*bo$AK#y%8hyaL~OeQ!vIl49@Nd>-mJf0O%>uL^(^2 zeb!-^-nfy|_HW4ahX$D*^VWWwX9;_i@OogoS>pZMud#f%22n&+rM&Cti1XuV%_Lj6 zD=Sjuq*Du~w*EjH^lo(&x?DXcOuPByJRp$6N z+5IPO1CjPv=eu~&3pM0C|3mGo88q{B z<|_91)&o9cgN;0tC)kXQgI>#7mPhkjePKB732|tYTl;4_pSP?T!qREpI`(AB#GTvn zRV~M=d9*(fFNWiC7yPbNab?F$gdrPtHs96?!BoUR6kCOwJ8asO zcvq))2?*-?J;H4)f>QUO3+>*o+4#{m*?$3kpO#yJ|)4 z&!)NtLkbKD2?U1$DX8Gf%{MNd?w%^!o#CB>3iap5HT&8&{{Uxp6rMtiT6=92P`yJB z4sBwJKD#Z$Mn4d$U7(#cbsQ`Hlh2@YYkMO{VEfW9B5VQbtx1%u2e7CPg~|aXC2)5X zphC{Vo_qE&PsKt3xBYQQoXNK&D3(^?p}8xrG#{nS?n}+ zC4_&f;N0Keq+YUzx`#ghnZo?|3?uxX=0X|k|5~!Oef9O(-NOywUhBuFlb$PgSJ`w_ z%gW0uu?YwWjBB|>=GbudJ+E%gSDZ7mvT`l0#?72%OVHIgWS?DOIz&g>?UY-ye%Htc zoO|6~qTr=tTzZXw{>`nnrxKp^(HzjuqjPw~pla7NC83N#jz5bxoHQM;G!%^{HkRHp z-U;vjW#3!Zq~FcUd9NlpOF8oWu*Hdl7BXy{r=A8p*9I?f=ibR{^ddPe9w($QSG`)P zD8ir5<5OenC$@&Ed&``~6|bTYngM1`@C#Aq5=ZcI1$&q;2v`*QrCs&S&PC326D=rD zdNWWmV^)?S49OhSBPZMPn_@@yl)$nX_S{#>32XR}u0OVfImE zo=g($jCmE0>Cd!NTM=NRL#nPlEvQ1i7*d4Ae_Rqsc#{Cbu$koQoV4pBZkAJkKdO7Ew^KmXVCdM8-gqk92bED%l@`NSQ=(msqZc|K4Gt;FypMwd6Xt_xcL_19M0aqSWRy%48yZU0|yYl5=!Eosrj|uF-w2 z8nH)pKA40>6f*3_ab6eHy>;clcCf3@dxPbQl#k)Og9MT~brj_2V}Ca|N#ZT|YsQlh z{uhx7X_$D$4j1B(T?;60A?RDPorCuk5W)RKb)DN5d_PrB<-k?XX-F@ z-OR#)d!aP=qu_g`?1!DEO;H;EV4~`0hUAgd4Xv?^UHxdm(3}7j5z!r5!_uHCoHg-Y zz5u`f)?V{}N7c`-m+qZ#V3|PxwBw8kin)l-yUj>cTeu^gMRma045Tr}f4vq?{QS9d zehyYbImMhY$)qpKl*Kjg3Q0^7{^UW(KbAnk_X`crAAOG(l6{eHgbxm+!@wM84BK-r zYc$k^B||P@1)|~sOIPChXYjlo*X{~Q7v^mffqq868+DN7f~8hCX17wB*d|24+4#uD<2LaZlL= z@X8`^pkjo!Km>pn#T6K5m+jmEB^*Ud>H!5<2BYQxztWY`l8Ot7K{x!f#|x;0xp`>? zTm+0nBqT#NKfsqDe|%%-Ben80|EUfv41IR(5({jATN@BEe&B({#9)<{z(Y8BX#Bm| z`5@oa-vHue)`ei@P@B|`yVIV@k<9&MpJ<9N;cZT(NAUQJW~EsY-(OS!lQ1s&>Q6$T ze(>RmIg0fkhnK%B^HFEh(cK-v^@KWr(>f#+d>KjM;^#N*ICyInY9GGm&zW#=bn2U= z)a?Pb2UO881_|> z{qW2zc{+H!uBlrctwyut>e=GwGjKG87?9ArCHSA5vNuvtMI)sqXR*c+95LeZd%z}i z#3h|yC^j}0@Ib}P&CONLFaA^!kw?NJ{+iqW%6w}W<82c)jR13?F` zl#%>Ugmt*q>(8R{_Sb++3JloTnWF2y|A9dn9{3Q~dS-4Ywm6+~cX#kf${H9?=X=~% z-F?>RrF+6DI4dmbZK6_rANc$BD>Y#D5i?L-h!|n|*9l(Hzjn1%ag6?6MN~W*EWT`N z_(W!M`B*}xZ`AT)nOG#G@XBM?$Ow4F8*uk7p`Gr)RL~AAX5Js5)R#N>;G#d(Izsf5 zTNB*l(08Vs<9?zkF_i!2#}q;!-jS_^BMZR>;ew5}1YUXVa|SoAZjWr|BjT{6i0iYF zK+)>t9rK()u7`gP8;G&9-LhuTgIPlmbYFg@8r0OMEYpoiONh%%HouHc&Ws5SO`m3~ z%yo&3#S_l|W=d!*q2ueH&8O*qO$$NBG_HG8xvGEfnH+PFC3^du ze_!>)6L5ci$^qx4xpHLFc2MfXR$6MLf;xv~$(iz&K8yUuSeMsOb@q-dwCQ3@`28Pt zV0fzY1bLbayV^--T9{dIY9)01zb|R){ukHGF0#7`?E0magFw{EX_~p8UCF`)QDL{n zcu4<<9Ws|RdFb#W!hl-k*QOzC`>PxA;C$z;=t^umEWSbYu!fYi&9#<@&L@N`TI1O# zp?YhTE%VP~yprzVO(Nc5KQu=r4Cos!w^Z5UV-aYu8V!7@+89#j#tERvGi6O_>1LXW z=lsh-XK3)fJ)cJW$bG+!L=fkebpqZd=jA^Zg8$83&K@J+bvR$+n3IV0FC4|cjdIgQR&m>mBbX=^SHeT>h3ENdua009d;RCzR#2*6w=bNVyi!bjLE7bwKv)) zxA<&ZxdYh@7=Y#4^u{M5GUmtt&iQP-j&xY?z@)nSa`#Px?y!``Z8B9JS2ev_)tmZ^ zkDPMgj)(YSrs*7qPWnFe zsQ1rMzf*LAW^~gANg(GJDW=_}ji!kJ*LVJ~c`+;8~1^~9G$ML#fZ28_lP zo0^RavYb8AZ?!7i{{CM9Yrxx>K;2P&ebMX>$YcXAFWdk!LSNx};G2H#Yy;ne*r9Dq zaTzPa8W4_pq6ZQ(ZB=6@9?RA_ol@@Y1j^Dt9wh~!y7b#M|2S9~YdGWi@0*0pPMycZ z%0KJFK$6>jp}(cU*xbp)?xz7z5ogcMz^UcDNgMd=FK_Gp8*)Bnrm{j-;ppTQ1T3iy zsm_;*G#*!%b`j-iAjj928`_zj9uY^3`qB)lv4Gryy4mF$=~h2Da)WMx$Ug3yekK1t9D@yhG=pWzcjlwg#ET`C2jL3kw(_mG$r8va>oPM2+cnCFwx=5Mx zyLch?OelZz*nOa4O~lW^d+o#{3w?GzkPg^?OnT9$UJ1h4PH|R zDC|7u#C)+!Kp1ZQ=2`RB z!~m%}NdnT+-U-C=|658CP^G@_M5RP4GZVm|nyl_K{}EAu1#$d?@DMi|z_S_R>y|)te)dlW*YYZA2K^_w98na^|?EC0durm)IoID2W5P8V@hS zCcFn(kQ8RkEml3Jd$9ZMOy7uO?;7}(9K>@_hM2@nvY|4O&RkpdQWcIWge|T?i%X$| zohBlr7LLk8rTz_#bX7$xUFJgnYKW`y*|bLn@t5$L+eXQ648v+jb<%T3uv4cvDpexz zEKdBdPmOa?kJ8jhXMbzs)3G}|kFa>{h;a&1Hg93O4akomJe$=he&g{Tmctz`ABC;& z!O*d#g|;IOJ`hw#Wn|zR5BR@#NdE-+J`nx}EMKXzW)|&80PjGfx&*j+bjAs-HIuqy z=Pa{9hz1`x#JrxpJ5-(fJS~>K__kz+IXO~UhuN;!HFq8X#uEStA+|@tvrj}5>m+X{ zvUyB6E4p*shfEDxW&@F78k+ASYy!}skfNMkK|uQZJl%>h(N{fjCJ$0&hn)?#iaaQ~ z`yWLuPaH){2Aubt<_Xo11Y8mPiD)|2E>8j1yVX{Xa@?OB&T(qKL3YEWcy}h?8ZLx%{3l!T9FJh%yrq9bMmYJ|QC+gUhmceTS6g+ozXt#$w*Nj6 zn%9h*xAqQSaRIMhNs0OMO^RTj*MzugJk`H%jC%WWGsTuD#yuv=dt;3L2ovZP){gZn zJ>IbkR=*akk{%`#mq!lI&w=UwzglUm$Z!8y3jlqYcS7vHdAG`%Icu^;!y%6VZ117U zI*FwUi&ByBIG&8(tMppdllv#8vMW=LQrJmR%O?%n z*Y+v|{eE58g_T=6JluQ-0P4V3Ds=}Zq`Sn$%N_c}uJhAa`DZ+o1Y$NRx{44?*fP{) zFPU5KQHINd(`YO~^i6_&jTzK;9P^{Uf?R*1CU~^TCSjTNM}am=KAfmBk%MH{ptaMkZpQmikfawfz?amge3ohqY9Ai)P>h&!%f~qo>|y)P{I-_Cy{(b z>Xa9Ki6r$dMX~CpzoQrLP+n+8_G?6|e2fqbyJD2;mCw$TrE8v=}OTN}uIs3|WWyNhQLo#DL-^B=H?Y?#+J4 zX!&UfiCyw>YsP<4QPVXWp5gdCy0ae)YFO>p#(J%I+Iv;67Or;_JD+CHO{&p*Ke7mE zZ1?K`12W>>&nOIffIV1~&O+UBN0D(zz8qQV;0AZjEzh%!jV=s5a4ZF*v z+c|wkI|zap!PTG>RM9JEnP|1ab};)uP;th;9{y8X6ELS&0cS$KNn>n0b2hil?Z--wVKG<1Hx)4MjQEWvCs-l4o9sd;de?@J5ug`D8}@{CL+r-+&kj*2bc?(^!weQ=9PGP?c6Qm~#JXL(w*sdE?0bxa z*73WCVb7b~c=@-~@siDoDK>Q)aUmji1j~iTft3fuHTfJ**WSU{8>NRR(=M@~C%R6e z+g%d1f5R^w67yWPHl0cPTX%VF z4oj20`wwZ&uB6f{2#`1d5^&oJU$4C9`dQ5Smm)dt`IYn+1s`CX{~7-?;rRi!O&gm~uRul{@YUd8QkQ{csGbaqZUy021QA! z6LJQ$)W_hrG349w0$O3iMc2|${T-_dy?5xMTr`GC40hU-xsWtW;9ZM61$qs`@7)hM z)2g+m;3vY3s(uq5VOh|M1302;0ib?b)`A)+N(Ex&1yw7ldOwkp+)HU=_l~{+nBZRs z#v-hiHCoj*8|T}d{eI1&Yi`GFAkf)E8)nf!eiKFO(c~P=zVK(#5CAhs9^=i#&&j>O zChGLOgW^=bnz19Ao|nt+OI-Hw^K%T%c!LI_G8Z551l*aT2iB^XcUObls`1uY_!8pd zW-8;wh==vKNzmn^-x~;UiI~e^sojJSBx@7El0h;LZLap>6YGpN6EsENSBCHsQ`S{@ zwo;J*Q$4hNI@m&&3kkQ01^401@@8<)xV!u>YSSi}!cex>CvONL(1@5zKv zdOhFY{O6nYxRqo!nq>p_j3Ifap|T(o;ZR(?N+Y{85^u<|T~)S~LfL---`+aUn;f#M zA#{m-i$@WHHOHB1>)9tYii^W+-HGNcpX)?d5QPP*eUv+EE5D_5RfmZ}^*El_Y^nfl z^jNzW>0n%GO=IJsX=u$PgQc@|4J1XGNCD99Vp8N_<8NR7kDHZJ@%U2cZy08W=Iejb zlF}A*eaGcpV{6QRgwl>d!|98g_;YhJ()y6R*@ld5T&4+>-%i5B!npJ1`Y8Ss0&NaI zrP(pol1dKCSOcZHe^$*?EHt_iv-?NPj$|YYYF@psvX#1_k#tq(?5dlv?_dpnCS+-= z@zEJ^B(y^9&I>;U2@-e7RA5v8ifU`Y9OLctdM&>WQD@4r()-8!PlYdDJWJC#>liG3 zFh}0@hzUmJtl%vLiGjF<={G$JO)$P_^w7Mad|k2vtE=r(-^H){NL+GKUFFP7jvWFq z0@@%Go{&`(ZKiTIX=h_)Xr}i+1iA{}3f)GzxwM?Y4EzvG&o6wtx_LNA%4Ic*|L{1{ zAg^$P@y%qz4KKH*Qxfs+KN*YWZ1K8xa-DgZ75iq}rRjM+!e~Gp{Kx=d?$n&ety)!_ z%k$e(;7`SgtQx34v&MfVM1FcI>-=0%pg(Eq9y_0|bWf0T^a@wiEFwl=5e()|I))K` z4k-^9LnZP^r}!x7kW_`>|4=5v8O4B`YZLaG}yjXpQHD=Az1Z^a>IVFf+I4nUoMtF$u)Z+@7@)O|H^v}H(&8gSkw&$V95ed8L?-TddU>Tw?`y2!#o1WRBlE+6y1ToFGw)trBKd9sW-x@e z4?RlB!1{WX2UnPk0cmLkIn=caj=x5k#jwP=)OcqP^(xg&}#r`ZupL5pi8L_^91b72vC5A9L&{HJNc;BHWK%m< zOO`GM+of#qrsy_GHl~4ytmTpf6wJf1XC@8An7HcS{)ypiV{4UK zS3V8uq-#$F@wPF3j6?H}=XR1Jq_)Md;^AHqEum#4p#Ix~B8%6Hm`Ac* z1N4G_z-HXhqTtGM$=khjCf$2FZS(@-{W=B6V$)(8&tlHCrQ=$R?CEwxv6tCWATmC@JLGq7& zC1{>Qg3b7&3(vy_78}pP2hIHym))MTdCyMEFh=d0hTxYyB(RaHI^UdoO5uQ}ZOXsq zeBg;^<0jlW{RWLOHEEUe$lr!*0_15Z#|s;W>zv_~JCCw0dyof3nX*c4Y0eX8Q62D1 z=JC=@uQPgyWG+#T1eUg$zb3-bE1a##@#Cs$r-sf8<4$gP!alv>ylA$(eAWAZHgR~Z zI#yjI_4qpGa39`!UtlZ@q0-Yp)2ZCu^y?56zh6k6H*{BW^lfs=eFr>b`aA8MTRZJn zU82=|8?MS33Zr5|l$_sFk>emrP}O*-u$m6A;XQN}_k#A$Mz5Tg2frRgk>a~2i8MKn z?G_cm3-}m9;&GRl+GEGjUA0dmxZuYRY8f5VuURcgn~p(Zk>&o5N-tB%#HbL<4z+41 zU)G?WK^RS6&1mW0W(;A8#NKX<554jMssWk~Up=l8KCipN3a+5t0n6atRs}Ej9ada@ zJbg_n6DnV|2GQNVnQZ~QkIGG^;OV)cuQzef=UqXmEAh7 zs#(l!=Tz*mVPje9D|4GZQ=^@m5Xi`_!BAff|FyecIr_N;4tuX}Tse3-1x@7$Qo7fX;iBNgOEa#cdO2BO7}Y^RwNd1 z=A)$4mcxeApiB1fXz8Dbh7iBHysXh-06b0(o}LjOp8*eMJqriqz?ab0BpQVtUKnb< z1`z;z;e|*`3z3{_j_y+DYP9b69`aeizest6%|86JJ0R2X_URop2j1pJlFEkyhMi)r z{eF5R*uUmZG~+@~AvrO57wK%H(3Feq*xcS*2bvxVR2tN@w+=9|B#%KR>jp2Bi>_G| zQ^SBN9m5A*+MRH87TCz3U%JrZxb*d^ z?FepMyeUHP^BIlo!->xm zr7*76Wb?U)GMJkfLi5u$w+W`aFl>H113x#@`PE9IHwddK@7LBZf??ibLh!m(DY{+_ z*u{^x4+JH*c^|x(tBSR&Ez7No4c8sBt(Z2OKwa~xiF%#n1tV##lU&!ID3b2>P*fg} z+C2D>4iKPP6=W46DnBaW7oN%W%O+db&GkV~HPN%hD7tqdM?MGU3SD3rhv%-|xa3UHQ zY>Wi(J5LTz+=$wO9DPpWtm-vM^XG5m{L%GJ=B8^@fu2Z2Jkj+_eSe6(xrpT+_0Ghv zqthsV(?3J?4$T_t6?sF95s0eeD2tc&T*s#ek8{3Y z*P-y1&dEkQS3KwSKpbw5Ps;7g=Qs9EE#u3-=~@x3WRBvO)*Qr1`NzrIg!f4zQH%Dv zs`6XXv*7aZq_mB^lD(3!2r$KmnBl>}$36|1lkjhVkZ`iQU zW!R~;!`c0UDB$}VzP6@~0{OSX8+t8qmcl8N#0cAj)3BnzlBdZ|+mnn$VE5P1p!KDu zo`k?-d&-Dc{Mf2yL&{xGL9gXax2U_)TTxadGy!_b z0#iwHi| zc88Nkk>36LokYJ}cyAe0Nf@7-AFy*gxFx`E$Jf^!uvlh;QbLG~44s*E@(G6!Qamtn zLXFiHp|l18ypBe#IwyxkAW8}GFc9_Wn~6USZ3~KwTK=ut%A}8@%zd~&xl>1`;w)bg z#S`-0^8?T`Vw{XX;8~k_;s=b3G1#W)BL_~u0KroZz1XsE$3b%W^z)ODGe__{8z?d| zGH`w$0*+cc#AC+?pOEqj3NxfJv$DuQ$zwro&4Yl^Bw%$y!`_Q&TA|%9im*BR;ash0} zj$zn>Q}oZZz!Jj91Kg4f_GByCZ@SP{g=!jTpop7bb-OdCkyxJ%DvYzC;TA<0@gi(5 zqg|;_5DsrQx$qTpTU5rEU=r05A!dnY7!FXHN zRL4OI&j!UJ)O+`-Y3v@^%RXq-=Ro-g1D$wYz)Z za?e|bPF<*eT<&fnvlp!~I^LJeNwc)?Da`hmu8Gr1dm=GC=I_vCUERgX>H-+2`MG7k zqCnV+d8yaiiztW7|37+6_2ajH7gLM9n$3lDNj!$&6-nF;N|0Fg!Mb9>6?osh_c<#% zp|Ov#ayf~xv%vEn*guCgYfK03I%GN|t6=N-`x8Tu1=2-#gnyM7^79&ZPelhKdwKk@ zWFvhdDp~z2{k8wB9%EC4Fy{`g{FpHdsmilh>B2n37u{*??&$l&ek&&a+p}fT;E-m^ z=Jmo#WGp0@Mpj$LpOEX~d2Fkj+lQs&A%3LxDT}q--f$Q&bxluGe=F$Gu_*4F0cFGt zOR@reAq!l#JmFlZ@w$d*!1=N^ft7G6Fc$Oe-H;d-C2SD<+f=~=zcZ3Ezj%Z~2&(yh z((fr*YliH%d49k5(OO#15oo)8FK=<%eM}adQpKZQ7IXB;vgi5cio=ccYH1W_p9yAL zXK!oVH(8%*{lnE#RVgpwY-&5qS`(}Q$y53wx;^8gM#5O-r7w??huZJr;!90HsBuM@ zLyx5$6uB#U!AC9j2({(T2rqk)llx5&u?y^d7)z-3j?1ZqyY4vw<&)X=TZGApZ`6wK zAx#DWmt8{Vzb?-K^^=6}y2VQPM2XkNYHNfEIYZA)hjUtH)+;hY-+k=6Csr~`&g*DK z$p#wb?rpDqXllz-vr^(Lb(*J|bt#I)B%Ti*KXJLd4mrdSjAPZS^>(g4F9o+R*4&9j zRuQpBtjCErJhZxq7`>l3{>5&gMwj1|#X7AM391`Y@cLYrBk270N$rZL%&>FlVpOQq zoJN~0yD{NkWHjra^Y+{{n>RLmp4!WgSA$51tz@*(kzAvWX?z!uLIEc^nZQ+9{3xv@ zi~F&5pDcGNzz=Hb?n(G+NMQ3(5|UYP#$y`5$SVk58ko_k(^f9x5tM`5|826 ztZn4mYPrDgBy?T55=8;aEfkS}&wsY&3UvT`Is62CU}R=y0&--5t#+nOGxiWFqkh-F zotmMOlQM0m9OhT1`{(By72Mzpw@BdcBJ_tRB+wfrz7}RoV4W>M+0tfU2a}!61$B|2 zth!bBiGgeGprV_SQ-6mZNo%}MT5wEM1GSCB_Ktf^%Mt7zdQjIVpa)kkj3^Hcx-AhEJ+APILC`sI#fT?wgcC(nRQ<3 zdK?--lTuYbuXHm=KN9OF9SP+7#b#nlA+lt;`iDPQPhxNzq+L+IxKey%<+^S%Ia#(r zGVFCYUzyE2<&uSGwgq}5x%|_T_OwQO7>WsL@6uB=vr#70Ms*O=4+Ct9^-DWP79^Mr zG)LtxP_m51y!-ZXLLdzF#c-7*#8QUD!C#<6TIB!Oc@gJ+Fe0bI7&>9i*=!aBb$s}7P!((^WN~>2)nWd9@o+Q%3Y^p`A}C^*l_X>^?(F!#x17&mVVlY zR`QI^8*nGZ91?>+IM|d1jhovU_I|&vKHs6w?F8G%by%DUN)g;N-wp?}QCz^$K~dde z7sTPNW&TNW2F*B<^tsjdj+~Uy;nz5_mJG~^e}ZkhN%{2E%7{-#ixOazT^YLGA7@fB;FF76U3&!Jd) zAUHF|QtzZFm9Dr7u?LN(lAFj6deAB+jYPbk3(KbRTZ(lqRpl?&_dg@KUvgG9M+jsV z&dY9yKNj=G5s;elR1SwQAmGxjqBkSl*H5F;B@FgHL+G>T2Atmop1cW&@238O*GN67 z2l6{jHJUH^m&ig;o)tf>1Wjtr6dx@;@PU%GPcIjmro)t-XCCq9!&R%wR$R$nIb3iK zU9H)759EBko4+40`cn^%e1ZEo2v5{RX8xq{uw-N9u6AYk-LxNZLiZ-_XHD5dJtyWdq!5RPbw74{(dx9R z#*bq*&M{!2xYSAO`4#T2I2y@^qp8owV)wvBkW=seX8Oxb5N`G0Q9@$RE9mA~x2vGUSOBapi#r9h_|pr zE{V$cQ7l4JTk^+tUvuqZY)m>PQM-`v?q98LGtHd-j$5TFQers-5?Xo)-PbXt1Pu;g zPJ*6c_4F6(D=~mogjjI=B{%b=h^7we2o`uE0f*;! zooXg`z9kq?#%jGx(JMDcOl;8Y-*fT^F~^n%?6)es3&{M0gpc8l{{TlC2uS+|B9PX@ z8kGRnTPB$|TO7aKxcivDsvr`&+@PAUP*6p$hc?HeY9tcL7HOwz)B6G6hN!fQPX^U6 zzK0ruK>~beU?RwI_%MnFXAQOd_i})le5SI#;RgZ(#7s3@5K{puF!0BcVe5I#Ic}vo zZO9;p23W2!778d~uNEn}V!{Vc;}~FcDwcY^yV-*#mh@eDu!=rAvu?00c_;Q$h4|i} zjMs4WhOrI>-1fciePbJwu|eo+=vo|Fb&NWJ?mLa#i#CjT%KSuTI;j<_<^mh6DD0xD z(w?ml9A#=U9Q;3k^9xemsVP$PAuRi83FokOtCE0(U&NycP8P8O*Lb24$& zxLT15!=RIAjXNn3v_?_FPjD8Mbb*g`a5^P2u!`l#{F8cME{yUgC z>{lj=)N6i2AddH&d=Ye67N!=-j+A})kX^sQ+5 zIT-Pr9NNS<4rKlq0$mUoPqJr3S~O~}8Uzl3&CtdkNR%8z%SaI=SRp$iy0- zTquu_R&&K4^ih>ePDYSfvaJN{UZFZ3qmjI8uaWGZPh+jz?A>0PaAI{fm__fnc5yu@ zMcXk*j`70wv2s|x6cQkT5{_8@PwiVfhmTmu$WP_!F|MJIo%=WOC#GXCM-HN$ECY2` z9fZC#*c|SO~x0fJdHtTIW_r6HNOkw<;dm7#R$u?)ik}OCvzZC&^n{9Zwip{ z6x!%mrbM|q|Eq?)biPON@?6WdR6}asVNqcpqD}8O$8h=^onX33H%M~o@uN1y5tqDO z>VQ{Sr~t25$Qm_%HS;`X@q)fX>*Ly&t&`A{^i+b-c5d6eS`XOi4RA|>y2`!^dodT} z7Ksv^-S%!;Htvl7JUI1v!g^1A$tAwo8XG#K%XAdnzK;)ZU=_Zru*QD`IJuAXMwtM3_wwqpcGHe&0CpU; z;sJ_8a{A<9sk-(U%VHI4j?1dG6={#lWCI>H6cU6lrpzTlb|CRHA&!k|Qltu9213Sx z2^QK%a~wgY81{eeKo4uQY%>mhTKYaU15}3sr6{0q zH+uDqY8kXOukxuXD7hhSlF+d@Q^MvnWSm(h{(6d;^73~L`+v3U{dY5A_Qvl2I^+Zh z3I3GQR;oosP+mv@OG7HX$XA628;6G=SsO>mF&c3ogg%M#+bV&C$kKed_qO9ANy0JD zE`;|>n%F~Qmmkg-?nKy+@+pmD7==1}Z`;A_PNWOO%E5o?bFmKtOpSG8`qy_rP3GN; zGiYJNCFVm{N*fH9#yTM~aEZ zx&=Bu0y2>8QK$2*Q?N@2#}mw41|e9Y!))>Y>Pz%On`MbTHul)0)r^bd)xgO`Qb5p) z6V|q`88XW+XJ*3_lW-EsYN_&x7@2A6(P=0_qr9i)U|73(O3ub?4S-e#bj&DQs z>&vy!CM2K)U(|DUsow)*eYZ*T%dYP5d5eg9>A6&KQfdBaky!ud)cY`7|A~D@Br6@F z&n4m@jHWlXEP+Js}^MCn@Ri|NQq z^W$ zn`YldtU+FoUv`U=p6xp?Kd7oMz?FSX$EfPym3vy^hqTN-{w4Xx9?_P@)FRNG#dh*8 ziH}hk;zD(No|5~0jOp(@b${{q2%*E^Q?JNF1shA=nz5VM8h@(?b@muJQ@9dZ+|!P| z!1o_+?@S>5oA4Hw!ry<2h_=g?pCc~YA3kCA%ijNv{&Vi@J;%Y*Ez}Y_QHbN(2l7`2X;$n0WFCy!n zp6jwHkXMqA)WKkc3@QDA#qquP*K3@=6qGB4@zYVp5DMP| zP!T~B>{ya1Ed#hfx5-7?#fYI)5-7H?cfVUi#%Ud;_L@hT>(vOcko(>?K-Uj$eCuN?-6P~y*_=gw&Bo@+5?XGzaF$W$YrMnaJU4>_YF#J_r#d3NRYu<7Lb|^VnAki(#Z*5*2{gR7t4XxRM|Ru zEE~JG_dE3;zoA}jb@kq*R698NfkI6`foFGm1jZ6=8o0mV9Ic^4B!6n=O9dpQ|E|Hb z1(`+$jGo}QMJFXwIkkfL07gKV*$5Z9a>=@K2@g;a^3He=E!?m}K><4{qAS-uxPad~ zRaze32wD2A8VqQ~|FWro4+M7w;kUHD`y^+Xx&pIwbtYn1X>8*AkA7<#^tmBEo!tpK z?O(B)A7)RQ?Wa;h{fd#d*Za|R781p&J&k})Zb>X)_ANGwbf#B1FWuW1M|V03kyyhHUIR8Rp#XJIAn zIph^tnrhVp2*2qudB74FKu#<*y4~$EeXx%4?NLxK-8eno4iUj(S+qABKu8CfNn;Wq z3SkGhj*brL@C(|xVuV>WqK4?1s7|?1rUA;LNTiVM>WSj31okT^pS*=Seep5A(y~WV zql?URG)CNYH>g%{C5uPnjrTZC^V5>V#2v>WyM2kdYR1(8iZ?~ zs!66v+o?2C*Nnq2hL=ez>IL5im)fUqQ_MpYZ5#fs)N1$=5QIYSAlCsPV_?v2LU89e zvUOzTuu;R-C}3a;G%`X}ckgo`|6;l0 z7y#(yrO;f^r9{niYsA;rFwIzkMnc6GRveDc`X@~oOg;a2i-`{O=B1%*B3pDWp&+4^ z8I}#8Pb0h8ID3#??t(K1RP*jthbcEXD{&aS-Mf>~b5{z(vMilDV6FVHVh{3l>_HOE0By?2r0%=;4Ck zYj68k{kfC!9Jcj|Ro(rGYrAHI4dsh4R@aJwpM-$MsyM`FhJ=7dpJw}BN7!g{b$*{J zn?Vn_RG80PN9F5FHfs0IT*D!m&iOr+16B83$v_QfN(7nwP;3$NU0; zI7~D>w)N^`wCg)9Eu2FSd$4W)FUV-nEtorxc}Z@j!WyXJZ8dgbS_MP%4ZZK2(3b77 zyWm;7iuT5_Pk(0Vwy{$8_+KuvL&_B>nA#fRV@~igF{!2#zDZr+j)m2i;)^ZS%b~^X z>`d|CvfCy_Oj{E$ob)U#u!5jAbMgXDATVg2#6Qpjc9x6$f#xm03Uq<^msTx$RFNKl zBM9VfGQhI`+vx!S9|I$!kQnux>oN3+Om2hWtXHS_k`#(U%{OCQ37t%R$qZw$HKufm zVL0$)0e0c*J~p|w8KNG(+%qf?m;$p_`MvPioFb%Cv(CYVg`doyUGikC!CE*Wc|@~U zO&DJ3Ci$Z*-~g$IlodA~F^nSv5CPB?ErjxZ=z#Cd1AOP^MdXk{ z8}9E12Pk0aY17R#+G=TjONT=Ivq*)>i=D;)=tE&l4E4`` zKSTNlmjIb0frmDI%Kh)r_7_=8uoM?3Gc(ty5mDya-Fxrog2R1vrc4U&z}fN;A%J&I z(P|Y=W~^*Fy%fimpd%?45u1rIKbp=tI<7xj z`xD!?)yB4(2943!w#^9|G`7{av5kg}?Z&pP_x$d??^?5FC4bFia?YOp-TQey4`-!m zd|g)D1BoQ3X_2xdf_MV9Y&?Q&t)D(ie5P6%TO5l=QldGC!Ic`~A37Xohg7gwU6q!T z;9RjaJM<8kmXm)_Y&5SlhUS|c2eF~1XlMuVXve>j@0)F+2VqR$he^zsljz^(O5tj3@H~N=S|E-=4%FWT zKt>_5vm0xyW%u<4;CjNu3EDH`c%WYHA3WtX=$b6c%8Zgjb!Xr?lb>GQYZb%{N#*7@ zV#@Ai9_bhX&)`ar;=jf}G0c{u_AkWDWI+iz^}ocD^%!#6{gwTaKINXh zfS<)mfoBHidr1K&Jhp`)oMJXP6B8$D01pvJ$Y}>vXTvGWPQOWm2)W(^vXM;SfL>-b z9qNeT`tM!1eCy)^L?6iG2R=`BX%02{AJ)4m~dB)Rd!-YHyHAmq8Ar zy5PSb>cIuA8)uiB)e8YR7eYcd2YokG_53;gmf_Q`(TpWx5=0fW3<)M9V0$?jU}`}s zMm%ed&L{_#kMwie5wY*(Wrx)qgx}W69I2bR zHoQtU9`4w*JfkKnQ`5~x*bL3Jx<<3uX(KTl&o0B}e2RLP%b;}Eg?;qY1(<$AB$A{f zCC#_|YBKwQvgkkfYdjP~g85Gru%>)H#s0V=3kd7>f6(aoxFw)yu!NML3*?j)uczZ% zF<(T`cpR2@sDDjc#+b#_Evc5F9?EKDoZ-v+i#*OxB}GM0j!z|7(hM9sFVFrnGkm;s z_bsv*0Af4DNc%vs)W7?ipoX=WFP}O!M}I$7_&amJIr(kQvW5(+3>R>_58;;$hI55- zT1<&Z9iI~z?2)GlRWID-cpQU$wR+2TnLzdUb05Nsc#1>M+71`{HO`fEXS(EW{}>F3 zY0>fJ$=x#fsxxZ68v{Y45TsLi!E+W(J^JW+@=7`4bzI=A(I%zAarV?7xNf00vtiAj z`&dbj_zF16{n?UazLi_HOiXC(xZ4`o3hKR-%ajy2l?}Qmz%B58N!JgC;tou-i|bFI z#`kt|3S7$+X=meURrfifUAY_hDqu~dd6QDPRJVah>U@@I-0$2vc;Wvb0{A(R$p_cg zvdza}7;$BR zB-?=8U>O|Ybn_(1{*?9~(4@&u)$te}33KbL9SwgFV=`B7r!VXwtr%mL8bYd7@!V<^ z*AAW+AQ>6giq3LsGU5VDtN%9Q_*DFekFGZui)ar^wu)SNqX1WsZ{7EU#J!oUmS3PR z|Kg8R|CVD<*aO*AlYCt{Pp*ULoS{$Mz^H~nzMVF}PO3Z`0bV8qL@EWi?E}LvxB8@# zX+Hba^k^7#PIc?(8W;rc(0|@|{moG%Q)^1xO04)>ywV$9LMkyqhBR-9PK`~8kOjoH;e>#2_sP zbBKrp2wpO!bQfdm=Q**s5|As3t-P1ltEm)<^R7d8Itpmi)|9DNA<3E)rf$<=!t;7E z2kG0R|2#x#8&kwS?|v%3&7o!1?si31yhv;>-~5ZOz&oyXi4!tJG|a%we4Zgk7KCLG zy{oy5O%RL)qbKFQh=5N;<5b3N7kZ&W8G*Pt=-lIwS4Phh;U9PO1a86{BTkQvUsLx0 zJu%Dy$(!IfQrp;H6%=v7vt7F+lrySp-h(U%H>S-U#%v(y>#aVX#qH~ac)S^b^c`3! z){dsY#rse51smw@%e8&LB!B%8Nj@RRQ7)VZ?5B8QoYn?AohUyfSgJVaZ`7XW?1Y*S z=-%j!ZLXTu@9>w@67p}Kpx}y4@P|}Vys!ElV#$hxuQ*dd${6A739LV5_!VVWp;?7g zp}xdZ(SPI4occk|B~x^EOw>p0?0^Lj*y`cx-kFA`A64GxH`#8)PzOERQ*+I@DECPG zm$hd$CYa|F9bMe>QuIU!xGXXc&aeDn;_7ZCaxJtH$NW_#{|3BRPzii}-qamZK*`+D z?1vY&sHVBsgu!})VMJyB$#y9+DYE#GN}t+AeBthL( zsmHpr_vna0Ust5>WU=~c6fnX7j^Vkz>g_oaRG(z7&r+LSysHHgU&gKyON^q2>U2F1 z#%PJ64o1fWH1y43Exfci2rxV2-R#n@9Q@e5MgV>$&7`7B2UnQXzO6Xl#8ZbE>S!m; zGeeH*+6VrAgRNja6KJm0ffW@(MH&?Z8!t}+y~_L5^B&X>f}U-!kc1auglH@=Ii~jgyZ@Bs!#eIg;Qh86cziVU;Ete>q=oVZ2E6 zhgEMe-zub}g4-twBXSQ@H4DAqDU?s?D>j&1%bEh6zj6=7JgN`e9wzjk4SfDv$`cDN z5^^6{F<1Co_Tntl1PhB3FLBL`3aESlGc%D15D5k17ckG`Wvs2Q12T9(b5vAx2r}sw z**rfN<5`KX5HD+OlU&?u%aZ@nhTWOmRR=A?r0P&>iS85sD=bW>Bj7X6TvigSewgsVQ$cPuIHssc*4aDzmF5kJhW}C)#`95KyJ)i+t5@7WOP(uF$ zR{sJdm`?G&@8#vPAYcShsr7qCpB25p6iQZphS3HYY{E=qvG+{rqFpH}S|z4`WjyG* zjMrep7&v%S_waSVe^85{yt>@1r+dSIqeSGbu?g9~n+$zN?;Cv0Nuoc zs?S<@<<2F>(7GN%*wLc+-jfL`zO~V?z!{sV_1x1HwqqafaF*=)JHyykFP>R zmhdyL^qFu`kj;2>KavY)?HLkjQ9fGQyjhklx;OaBq(P6dc_&|M5>ww zOgk-25eTGKS&NZZ%(PRynLg}do;$LHylP-bopWuy%0Zv?j%oYRy*|;B*_z;3*=UuI zuauyXgP8MxYz9*dJ*YnBC?6$Qd$ccO~8H!kxMz{H8J~avI5~9?!}aPi9|YiK!WgleBprF9u)K zVA-!fmm=FQb>_gjw0&R@LlP^_%q?oRGu;fZ!VJNqhTzsUpfGZ=eyv7-zw+qr(_rc9 z4R{H7Cwkuyc|`+Ax}>@G_N*vEJw+&J3N28}?8~roj=zGJoqOgrm2FLl;nrFPRv5N1 z-3p2-R4c0O7LDtdw{Lf$HBwU_j|Vh7@2+WpbEuP(6UDM7F`GQp`NahZ86})##BcJ_ zzkx?$u(F9piIfoP9`kjIers-t27OtyJX#wTdR$>NCs#~+Q}YRxx0x}L)*cZra@ACo zs8>T-Bn`HCD_YGbl_~$?8T*np*s8W&^{ZZWPP0m+>`ubru}xO+nZ${;4S!gL*Fgpn zg59V@5#ckwqJjFcDDOcWkSu?&8~;Hbb-5OYG2BJy?mMFPKvcNV*lj-!k)Gxpyd2yi zGmzj14cR6VyC1yK=AR$^@Uyr>Vy{m5^GL{p1CcA$=I&Z;4?o%zfm<);qX{BFHTrEjW|4Z!QAinp}1vHpVXO2yp zK!njKt#lx3GzQv>(4bQfr##ST_BprqpWov;C4qJTj9?T-`~F;Y9OF8zXz7eGp zPu)N1ody!a#YYEcixAvM4v~X@ZSShnip#%t#vRm(8uhvGrKYEeSHhXslyU{luftI) zwfFGeT2`Jnm|8-#Wk~8SOP(rszy(j`eU_zp~CIEH|_c^h8Y({cJVyUdG z?48qh)CZp2AJ$@@TrlEIHEyU0Fbl=7OoQ!ZrOr@#al}@c2cz9AmIfgS!Kdd^)LOsz z?Ij@H)lZmGGUcz6XNxHr9!+8__T!C_8y;sorBrt>{HMlXHcd-1NL&*F0Nq4m5JS-q=Q6tvuWB#@l zEC)|9`Y93GvWSgpT(qEQW?`BFck9xg;S zH{NgQd|xjSn%i|w&(9q_JYxHdVx2Nr6)<*K4d-Z1!KPnUscSFQCa|v-9Zk_8o%!-) zIP~y=>RY>HSgTo_U8AS~@X?z8L(AWsSO9lH@6j;AO7RcAV>U@a!GFM|gdfUyf;T*( zIrg|P*x)KI6GbJieQ3L!ms4`=beYIKSX~_X&Ent3*)sV}jRlGbgsGSg{rGE0g7E6FZbmpmlpInNV{-{iqP-gA{l#R=1*NOWxC`gDA^b-aK&wWkY zl1qquDsP38QW3E%CmQ(|26D=o2%|u^JW|R@;SDHU!*w`O**QcJ_jDB;86s zc`>|XyK)~ipU+-h6ZoACXZ%hHwg@UuSY*gtU3Cv&CY{k$WgkH+KH_*5>URsK_Fs<) z@KNA2b-&^B)6sd{okR2n8-K?RbvVfbN8LB805ZQte}Zf#a#ugUXuQc>lg8!E(`!h! zL2OeK_09^De-A?R&{3Up-?53<^YcO0)Y3SFkZF%?-&_B`7J${t{fIZ_zokM|RW*&x z%{{KX<)!1&&iOs89o=YL5$*w`#DDV9Unh=!em|=9{eSr5Cn)GL3iQiJ?x%LYO4Q?7taNgJKE z-EzLQtT*qH_TWo}C=8QEA3<_4C8PwxP(mq$C5L96W$H2n&B_J-Y5GaKc7-ASyy>ng z+(=Fc8}A{wpo5Vaf_tb`EJuVLkfp}wo^GqcTC=6E86o0#l9J%Jz8J|DQ+24g|SCV z&Vs%-hQ{mU{8LFFjkszvO7LH!@REfh))#|&7J&oHM zouG2#EcUk$b75YqGa7VT2JHNzJTYG7iG6aJ8fumcZ(D*lUGzV2S>TEU|HH01G`Mp_ zn2LTAb+G>UIL$!eW;`J&g0Xiw37l#YTn-(LE=5XbPQ{CO`94PSw zBMJZB`%TIMQh|~rF^)N1(bLlywm}h`x#LeXfRjI4&(m@!N@S=@T0PEUz(eQoPqvwN z+PT(}AgpNe;Pn<%KR2EbqhA?~0)gf_ROg;%(41}B#9PyoN70>=Mhm<-)(?3 zB@a=577b~dkHSF&ywd?6WbdTa-Tq8k@<0Tk^^dQs`BvHpUBUgsIg+PvWqA8gTc+I1 z@`Xt;bG0NaS4L$oV-bxN=!G^mf@w}sp93X8Ltu1gce@NnnTv9pU5gjZ?ZvU`1?HWA z`rVlr1U7SIOXuy_l2a-7!+o?_saejg`+MBXXw%$z*{@6mrFn2lQ)Nv9_nkRevUX4^ zu*KCVyllZMH25J#uOTr(bE!KBge6lxfua~wj6B7l5Ew{p31fs^2u$(sBt|XEbzQ!= zY@m6Dp{2{Pn3*nh-l45pLr$mX@j6!IA(_q>!F2Waf?MAwo>-hgr;)afUIM^7V;eFS zmbbD|6F*W8Rf_RSYQ~HWz)RPhqxE@+AvwfLFMs&8SxhEF*4)3i1a;S=Cg<`U5wl#W zTO@@~*$h&-{o>;7M z!4G7@hP8)|&dxu_ha*e_b8-u8O#6luf>nVAecwFHz7@K$?soy%L(AG4XbgV{0__DV z4ccHsL~s*0-t4e$J08{o)=dD`rwKgUPd73ZTP2u1L^beDbISBEDoqg%efb2%Dlb0j zL<|VB27oHR>ejM$#)=H3FgfAq?)~$k>xC4+55DCO0i&qB0UQMd#jDFH6G)?Q46=>x zKPRaM`BrYpI`E$N+c59XB_dms0dJ_IF*S#TQDOQXzYVrtUm;KK5G7Dnn#5*J-_%Z0 zvEd_InVVt$oyhBpxhveU^aLe3w2hS7zHSzFkHiK$8vmMRti{5$YDvMFd*sslgr0)H%Y z8QM35gXP^{a>j*Y3iVQKlm_u8@Qnt0W^=m}qh(uJ9nQf?+qAglo_&ECw;KiPbFT~9V}t8| zN*TCYW()rcmNbWt))zBpqiEk=p73TZ(? ztsQqliPeCT#%3aL;Ao-kV)5lzi;%^vAy=B9et_+#jcRrCXD=91BS7C|v#G|s?l>)A zka4Hd6J_$C{|Lk9k;Jvd%-5fFJ-ghK?cOKO74;?Nt%;z6{ zS&Cp1{ju=QajCReRPnNN7da0UJ`eD)tGhWe=o#f`q$^dl6cu(EmRay>#ZC;> zS0SEl03p0*YYX?|AmFX~@%`nZcBR5B%ebF22EPPDe$~jwJE%&h7|6j0p+&d%5a{r| zg8X=F{|L9A7E3w**%=9JxQVeoK1C#X)Sp!!B|#~r*LT=oBDM`i?rppiD;>wH(BV4w zr(_59H!sjyX^5^EX+EVa?{+qbEnHZ!=agR>_u86GVU(Kryn7P&X$A1T!AM67WY(0{ z;!HcOzCQ60b1$Nj5!0(5#@Qamr;Mzssnv@{=>Rrx`a@b1$NL-_dZ|Ek%YN(&j44n) zL{h=>2z*fv?dQ{5b3M%6p;esf(F!@WZKGr-Bv=U#G|drHR>sR9NL?f}?Ry(UlR|Fc z&`NC$Sx5U0XP;4$A{sX4-y1C4%f=v?bIcTYP$X##2o_~bGBJW$hdsalJ8S-w&3DO+ zAs&$HUdWNaYRv?k#fY$E^k$55-6arW%NuPNV_6!%cNGRzY}D^v56iK0w)&r)3TSk9 zcsGG>9>B6S7G?F5mro#Zt(tH9KcV0@_B0c}pwGQrRi=dE4|GR-RKxjB9v+?+fA{FF z|HXM{j>G1oXfoo}v0+H_d_z1;L2`}!!6;x*U8{9$e-!l(;l(X)7Li+SOV-B6B84x$W((@xV2&$s8~4S>@KhZ?|Rs zye0T6kEoeMQ6HCoe)ajWyEt*>>^EUjL4Tb(UHT(jbZ*h)# zK_dUQYGaz*WPcjF_Z#Mu5x$C$@*kG{b|f!cJvxDbFj|;@spSBi;QI_3GD3n*Q^EW! zmrv4jRb9HDN)cy#g_3coLMOki`caYvii)7b#dc33bbMrLW!34@ zHGDEYO`0+Zc=5nZ557hkYi;Zkfb~kpDvH8)xyL;HfY>}G2|4{d5xgeXhfLl0{m3K0 zA63HVpbN-{d4DB%d4m8RfM5=YHGaH3N+b*o2M)s3UEVPP?*{=3?~0c(zQ5`#u4L3c z|06=nAU3nHsP7VPOvmIwAV>1jnAp~L{<@00PreadR_^UkuTS7Z`Gv5F%1G#gOZJBvQ1RXMlrIkcpTF_*LfDRT1 zy@V3+pMSw(;d5p6MFd(&9MFl3El$i`J9Na$L%~dYiYA69rG|z~H>z?MpS>#W4W5`4 zo`)dwae2#AjX4%4PMqR;S7XN_7gDkaG)6K3dG9virgyvcA)7kb`aXu9k7=LNv}@LV zrT*0CZur=AsTl4_zj-(l()gr#dVn3C35#(s93Te+3+FAz!>glNDS)MG~5G zo0Odj6$1;rbqOB$^<@>7`2M9Z7*i1%oQ=x$mROZ55m-T{;jsm&9&H|b4o?DEu5%rn8AkE+hUr?X)hnpFDp zyU8@0SrgQTySKkbu))IuEyfx@qy_@*+EHjhejQS>y+!+Tv|+->{d$LgmXIdHP~}v< z%na7wlI%Y}2Ald_)7!Gwojo|?MNi+EHOV#^aND=>-(bb@JQ^?cYyLrd)-Hs_RQ77ErV| zth&8m@up*Ml)L|;DKP&k7mvTAJA+0=y(IPjhIufkO(N>z0=P%r(uf$TsU zT%={>M&*CwY^huvnIml9oMmREy($2LfW8`_I-$ew z@B$ntNC?lTyU&2)_s;uAl}?_Gz}B!)zk8<`x%eW})B~LF$J#^MAke;pBLX7=yU4Cm zfnl@0?;Ru{Dp14%1aKlR%acys?P7}(jHxK$RFE8$#v?TqUbBxBG^Bi4+#1a;3X|ah zrLQ)=TXvA}@WBGk;6t0qYP0$nQ4BN}w zqW$y^%EkXZo(V)nC;y4`(=7qbhN^4pG5p`O5<+o(MZSQs!TKqU`PQgJJMneQKxnMS zGt9mzlW?dE$v5?)Ok|-x_Y0E*k_!xcV(P1KBbwe_71>j-xvG8wvO5RCE@+u@ZXTD92-t%91kr2V7s0mYs@SIb=ZCo(!G5a6 zGDntuuRd~rp7vtzs~P#T|FGBNIhG%&+%H$nYmhN0ZtNGD7U16jNBe-M)PO&$%@?B7 zqYAGHOq4U?y8^GXB5znZLO!8gWRct@eRZ|E-G1B(=Nik!#-|p8W$r4cUV!T!Pqum1 zHrJ)JlcKq&6e4Sep&lF>9nYupo*_Xj0aIegfWG1WxnT{n0RxI-P}!QWc24yth!Fpb zI^4WVX3By)A0h~!QELJ9@A+z7LD}szvZdBdLW5*U9t;P%`J6ME9IjCI$yKQtJrXNMg0YuCtr$pC zL1GNPi=_zIL@z7T@s#8bu@a+uK}z#H1)Hy8-zB<~k)On(P0)E0y>(<)S@ChCtcN~s zqU!e0#iINfpDc8Dx?Y_twi0ml{1<-~q>HJRn({dZQ&BXC+&zu-;abaLX`J6E_R7+2 zY+Z51TC%E|$HlIar4E(xY?jzR*~On&+}q1>hl<^#$QWMTJt70gGmG^~e<&A}(<2y& zA*Rf3|0PY-D2zcO#QZY^6M6+ZY1;RySh^-VX+DORTxZkgeqKI32`#pg;k+m$8F;X? zmsiJdgHAK_pJVlcg>^GcLEh{ymoy$xvAzTqbz|V=YG2b?aqGcWLaD;ZCc7FTfq}OY z50Lo1@)#b3%$W#&b+Y^93d2S8z=JCaR0TwmxIw5AEd~9VaKLkj$At*sp#A19XW#(1 z1+>T0^citI-;TMYgXI7WY4`hl^%RXL|b&6R2WK%YP0Z3s)6ySjADUAc1P z1&Oggt*CRnrN{y;Cb_+2$P_vB*3n|M0is_9?Ab4-+eEt>6BCREO%@C*gwSwLUPHu? z%vGKLzHx7Fv4JUJKfnNN)HTAFLb+vjY8EkU)dom@aw*3SJeGtqKLH7v-lEY@3=vPhpZM#;Z@@VMx(3yF^bb@$cReGU-ti`Pe%K0qXuNf*ZYB)-w zkgc6el>f$EQQOioesuSwrfyuvJ!lQwx56?I`zRv`u*o4013oltxf2k<1FBFA z2&A|x==ugE3O~TcZd3#h~K32cU;yjBZr$8b0 zU+TL~poRrc{V1**9)$$6PD){$^Y|0$0m_r|^3QU!AzCirObj&@mU^P?0)13RCPL(V zI>`Ru^uN(LPK>^`^fDv#Bt8T?miVDa{6+$0_TH*)h;?p@C(f~wCn^Kl5~kdz+Fz(% z&!3fgykd{O49b>b%fy4i$|tg@Wg(F6m09ME7aok@rb4pFOtUe9Wm7PK19A@|?0X&D zAW2+PO)61kvh(k5E*H`1<6T$oq~+)tF6lLAZO^Ps7c2lF6k9 z|9>wB)dbW(MUa_YcV5%P7YXH#$?p(j;B8=@jflr*2VI)0P#hPzp*kXHr|3=6!P@z0 zS{=AD^B%Bc3sLAB7ONEwgyJ z4Cf9i1B+%UbTn|^yi7-=I28!UBJ}-*V#|KQE05AWci6yp^!@>@xHyehHogtLn!|!q z9=`t=2@%QsQPRDzYUmf~hqDsR=eFm;)z1<6i#2A`H`J?Z2>i>dt`6U=flH!rKY^-6 zPP#!XUrb)kF-P=j&1Q4wfLOSsDX+YC)zd8Shu$!shGtn&>wWbV6hUN;|9DSOkH|4G z*Em)Mp{Ls<)J|H~CnU+(lxvCgbk{}UYyN`vwEEv#4&gbG#l9L}=RB()D6D9d?Lx{o zl?U-Hkso;8H1Z5C0w?8>2UcvkJ+HQ5P+x*W7!;^hq#^`)iBTT|-tPi7176M?0Qti= zebE8#=1-;jT`0th0dY9)Lgf%5WBEb@)o7ubxud2wXyc9Ve19ca1-k8OB$XIV$SV9A z&jvKqG__{f>%7YR>Vs4Zt<+$RllI^lpc~0q#HIS^bBZ}fe9%Towa#pk@^F6gXrf9b zbr|Bqds%fd$g$ZZHQ2umUDXPdH(Ls=R%09=)_rt#SIu-d(c48{`}c6mx>5h2c;s)y zhHzGtA2QOUo>5NZH;nF5Us)n^XHh@bd08jBmz$g=LS!d+yG1;jFYb+S0MeBJ{)hi4o^3MmfVwV)mKx;hfiLD z?kOeURSboxwQBPO@%@!_2wvS}D6>mt{R>(=3ze;4TCJVk?4qaVt9{Ndwrz=xsR^5D zO6vvw0Z{<=V`1@lz6HT2YlLksifHpac=F}fPh^j3FO-#wl!A9tMr4O0AsRg2=c|&I zHvi+T9Ssc)er{uW8j?&itwQOUJ|XT|*oPOmX&t~Lapl;5cE$umwz>ccg3a@N*wwRi zlL8gQ96_(2qbIUav(V-XbH-G8uChDf9j4jVR=GtX@io_km`qklrhVBIFqzkNhWh5L z;IMWd>hQprh?X2ViIU8ef{~Ai1i#~Q}o)f-5bxoh6;xIuw zj!~!>=^e!E72g2GXEL17?5>47>><0$CF|bql63}*IfAhdR%{hKg+LE#xY@tMsT6b< zjn3FLzVM?!Njl0WFI>U&4YzG)-@_($j+~}@3zIGATi~BPg&V;q#>WmLuL{EUyX3@j zTqndgDO;5M&TP?Lq&W19fj?5N|{B8VxPO;j_hY_6GSZZXa_{+ z+fSC`1fn)Z@qQA%()0-k&@`D@Ei>FJOGHrC(TdwYyjEyu$<}$^ zJ2lh=y(disLj0F-1Vko{4lsGsn>`hhh(`M{S5birFbUa&bMp6FdKvrxmr;P z8^>F=aB*6#?~{~9G^U}JK4{e481=Myv^@7gJ{dS$6g&TdY%Ayk>29#Ve3@rR-m zmXmDw{r1rqBCi#W3U0}w@!Uvke54$1V@ABoeJiethaSJ5O}?zI<7cXSZXH{UhYc-9 zA${kA!yE5bP4-n!`mI(e>9$(5@Vlls6$8YjOCuU}niX#;YTi5E?!mii&zdd2{r2mt zoSYF2vtf?1C)zKJBuPiY+w|Cjh>+<+AB+3iK2M@W>aOcc>+mDb2EAFlxRZ~2BC^eRK+~KF?7{lv%I`Ajlg%*$0%Wx}_v}6%#IdX^O3R<0 z0;rJfV@FD+4&UN)SKAaBwg#kF9NoM6e3Rx-N(R4sU9ie8+486?^ITGNb2qF#`gQ}i z`425Cx_Nod)UuJ61e|ol9jW59JYxg_mWPImbChlO@RAe>e9vNa7HR4o`KCAs@@rd? zC-K2i3YYENz(BAQH85h|++VZN)z5-3i+6>g#!^jz+TVl!1{LZQ%o&vyD)XB`$L-(= ze9`qpnCttDz`YYfV;%8>Z=z_z))kAdX|E~qGw7P=tZQ(gt@N_EdL@oasg*Pb_>hU66#Zbj$XOm0J zlBKU|pc`!ZAC*VIg^f!J_#9>7C)!-Y5mkGnEWye-|G&l<$j1bzWLFUP+!G4+#3O_a^i)M zCH%n8^o#v*cxDtD=JI~?@NC9Tt8jhOca==gm^OAK4Dm8-+g}IRL~LB5As`EhYM;;K zpR|aOn(oC#?OlQ3z0j@oj=703xm-%lU8|vof9Q{*39$*Ju9tHfKt~MT=Hsufs=5S3 ztq4H%rElHjC1bPW0UF8CI$*znNmTjn2WTCDphytcMmdiBCqj7>*KF8T#z}EmYu*Bh zJaK%A!KuD0@Qxr={O(Z)K$3ab=)RtM0p>)Yo;dhSr+)JcM<*`?%3j`R%ovolG}szT zds&7N*GQo2-5E}#<2^<5ToM5znE=YAT-kY-AVCX4NoxKfPIB*C7L2T_@e)s8pEI92+BeNGr(*6$K+boE63oUL9c!(x6(yphrZP2{?s`~Hlc z5O}s^Men0}SudH4zcQSmOv(;2ll)d5{b!7qG}hD8^YSpsES+sK(kIHEn@AU!4iid& zbY#p#w+~H73o@;M_pE>=hwh-AY*cG5J?o#$g6Uo5JN4W{I4w25ilckg;#bj@=>)e{ zgW&awa-iuN&CIm5Mw+a?Xlg^9Tt5ES;p~L1Y%jd|S3r}DigOBOCGyp^g{K5e>(^T8 zX!J8hHXqO?=}<+>pQw=#Fo_-=me3c(Ofey+A5z%*tgJOjQJEeNHLG?tYxX@xQS=eE z_;KJm@FiFrMs79Zq-{rs&f6f42Zj6<<9`b(92&%69nq8K;cEuQFEl-NC0qzoB?8dz z_7@=~8012bTiEYPX0m90n;zV)H5;&Sj*ed z&%fkUmku$gw@^XfCz+XhBs4h}lWH2(kSO4t2bx*BVG5Y&jUO?ac0%0OneYnV)+c37 zUra(PxTuneg4KGaeui1xHr1iebD5P0tM-IO@j+_Ze>9ocAD9uVQ103eCR$^Me=q;6 zBy6_sq}zX}+?o39p1O2S?t4~bgQ$&kzq4U2eYRQx{@4VDxts5T&8H;rs4$$%Bk%;_-?DjU?d;<7)K{yvghGLnJubJ;xt0-K!ZqFFbr5Qdwx zW4OmcM}qd+6)Y%$$O;}r+_WVn>B-%tY;yunP+J zBHf;J=fzh({onpJ432NJoGM|OTxBSZB=USyE2j=sSZis(KSY%S#9k<56bza9gVjtO z->VXl%}d8f3ylL_VzebYDY-;!YZ)2AAfSsOZZ@u(R|84v^oc$mD+cuTtuYBd?Q)zl zGmG|tY08NenGB4iomg0X3MUAwBPrq~Lozd)Te{i?TL>C+t>b94o_a8%2$+#Yt}%wUNWRYxW#o4=jW~Z2c$^M^{$nu}B)@suqI_*_ zAINDvi_4X@%FoNS@X%5EP#THuiAU}1T$y_5bWY@1`%8-_`+p*c=VMt zpMERrszB)*#bflD_ovYP+aSAK8?APHdnJs3O-iUumlX7S#(ub12M>FK{}N(9?jtC< zA;*M%DQLy%Ahs$g$&@C;ROaEe#}2~tisuqJe0%E*8zVa?z?Thnks8DKG|<@3ar^rE z&&zc0%^N#HklYN)OG~Z$JNKt=xm9Hflgfnb$jSfm;eQ9HFIzlCH|nT3Dqk>(t`)Lw zeM5&T9VU5^&om8CsdM7j%dFWrYqI~h^OWVX2`u>%l}gDEV5kTrQ?eR+4aanJQSyv>OZ_7&$q?lw9De!@R1)MwE~naicBX@_XS8A~ zN?uqREc)clho~q|tzQH|^^n&29&K_nYdZQrJuO_Ue)?fFZRej7jkZ%w4tBL4`?v4! zdd^f&u%{W|3!&(Rm6yYMvZMC3MX0UE9O06G8R8^ErIU>dM4HbouuZ2YFPS7A$hTgj zf;&(32cGY*eEMC!5##PBi@5X0?08X`2p=~aA1JvWC6iYM?>85YOBd6hF<{SwnEI0I ze(yGzNClQX^tx3}`bV?z;IKA8-h209;~4FBI$MNRWpJoh8+qn1oIkAI5#SF5!c&#v#OQoh_RQj_u^mcu>CTq(3a(zdt-a)N&E6w(e_b9q@CxLd6lf zaZ2IKDv+zk(cXLlhq!QcX-@Eb8;Cp%XQwmijrjA`xfjC>onx?nlOnj$Q1urC-oXL6 z>DUmAq3AJY+Al^5vxtg*O>qV(m@$e%haaenxpR|z(#c;}YjIsdX?N(X1yRCn>}ML? zuou5=OtgjmJ=3eC5I@4tz!tu2j=9Y6QS9PzRbZWb(d5dcUoB!~ak?=1QeRsgqT3Q= zqhoRn^M%qgX0WBHmzVXJ{palb=(7H>Q^@(K&SKjq{4w@>JiOG$yXt`GjgR+$zi*;< zhN|eo zCNTY}%p#ldkWPWzb{-_h0p&pK=+ae#@~;a;GhgpBxp^N_I2?n^ACHaB-rVk2s`HBt zBYbe=4HEze&9cyXpz(pgf-KlAm{P_ta|Py?Vu&1|5RdBap|vxn96_I$12Vs$wR3Sq zOlD-lqJ-M~dU1CRJs6v#$Zhk+Xmw6sp+N^9Tea@dmADr(l#%jp_4eEQwUs=|gpnn> zM+{w^a5c#o$>U24T)LER1>X+9yN69qC)~S>+{255rf0r-vF;+b(IXFrypfID9aogA zwn?lKY`Erg*^W2TYO_d@rx-Rt6%4ensRWxa(7o<9Kkp$UxXI%`XVo(PszLp7?PfUm zUMO!)tb9%05&?_Wn!I>}5OZ#J87uV3?(W|N3;b*UVYr{LlXxseN#nSDpUIMhXPOD> zB;GnIvwG}60FQSQrFrOArv8SKFs!H(IoOHV2@gE{lITJs=P}F2TUTCf0z=1LY`F9; zO6On3JFs}GGD5$abN9|(fq&gj^6^(@>7|#OgUQZckM8X-7)EiGgu7V~amC1=q!I8# z|7bK{svC;->f!?P0?^pw^GUUnpC1bPR?7x}Fd#1qdFvwu_M1ZqNT@GR`o6aqqEX`w zV!uMlM`d;ObvJn@6L@avCENFScg{UO=lnAJGnDHa)b|d~%=7?=VSVOVaV~>E`CU6l zZm-V{X)O_R`92bgY_+aN#LjVk>lLR(H}EXaErTu;$o11gy2rddxdGb2z$73ba{L@& zzgP3y;QXCxmVxeOOSj8E2KMHOWCBZ@ElFqHeHZPYyQ}AYr>>}sm@0?{^DcZA#IY)J zHu|`N#4(;N-B3jUW$QmvUTMA;u~f323aeH7TAN0x5Q}kgLZmTDe0o)6g`ucT>aB(# zwQSzo$dt~ovKfi*S$iPoAp}E_Hi&r>|Awxvw-apVny1BrNV==nhPpGjlR-N0b6`Qm zvfq9F;*8MDbfEiFIbyI3B2_C7!^u9i%n0n(^1N;CseYo=*IE*AKTHTRp#-f=*BRs| z0w{Cjg6Rauq0vzi&=qdV6KM}L%iphYNd(vXRA~sU$Tg6P@HfuRHE8%N1n*lr!ST0! zSL=Q0?#=Lv$S5MWe)Hre;Ci1SlN=rORjQoWD2^sOrdFo_yAPd@W($SE3bGT8a!cbo z-HpYEMjC(p_VZiTuX@hqj>@#(0OAIY|4rrwfOG9qcFa=iK@b1U18{%;`~6SA+giZY z1AcgYR;oF2LV!8EC5}HH?HEpt>Pfz}TqT!&!^4Bg@`K2P; zJHO$X+56t>Uh7&7$1mnPOR>b=As9!z@kkxcrscgY@4X3z@<@W2*_R}=q>@~t?jaE1 z)|vNd^K8PVE-?DN;wVf}U@_>x1$7(*6uiBNkwMwg*xC$DtY1ItY7edkVU8v5HU*WYR$^_<_!pPF#SUH~cTTf(4aT$sY6dEYaF53G z?_e57{@(ciBd9&qglp9xS@$)&4Z%59VXSUm4AuBV+3KlrLE+mhJadC&Wn_jcN#~$; zgOlPk%9>w>*wDH%9(CeN6#Ds~8Y2iXagd^5kfcYJo&7i!n%E7;u ziabAqg;g>>RuHt#QPN>ak|SAB``+G&d!C+IyzVxQTzJn#M^!N}Vv~?r0mEWf>_5AV z>9Ssww{yv&`8b>LQd!Ypzx7XLYqk47ppp7tvqApO^wyBZ*>DduY~=bxuj-mun*=eE z6ydjx;fsG@v)<(jZ0%jLbUr4@FOG>k-T~vGFCH`(p}@?48xQO>3`22@%Lpq+Ttv$c z!a%&!HIQm%Gx(EJ`WsGNe)TWeWWO>Bl9`;ooM8+bn`F9)5f{u%7}mrX`&i5|Gi{3~ z0`wH0#HQ;nBr0Tl5m88DKo{>j?6$UxONeSoFSDC#lT(lKBUKUuwSYXBkDQ|~N0dJ1 z%FsoNX#F7$oWQr|SHmzK>Ap0#_d+27IAF=OkCy1S6{eu6?^yDMCaqLC!7N?~Sa@>0 z$|ej-V~&IcA0;>NZJY^Xt57uiw`D% zlr0m)PlT|c7Ptd52f7{wm+(-KvTZ^wFcVZ*>zzkR()J*jm`JLlqyKJ0$fG_~##NjI z9b)i#+J?-gJDZ)~y`FFBJ+qmnXFMUTDc=)@Y?}H7W>y@(kLtu$J@B-xl>Y$l1`V>C zNh5uKKwrtt-Q9a7`fq}@8xTiYc($U1HbC9gE+;v7JsW;=}!DbgW` zH(>HPgl)q%D93P;OYW-d+$3~%;cj`0Q>=EPBx_u=5?mb$+=~NMcH{-$ z_5JEDlvqZR8Ah}0g?rW&qL5~ikVBwCRsdXCu^xZWKSszw>rp?51;dgVg$#^uIdmOug>G;ces(0#sZ<>1HcJQ*u`Au)D0J z;w?Q?H$jfSg2dt`zC@9$7nqE9{tdnU+b>6}9fy8N`;Y!?nIP8_%*>>zJRQZYRl-pp z8eqy*(;?Vo?i-!><4o@h@%!a4>DA#Kq5M466UOR*AVB2D8^i~n*o+wYiAD3f4`v@O zv=vDy#p{<9=t^g>df1%q@ZM)?WLh8VV*MPthG(sTh~<7y;oi5LJ2$Kgqo1YIaD(0C zSXju>v?E5o-;IcQ43{GgR{s!s6{ne<5x0D@bY|GRsDUaWMTRk__6vyJI;e|F_l8>% zYK9-3Z+U(nwC)9ZbZ_E@5T)ik=bcntWi-y;M6Z-tqP3rW00Vj1D#*%o6La4MNRy6W z%E-x8aEGN)b09@-$en;g!hH#qRIX^$I)>_d;Y<+~`#9E;a6ubtJ>uSPqdBaOp1g9O z5BcPn^LJ5_znF-VBh}C*drraO%j6`Ow%Z7o&0XZf^Dd#ooPPaDOe$4CdPGa?uznYS z#_J#NrlwUhOdvMsyE?BOb$646b*0^pWw|8qN8Q_>>{lLc zj1LCh`s}PX+wZFfY#rf2vb>G$zz5l81+PPwCG~w^s6?DftwCu!?n~JB4EFT7WvV{S(mxW{n;n_uz-n!Rj;I$vdY4}CvXscwRB2zNOY*Gy5~G_FC9V!a zKKneo@S41_%3I_wbMG@@GwuBh2q4YwEvuhr$gB2eHAK&iiZ+$*3%*&PpE7B z<=CnbV4v6j^IvlR%C<0>AivbcNeiT!hq{hu3>f3*R1=i4;amAoZK9_~NjAW#D@vV` z@4C&a=;O~-&Cc;tzh0Q=zh`@bPxc5@;7eOz=zmhc-M?kS%-7vrC`eS{^c8x26D`~3 zlA;AtrlKky6%4Ty@LX(}0wKVH!SCC@q7(ww?Wtp5c1

{hIhekUCRV1xjY-=@x)S z6=6$VBX;3F!1lxR;3T@|mkSKg!%6!l0mLBkl~Mpr;+f>0(~ ztd(slq4V87!B$rQDkHkI4dUdYK;}OI-9J=zFT4tI4L>s%JMkd4uM9D$O7K9 z@2cYF#x2KT29T_d6zUU0lWZ!lAMLxQc{ObdsfIXEqQIA)FR?BeEO@}bU;YPM4!2Rs zn7=yLK)a+fa(@11LpF-RE-_biv9#vT>y__f6RQ9DGfMbD`oPCi&-- z%yib1c@n_-HD8=uKKqOEnyC)Hyw#2g3_L5E~Uqi`~ggyZB@-u$n>QVo*b?^qCJCqOL`B$xe&b*Ci44x_xn|UU*j@7@3bQE(t=f zjZSlgt5eZ%Z~Sg2l%@Bj3B~OP?JIyx2nuQy@>>W)u1vvAdA@)2jPQrv>rLCX>4rTl zS-(gQzK<$}-_t?*qwvSWhnT>mERzTh9ZUmOIcEwcjyXT&BHAu^_sQvZ50BZ*;_F<3 zLr#R(G^}s-&a->Kvv;gpqowuVK%ROzanY-jfWQ)?rK*Yy&{MM=k$OZig1op20avK_ zryjGwpB8^Mw;PDnI+WKwC;In}tTj}@m-O_WJqHNC@r1+`^%stwm!AE_Qcp~|MEpAv zO{-yr=P$T9dh?G(P%w8E+qQQZyLH~Xf{cZF?&`DI2t+5XH~xXGZYo=;+!R8>b{knE z)x}T&pcfO!P2LxSF1S~&BtYY&TZ)A}?PG;vor!}ogAPYpL8Vkp4uPBXE8=t6(NOg= zWBAGM=3pozIOgH^=>vGjo{AhSt4n%6Rhz=n$p2_*Fq7Px+`MKG225Ndr-~S7wo+vBYlOykU$svuU5* z9M;4z{_#HB>FRpDw_rcii=n~CJcx}75GH^F7bb+6l$=tt%`gaW@Gq2&c3c|91RqHs zk;lmpyn9bFW9S!+M;aKCGz6|o&^$k|CgQjBL^u6Xb{*iiGLD;Vv_5opL90+FPNv0b z5uZk~F`B;cLOWfzD_4x~X_2X5DQ>}enUAdgwPSiwjXpk(X&Q96y+!P;%EG@qr$&$; z$4;!zijin7I)I}5M?Y+l&e9{jFAJpnB3?0KW|Qv-q(78yJ?`5x83!aH#+LByBp;5^ zq;l@qbC{G%Mh!3?lXOA<_G0@SH7R}GEg6|-{}D*+feM|Zlt1V6(vjbm;(h8R`Jwot zhng_*urs4Pr&8REp_MJXzP5GqIi;nQPUaw~%wKg?beyoPiNkzr!kZ?F-NsoXCWa_b zwG<>B)BLS&gJ5Y-dx%YmzHmPT^5E_;pKRJEBL-nYPCw?R`xik7;w$FNGt}sPFCB8? z?!>V4^qs#Fbz$32OWBWLj>54Rc3qk(YS!qZ_`*b%xIU;1dN^(M3>(OLy`S=xO~HGQ z@sh+pK7tdjuFuitEe9;uc21t>;=CgUMWfl+DB~z2v0TS^8KqF>>9*EQ^ovBdM%)}G zm+G6%oSsDEB-5td*M})TpLG7ncWEdRj-8B!oP7IXE`foe6SR8!1KP-Do&2ElJ)(z; z`<_hxlArJ+F1JT46MM(#@gT}W?-7-GwEdihP1(W{$cBt@BE%$-s2bv8Xz%J8SoQp3 zcqYyY_LEFYD8-g3G~d=4{D=b`w^M0YN^_|{b%$GXoMcsv_)ZZxv@5td;$gc0k^f*$ zD|%ED3>3SoFL0=m$Zq!X9=+*OkkWHFfd!caYNSuBv&%-UeyF;9m_@xkayMQ=o;e?k9yRS};& zeD23LQ{JspNfdf=y9Qx|DDK+CJ$o2rd>CNg-rK?9=?o6n|CpXg8I8*ykC0i{oXPbP z$Hdr+RLR=v=!|K!!ACfKbNGzzCJ!Pb@s&G5MXZAN8_sB~LD!FOSK12KM$uX@3E^#z zd;xVckaC%@qgCeoEbWu_{`uyR6t+~)4fLDXw}6EIxS@fsU_1>Gy=B6r1?;EgH7 z9pUfl!@qolb=EB?)BTJb1&W)J`lvOecQ5?m8PL^-IC%8^j5Rbm$f8fXx4SXqRPB;m z;q&CI#luPt4lUtzgOOg$VK9O<6zWpB1dO6};=Jn)@#Jp~+i=AQ(b_#x*A;6uZES|m z$w@sZ3(hKQ2m)y2?y1laY%QIr(2h5gN-b_SN@r!I)_1#t#yMQ6g=U>wk|N+Ow=1V#JsIl~c2 zGdVX!Xa3Qf8`&J_55{GEPaRwv{Mv?85l%~-6s`%KAA5t9pfT)pwz=sqh;DQAlKP(g zf+Z^8Ee$X&kb~M-awID~S+vB>Sc-{KS#I{PJ;UswnXz_rvtjoa*BPN@A9=>4gpaf( zssBts7kAx5IFmpEltQiRgrG+9KVE6~b6Qku{zx5gL83bl2Gis91j|)6WJU#n3w_h$ zjsD76D|3KO!(pDLmR7R5E-d`T5L(rtd(V!iLnc3dT$DL0IWuze@wGG&CjcN1(zu z40~RYBfv01Ps1#1@`S7QpA08jg#USsR(`I#8V?w}{$cd@wbV!LETMZM7CQQuxx760J-`qKMGSX*1`{BRk>R&PLq^f%eFG2hD?YqG#0`r%YUY&Z zLkZo-)VP@YxP3Yz;o{O2H!)$m6lJAK4;j#T`W!5qSald@{D#K4bn`o)O9J8Bl$=eY zPDCv$Oz9|psE`IFMsqHXI(wI`hfZu%0o-Sm*APSjwdm!c|yr;q<^TDD@nY`DY90m=eDuxo%n467B^niS^qM3kM>6^O)Aszsz!2A=nVjruasSl zA|z}wW1T7#u_tX4j+2wxnzN@|KARJZt(jymQw$P$O2qGMt1#5oyYm+DYrQYu@cXu{ zQ(}>)K{IGt7;>xOBaQAW5-?Mmn*!pc?cx?0q^t%ng$u9M)C>Lm8zAb@-*Xg7E} zOvc%rW!a(l%l%Rj^8{Qw=94&EI|@GA9Z4e^xCl$Nzn~%&&A_4mHhKZ5MJv(?nu3^Uc-=&D)-$0erNhH@Yle#U;<&q?*}gp zCux^w3>Erhnb!c!6``X=V;7%9;h@N_gsbkkdWKrjeH?To zE`1)KeQ%RcDYPW0a`IX`daGsW_W&zr5OMwdM2K zf5^gQ>F4(4!6@hz^C!T+YoHQNcG7k6#Fox}k>e!QAhCd+LqYbK9KC2dk_gpJ>4j&i z8SXN(i-zR^Q&w@{NQ2rkJ$#mvW`r7<)*1GTnf0N5bj z&1AX(MQ(YhU+wLziw*ZR-e?yL$$dBW4;#CiX|n!$?P&8CY{btMAYzn z%An@fmeRp_RP0BtSv!WnNVkrWbUm?5L5|jKYn68{ZbS|!4l-{E1)Z8}s_-6NW?tV$ zoSVc3ruvihx%kT1b^iU;Zk`JJ3Z04^0#XLPFq~?g;~jclH*G@P*|5B;egtbC_o3aHOs!`bZCceq%E3L_kmAbmm0V)uzihka|yMR)x-^ulJ&;mrWOPKhV zIoUs(bbQJGkjU8d@{;1L);d_hi@Eyi?h&|>C``ABc%&S|qHCSlS;Nw7`@9xP-9>)A zgRN_qJtq!FRYrErGs(6H?=Ey5SkjQSMdT9t1mGmI`6YBC|FZznQl1{!rHtT$3D;JS zXB{#gP)vtWxl335hoKv0`__rcK!BTD_?Z=WJ+-i;jX@gN7!WMAj=8=vfpoL~T`+v< zB4$SF07cep&=&HVACr6x7>gdm=KVqaKqo255AVP3M~o0E{)Lub ztf00A;?DN;42O(~`oi8J1AA9qo}Pzc-mQ8_e;|u@z)-={?eS-b{-`RR;O*rFK-4}Q zw)kU}?;j3%Tn|Dt4$l~fzg_9fwQMWia$%AWLiaw+6S!K?DZZ}GDUBqfzOKA&MYgGs zB>mA4^EmVvvx`p{+D>5FMB;(N{Tpe9CpRAZJ3(#aGX;R<*(x3f%u43K!%JkfvAMCc znXUEsIByg(f;tUh7Wlux8l}S3ZEt}09a=_W8F{Jc{uY?TL!5GYF7a`YIzdt#MCd3~SFZ z?M#?na`tDRl?L3GWhmc+H`gLj;`Vuj+f5JS>uBoM*8KHtK8=+SzKk%@g&;mgy~QWa zQ^Y$-7(T_|dV_7>$J_BrEi?lt#W74>UTvnKr~?*RR<5|So}SsM8b7rBo7943AsrgUTU(7 zhj-KzC%F~o=s=b3K{2tIw~_junk>Y+Vhd{1?Rw?AVhQ@$6Bn3Ru`5AC9ECX8p2jx$ zTUp*)CixgaSD*%HU&+>|N*c|iNFIbc2bf%8{)eY)E#q7Og+pNQ$(xbfs?v5gF_G{_ zlG9iNJ16_DE<|Zer(9CC)5Td3_M^M4&y_CHq|vM9dR=) zaTtUNE;;{k=(UXe&z6sJ1e@)2a5pwKb|6yRe;NVgQ}eGfj>A^D%nzKR2xR}6N5<5y zXc;54QTrzAx+M_o*-0FK6D$1j^yT$!`$Mqud+HxM7jWv8@dJsarV?UhM-5K8Hi;1j zg(eU&!oUo?yc=E#s{x1YliN0%wsrq>ICerp?o)Ruuh&+?wtK#d7Wi}ndFA#FdQy_` z;EveB&+U0bdvrkJqw_V|<2X?4FQ7*1m%tgUYUn1BCh z+q-&}l-r^5k|}Bl=p0sbCDImKSA9%>@FkfrypR#{TINW0(JJPf2(q?o2RK{P2`NX% z-Xuzr;M8z_v-Dd@Km-4Bk!R#DeE$cHt@U|-}) zO0FdbADqO?wyKoM?^AxCxZFDFP;0pPJCPafoX1hE8_x zdxU7M61HEmpx%yrFc^;-{qeS(8Y}mfvpQ$DFt=^8*Uv1QYu+CDsmEyl&bS*=e@K5B zNtp_3od{pHuH+e!g3<4FR0wosG+bkKqp(GO&R~=25~qDV|K1COxoh7xSWTa=Dho+< z7+a=Gss6PZ0g(!V&Ni8PKF;|?o(=?NAiwSbPhWVEu4NvG*Zlb}rBgP+BMK>@AVUV! zap&n@4;_kcOL0^1a;aHTu53GcQ1$qZ$=E%o9-1(S)dC}BgX;ULH3kBtf%2r>U}h12_i(K{T(6({9vf;|%l?UW6vGWA)%$CMpAPqQ7@#{L0s$yh#V$zei7 zYv0N*;C~ORly7L3#f?7#HP33y@6bR%s}bvk(tfO#|;8v@JruF*eUKp{bF>)35=uI9aCQfP|(*kj`#|CiD5Ks`K?HO>d!pa0~%@{|sd0L}C=&x(rY z<9{6W0wc3M@LM+CBb4}LNQz784o%egRh!+IxX~?eh5iSW7$p#2h;RPShTRkq; z1;m*&4JQYuQt5A|e$KBG`Rsz)77hmW>vvgBjV|fKgojaaz2?J*=((S<`b^<2hZMin3zU`dj^QUo1Wiav@z+VjA(Y8cN586G z2Nu2x94uXLPVt$k56h*(ea)<*Q+vMRt|!Fl)9s?(`uwE6FI6KDW58z7G6xro-QQxD zJ4EkN3W8u4eyL_8oNryxWocaY{r*8I|uLXxc>Xw(L?j16r|P@NZFUm zP~z_R%gQV}(1QHstI>bcAGjB6F|&63shLW}3Qw)PL6D(yW{ef}D3Yhd1ZTzR$Vvm_ z9qhCZvkVM%2$kmkL5#Yw_$1-4hf|Oxh;PIuJe>tRuO(R(e&{HLd~CQxEv`tjTdDlS z0fXe{Qb9Xf(Wg&jeD}!gV_$y~E!aNJz=13@;rlAt3oEq}*e{u7^)R@CnsFSENaZ+B?t$dSQA0SqsS4@nB z)mIw@1V`(6EO3KW*?YF?JUB02enlKKJH{HNjd6oF;$8NKYoO}Ud!3Htd+MC}@-Ar@*_a!$rx&{MSa1Qc?yhApJ!)9b;k+RR0 zqJ|DZYgQy-*8xc6Jd6tcP_#f;-(2Pas|ywlg2@vX$73~$GS!c2cp#~){Wx{^Vr zmq5QKq2!ry=0jD?ZH|}?J(qDd`mK2Z9h|wHN6nKP6r+u16|GzRIid^p#I`HccHLwrb z1cr8USDg;w5I=ux`uU{kwEJ)Xe|@dHF5n*2aXstHDd~=jYI^TKg-c_cV-6xJ1#RZXs4X zPlCUclpN+HwZd=5i<5p5fC{55tKTn?1oxrXg4@J!dCjl__NU)+R(UK!)g{YG`b^o* zWs|s5>tT|7JcWv=xs|hX>4eG;c!eSU%uuzN$yU&5q5V>Dv|RqU^^`XS$4s*DYL{3H z*F?+&T@}k#%-XnP8oU?i+J}_vEOejD#y{le$M(7t?F&cZ zO4Qcal{5h)YZH^k3RSz5RVkQhG+NH>)082>i|3f0h2u42Z+*O{zRZ5?DSxy@TG8&F zsyWF?_(bxWHtM`rw9^){0{U4sX)oHx<*$%c67cAtfOQ;BDRc=G-G#tKz=SKCG%^Y7 zZ>}&I&~P`Zg72T;ww7;KJmOEPpkcvbBtx$sDm>@_8>i_{uJooEQ?YL*2@#$A`_wQ3 zW|?@uDg~+v$yhSbec8D2A(9Nedo!60c^7@$3W^NMpe{)$qph%ks*zN&gaTk{T02nA1`9uTA?yA z``siwZz-D-NM1>zex%NALGXv8Cr`=abY)3{rTFB6xkOBi{+GVV0Z#oC-ho=hlNTg) z#p=MV?b=`AeeU0+&g2#pTL^-J-)DW@IH>|y0*$;I*@D+*))hoI#q*uh=`#zZ_2 zKH0qFbs73#qze(m+82DLsVWl-h7{E1zm%09OH9+MxCOwFHxoOb?*E%UiVq#9b0h#y=iKDIuGut)9_E%F(&Pg=D0mQMVW8Lq)j)O6{vy}5gkje^K4o*4Jn>;K2NjMFYRr{5fd1Zh#fUfYJvUhpFsoI-I!t%E$PdbB=JU6`paGFW~j-?|( zMOL#qkLdflrb7N+b*ilw_eekM+r(0$gS~1gCMZWn;^NnlPl5yVa-t`E&TdyeDnE9T zUhusyjD3rd`vrO9?`ekRlMxx!Im;LZk#5b{WqNU9pr&cLOTMp^AO&sm@`$qk&~j}2 zr>gYwRxuJx=iYZh)$AC-`_(Pr5sN8ZFSqGazOx@|ascm^FJkehPHY1@jjB-!42ub8 zy<%&x0ApZx@Prk$J&*kh%TQ^L9&5d8%_@ zV1k7XgbsX0P6g57=PhBV*j)2+b4}XTH4=y@P>lu4bsOJ{7gRDY;FWvu<|ukGvYr%o{c~={I$QK|XZ4&nS{_Bo z%pAcTLsRm=>QaII-2JhkEn!^X`b}Zj0kTN!ndG+yH%zd;%9HKNw@bwX6@_(Wn-T8y zb~`EkZKgMkK?Mp9vM9z?1O2^IKfERNyYQMf(~E>J22@?%1>-65tG`ITp~R@td8;T@ z#7f+(PTzzKny`2;q{C5LO#aKPx7 z@XE+0AH~M(ZNS<`Ilo-jd9|(Yo)jx39x+&na+4_Q@|S8Pk&A5l36+9dp1e>fKQbt< zi)^i_f~r?^QR-@+#x2AY%u{gW**Zk4$(u9{CMxi?Ot`fX(ff z6@!ReMClMGCaxd&LJn~npc2UhPlVuT;e)4Wr#pl5E^GYExMqi`fA|Pl+<8M~{}=*k z{3R!4&L!;;YpB!gaBVM!siEk(EsmR@4eoi*ho<{a(S-kS?;iUzG60AOr~s=wwBNu~ zmR)7TKU#(Cu0LlMtF8yl;Xj%T+PrEDS1qIjM1&|LMLg?5yZ6Y8uWjx=nJ{sg75^Iz zl=64%a#XmuxO1A1QzfS1Hb(;2P}(J)4dL-VY+oszvCX|nCu=vf=6uk90YWdV+HO(c^%Q=x^B zru>h{HSxEKaccbn7Ouy%&XBqZnclTsMelQ)=hhRTh&XX7!1qQk6Ti}&Gj@G#i%^}BP) z`NrVq5;ftjC{e$4hI)fE6{O8s_>6Xqu^F>S=dqQR*lym_WYy@9b22WcmW}p!t^A(< z^$r@_u~i#g;r<#grZ=ypD@2~nFk%F%trv%k*)GKKJx%gD1@ndPpU`?ecIR2a&{7#= z!fEc0105ta!s+VYo~@75RjO9igF?=oCi5*{3mB?2>rr=CT@4MdZa8&|AM#i-Lpr9b zN?0`de?4Fns?afrI4pC53@&D0bv-it6mvlmWZ|Ix40_`!FR1=Y0RARE9qtT$=JknA ziCf*7WXAGytp}gQjZi$y`+DGuQ^wIM&(^7t--ubZjY`i#2WG+9u`L;)Kwg&-0^Rr? ze8s;qc(xck-^8d6M5Bh1*9N0*dv5C0N7jm3N57S3k5lJYvdPX=crCJw{H`s>@L(|J!qNMz`H|`Ft^kz+c z#ev?Ta|$yv@7YRgO$ly%1CWWjL^1#(HMjRQDGBv+DvS;fAO(wl$&&&nPBztOc^e54 zxjZ;iLTxh2_8z=3PL8^bKmwQVk7ONXI&=JxdoCx2a7}Iu00RSsq_dQEy`O|=Lq-g9 zg)CPx5;9bqA(Nh_b*vqg!*s6lr4XzukQyrfzg_@ugBJ7kQQ6eQBbfK=BjFu9Scs&= zhP!k(-k+`K=B~x3+_0vb(Oq*P%f0Yg<@WKoJL8t{m4l2b_h=36n6|Fg3VijRy_GC| z`au!SkRZfXA_12#-&m-VVrXn}$4bITlGB~T=Wu~eYUkhL{GtY9xE^j>Z65~|>^;Nz zo1bm!!x%jG zWN8h|jUPwOaWjE?Y93GMdJnI=m1ArsAOsCVP~o6cu*qm9DMHWj!a|3Y)C#-yspo9X z1m7aXHHS5B57XB0O2tqrSNGE2)5qKrLyS93yND#54N_D|Z>Xquc|{^#6OcwkSt*JE zrz5DMu-s-;Xs&KiPEdIAm{dkATZWL889M;vK$;woViKlK8S{j<3l?18yVY!J*#7!n zc7YZ;?nFGF!*naW_zmQ2s^Xv4bumxAPR$z01FTW-K%`+LRJ zLW@gmpo6}<^s=ju9NNf_ePAbgVpv7-BEa~u_YqAEx(0s)vgh-h!<&-c zhyT^1)bqCkneG!Qo0u`hH8C@x=yF4mXo9=|9oX!~xOsbbmoHAWmV{-YrAj5WUs@VX za&Ow6F6pQjH7Lp(a4MKV6 z;fUi9k=(CrZ--74@zHX~=HW=;As{7(s>cD?u&s`fw8A?Ggc5MJBXBr9c!|mm#NTq z3GH7xK=WJbrplAslcYy?c8zrQ&UKKAp!3+@{4VYcwe-2D$~d{W=kJSr9<6)Ito!$TEC!kdJ8JT#7{tN2i#fd8yK3ndB%ft z`tjYTI5J8k{a6qvB-zcvOXGgo8R|N2-6oZ7f9EA_oDroVujMd8ulX|~#aPWYXhBoH zk>Qw8Y?pqO@;v#wvOA99Vtbn~rMH#9LGAn67OC4%4|hBJZ5!x0fVL%`zyk#;MNZ`$ z*eyV(ts;Ht93#(zQHZAkmDBE+w}&9i4*xE16~wyMn<*GBa`ke(6Rnfg_I* zt}~?~JrBCR-4w4djAwEX&!kiFWOr=6vJ9VrEZ-v{5LT(?LR8kza7(2{w^B=FA1(QJ zPvxVTQNeVD*T2hhp;z4Hz2XD;5xE2t@KXp>D-^jq+ohB8Ao(U0>)-z-+k%=_p<6wA83`k6F9(4en_3PQqF%55CpAP%sxo?OSk$UqY{CLP{6K6sZd3>R5M!_K>kQ|R zYXm1S#v!n}w|kBl-5ZT-=IkOWHi$2ry7n}Hus9U|D+1gbj`E5kE#JKBBd#lPRMHfF z7L_#5;Lk7B<73*WRQo7gaQ);nGZF%XHD0N~mmbbTw0#WsGqnvJ1R%_LOIx>P0y;## zy}c$q$$+ms-F@{PHfvQPBBsp>$2B|Aa!?J_HMQ>AsDPFtXX2C)ab$gRNhE@WkV5mI zCZMp4A-}YQJCFut5PmY5$WIz+!f(jLun*(XgO{kU!#LB5=pKPB+Hz{jQ((_4HPOrb zDyJ~HFstA;o0`#;XsFW;b|~x1n(}|WdNzHDjuKFtP_J%`~Rrr|=|p+6bcYpEj) z_IEl=W<12;mWib#wb#Xis6&@?B#c$+%UxiR!3SDK#sxn%?>LCu?sF~aRm~Hu-f}hw zyEFoVbQy<(M5DDW#(JfczXzIFmRE1m`^~U4|mDLzJX!5!Lazy*(%CrDWLiw}B zQ@QlqUzPB59|!k;30g(QFwaKN|CSVPHJ44Y?L{dtGuM|VH-&y zIR^J%oPM}2AdKas9klB;+ra)V<%npr%x)}^^}|TcH#}7&3`*8HyY?!xWL;s4d(i%? z;gHwOiEo$x3$hzC?=*q8VIm$>%xlgjw;g!A=56 zqImSjiFBhKJcv#tzwY+91&uGB#nUb_M_i#|!BlQ?8)OwI4D3dCF7XH>MK3pesc? zw_t3oleq3_3BOvwbiW6ZmmIf)3EU@&?e&K0j@PlcNJ$WwH>7!>{nFQ|^?_DWXSH+r z?`-X{2fs`=^n;-v%4dx&#v`*UDU5}kOuue&p~1U|NcMKg4+7zGkz#u9E#(vsV@;Hb zMr`h$@y-FCI2B~)-$;ZGCPd*Tm$Q%Fc@5ha5cl6fx5No=3DvPS)t>C!lD@vaaTX0v zNpe{puplXfiXI+|;2kr79u0YHUWY0TT~>dfqcRAFBQc#4o(3DMHfscF{t!hGSmFO@Lq-!Q}sL|f?8>=3$*2*@-T{hWCZ}G2q zaL;!@3sbaiA@wKChEI&AFN)O$9p7gQ3J0{Y%_5B`@%=wXkovTM>|_$%3o9Q#DW2Ht zIxVN6+9;_W;OYUi)?Bt<3l;p{(=y}PeGtu7p!{OpRid%?>?yny@6|)fqc(K z86GUZ)PZ$tBEMN>D~7Gb5dci7)t~Z2R8XlhX$Yu+jusLJJ+E|5t+#U(Mp$RIZ`XAu zROq5j2%{xi!l+Yt=;_JVH9obJaAI&rf&LH)n(0c(U6!b9!(*~pdnM(vOYj#lZ<@?s?Pe&H@tPe9x_dp0?;PzObHg z#5Vzbj|XV+Oh4v4zP{_o^^yjno3Pw{r#QPt*-kg?ske2vR{^TWbH~mwLB)5VlcYnx7-MwVEN3f5kLj7(cgVr z#L4URf}{CGn;vrx*A|pVmvel0TIy4zlVe1Ws=J-q$&syWoWwtXpq8BFEz&QrZTt`r zp;c$Nd;P|x2`=!>Ea?d8QQrqr{T2)5PT{@}z2fOR7T|88*N49N9uK?^o|QV3p!s4D zd*>!gHV&|n`RwX={-PBvDO+k5Ar&gBe1%hRq@xf}MZUZF?`V_{T(|x49dd=bjU{i* zFrp?ke{vZP1_?;MTWIfJU|k5PVs%y(Y8j+I#=pPF@&0SIJIZHQ8Po?xZwW}002S%z9`B47J!gv zDHC!y96W8_{$*y2>oqPeF0k2bFwe6$GE4yP*GLjpN8 zlgs-)lxo&W`dnGq1fC0~{Q)NQnHl3C&70oaiifIrbzRsos+BfqFp%!GWfl%p%b5|& zGmZXgNvW{s`fk=Ve$zpFdWqw)y)Zhl`pQNdb}_4-T53j`yBvcoZ1@AoGvQbUCSa-# zC^v~jNaUqXB({Vk3N%?DkvOb!&Y=Nj;CXH!W{f;vCWedDu(yyc&lVS#?L)(_#>IqW4HeM%%&s2qfp~}k5cpl?}OFO90kmC4Blu!tcmQ*Dk4>Db)e=+wFM_sXq`ukq zGvM`ru&_2C+LQRVs zcAjUV#D_eT>gF_bQ_~j> z&x(h67zy*?JzhV1g2&(f2l6nY%o(H}cv7Sz#pI(>drZqRmi7z*;hegHX98OZIMBQ) zIx=R74CxgSX1mAgvejoVU6udHcq)JC`CogE`kHTbt=oD|H7#@*n6-TJ-;4OE9_1xt z;<3_P*Ry?Bbk@X(R0H44X2>`mXK(avA4T+Gv`RL@-@VRgU<5j~aR>fA$#W z-aEc}x{G69qJxMlqQU_kReeAs0^qg9Z5`CnWAV~v{!K8aV=#;W@j?DCa{;Bg4t8%E z25_12+mm1M?$v8-R!JJ^fsr|@$`ros82 z*aZ^q+`T}_2jppo1aa<3O79%Cw`#b+fPny_BE|(~5Lv}e#UmDRta3+Whds*-?ST)6 zPU*2`JX9VNiG)JO7i5h9aFLp-B;D)Vj@FePBE6>tdNW7zK)}h0uzUX&Z(cmZ!^htM zOvub$GJs)tsy6-Wd2HSNHu9#&iyyjf!<@q~-1>}<<yZX4I4E+8K?0@Zl3Wo-zJ z+IlE(Iv(}EtIq;hmQ@jJ_gEs%@iv}la}hpPlz$lQ)oij_TeLGga&;0P;|jwRQ3kd$ zyS+E?7$U`NGIu~SXL7FNwb}LAYw_o$eU57tjj8iI*ZaeBj?Y!n?6Ydv=y`hc-TGqZ z;ZF0cQHl(S5`@&kXBMY^N$e@h3`@t?pWRqO9(~<79$7jJfCy$XJ;745jQtC7{;M#gt%U>B~^YL1>fcxQJ9E8R(eFE+7a}^SZmbQqT~!_Qllz4 zz4O$a^5%$yh)1LhjB3xJb&LoG;x zGfl?%JGGtw$_os$~HSTlZvEg8mcdw7^E z*Z87(ru2K9*bRgn&aJ2^Masz)Muy0Z1OkRZz7zJ$uOS$0O^)eImd-{mPZA~c&0Kpu z+rHapwH7U@HfR;vP>4h6!8$3x=ZuJrZ{ZX6zT0&6o;UdXJNeXNI9nrb=s(`m@G^N| zbDzKC?!#`FW7& zqG5mxjOVbNx<4}GBSj|6TvedgkEY1jFf7z zIU=eZgUL1mzK&J$n1Uvs3~7*0sTzQUR#XX=<%03uNP<1BiBj8P9%ffwNplra0$x1% z2}2t2`NKyjJRoZpi40qna;`?D9v3a0u@8OTUrUN}k8dL%kI(+2cP#O>{uxWS&VJ5W z9J476i};$T8V#%Lsk9N_mC|tZ`Jcbo>s21fg>KAM4{7Hcb%jRea@Sym?Bmvm7}vT9 z$}kS;kBdAm8mW#Ay>WfwngSA0Dby!xmxhG>v`4mxI<`h^$F$h5MVxb7H!J6`q?0VI zZ;w^%tTVF*FO)DpR$Wj^oGj2Hi^`G>GrAG0$f{}(3B0zT)g&ZE6*5dBoHSQO{0g-BO&xs zD8-GqZgfOON<%|GH8L|ecu=u8YdZJt`WpNF9_#T$()0;fZ`Me|sHIE_k{S1$ChFcc zhGg5%c%BHMBf1!?2O8WsZgoj3owSDXSo*A|NBKE9-f&v5Ig)Ba#{XcAyR4Qql-?ma zSTQGF18H?HAckWSK5n{%1%V`U$^qKUia}`*xJ@p^?=H!~e$RVdpwYn=97adD zb%8h8ed*tpC!dU@pRPZ+*o+s0EMutYsIB z9iDz!_jJkFA@8ojx2}aKMR9Gd2~~V&LnAEpl7>O*qglg(-dG{4q(I1dH^Y^0^h}qL z(tuSO0g`eAg(bQ(Q4(Pm(pS|CDxTP!k+Vc`=A3bub~qdkm<|*6`#tuDgLH_@8HfE& zpRIe!kmg6o7yzUpY09dk?2H7g$CWA#1LeUhT zAq^M?@jTNYQCU%FrqqH~18Am5nDT7iRqxsy_OEt=);&mON?^od`Wyr+fh&k&R$Qm6 zuSz8;z2{=!#uWV&=*Z59)lFSRU8&ELfYt5iQWOnF^yvp4Apb9WHdVFpU3>fly&=i;4j^~j^B-N-gW#T z#kwkRy5yFc_HSH0Z?!SRwXAe}i+8wtUT*|l0%wsg_58=^OMY+HK7L=WW93rrjl8j? z3z<`WW|S#${4q_)-rLRxzQ1-YDYo)HhD0SMSHzd(BS`pVQAN!Fr?KETz9pLL#}hAk zm#mp6S5@Ka_alzU6muJ|P2A^@#Zhu{a^mkABLD05FFHGF7>&{fjK9^0Zy#SVL#5UT z9|qL4X{&E4QJ`g(dUX4FR@pL1Cc(`PyZsIJ`vVTU8=z#Y$I6Zr8UO6>zy10%3JCWe+y|h}MgY=jgd1#T@8}JtOE~$@T>Z1+yn5v_I^zG#70>i- z-&vMN)d3)9;yBwVj{`)L){$)2~ObGx*OI$*h=;)PZm~OoAy*q*0B6@ArABOjew?T}ygaKb|EW$=AgU zP+9S9e7>JwR;;T=)37#L@z=4kGL~TAgYyI1)I85P>~`4i_g>TAYKhMCjB%{BK)2g1 z&Q7;juQwRS^%4G?=NZ#9$vh3KmKqqKOiOrCtYr!S>WFf^PBRri$2~EKglG5IrKmwT z^Xx`42E6+`$bvP6rlx6+>9EJ(9?pt_H`mL42|WBLbL{#?fdm`wNRVyO+F zOQHKscJ9Z9#(O@wbdGvVM6e)|>c9fA25ltK{UCuZ$r>ksG^4|QmL~y_G6&uzN)C%O z<4fSA^HnTd*P674hwiPNPe2`n@Ju^fAH*|(VBAMNIfou_K7%Y ziwCu(nEBM`Xn%ZtGLn9}{_rxzCYhh5J3MyJhpx!rY#g#Y}6#Q( z!U}*4YsNx=rrfOb*;xT5F|d-*QQbeTYik<_sf|Pk3IkD7qgM7(l+mPu#sL%v#1Y6g zdPna703ZNKL_t(roI(KK`dUJ2${v8lNNsi8N&#q)`-PU|oQRE_VRiTF+Vtm+ASp%i zC)OrLYZSbH^Bb=3oa5}`GfYO0Ha}E4ZqJOZTPWBR>9`U8Rx;pNX<`n0ixxyUxCy+Z zKR*`j+k%~FXgK!FI&Jti+a5}pgy?J{r?(cs)bn1SSI>NE=3_d|$6mJqsU?NX=ujFB zw2Ivl&|U&|@o#Yqb>3!rVLkt?vdbfGj4 z?ml1k#*-3TrORI4sr-#;&Q$9*Oa|z%<_)sHlI$u zm}AWi0roepZW&vunBIzb=0FuNYj`Mur1_H0E9rSIEK2%3&A8d`uv)EfetIf0A{Q_X zc=hTP{_)R$;AA~wl_Y)suoowreRrBCOnJgQS(6S~C!Qyqo}S>#2VaU}E6h*EPYDGY zm6`^Z3%)l-|6$LgbHJQlnc+3%5a^0oFvC%|*_3c|bB*iwS5i|uI5CZeYt37e$8~+J z{voT8&{Du1&*^%5O>pL;PQLA2v{6YqHvA{l^i*rgRE)1Wy-Tza2;j_4Yklp-if!S) zFDZsh()5z&9o{^Df{XK0Y|idtpY^`fp2LV&Z^M`$d-Z3$e|E&jAN!v8oIb)Ub#khI zc8`(!pL+-VZ5T2BooV@Re|+`wOmI}hnQi2iU~1#~Jpetr%B7{>wI?LB}P z+wF<-tMz(~an$BQ-hfn|1s#VOUuaOHbD$ezBG#vlT{aa!v%3E=icHeVm174m{m{Rhd4HD(d7+0$f zFGfd0MY47sIm#3lF-!EVL~dIUg{_71jE>)bNRGw%^;muhclQ|8V2WX70Pd_VS~9L; z@EY{dl%z8KmB`Bk`nyxrw|e~jN7pAK>8I<1mjMA*CTRZD$S~po>Aj-%Spkkc>_doUe(CKTo4s}HgM1W6u2t~ zRr#~~1VAb?S0Ny`lW}GJj@4p`59b;w1QEveR{;XyUbGC)buCqJ9QBcmdGIG{zNZS3G!ZRg$vI4}MC1Nvkmeh4HrfG5jG|e;eJY(J+aG3VkANIJqxdylJ?f={epqV@(9&2__W{Xbl961Hsg#M1#*)JbMvlN{9Lc5`khu zm?52vWwyv!1oxozd8EM$n{0PugBfIMz>?4@8_XgzG?04}6D7YZY!C`IK&xL)rQ%LN*IRmNx)?4cD@%i%1gvzg$E(&X2f3IuC z=<9_3nXBb16xMzTG)E(4{eG|1FDY96JLBKlcd{FdY|W!FGo|*KOXCMyN>G(AHf9^Y zyw28iLBZ^okb}R;j8J1np%P}|fGO1E042hN3Su;BjX)UyPuAY5y0O@_qF3V(304^Dn28?Rd6y8(Zps9=pi3SD3!h<}bMkP=pG1}!K zB}l9pUD;2_Trf}4kOQS4=NX6H9*1edG#zlW+hM=kVVY;0pPk{aU;hY>)qkxnV@szR#YaFBT_aBjbfPlG(+Z38;kJgL@cE=hgPcp{qgHk%H2Uz4zDhez zLooV7RdT~QYh;q{!zuxJcZsJz|A;TY{u{>AJ4*NZHmil#DTWa{_6qZ#y^LoWPv{L1 zk(YjmuiSRsW{_L@yD76K7g~k6om>CRW^KE*@OgZsBKx7s`HL#i#;0wp^4|74{TO>J zT<2*9RzlU$?dKBY`SF@W!)ugB{XKDg;@@26D<&80Be-<8KWMr=D&``CKUGEmRn~sU zIND#g$y$k)Z2#8Fch);>wp?1HxYb>(Q>%u$L(Vu%lSGJWL#2{4@-%@`!Zb}_maMh) zYK612bF5b@Y)&>fIXUq;4QY_FRV8~ABr{{4rFkB>4dzKiC?r_}%uuBTBF7+&my#OW zi|GYg(#$4Ggy0wwe!|K}&B;@-j_HM}6cBm0^r3U28f_6*xj`f{W}0S*ge}Nr#<&_W zu0|ZL7~?>`3v99ltzp*IeTfcBsm`%s7*+q!^Q*YWbqC}B9fpte6ZMsdUm4J5Ns8~u z#!EHIQ^yJ-Y1Rtan*>Xv*K$gJ5UMO8)veG43~&+s!y1Gk@FX8USeo#v6e;>lP7u9F zqm7vvY0x^LhFQAjnPNybf7YxD26z}j)CLztJ;UbG$j^l{YCNY9DetNczt~FMnSpqL zN8g66Kg26~e7cBxEtrg@Uqvks7vU97b{frL4XUxkV) z#VjvtLA0$2OmQYvKvZc9sgg;iqk>S42U_3M8MsDH!UQZ!{ZB5l)&WvO=wZ_0U~meD@#!18Kd*w4d?$z0dK@ z{d?hqmC{$&lCB+(!N zk1F7%W)G>6&(52bQIPqv@26zOi}7O^66SdVXNd$J#=){LoxWQ7C74p$C~_$w#q$e| zcxCOjte}rg_}lkQ^$b8#6cVK)4h7$BUR@+lN*Xz(QPAwhB{487CxPj|M~)WV!%`qA zP7DA73@MG6_V4lZ$&YyWm+!GXzi>Ef>k*AbHWebPPdS8jYynMgxU$aRw!T$yGTMj& zI{_LWEXxp$l@>Q#oS)QjnF8Je$pGwpOqB+z@vr5V(Fm!ZgnucFEBU?k>VN<97jp&E zJy34;7I4~UMg@ed1?U$*oLx%>#(oSf@2;t`@tLwd(HqZ@Dqg9pPaT!#Xk-<2ki(gX zAg>?)ZAxlm+@#`rwj^JD!NQo2o=?iR)Yw$0MrlTc*17|WeV5#T236Qfc&8{0GHVUK zQ9iB403z?)9!tZpI>^8ShD3m7HJGwY%8zAijI60@#Ed*o$R(o`OQ95F<-9-Ou-mEA ztzbGFFwHZj!yeOgfYh><|FRh(RX!4CH82X;e*OLp-aUVgufO>lzWDM>Ow$3Y^$Op8 z`&azG`yI-Bz;?BAndb^Hl>aeAQR?>K>hcmO1*hj*sa?u-kL8RA-%B8|uoF;-J<`_< zf1*H|!o=X5g$1X$c0egJEE=3t)10RnyZs*5*VmX2d#uJJ4#=rs99Kw#ws@e*6$nWk zYV1mNi@8{NHz}Q11iR5=4m_tYt0Zf0#3Xe2LV8PSEbWOHX+%a1X+Xk&k{LHwSC~0t^fSupKMaqr$e z3HBghHLkJQtbG4$e`AIUX_lJF@g+k_gH=iJqEvJ$Fq>p;*ku`2zyNVpmBL6|yc}1= zVz81SriW=1_1e)iOS?;FHgeoWWf^f9irV8JF6xh)@2tmgw^*5+j? zVsOpmAix4QRU6Uu%E741TGA)A=Q1{c>#=V8?1tBI;dt4|?n!GrNr`@KeL+Wqo*G#b^P?R^y_ zS(77qW|a$(Ii*I}3a2v$QlBSAJb4BI;9NZQ8f^EO$IyIHYkV( z%>Y)d8>?f|b+gZ<9%J;hXjF(XM*}lN7y*wigo3dGF_@REop_7XVap{0EKGMg955aB z*zb3k=8OTXAV<;;b19|p|dIiU<0Im>!(#sT@} zJ>I^2ipSr6k3$A>p7HSELtMRki|e;4)r*9`p zp#jtNftC%+T*aVTs0u?;Z<$4h8jw}rsWWy1d88n%pdgW?)z?~e4T+)MB<8s<4Z7EUErtA2bvoitIs5R1PV@M}Q z=DJ=>Kwi~Yk0uktG-DvbVSkOwH_vf)z6E2@u_jnOBiPAnfB}^MXxHSrH}t@P>ivO-x8v!b@#n6n ztQcUm&wHcAk%G=pdZ;wkDx6pZZoMoqBYZoHR*t1qjkHk~#4lMvd1|~|@^76_l?nB4 zboB zT-->S=NX6T;KoywB8rBtCCBw8mXat50Etse$bG=T1#-@6?XF=QFdb&Rc=`+O+&RbQ zWP@ow;N)b3ufBYMAAk4(tJPZ4v5jWI()RVF4m+HlZLwOdq_GkW zT8)GtbveTU*C`}2?4i#lS#Js&PqL;+AkP{>VsSvu+3RnYlEFE9RH`Z5M66wc;o?PT z!(+f2M}e(<(sST-LxWNzH7vz3Ep*MzITEeYC}<%@p5I^_)AcvJ1`IG#8Qg9>_WS-ISo5=C{blUH8?M|(ReW9GkK(X-GhqH>St9imai8K zmiApF&7KL;@!e&<;Q1PJt2{blP~}Z3nr%uUTZ)v&)IEUy%}Snt2>bmWTr!3<0!7y7 zWV6Lvm=PABBKV$)VieLEj%u*A{dV1+89!-A^~VYE()o3Dv=^e3@7RJ(xnoY2|ycEFuOt*%<0Nm?4?tStWHIi$ddL zkUf%4^73es02iB+(T|pQVuU;DSQM|3nU>JC-TqU#~0`cxrI zLh&jsI~-gMoNc+TfXTz(`uE%K)h5&Oc)3?f8n_*!EE|ENUe(J`7#}AJc8mJ{mT&&~ z>ywf6)AhlNfxvW+0iXTcdl>9<10gYe@z@(7!itMUnH)dkNYHX%U<_EzO*=&L9{E|G zAAwnafT|)Z2RJqiLHJu#g5XVQs<5i7W?;ZCWsaP)DoucUtqhdgoLE4;*F|ZVhz!Rf zJk1zp3@TYeiBuU*(&r~Le2{f?RYu4)#ho=$XFeRj^MpJdkmng?&d6oPJk46?M{0N$ zO()1DgIEu-qkEJy94=J&AJ|=qts7_U}5Z+E<{oreLBwO+pZ_ZSIT=U)PV&{)76E3&q7?n;=8h#5WeCCC-FW5!CWKpF;b zXfrU>5GEt`W?d`}JC~29Kp1Z;1mvmYUyU&4>kUC;L=o zuT7UKzpfZFe!s=AwqvDnV(9`Wb_oMt2gXPRm#?4U-FoTXa0WT8a?S{8xc zL1>iorFpl8-WVKGjc1N&sXC#T=4G;8@OYKsHi!P_sQcKzhMgz@X%GXJciGOfr+jmL znHtI3b7JG^8?(l-3TfB%NQz&ZXt9*QYUG^f*$tsqHp_Yf9JI^41;v0FX&A8Giqj~i zgp-pKTwGkBlnfYub$lv3r4$w!Q>;Wsz`G64sK&Lbe}%mv0$8)=2)-Aj1{*FCoFF_W zSLiHIPu|5EtU`owkhK2H3@Tioqxe(iPz|KUFM9)!@gjCQ5iI1Hd&ROBs&keZILuO- zV6_@OK*J(QNi+N+#)x_^g9BYgKBVjD=fP-PbySlFw(h!4$#8sk4wwU?=lZusZ$W*Y zWoMDg+REeY%-Igxnu0W{H+q!~8!N80ay)ENszJUweN;&c6MyK=4;c=zxeisowE5ZE z2_)B<5P3F_2*98}gnjAxeO#l4SNWR3_t)v&*2!qz@U^Ky;aTx~$eyTd_p&%AZ0+Jo#}7CG%S)zR30<@#hK{d9fs@&nJ@crSX7MGu^o0p9X= zylzLwi+e$_3@lYXxCTV34B9vZfZC_(B?r2{;o*L=q8c3Mi~_boC}x z0|mh5aTdv;!Y;f+BW=v<o|4;SfH6OMzjt{dnz=a^AL zGL^xX%7no(jsi*Lw*t*6C{;*={o#P$pZtoyZ_lwB2jqFey}S4D;L9)Z?6;qBXE>7x zCsu{kjX#9JQ&+gkQSOw}Vi7WCpe9&)2c?9pk!UEYbXZCWDkv6XM?GH#t_`p!Sjs>G z52j>`5HV0bCNm7RG@7*DOg+0sMRrDYAN1H*9YrQJL{q}JTH(d>SNP$FAF$b+V7ocN zIIi&7y*s$LIForZ0M0rt21B}J!hzQ^$Opld=6dXnu7cOIQXkBK1qFLWfv}b3D1OE& zpK$@6XS{m$E0_zuc=$Ck#5us47{y1%Lntp;Qex|SA|G_VAy^PGPQUw0rx>1x`NZu5MTiKbN4zX`&$Mjml5YaS|mVj;aqlyn-MxqX zG-173w9%;Ux&hVZ<;dpaA2LFb*rQD)c<)cc7$QvPT}P#(^QF zYRm}la}GdNfvH9uSw`u)oMjJ@@XIg1;^oU%xHvz@FpN0au5j<(J#027Uf;YLYT7g1 zp1JxNGrK{52`3V$QS6MbIL4F0Ix4SQr7tOtgw^4r0V4?0{szyU{Ddzl;q30`0%?jV z@$C4o-=A1E=C*F{f28Cs$%6mt6?y(`@95WmX$(ty)GOTpj^^Id&wuT5J`1SRM~pbe zgH3)jS6U;}A#fZ;b=$tl-z|a^u!uOv5MU6ez*YN;{azh;GybKuh=vB&EA)RQGQMW4 zF`L6om z;()G^=^8o+i-Kn@9by@m$v!LMEV3-Dtn!meUFU(!p=7jJu~AQVL=+5n0>DgvAgjfR zipZoN0-@vyWuAc52`so{HLiT`M9+XX8Iqw1rik*fmRyoQiz7?)1cQ*CodU%t5qCL0 zf~)CI$KeSKzVLHWOqo zBhV~?Ny^lCR4g&HM;R;tt3ZMf%pu#Hi%?^^HntUt^~mXDCDQ8E^ILgb9cwY1q0e=b zxxP=Fbg@op9apd4G&(_$-!Ak2jq8(<^waght9py5@~@yA`hDT|NVL)@NDg>k+sE#$ zznT%@_<8XF^xyS6mAMr_YKu98Z2@;QSi+b$#RF(R$1e3jdAE1hmpTwhsu+mC5W$#W z1*{cVkqT>zgh_Rrl5VVqDor<>rwRMR0bDXrfRd%MV#x)&n`@Lj>0Am*nS{BhA+#{7 z5mEu6*L%_NKm~$Fa}}=z$1G8vglKRB!iu}XE)iy=-ZNc$utvNdd)`ffvd2|G0~csS zRGS!yRkjQO5ILwM6@W(nv1VfC3^V3MgTE-k5&_IeBJ6dn z$vZw<{aaGnBQNakM~ITjd3M1;lrTikrU9eG-~x=RHLk9A`0J`~zEvA$_6=}^nA zv@*y6H;ONroFi4lAmgvio9rf)Z)$|KFGe5-`;*dK1?TK?hYJiJszv9LB_6y?n5(P(+-cvLAfHrQYoMl~qdG8itDi&4uEtP)|` zU*XN~zuiGU% zvF#fcargd@yEyzOzuS5kkCrX%*G9fmN)42Va#dMdofmq!f`CXDOqr8PC8({USnL1DD#AoB1VmM+)Jf% zH(+VWA01O+_Fe|IZX$D2Ltn1*L^@Vxl~jRb)q_=e*E*fHmlZPxz)-og$|qL6!t0&G zjFU3K+8m7CFvt)mvgl61@MtCP>??le3Dub@>sF}hcSY%yVLVQ1n2J+Y_tpw6FuWAO zQUozfR}bgBF`9R}f~~dCgtdkZc8k2|G5kgFh@4tr6`A<;F`vAuwE#ym+1JG4GeF0(MOTrkZCfQuN3 zH0>m*x0oT(JqaY8Y|YUIU?g}wCIUdCDjg&WLtyO+POO${^sJc&jZ{I9-z+sijG?yw z6qI6T;=2W9wlPblWI%6IeH89Evv)Z3J8(1WZDNqHW3#+F7I|$Q8LgTo`w4d;g zfBXYPgzvxq9(T@9K^NzE@a276Uftl`+jqFWzQ%7)pCKi}>Dd++=jS-zo?u*!S}fk8 zx8VYfm@uTly`gb!K*zO+rG6iy*wQQAnqpv309-us&VUVvwJcinJLd^cfBP8^ACK5< zKSRz^2S`8-sg0oRN^3M*kzd{Os?gL1Rc7=v+NhDfEub+vlSj#+^oCV7U!eP$0-bcV zk%Mx$WL#~p_H5IL6sJy+y38#%qKiOA=1VAMbpi|S&}z92i?s-SUe`ZWevnk&QC)n&Jf`Rod_EFssm5!ql~|ZC ztX6pQ_AP$>^;bN2a35cP^9V$Y^E)T_>d{xYynK(#%eT0?y2AU*_ZZTEJ9jT|c6Nr7 zleNk%hBXwFfhDI$S%=)5TQ^7sjFDW?BcV^Nv7Mlf550%$k#kw)`=fXg%oq}3e|?3g zKmC9&zxg|8a|&cOAO+San}}zZjDzvI)u^c(QZa&jX7r1IouaIXN_32nj7^Gq!)PC& zADvFk`@1p6XZ3aJnkb(r2LrBOdiI~Wgd_+SEoz@xZAniX*8Ov=3Hh7p0OnM%OSZ|B z_UgP(s67Dc8UYozwGP!KgJ(;tw!P(OFM8uh{JtAW^|ewDl#$uWj2JJpXl@I7Am`Wd zjLh0OKBa_to^f+?<3`JvIv;hjd7dRTe!T{WaI)Fp?CcEZ=jRy55r@OU$2JT@Ll<@q zEZWpQi}Ng*CF_o=Q>#YNTiy8Nk$O=4=BeLiFyp%Sf_Ygp(-?-~E&X3jt{}7#&xQ|$ zP1nZ1c3H*%lxzx$M916NHOvO~PTq!N$z&p+dbi%Gb7E3Hq*xV-`@vFfz@973lrr|y z9{XvBbBl~+#>vSEhG9fL?153~pESxb1h{y>2&(+5=Thn31hTDhF=KCSE@|&=)=25N zm<%U%8m9h?R1jRupjUm8ossruG& zPmNaQ6dlVD*D5&1KIZylB>i;#@kIv4(-E`tTNXf#@ON%f8swusQUuNv;?)DiC6BWo z#;O6=zo7?Rrp%hBftuP|&h7P*qWwvm?Ha=t1|unl3doZf>!!m2`@;@7ACM1HIGxqg zTFL})!L;9Fo+po-%q(ebB>IF$eVQRPc}NUNmqbcH()7!eVd2xT!ENk%?+>N=m8LR8~({(TG5AE|Nsi zDa^>auk1n}zIP36FuSM71toxy2oo}fVTGHkOT2pd0uLU4EdT?+iKV&rajiH z6OZn#&4G#=GKm!O8UuDqKmkFzkh*|mi7*vv;Uk(ar65!7&S|NzMyGa}!fALn$q z)1hEoZ*Xzv4o=U`@Z!ZwTwPt_Fip68{~qgcz{UAF&d$zpw%uS{t-uVgLB+a1gO(() zrHw_(ZPqc`R_+UF@uVhxTO>*q&{1V2rQ`}i85k2VUESc>Pe0 z+%Y4hoRJ7p>pI6h6ft3Ez6FBJ7KPL{i-`LznF0e+f=7IZ(vB$F9FJK3&iR1(>IRdR zOR+tl4}0Wkhg>G)X-3iXI?hsmQeTLy#z^D&gDiqJ{8oO!i~%f;9TJetgGCS6Oe8v_ z3+ka*C}Dj884na#l_vbQeSgA;LgPv z9zJ@6Uw`=tt1@CUj%s9+RCg2t4XG-+PH(z5R1LsU50wbvgjrMPO>q`B?%FiQl>E$^ zT-K>!7+i}5bJivz*04k!NTxR_tyf+U&q<7er#fa%I##$rR-(k!Nd&^U+TiNy3jh4! zM{Lhd@$KKg1p|2g;stK5Z;;Z6&1QqozxV?0udeat^=s^QH<)?kVZL) zfXg?pkcJUoe)BhQTB$QzXbm`SLJ|2^460^)i04nvWAXPb8_*d*4tPnTyg6yzNoBC(YAxlU z)W}&NnFG>6UTQ#3vy@NCrJ!i$faoMyqCv+2X&{WN6*ij<&d<*=9VCKuv)MSWh(`AH zdhK*jYbdI*L!-^*&%%hBI{mU5TGP|goh7~A^#a8)hIfmeIVr_Np8j3;OPyCSfQ0IK zvS0_YG3j^HFo;2wO&?+Vf3Rjr5fyI=WF$pUqq-ARn!=_}okw~LhbI}@? zVy3s!RJo{;GYKy%1TPt~pZ2oGMGQsbdV`ckm}8bzt|5s&npD=Kh`wYvy{Q9Vw7)_Q zpW9kkaFJ)|REI?B_5db#SocBkZ`;GnHNeX6Kq^1ADQ?F{mGBx&4AnDaoaE1DyQkC& zaL~q7dh*23O-bQP-G5>T4pmHS5y^EddIMDhq~TFNxyD=7+3dV4JjZEC-(&RXM%oA( zIKd;J-65=F27r=0qpuVM=bEk*;dm{bD&g48bb{E2W7!xE^wFeC_f{Nae6`IQHoOse zhhuNl02_OLTt8+Gk;ET&eKL}My8hs5J(#Az^jGgKt%jPGQ2nXl5IT5VxVL|<{p~hz z*%z5_-)DzQ-5$ zPh!MGLSlJ_L@Z>0k}F<`2m^6#WK9Gl^CBe`ta`wWxvI~T)ss@xP@A;2p%+1iGH4rLo(qp)k%b4e7Nr;yiYf>NDXoywh#!9X7oNX-g}?v(Zx~X-k2HN_bYyL` zbexH8+qRR5ZF6E<9b+c8GqE}0#I|kQ6QkpN{eJh}zx|`T*R#%f_TE*stG-^*Y-CnR zke`oEc3ePEpHmOf&H1Ce!OrG?Q}NjoW?tYY-thov%6j+X6(l4@(327%QkkpQBGiF6qvqD7N8|kR(B0^ zN*7a*QyUYxDQfZ1D|~hE?W|BrlEbVR>OVnB)rEXD*AVL;DSK`^kWaS6&nchSttH?0 z&kN<%oz7Zp37Bukl#p_{iD5s*#6CnV{kZi0;;Y^{?zO<&tpS5GhMY^eBJb^OBKzN` z`b_UeEh;>fo4*MUzz#CDxr6+=TsrMMz<+S=;(ZHBMNR~b&iJfrL)A*$p+l)FYlseC z7`SfrdL`v@Aq4%J%-~=f6_+ra+H_} zd;_*t$#>dLL8%I*=n-MiL-NnqXtI9W`{zo?(f=R})+ zwOstG*;C#oQtm@gwyRZAkQDs3%ge)77P=ADRs3cmQ>~rt!!J+$u?`D@Z@EOsu%He{ zR!Ype#{6st)T>X>fj*K=-ihJea@-1ni}>V>p=hQ_igU7COqY!QTBkaxTOTmb@v(}L zSCWdgxzK=$f2-oV{JX^0XNU3Dm+M60Xb=nziZ&UdYvt7t_P`g0K>ybw8TW8 z$_PD&O_dw}*-2oGAQ&DK9rlJ;1;NC^-QHBb3Uy=#EhBSvYBB_hDq}!GELo_HVY0!4 zXzf2ek)!DSlbs_O_1i^<=J+|(#H2ttybr&ZqnuGY0QFJR$)2dL?E+lZc2nFNu@TC= z81u?%=(IXa#E?N=-^p7VT!#ZUb~|UZ?{{p4l10NMqcHx&10{A&nf0;W9xVa1{5oFR z{bby)eSiwQgY}@YsoQo@aAQ{T%m8BEEzzCfLP@+u`X3(Q8%NHJPqSKOsd?oU5(Db| zAJ*Myvr{?X3YvQ!h=>%{v2re7gl|gkS4lrO16YWS0<|j`|Gel2B~ot|p$o;pb%1<> zUu#KJN{NQW`dcEcVg|mc^mAHe=j58M8-`B&M1qI6KoZj)7N4aSTsIMij^@arw84?Y z(t!_Q5u0zcK#FSIDMZ}toGj(nCA&H0V-myN$dzJgh3vxoh1+pQd!eIVMn@F`1CJKV zdiSrp*R|e-qe#{(+7}JVj_X`?;G5zX8Gg2Ia=TyO9$k#{JOD!q5gHhH zbQ>OTaDFx{Vz8&TE&@fb4x;4?uI(=0@TLDG>Kr*mC3p$KBZ%-pcso8+FsSPhVH7;X z37lG{lHh|&3H)&sx$jQ`xq>f9fgcwwq;k(YUl)NtbZT#p(v3|ULHB@v$ixK0`^`a5 z-Fh{MvpS)@k112mGsQ*ke%oki4g3-=wdsFc0{x0kp@ra<)=ab+{*qc@rXXrPr zjh7X}>NZ_n^mtY75bbVy)b$4659q?;-DyIIN5U=7#5|5R9xf|@?A#NV!ET=XJ=-=B zDD2!*+3suFVsj-miUL}$h!^r>9XCaQ3kH%PaJnrm&*aIcs2;&nS>HpL%g4%w>GH&^ z1m|<>Ts1sa?Mq=Ez)PhNP6Rp!=nkM$J$|*NA-0)S(tVxK7DSs#;5{*&Y(<2M1-y9D zH#x*mTChRf{oNnEB#wghm_SispDKDL0QRcBJK^0>V+Vv{(zp5J?CDZ zu3^?*3)bI7Ch*C$`iN=ozckca>8SpMky@Rz64mkXC1UDKEw`?1fe-}++tSJqq=rV7 zSo9^~xpB;mCl^YUxkmW}T3PhXJu5A&RW)|nKPtyDBmwUrb9?X|f1sCO;3wgK$#ppb zd3*cQR;_qeF$Zu)ouHlPbe>g^oEH=zk#!;e{(iyo?6eaY?$rH)fA7~T$g$nsHF$L7 z+v(51ezL!hXjN9WnrqMc8v_0>OuM;G!BFuNPh_D@4%;^%9<^zLRA%1<`>Iz&5F4A3 zkZ;tZW$1kekZr*Ba7EL>#dSj6*GwXi#m1*K70+}h+ct*PM?j0V{(18G1%2kCr-xG8 z2hf1I7g%jTV)pSBWq{`L!>{$|0-cZL9WU5y&9@4?IINC|Zp$c_R4_kL(I6B)4pDxK z!vosSA>zCv9`NJMX;J;3n?GR$Nc9F@yVKqG(Ls{|Tp7)Daq|z|3NUU&YY&qv!L-*x zuNSfoe*wK>Y)NqxT6PuwLJVQeFm-OzaTE@*X{Y>G7>TFS60_}TAx)Kl)u$p;-h6y5 z2med|yA~+BYD+0H@}c9Fxy&*2)I@IHzAY}-mPBRIA-gA@`ZB4 z8=p30jZk)6u8F~#?H4e$Pcu6v(-tB9*H2K?QQ`?FDbAeT@&$%2`ib$k_UC#dfA=`> z!^}i^$8ld>+3q3_7>|>D-W-V$aY%*H7-L!acI)Ph25W(tw8{M$YAJd~_GJ6`!`u)Z zN6BsNR+)uSQWD-@X!Vz39@&wUK?J|DxTJ%ZaB8JYU&2#hDkGar<1+fNLZZMkei+(t zRjUfgzjA!jtQQnPYDend91{9!ajc2^sT>; z%Doly`ycqpr&;E%f#WPnO7v@^p8l(IbT8!<-w|@DmZ=6_p%GWBP{z^%3eG!$$X#l)Lnp9G+DAP=PcL$7EGoqC!AU6;DJ)r zBGp?`nv3qGfFOz*(Ck@(aoC?p~)DJXFX8gf=RLa@=~$vmSwQc%7&7nqaV7z0J3(7;U z-?(H|!~g*&H&)rQ%nCa=)H-}?RAn{6|X@^i>=o|2MX#iFyR-!c^XF9`=CpQ&)6gZ=^AN`?gmulLZ=+;Uu!+msT#=<>& zPWp`7`)nnliIxDaaUhvtTpNK;G&p*h3j|(sKo=NSZ7f$LvJwAU_iP59YCvc)q#(3k&BGQr zULwqybj94^?nrC!-mM@H$AMfqC`aCge6tid8yC-n@MikX_O3CV96r+b@7`Z%{-L6@ zrsmrGH?QUu{EFuvo`bl~|I{uJC%VRt)_LPvyZyrdbC0R2B|c!aO3D6D=>GnC!2%-b zKmaSY8}sP>Pc`;jK|ly7sCUU0It5gGfxQ1vTD^b}|7khR+0*tn&9es*SZ8|wv()HA za=+({HWjwB301rKJcp;rLK0Pj^yfnUeMSFRHNqJYyoDv4$X1df*CJu0js?~#!v~}K z4{Iby$WCG$qu7?07E!7{LF)bPo(1$MAa%c83H%4cgM>IBi>Ot5<(r4K>rp)K_eZn; z?*6Jr{CEMH zvhp&&)EL#Zr9?7wiz_lfgKQg}E0nv0h(`U5s)&hLg;ORdW_SK44BSn47ib&+73}N@ z6h@92Z%hsJm-!LXBmF{zB(P05aQvN;yk4p8 zYHTdd0)N|?Z`*ba3o3&~C9az59Wmj5^&8jqdDN4zXS{i8LSJQ8R-n^o&cN%)BA_G} z^n0GAQ1}yOpKEE3eqh^(yeSp9w(0X?GhLD$En!?`AY%iCJF1myO1U_1+@7ZS+?sv0 zVx+@EM~VDku&O>IkDFCX;js#fj3pF;T<)%{BF;#l9F$_GrmP>2B7u#w;sM52)?|?R zj}i9j|Fi%xEp>cs7u!`i_9$iHE_(m&0Bcz8faaP z^~R-Nw8(6@C!+2x5(Yt@0n6J1B`3IsAYO*jW+A!>LEtVBwCprh^a{F1R14T!vFP`+^RABtZxW_MU zC*TEd5c&YDIH~U*Tt;oB3Uk<2<~Q@qD8TiGENqt1bql_=YHt`*nTKCqt95xn&51nm z8!N`Q7%4ES22Ny-v?w5_Py5&jqV|-IAo}NIJFJw7*Jt`A5~4!9lmSirlJU*U0@&-u^|; z2NB2*-{9tkC9n_W>lIJr{Q+Z{f))8ED8%Gfw3M6UE$CV|Fxc!H$`Js8EN2zCY{?KI z<+wq?1E7~KIcRjtG5jMSeqn**A5Z|c-s{T1q(jJM7UbgwGDkwTtk^mmEH*6{N0}PI^S{ScCFB6Zjr<`Gg2+=ZL^||0x6n+&$3MIC^?N-^lwt z-k|0Fk?IWmA_l257_N4{AW%qz2ahF!UX(>X5Edxs;LVbhN)LE<=Zb1?K7c#&d!H%A zeYgs2~U&nxIXy9yfy^WLsU zt|d)a%&KRa0g|7$*S&GMD2#NF)3xAE=oWUC7Z&-xvfwC1DN zci(iD-9|fIwh61xx@uGrW4pu3HasRb~qRVLm22l?=RW%?k3xFy*0QL{7zRQJ#>_a^!BchP!8( zi6tGo)#fYz)zOdy3$!x>%uqUICFQHmxfC}EMDRrz69d*0UBpaH!{yg>HDmW_U4mV- zfUiq9;hryO>s1pGB4;0;uv%h~{;&6*FB+pB0POd^wI?W=3#|Esy6x^Wdj{E1h_^)^Crg(KH8Pr4@Y9+ zL|w`PJ17$J#=F7Do1x9ke{PL4rHydQmgeA_2uE?`Bo*Vy%Du?3o@~QE3%yb4^(lL0 z8kh?&$)@dW+_pObGg&-NFApyW!Y_vy*%#ig4{(6oiD&QUhXv)#MXs!=Fi?QccDL`q zp6ghn)yycz#L*En$@XPoXo>|N$cy`gPvm_ccF_ZgIBL^05fWC2GVZCstsoZA@uz=NJd>qvQLf)NB5Pd3P;WibcX~vsNu;#5 zTx2}nJ#x+rs4AlNhM~;ipPH7+88IIF{rOogzn(vUYX`QFv5%*DkTMIt3o<2N<4Yp? zZ$%ok9~@kVM$W||h&kbnfd`Mf^}w z*7NNQ?+l5Y0G4v~iQVe@MWp1aUe{g%?UvHIN~hUnk8xw>Q9S4#)=Mz6x2{HNlhSiu zsx){ucKDNQyo0jq0<#1aOy6q>vb_@HJ?v|@>zhgzXlwa0a8+$%%G`EUG5^B)_;%4= zs@ftr7@tt$x3?@gT>JWzI3a{r$z_hnj3BvJ5)e5;Z)-SwFZD$=VL!t#IwkzB?EkN5 zv}eq#yD7Pm3-lovl162Sd=<*%du#UVH2)!hv%+tc%TSOSp_Z`6)@ z1?f82x6}{z;RcfhB~fB+&&n%hpmX*%tSM$j@NmdVE9yU!$8hShb1g1D>gMwr+&Nki zg>DAXW6la8NWAh`)<7LQDZ?!U$YoSxIz$&~;dcCIl(T!|M{@~T!YYq;8>DSBiZ7XQjbR$Z-8++ zovm)maqK=DR9t=f33F=`X-!%?JNHjdBS2mQ2vX~ojU|`NKP}BVnSYF2#w^pJs zFRy8j69~X2pRs2Y_VD%|4Cpaq2hpRc0|I7@lDQmNOD@^JAO+$tG@g9qOJ@{3s(?XM z8N{-|{fBkGR612t_Dq-%J))>)IHqTqUyhd;h=sj-C(>C)*#{hZ${dJBMn)KMPn@Z6h+l>J58fY`XyWsdt)Tzhdj+Q)o}-{CWWx#-%M}40 zb{UxmTGK2}(miS-Q`?s+lWTY78i=LMlAgYV->%Gn#dkMlggf%6H#_khd^;53++A5}nvK7o=gs^oewwu2tekg=%UMa~G3)GjFh) ze)W^7EMf|M`vV*@J*`kMyGfIwz<5zUhz}4NeBodpX}88gjGEs=o4%3YhG~{-S03^7 z&c^Ytj(4F9ukWrUCLu=a!8;lCrQ=@oa91RNUGs@*Vl8spOlU$z(ZGFd#&A7MIi48{Q>VGty4T6^6wo_9yCy{!={37vDGPB)G zqIC1ii~Cpmb_3zRtz$Wit75AjhjO6y_9^^DU9%D}K#3M3;_Hu+6cG3^CJ#_@PsE5Z zaqh$GWU#;EaZ!2P0n*L1@&RB>PW*ve04Y>gDmP>&sq~`}ME2{jcDH2U5H}VWsQjhA1`8k(zkzwMTe!)jf>MWD zrMfCG7?Fb_&G)AP-p8>78!;uP_xfTQc*$818W>UNgc5$aOLbx*Ut~kFEU9V|=U}`n(6T32AKXgu zbR*&;IlMYT0pbi4`XXX0`1WL&gggNI%F#Ksoig6phvqmWe^jgWpQAim-f;T?~l5Pn;V9*B5)8$S7b ziY+9Q!o#{7*XSAWMw$OE1+#kj^siYT*;4xX1DWKMFU3J4ng_~@kvPf51q|b3 z6e2AxErPFy80VGyRkhuPpgD;7l!#cs8z zrpEE*PNb)FjptBzdShj$VdGlmcZy&#{o1gOrNy+XtAsB0p=6wxb*OzBEEq1L(!Bg_ z{di-H_H`>hhCSheRU0ma;844=wE!2i*X*ykcHC;3+M)UgcZm$*plBdnn}hYn(3(K| z^zH7L+h~=H;$FX)!FiBpj>_IBak-CW?%0?o9`WS`hH!>k!zEWHxBAW&m)gwvTQL9Fb{BySY7Zj&XyzPNahvXkvQo*3G?QlKFJt5SSP3oC6&&Y01qxqAnvy_Wy zw;F8%xr@Dn}^{gZ#>xqqOPOq4taw)`c`4H z;f>+2Z^pV(``lZNu^TxiH@4E<-nU)?ieG+<2#CP;x@LD6^^J8H=0K)^Dom^};eHK= ziRtLLDFtkl;~ZdU3<E;u`}N4Fb_!p}zDd=BJmj_R>G-MBGE zO+(cs_3=t-7P-4h>InqNE15Wl`7vwvp zfvdLx$;^^(l^5H)npQvG9(wgi(kfqWjZ9)9-}}u1b!yp;@@m}d-mG;1aeb5ziaSTI z#FQVOugU2Ub`5Q`yDLcCa|O34r9gC%_!$BRbiJ)<08VR1_^{-8T^thkwSNS9I+6x= zbnd%g7tG5MNq!@} zYU@p_YaydHeYCPA)Rf=T@$?DbkfGd|RxNXs!q~{T$`-Ux|6#j03q8=(>iM_C!)p!E z#KGd)@rm@92x+8y$gBt8S?4cmlpYC%esv7y531%3(3kt zy6_meyo@TWJ8ZMy&T{kZFzwnlagbW!bBy~F_tpm{e2svo!U#;!h|vN`%j-QIC*VV9N@=4u>&7@`V$ z_2f0vQUGYZ%4<_mYwn~A!!o~nCaa_*p~LCd{xzM0@HTWCksK90-H zgJWQcCmo+><`5?hKt$Tsi@`WZkf7OaDIKu?HM7LUQRG<#mxP9d`Yo)fOua}uMKy4L z7tckNE}!aJmBz^O19;Fe(ZZ$8(1ALDg2Gz zdi}#V54FnP{R%0;WTOZ%+Wpc`V{9b1Tf&>EThE9du8K0L2-hC)@V*Y=Y9kTZRox5C zr8dPjE{%*BBWe|Z5GQHXLr|ej#!9QP0~c3ac8y3&{pacX^hU(3ku4-3bd)?2&nL{k zzoZRnB(f(a5S|O#4lkVP5<6~t*mLsV}< zKbX8AUyz@A(kmCEL#d*Vz;Udss$29c+X!!@MM>(zfp0=tQ&RLRIFcz}Z}v)fBy`qz z8b7?7;O@|uLuHY1Tu=*N7EZ?U%b5t5i^*Vgpw1oUJm_Z1*l-)1Wzg+K9#q)CSY`j3 z#9$L|;K1z`fyGR>P5(gx+D;%reULRDfypepxKXd#5NFdEqHz~%XIYoEu3p`4|8dJE z?*5LCDu&xQ3saVu%AY;(>1jv4eTxyd*S)$Vh8^zGm=kJt$jpd z@62JJ=OxqGuhR2Ge)wjpAm%h2Kx0*N)h3ripvwv2>a}vKG>qhZyIoBxiY#FPQqTOmJ zG*??bw4nRt79BFFcUMWtAlEyK7b^a_!v`*I)1I$iT?0zd<}@q(64+P5sEewTjd5_b zOA>!IvK(q*=gpGc0;9+-qYs1+^2Ox5v>1Rvb{clIxU%$<{1Cj;9{wW!R6G=?Q>i}l zxS!Sfx?cg3o&i_#IuV)gx?dy`E728diE)YOSKbf{_e%2vQ%HcfdC0-5&Sn~}_+v{w zUrHkL!m|u#zRG_S)oWk;rXP>6R_@`HNr+9_cMa&{*QN7nix=2K`kG_l^Do*zIr+g! z!u>=-!$&j@87G_#8)Q57D&QXGjJekm9N0al0a4%K`P_3r086Lazbx$N0$PO5@JEo_ z%U=cRrW?#lucX{f573ZsyRDuEO(LA#pfkDV2s9sJdi%)zaGWt`FSz7KMo#+&^rcRw z+dW%PTeBZF6)s~eBP1qP*XG(50TZ;)R7nE`AalA70chsZEp+eJCT7~&x_$`fnS!=k zognhHK?^7tV}mXF6~y)-7Aqc1Z#8>c8!aIE8X(vt#4ETzwqVuidytt{czDuCmn03&!M&f=ZbJDcBUZm=f3vN=!X=p-O@|$0 zd~{|;scmNVV8+jz+Hwoj@O#~WV6_%hBXp>S{_1Ba_w%qEj=MMM7B^O3i~E3UZ&KEs zj~~K)nqGJz=2fb_^&$8&TrYGj&TrhL5DhDZF9i$M`gWPOBrs!I&2)^wy}<-R-a7rB zP!~Mw<1+$C)R~v!A=SEK22S&*tZxOcw$#J?uXhUGtego`d;-MHD4W_GQb*LE zIjF|7Rf?4!8k_32?AKbDBy-JTEI_Kt?AbrnD;qakF(2JOnzri~{p5Q6x2_4++6CUWFxA)^t+}=h? zAWRSaNEF&)-=&yjY(-{Tv`AGOT&J`vRYqDYcfA(ko}f*_lvM7~mJHVeNd9O&4&k7< zWSt9>iKgoP@S#X$yA}$U4$saeJh*iy3O=Y=X$iu_b0c~#X3gZn1oS!XxB%QD*+3(S zsx~w?2id%$`GW84ER`8#9@(HZy-QL%vH9Gmp1>|95g652yIPrF-ASbpqSY+h;~K&@ zs}R#s;-d%_II%L14CiVU#=1g)Rz?NZH)|{%@lMtov0DB4+%> z`n;;xzp?1?6zN&Xx)^%`ItOU~gaq3?%v*wk2G4k8tgzt-`)1wqwW(}a`itB5tLt5Myd9^-fAM!cIgo@0{k@B6z1C%vBrnc9ztX@2=+z^=}m;J zXs`wja2%3VomFt3yJslIpd1eh zGzgBgF+*|bR#uYF+*`}bnM~C+E4m{jcj=xOT)zEPni_dO4#YvUD{9UhDFs)#fj2YHPfo#>m{M89NKeQt%h%(>~V@kRZc)|K+jcQV@yaW;HNc z>$^~6CQzvEcKtXIAC#9~;5-Bjdv**^gxwx3d6|EO|DP6sOF2*20!LIL#-ee1)&uG7 zBMyfpH`xN(IPfEiaUx^t*f{0(VVRQ4$grF7&0tEZ&6$bDFgNg37u$jzI#7o^Q6zd zBT+|&VB=&+Q*l5Xxp>*^U)6;Rs!})VKPWr25dsH3Op)+6@X6f1O!$#U60yrCb zJdDe~vggkbS5g}ClVf2q@voK`;a(S)ISAy);<@&IeC3iI0ma5C% z_D}SEk3jABrGo%tJ5p6fFyqp^T0x*@>^{Ar$t(Mczo5rExrM2kBhw+M%nfmB$?kfA zH;@++8Gc4AfdfTbwll|iW0h$w=S~)#i(TgNOMZYyokwc$LX3htfm2A#S0yVmE|*p)8W96mX0P$%Yeu(PE!#p@%Ao0Y5p2QdtVkbqvP@5at0 zZpAPT=YEf_*Vle5A5{_NJx{Mqd*bdt5iUCdiMG5-=KgNF%#Mf6@+Rl00K@vU*jllK{-!azye5v9S|0d43^HX&W0^H~ur06slSGFF!$A-P_|! z0qzZ=i6L?+U{-H3T-ecF!lftZHcuKVETDBgj)vA0+UpAyub9roahc+p%B`gT9$Xk! zR7ACHM`b|(B)I-Hp?7kAe2jlB)VP-Y5il||#J4?Q+x3Gz6O@8EdY@gCY}Vd<1R^3{ z?3Hq@QY^57>?h2r=^Wp-em5?734T44h>{!ef;owNq%INhc4bkq)3&)5>MhZ1M_!9d^wz>p-BY$iklZ3X&9?=6RwR9Z4FOdLl4%Nrk z&>UJ7dn`f@SOVH^c%t6VH=~${`R+ANGKeRaLeWSFx3<}kxh26Qa@^j}wR`q=zCL#7 zqC!B2?&{|~=uSS=bKYK9$q=Q`x(J#$@?+S@d%u*KxmCleW1TSE>G+lz9~E*3;k{H zSjNnkVTt_dmeiz)$%u@6gT0(Z^l2UGnq#SF&7x93XB_aAU9iQQ+fgu`2!t08A|yqy zEJbU-^ICy!gR^-!$L70+=m~z;r+}OT%yL>W>}FvKEi}szJO)kci4%j-)Xp8YGmDV> zo^@UXTt1qxjtXs?bzM@36+zF=SooEG&H%$1fAS$Ca7@=eFr0qBdYywO8*5aEF3UnbtyWtOMJpf4W>0Ia$DvLuVs#!ArUE8}Zx?6nGM?=A(d>q(yO} z-foy)K*#Bqc+SVjlYqI``lE<8T|g;#QA?ERReZ71(Ki$p($e2m7FXKcF^(KV>l#Vf z3Wl!M8q)NQE$g-q?=clTMNB$i^IOKC{Z3?cVjeY}S%Lovp-FpA!uadA;0)mTh782_D~P8}+jE<-XR2tX{%f4-KGEo= z(Esp}tG#{g>QFB8_4x9?81WtV+R*tVuccsaCpuX`IBcA}BcY+st;SKyunY84!%9z3N-ofGJ=jGi!KK@UU5mjiypX2J| zGY-1&lgEC7a6;orJ{@9bH{Xf17pkcM61Arz%BPzf+?C6<%O^sjDZr}%IcV3LNfpmf zUN;pzXF=w0*0W=%E$(AGNmrgL6K239#7!;1w8hRQD~+1>KsSvoYswpVmE&A&!RJ7s zd3xVz(vl2;{Tl+{;h~so^?;usW*jyVY}muh&<9`fkH%Pa=;X>ivf2BQP2Ak%gYc;K;O_1v~Jq{@rDz4ovxJO3S+vw z5^}r_<8i0=EnPgZkb=942sKGGHQ^3Jj~(T&W)Tfm6#t}`AW>Vt8MN8Fo)}fDWu#*^ zKYXP7M0!GgG_!CoXWmj|oAVgN6~%Uzl6LP_n#aVky8^hfxq;ChviKS#6C3iXh{Q{w zLx7m3mVxnh)OG{*P7}ncK7!$HKhgn{jV*;Pc@BvP?!c)am0RVT@_BwRm^dh0R80m& zTz3UjlO44g5bF$>Z8qY7PTRp;3e;Q|k74)s9Cy{E6YvHnAPqFM1BiQQrJQjCWyEbq z=dw&h9l1_FK4MMtfd-R)&&HxkhI1eELcw3l;_%_P+4{2{Ob%IlIY0DLaqTMXWLY-C zAbb=L)*QVyw|%lNbQrO#SL~QsSag|j?75R(60GlCIXjl%)eOeb@|G?_fh+n%-xL6)C3X zU0UPc^jGxL`4e0&=~~4IadMP9C(k^)_CK3!(6e@n@cC%`mAZ6}ZN~x9^D0_`(qqbK5s=g5 zkx`2GU##-F4i68DS0WMfF4XyA96CwtKJ-e zL>@@Kfuf|8p`or-g`~Kl%8Q~je}utZ9PGf0yeYGD!p{RXa0uKkO$rhOw4!V-s=d>U zHrFR2tDQ1I@Si7Jh26SO&owa(XE@{To6hN%Xv$q$LC;(Tjp}maR+U3Yb023U(Tpca z0V=m5!o9UjVeY8naq^e}; zTF2?U_5sY-e=~FJLh&gT(OBt%gj~)d<{dFn!2j5`vaPr@(=aX!@I#Tgu(t^c_1ls9 zz-No9J2uFgUDUy7bBHFlQe&Z=fY(n!$I?4gt17H!rB3%caz$NlOPdxy@ZsawUT9;* zo*Trp_WZQr6spYJJ?`!F@1$~|qnjhV_xIlQN6K5>7GAgb=Th}++x4V6i>&*zH*4~Z_4Ldvrh6b!zikS+f|2zdi z($JAmSd`XQp8?R0dJV(Vo4-a9Na)@v0dEUJ;h?wwgVVINSHM>%%kB0;)s0$*Ou-}6 z1D%~wUk+n#&AAci1laSE+xuVG@sZE{S{&pZUF%ei`O;5t1bG32?w+C>o|uv#c10Nk zgo&>FvyLU3@f~17moe*~%Z<#kN;z|`{5@{)EbW??TloYQJt;1~0rRPrB}O9|Z=Z%F znu~eb*4QkF);siO?TpwG_Tc7r@|K@PRsY=_MQ+Ro)KpegVFf-9q$`xE=LWuJgKFcs zr{u;FV;arm2?qBC7thMd=4L1L1beB+l%KGLnlf#)pkr_MMG=o6MS~AV-2Br(Gd01P zN^M4Oo&|Y&&ODusHBTiC&SUu zj0B&!;F2YFbG#R&uO)8Joi2Yab5beinPFJTI(1j=2z%Q69a?3Z<1U%L4^pOYoA;C! zB|p1oEnFT6hwD$4M^z|j3fowxLL$LI; zs=}r$B^Unj@u97!g7nf6+Zj{50wOds(JD3pGxpq89b1D|n38>adt~=7F{NwuI*cw? zdQnVAe8U>`ADWtMIZD={6pnw6c6U*;;BcDfIu$8)gJ6&Eb!)Zzy_PSqh~U-A}$Xu|tj8dhh( z2NOtka(6gpMl8s?_xh^WVA8qwyeD2+Y3|`RVcYbdtgK-)bEXt@G~*4$-)v&G#luH4 zOHW6lRw+b}gbD0hbCdnmHfj#oA)qL}nJv^Ob@9$HPB{*}p2r-7Tf_*vk`<0+faTkm zXI?zwpS=wbQy&nz4>^Y|j>Lw~19I;#TXyb5zHS3=m$Z$4#QfmTncJAnZMIvheX7>B z>;60d8AaU$4Gau?OR{ZuUQ8TDq;K2t&~l&R?#~?8*tGF+28moBphpv|0+`%_^3PlQ)B*6fPDt>LR5zU#dAb7`0t$f zZrF;M%LzaBJ>O%oWsmNj00}sD-f46FS1R^$8>9qOkP0oEUokVQQPeS%SSokKk6%ED zU#2lC5#A&m^@7wPqwU6RD&FJ6)^mqJx-05`yUaW9RW_$EA`}j?e*vkpOKp2bJZfe* z&|Rcm<0Vfb5^PD1c{#mVVa1j^Z@pucB#!G>ZX=bJ08c_&di=G+r$79xYk4G$Oph|6 zfxwFu82=C)Be^vkc~?7|X8rYMvWY0((&RHjP^WV7Ac$;*nQ}QIypD3FcQ35=|7bd^ zusFLYS>x`(-QC??f;$0%YjAgm0KtPpa2nSj0fM`0Ah=sYkj7o+`_GxV1RlCCTK3wt zs@|e2Y3Vp3N59i}r;kgXtk|%!n)1t)=a#sz4 z4mY+LYJ%gx zYZdS*+wZ%ab4^HE?DbVw3nEVT3K%(WX)&en4#y^9tfnElFt1JuQC)=Kk5RHh!dR`MSw4 zx{ROilQ%tyKGes?L2R-+k2b2{n)hSD<8TQ*58Y~z>LN-@b#W=w&m>pK%#OONh=IcvqN8v}5`-LDq@4mlu zuZyAtZtP;;yzXF-U%-HKSIh|v^G7@CFXqPzfZF9MVL4q@5|H7kzYP~&i$M`~(P7O~rVG&I z*c)=1^_pg~GVqOZe+G6Hk24(ap<;S9SI$g-UkHk)@I=M%n z=cIG1P3uad3E(e#LyIq(WCOk}j~(eFe_pw^|AYCIgS>7)F-Kz|m>|_#v`M&5p&L%D z5_A&|V`1n!Ow0&)PQAvam`F(rz9U8$Fq<-(=EA!S2on8V=|yTC6H(3O*nO5xf?~q3 ztl7Emc^7-XQGXu<>SbV(K#p_%7e(zu0Yc^yg8CQp1#hM=`wS8o!!;#F=wAEA-)a7q z9*dzgCPI>q%dno4-O+*s%JuS=JEHD`{M{TW(MeY{B?1`k&dEXd>k2-9Bu2KS(@c5a zx(Ii!f@Xz0riUS+!XISVYreQtd)UgIUv9T!Xdm|dMs?sPJfs%|fq{aziJ}j)NtREo zJLD@Nb)u<$g+y+fsR!`%6O772tgDcF!0&6k6!`WCZgyfh;V(I1CR1E$snHV%doss~ zqn7#rP3(XU2HW<9W;AR;NNlc!I?giw+T#_Y*#K|2_%L8^4^l{K``u;DpVzqQ$T$&R zRnsS_t2YU5+Lz=^m6qh++uxT`dDL?AFphR*y-Plp(~KHx(9xy8ftgl@(jtAP@?G{~ z+f*igKR7_AN2N3cv{zQZoo?3EZcSXQcr6M(PPH}4&EIJkGX^uokyeZPEH-SMjW&fB zV})|WX};k!9d+U+jycM&#nQO&pz_mTLWN^y&2~E-8AcB@t)1&TwF;uGZ6ppHgzpUu z^yV>XD$+CgMhoZ4J`F;frPdXBo*mCD*b&v+ZItU|kclxcU^G&LPfv4Qy8VXcF0p6w z#XufpTitINtu9;heiJ*F*Z`&`q`#>=8W6w#`VZN3*)(msdU-|grDRAH%w((DQU}P< zOO`mu>`R1E{3NM)<<;^$tw3l0u$ThFAy3NF@YiTNnDn16g(Ly08CmNmicyb|ojxvn zWw0ZKqB9JZ9EQB$WGzPuyh<)Ze}|kN?j(w)7jza=Y|6CP%hRWx!;trh86hzdRScUB zNe?O!-SGi`U*A#nkSFcnhapTkj|5NGDi^KnBQMKuHpFtrm4OKdgNmb_P@;9H$%|WO z+;Dzg?6RpCVak>;oM2jeH3X&Mj;+iO8)V>m#3HSr90Qgi+5ju6K+_w+&57Ko=UT3+ ze_XS$ceIoh&|6++PZ3y71CmSCXgK)Y_z9P@E%{YHG?ug%mzF&9`fOn))3R}al4KAx z+vJz}rB5rfOM(+SKw2P$j-dLn?W}h(eyUP+il}-|VZ~S8t#w zv8hw3T-jl=pzWz)q+tWX^G!`ggx_RO)#f8o3FqRtgUo|x`4-YG);Kt3 z?ET0qp%qEuvNsw9tOp=Q+bgYX5e{DCj|Bl;S>u-Wt!<1f)XeN9<S@$s>>Fa|IdA|>tA&_{X+VqN-nidH@8&xMdVo^skB0lGmAtR6Lrfy>u<^EEahzzdW*?)M^J6;o+Wd-j@nO_;lLLkf+Nw+~4XC*y*jO~*)ZFMv=?)dT4dRT#Zii}WYSOl>^T)hE;NqxuoZ69690tyS zKG|c~@CQE?!&Rdqt{gV1oZaB8e;0^4z!XYqBkHe>#UL+;SO<7i`dht8imzZW#Wool-#ym*3+p>C{tVM4kGY`i_lT3cEEbJ-D4>OqP4ULH49 ztk+;pH| z`jT~QCB1a+_ww-JN7-I=y@`j12SB6iHvgR)24S3#W)`L(18$yxM5P$l)qQYtnj+ey zbNdy@-URZ~aIj7*!!_N?fceA(j}mB&ISh;@+B5#}l_N9|pC6}}`HWDbZUVYgtnEzS z4tDm`5$_jXJ$s#zNlTb7HiH2PYB~A()d@^$ng3X2Gg?UAZnxfmrmBM;cP|e-KLW&S zTUz@t&uDU1g^oZ22^HUu& z-{9b5@+E!np_tFe%uUbQq|)E3I`f_lv$DqWiaB;@;T1EJ<^(&6W>dQ!FIP)krI${h zSU&fm0QC$5VnBEcnwpzKZWVy>CbnEY^KQ79J2*(Tz{-l%$o#mCW zoZVg1iqYGqCrmFNded>dO)L22H22t%93-hmF1ml2Y8&`^Kmp_Gc(jV&-(8Jp$$&{d z>qYkLopfU8h+yz7-Z2M1$J$es07KlG{H{aHAYU^L-f5|E<8=A#zBvzk_!K);XAQBM z5z(J~TmwodF$lC*d#wqyLlo2^=YsUVmcFmwV-s6O+ps2CMz@$o7kc(>5?)b*pZ;Y? zyj?2W%>T%o0lYgjGuusoKJ5({L)m@b@6zrux2|7~Eq|1mi|4s<7SOD>k}Ot}0QYc! zb>8`YkzdT1tyad0iIJs~E;w6P>S65qq-Fa(YxkAw3BAj4R$_B`nW7I(rEr@ITVLBq z_LV1Y$P3+;VslSq?ynF((Izg{JXKtzk7qq>cvCIpx~~ZR+NzLMsm{ga z;r;Ev^kK>+_`{;3VgWKbg`R(v$p(wVJa7 zhJOQ8+l~_Vy+@fuFUN8I@M^ z$tp$hDdJVpi8eu0J*eH2boU#v#h}4{)+Z|!rWsGCuPw}_AJ^3fUOp~-YFDp(m3?74 z-ZmG75jgf08|EW?$caDxE!edrgIc^n2p)}kHp;4&b%qJD-$F=-rg#EJLokhDtG7GR zg9t+AvdJgU)*Oq^vdI6GWQPB)RL%K=HmE2COUf!|VAkYkRL`$b>g7am69Gb9A&|?T zKX0A0A%lV_?zAqn-bx_~LBglgIQ%)F<^31v9oV7vsj3az1=x`we;{#mkuIVpQwB$lk0ScvzOyk*pjK5Cva-ZBmQ~Q> z%0*70I3}Z7XJHEyJK~@DAxQ~4u{em9j$c9}wTzjUjQ>DIWSWk=@tqqRz7Zbyoml5| z;n~&Csl>EM9adEIh4Gatj|TUjG{z3^xI~j2ga;c#7S<_D;CLr;t|%2kB9nXoSR8{d z<4l2t*lX;Rx3adT}Yib1(gWRV7ZJ^;%n5=|}#!>_KE35}vmshSk)C zhtJw!-&`|MQNtT=qFRoB>S^t_uCcA1(d&V0t5U{FiqC|VAlXyEBpvXtJ;Qc;EKXE- z+%Ln!Jy0~Or^SH@M(_i8Sfs+?B4r$-xEU~w|7pq4rAsVGK2p{+;-)vCPh_Ra+ai|H z)7Pu^+OCi2WWH33|J8z?Xht{>cs>sgjyM5=-djPPGmz`Do6Lzd>EMk5* z$t4*1iz~Qv)xptoxP9>*5fK$y9u^8TZU3)X){ojv=a{B!_^RZc8-#S^85DEcK6uBc zpL+SXx?WI31dJ&0kh_;EqX@nsGsw8SY629m;p$IYyUE{HswVAzupx{##kbed^1bZP z#Mo>)wgKw%)l0a5%a&#a{7Cc&DFsL63CbiVvD}jGk*gyRqx57aUat&1Syj$^5pmFZ z$LdYz=5cg(t{4x0bZ0_je0^h0#+}}FA_1i~LiHP39>w>O#OS4_dXkLbv0Cf8y1Dhu z1mE!l-*;@y!T*cqda$j`ulR4hd`qJSJR%$Rx_@??xLyfgN8FUUBeV)-`r}>mW-KKz7Ib; zjaLhwgOCx-s|If0aCH`ovGYDeBf~zwicfcy6+778LBp*-lIa>~rCTpFTtAAoSpGH| zX4LNYXkc}V99IU z$as#omXy~jTh_+rYlKX8(uTA8Ja3xy7(fA9T3TB0Vtd&zCj}Jl#lrRZ@1_L8;Q0*sCLEzO_;O2hs=;C7Fv`=|xCN$z#A+5VsT}|Tb z?6O>^r&2}-XsRnJ5Bfe+i8fsW0W(u)u{mpeCubSA!noR#)|0u{j`!%B4mNTOA?4cx zL$USUK_gf7-IP3uEhnR68u=}oEB9Q-roWX(?lyz&R)Rv0M=-2+{ioP+HZrze-&%bk zk9}Z{EEU#go9GelY`vF$qa3Bx;35^+vHgUJ>@`oEsIm|i!9 zJQ3A*`$a}eh9qA+KVr2y!y$f+!5o#vcRuXfY`As*Y<`%(;d4NS0Hk#Vo=z!Da10Oi_7uQ>P|*1^bJrmig$L#S1cc z0_xXLah8>k<`8Ts*F@YuTASm9MR@xo0aJ`eJq}hLDQ>5wOs8Dt1>XYNps?hUJzRh8 zlUS~tlVn&6eJde;)~LE4xuw}PitbXsAOdPXC~KuK>N_#{)6yg4NCcJg1j4Sx9x(N} zab~v|945ZLE@CkWQ)Agb{f4qAB7IFl^(eyRM#kc43G$rsCDZv3>gNA!$Wu)@$Xq3A zWdPTueXb01fq&5?{zq2?e}orGaju*2{1#S{kx%gWJ!6yPES*!`(7@1ii5SLrVgGi9~BD=v{F+p zYv!ni3)?h_aG?xy$#WfDcx*enMF*5iq`KZMop@uDxini;#Te`>1zQ`!(yx6g!7ok5 zmcT=0$w@7Z6)}f_mZZ16@m7Ug{LS#oUmCedHoY{rgej<%(5c!DF@G(blZK~F$Dya< z!MkjAAAlv^g-nAVOBb-1Vi^ONdL5c_Tks@afg%DXiHAN+X-Wm8;FuNeS7;sPlS)%= zq;sUK*qX1wFS_#D27JTc>F%8IX%2fx^q>CUl8u1_R31RTGWj}-+|f~KzmxDYD45pT z1frhsC++h^cfv0FHndoC5s-6L3(*(lBHT)K7WD7I{{jPj{ZCO<_ivvhl6-zcp9Z0` z-mys6{pF4Sx&l^cADvMQv9#LJbRp)>RuV-B^|6~lpQsMvqK*Tb_tnuH4O;&e6Lwxz z8=VsJJS>g1!FUG#u%?g(;&2KCECpWA5-ll-`o@jey0oO@1sIO;bd95tG)4{%(ivGC zR-9VhNX1`oh^!6V0rJ3FtBc>|6&(Qq!NRR5Jh=nVp~?umsps=tCCh zd^z<1{%Y<7q?NdHRI*g;>vF+Y|9)(A?;PF{gM|;{h^`N){P@h9*4%=FCJz4oIQg4# z>pc?OG2+8Mp0LJe2K%z#mulXK78ot1MrFL@9_&56WEwIxw)N`8*%`4;JYQ~^Ksv3n z*i6~C?DpDr>2)uJy+6Zhpa%etTRVeqW6Njq;k#FZTybfo8D?1W#RH_*JpUWCw_Xk< zeBVxm7%(v|rXy8@XMmLE+2GHA(mN%O7KshB{A?W?8GnV#tH#5U%N%}Z%J3}&;BhXJ zp@d6e5+*Eln(T2Y3B2Fh50&I=;6}Ql93wb!caC9WHG@uAXOpvQe1_xQ5u*6c|C;{- z!doHx1@Dgqey{)dhLv=57wBj<=6G=)@0LPd1^!bs`-p*PP)ZrG+yD)q`#H2S;_FcK zLZf()9Lab2??;ev1$w3)MY^z_i`ePQFY8{;+UL4m+965P^JbWYL<*}v!eFWPTtJ&@ zBUK#ooN(^_5H};meZ?i32=8zCDq66rv)4C?3I=Iuazr54q2om%#bVh&%*1={vAjn< zs#wYUHU0hYqQH~at4ZKBG+-qF^3QObuI>!N1YbXC_Xyn1i(F^_L)(z?B)#<$t~a1> z#@QTOP3l}*q#XMCJX*H4_8IUe{W642`RC#^e0z(YbCz*zg~N@?3K&a9k|bh=G69?4 zP+uRHwZVU+i=8>DC4nUzu7d*rmIj=gdvhQK)(qv?&hO2yl9n`qtEsb?(qC(U+0sin z!x~sEIlFvf#mw;B$e0fJaTj~gipYAXjFwTh;^FGrJ8wJVcY8~b&4Kby>*!0aN1&jX zb?b_|M@O*}vAaX|WQNKi>Zm(=T^&$fbMWLpbY?T)y)=9JS=5|7ZzMV%(JcYxX9~0Z zYhsH-IQbE9M`Oz@5ZxXdplL6|X6T8wj`H|1nzb5SrL0XtWo*f*vZY#&H24*U&(EZB zyj$+ih-$yYS`XcF)SyqMoZ^zu+r_iQMN`3RybokkGo$o^zkQb7 z>kE3}c8I~n*4tXhe={KI(l06&+mDLWLn0j_mZ_^$mFM4HMp{CmZkXY_Q)Z;MX#Iuv zL`<1RYl)CRey-dxKA0xA*PfVH;#bQ<;#F*PA-Ke7gv*~BgoM@FgH!m?5=*s%9G-ff z_lXcJ4&mX1X1^F6t$jGJuZm3tS-M*;J1#!R2@w`F#A8OenZ48A@Rsm@P2EP%f$xp; zl);2*PJlEQ%{;JQF*{&WXfn~uW=4vMhrf5b2*C8Vd2XSZeWsL>X`-)rk~63MOHNp0 zCyA|PJoB`&43MAi#sZH<@9$T`YD=%u#?}8l--VjZC`x?Kk+qQpBaE^IzOt)IQ*?sl za% zQHGYQO@IQy3cDO#B!?GfA`+~g%Pf@3+rxyFi`O}TBe@5CeD}WQ==Avv9^$Ge)kaepS{Bo??O;s0aGIvHYx>T_`-^(;+jRk83}18AUnf{48Luuq8Pt2q z>3RIz{jiIgo7!8q0Hz!teuWm>^FG4k8AszXqX~Ln#uvbngh0-#d;fpR>UVQvne!c? zM?H2;EYF6{A60qC+>BY45>WxyD(U$aXFmiPIFMc!ww@s@`hucCge||eNIk<;>E}oL ziYm!rK_@13mu>@~_ttLECp7llD}_W(C>q(rX^|a9UVIm}-&}oT4Pp1Hf@E?1vn>{* z_;NFUW2kfjTpr(70_JT*689W0Dyuf9y=OK!kU}Y;v@&?f6IeeN<3A6)+-i2ZjNWy6 zPcpJ{v1U`ZnRoPVOfP=cor<2UsX7l(Oiq0KX2S`UTU+fgb}%-{u)_vy;hR>zPWQv$ zv~@=#E<>;P`b9qmLi^g6%r&#o>&hKOPrD;yrdyGdk?))h!P~6w_Z!BQ*_qeU1pg`S zwGaoi%>%Uoy7R4`q!q`ghzMBHQ^>Wb^{B^qlJ)z;QWSho`JewYUZs-AyzW7?O zf~T*v`kdmaN-Tt_JAbQ}eD79xa`QF@fF)ERZed}v^}eH!i(P&ezm!8{S>5IC5bCKn ziSN>Yh=^+xuL5-w>pH6JGFVbtKOT$46-&?aKFqwo&;;Ml zyvJ5gDBI`TSlE0BL+%XCmwX?y3NLuOVR#r*4~Bs{a$=3Z9g&OormZi3rkP?+TT0+x zNcOQpiepu>)^imUt#w;xhWQeFuNllA+VzSI={N11a>11+28+1uu3!<^ zGKH5Q3ns(S&AUwmT&*jyd{I}8hJvkC9bM$5M=hAjmT8ChOPcp8Gxwae1-i6?Y?J_H z-D=BE-Qb`&WVHo|V=zv@eEKA?eAa@t&U{F#`!lg|lFw(uq`nnkivYiMO}y)F5{oS! zbmW)OObfGg3ki|9C{QcsarF6&D;G8Zl9_h>%ZQ57S*yq5X|xJqog0}1YXd%07^gL= z8Kq{Y2vLEfXM8!umz7)RxQGFn=7eD@JvT~4Z90Wy&`QnRDSw3x>bN@_ci_X0Ht#KQ zm(w=hoQ+D^hnwl$REbxDW+vA_-){q;4*&`x=P&*z0T$rFan?5QyGkcLryM|HQwGbS zQ1N$@=~F~!y6~mUDHYPAmSSp=r>|}*_aLy} zCGVP08~ef}%YdiJ4M=RdKOfkqL&SuxM@!=_Yzz>FWMGJ@6XLs9R->{`f3e zkpk7wL)UR|pLTU|=qv(WW3R%pmZcjzx)H7G2xD#^4jaTp`Vb0$)YARTCV$ZBxOM@mrHD8V?a%hv(pbh{Co1Ky7!xmX!CiDp086kd_>_!U?SZ41O5;ayV)AJn5H?~i5a;le^PY*S6=EtN!x(?=J<$y+C74? zz7Y4a|3e~k-w2Xxz*~7{gMTjzgSqF^w7~L;MO?WD@0|#2Xy$2HN1%3g&w?#EtX%8C ztW$tlrm57i3}f8tVS<3eEFNZ?Gfz)Y|9t0WA1iJJ z7hvcFToWB$!`n0w#gFYs`p*lao@AGPvhy8EW4Aa_rV*g4tyy3bEoDS$R*idq*iU-s zd0*-=@7NeVRPhv)O#EF#+ejDHCn(HM7>!e& z`xRBrO?LKUtDRac1(DAf6k;sXTd-#d=(1Q)ZVhzuOqtb{H2vrUt=fZ3N}i_b|5d_8 zXnQ>R(%86u_D07d#Mc#S_rMYOn0(D)nfb5o25n@d{9-fpgFRZK=m4;(qdPmf#Sc}` zJxGI@IY=EeC!WBd=q|7n&MtKR3>11;38jCtQ_U?79gc{G3>Zc~V^Ul^sJaT){OV)k zF&vAOzdF9i<`Eo=9rITw0Dce|EwLFs@x)U7>1u^w%t_ z7*CoQN0W2aAaiv(y_*(MKwZO8|VntcN&s?H__cs|M(;lg{)9*yg zVmUe=Ch-G&@BRuIW)_`KUp{`SpKT%YcbM~HW0H|suik|1Y8~A+kC)DHn55@9ohr*> zvl(p!P|b8zV{me1$#(D{u`5xA!rr^0>UKr6(Hqgy09IXMOG~z{;b}Gd$;f!3x+UNr zT(*pMfxSKlaG}{fo*#h{1vV`;USB%Mjkk&&Vp^BnTE+v)%PZ(V1mh>L&R3x9HuDWj zKHi`~g@Vy2CyXt18OOe%;PmzOOceHP6IIiQ_e0~}xz)ygk-?@w%RFQx_keo6MiI{=3s7m7*j z-!n!XvXmC>d+OL_y2ou<>lZyeZpgM$tGt$ZP- zOhXBT{gZpoCYAFvmSh*G<~6XpLBl1GV;6d#ZND@vzo%}icyy#KylZ%W9|t3GA%)}o zc8B`063@I7s5uG~`t7|UiWx6}VwinDK(~&Wn5drJuZ9HZ=tj0UHJH=`E2Ogd znS-?{Ji%pC}trc1>pv|a(K{w7~qfino$g5oP3P5d35V* zs`Fpt)obxu*3fgC+I&0uom=IGpu5xDi>jC%1wKz6@&INU&ec8F5MZu~E@qtLC2CZ$ znM|-Dt)1I$DsCX`yCij^+TFxYcEiIXyq8W`{hX)N-~-}(gQeS zUBw4%Hu|3N*y{wo{K#m$%Z1l%E#npRB>w#eOV_|cxRSF#oy&C643{%UT{E4ITUAvS z%~p?Tdi%R0Tj>I&233HjB;jMgx`>ra0#CudXsHzQW4>x5W}Xl9m&Xa)g1y^Ep?uNc zSU|`8;T>I8H}^}-%h1J+jfsVKz)EZP!c}pls}Mn7*AIr~{`SVvuyXchK&Wc+DD_hD z4%v9X{m%cDp0AJqP^U4O4H={Dv0t?N029bg9vQSB74n=AG1NRiW z|JlmP#RB1M*`B&-HYRXFYA{Da)U7WBgnnI3lL< z7rPkzu|;X~hR{>_y_V?3QxfK?CS+KN*Dvh39zgyhOU?F+H_MIM!#_G2x3Lk57ENkM3t?% zUe$1-yF!}ei}zSi>YDe&DH3{%s0-OS*3s$P;jv-89bdwrdPR1lZ?xJmy&P13U0wWv z`_>?TAohuv#}Ryhjt5oKfXU#gcuc4zCK5aqpy*4qN=HkBJzlr>)`cEk79bMt&dXuB zp;pHnvBV5rg4@;N9O2(8pHGw)8Fsh5kA%qi zu?laF&@O}jbn|Nu%ZhFOwe7DV|Gzs;9Ca6C1^GKKQ}DSn8W{l>0B8yo>-0LgD!+my<1>^#FXxi?pvG#DiWhcnf_-cs6GSsJ#>k;5JwGU zDYvJbzCKc-%Ere%$TzN%KNN(dF%7UJiVM-h*dhL|NO8ro$(gQ;kurJ0rIvecfxbOs z*%a?<9-G~sj&Z|3ik8qXb;N)}Zt=6u2N=Dl?h$~!7aK14r{?xyI|7(FW*Q7@0dfX_ zwac5zoS?hAyZdQU+lIi z8~v~cxE-@Ue(H3x*vloxOFN?pdxoBj^&R{3uA%D*2#ih;6~+`eh?k!(63i@J7#5uo zTgk)oM#a!CNM7aA#PTAY$y$Hwk| zYg-S<#py~@-^yrXys!vFS8x(DV&DhYEb8V7c`4;JcW)A`PVYOc5~B7wo;uR4?NL$$+2-pnJ&lxoZ?<`;yrU$IUqYYk{gv(^-gK({O zIHZZi(ye2vs?4$xhH3th)83;b3NbcmiD&%dq&?wZ?~ySnZ#L5Rz>;?3e+AEokF2$( zx%KF?0&gUs=W(ZN#7e6OBC_5SLh=0k40tIA?Yj}zT7&B-}X0^P<|IZ6RV3>9Q=Vc5!5ni~(n4ohj2)P>qn4GA%CjH4r7>BN0+ zkV0PewQHQ6%?u7z$78uCSIT~phzw)W*rcx{waiH+b#+F zIw+2ON#R=^JZ-%>EqzAWjE?%?lfG0==W{I7$+BGgD-9Zk!=$_S8Vu+as0+9F1!4gR z5Tk8ufnhW5%AZ*?zgMN(%t|Md&TVluyJiWC6As(;(|HzyT1R|ENW8y%!01s9{XB_- z3-SznLy)>iJ~hKrhRWq`GpIF}c*hx6DU3tLpOD$tg|_6rndXs$)@`0G5aUy0si?ky zguDm5ocr_)-2TP8YD7xI4}8j2PRVbzBVOSZ%a4Q7=pXTSgPlbHSNbF36Qypp=JM_mYm%9ssA;NkNCAlTE(H}o$u+j@BShUI>fT;ca z-7ULhu&VI=>%v;!?oSM8c;qBB=obsKWUsQ;%iOQOKVipsJO2H0xOGDwE2Uqnvdlql zg=t?4&DLGA3|g;1jBT?I!Wq4^c!#m$zo*nkl678}GE;!>`B)+F<$E&69K(z{(8)eu zCPc8MD5pR>s@kvX1%;3JOKEHOLs@+c2W2BeXngCb@pw)8%=g+tsM@&}vQM6al5V=H zJJ~ZSk|I0Ef7W%7Q)WqeKS{bFRLU^|$=qRCU{O4qe@YG!6;v8@rJiE#Dj6`G_4v}p z8ljD`sxugXj9$;fn99|KH_L)q%CoF-Hb{5S#qc(?<)1dII891^7n4%Y)khcjBK$jRR>EC?ADKBSO zURxWmXox=O!_n34!xeI$;)UoDxQD87^ArCc{|&>ID8>BF!?H}7t^pp<4+2Ni7;xGPiaBxLr{d|?)Nm26tJ(ps* zsI?acgQvNyGaBv##f619Sl8?t^r{2un0L$OWT9ABBKBx)O5QaxHr#cAqg;KfCv_h5)m#pdTq-A*o`R*K_$ z*bg=Ua9iz#{VX+>^>w3xRr24Op^)Tk(oKW3?67c!PY^+mFj5ih!&SzQ`vv3CQN6m$ z+AlM1_$v>jrO*HHk>~@ohrWr5%DspOUJhC8Egk#6uI5}suqVFhj} zd&o1}rUecdj%kdos^<$3?VW|@TCIGeMV$Dyz@X#?bg9+h%wlL zwsUSau}j4G`z8tu@nl_J=iO`W5x{0vahtlxxRTfpuH7SGO?LZS-e$Xj*KCSSZZp_A z|8VN6sHuMlropdF-Ts#-2aYk1?i6tmu%{Fhdl%bKx^iG;BD@=jO;cab%Y?)pX2=6< zjTd7zvX8TxHQz>}?|vA?`@_gXdB_t3DH(Y&#NU3JmRrT|E3K~Yv_)cH1;n$ITbt_> z)rrTLnjYx(dzjY9B@#?f0ZS?JUaEpA8-M$lb)lXFy&1@K!LIRLIh` zT_{`0UMUjk4>})VqER@_E<|fiM&+d!nyy}1f!? zxLZ}?kuWFPU@C3Hb7}0qD5oUlX4A10)hH=7hOfjjPCA7`j)|WCz#U`H-h!9*${Ha1 z1Ju|}K7kLl2)*g0Lzg-K%4=2MXv~<~3Uv(?aK{lKshMh3)p#1=c(Xb1nc%+s6!V~R ztl*)2O?Y1EDS zVxxoL8_~ zG1G<0x_{&q4yvn}efwI9)p5jq_N#y&@#%=8zb^o&L zs}1$_v;7fk3C4haG6MARdY+k{u&E>~I%sRo6~i@__+w|_8xEp^!cjnU_m&jX?r%`t zB?5uVR`H22Dd{P|#Xf}O?%v#>5x8s?p0#sw=rkfZe{bl^m6~jEg4M{dCMx?2H-8Lg zyku^u%d6WmFt;OavmR<8TSYFn8%`Q8G3$a2*LsD+gYmZ!_@)H7pIEPHkxKGE|@?-8{ooZ zab%2MkplK5JfOiRDO8J*;aXOHI9~UkmU>{{`}5Wt+uJe4J9g7C?wPX)+Raap{9Cdw zLQF%UJj=Lz&S;y8+x55PWOTDxGCefHi}+G#2Dh?KV&w&h_ngU2e8P4c+6dW_e3X#q zk#l`lgsUjB8IF^6`U{8Ux9P^0&*H}jJvp1|cS!J@ykw#&Tq!$5Woh8#No7IjahO{3 zE1c=!U(pIBNjs2Ie^02lYxL$M1iy@<#J;9)^Q;EK$Hcz9w_@C-7rRrR*;Qcy7;<9` zvQ#|l#4Im5P){8W);x4r!(Ep*&G3b#vnM;m1F-K~AYKP&&g)h|?=Nt(cA4sn`E<2dspLtb`A) z8NyKDUD*7WqL)4@#B2XY)W{m#e+K0#G?}jTB|k}ALea2E?*9WYP2-`$aB|012U5~ zK$w+Wnkho!{ZSq0eCnZ`a8E0>x;4z_@Wc3e{T>(cASC|wVENC!Yc1+m;tc63)E|G^ zC#pP(OT@1TNBGNSI@`0JV+M-QjE@0NL5LdCgi($EI*h0l%#Rv+gU&lD9AdA0C~MJGP*^B}$s*?Pj$m)fpe91g z4_mJSez3{Bp`Q`yAe%B!PMu1lw4Y~P1)p!)AcA}R>`5{F`q5JHKpXA|Tk@oE zi#4qN$AR_oOn!K7-meQML^(ee*}g((Yu<>3PJzPNfX0jFQS7N5XoQ|hBJvf}RMzTO77>f6&jm`O zK+VE$SaTu^7eY(ftJc&xpjpC}QC%St3!$5#8(YPfrxPqjr*q~Ogt-BLo*bLirlnx@# zq{y7g)g~XK8RXO0+LJ;^+3V{r4tLpJco1uKD~bVf^{}J(z-C}rxUKfcZ{C5+xld%PG$t8S1R0JXz*Oc2gFvjq+Kk&Tu@T)SWuw~Rw>Q8YWTNB!=j#n$9w{*Vw6?R3O& z7a^Rq?6#5@6y+gMu3Oj>X}Q3>L>i_I||AD7TNu=t*6f zJdyU3Wb-d5hNw>`c=1nacfM?U9A^#RlX#qK#wL`;=Wgyr+(RtEyl>YWrl1Cl?Zh20 z_&-b(T{>Vu%CrhV9H0z89Y`b47;b27jmDIC!RmR4?)gtet2}`gU|BAtcm1RJJLMBL zXC$UOUmlo}P1jSuFC?~)ngW->bOKSf?vK^ruit#FTet3W+xM+`lQ*#lK()5lniO^q z&w1^G$fcc&P~Y~p5uwzR<1X(b6yu23A9M1qa>x9N9$ynWkMIP!t2li%JD8hX+i~mo+wzP4sB$kyV0-5s6^2XJo8RuNaZU_qaY0)}RZ8r~Q?Q!v77db` zR$qwY9s^_RCWHj}tyj@u;$@>t?x(LwOORjS5<9yMP9ReW@H|!U*#xif=@if zWkW`{hRkt=Y--U9V$!&AXWc+ur$TXRg)y@mIrQSwV)YSFj3ojwdfR{&AqPO4C=*Y?OZQSEX3GpBzutHOy~1a8087HVBU~>+9-3Rb1^m#LSe1?TW|*r(8II6rp% zsB*};3(feM>m}CxEA7=K9mv08gYV7T)u?CvGXnTQ>s^VO61PsIZ>lM&B=W-v8)D@k z7e(P;Ca3y|d|eVrW2mb#+|o%LjRod`=ui1^Gj#D=;MOZXYfBU6q(eTn(Y182zAIdF z@`$rIZShZ@NE1E+Zc51VJ@Hf`)V_*^>ug`Oz60k%%W@&)82LjXt$#k$WVOM6*#jY( zOD+`rW+Z~`fB9j2r%+Z4@20xdzD8__bNq!O&y!ggKEufw?e^KcDOU?ZkVD6*Na$}0 z42>nE-O+_bnC^Hcxg3A))^OQB90pE>(gWzh*XD!X2W03uPNecw1XAIE3GkN`1%pM? zCd2*d93JnRJ!r#TVVT7xO=??a{Z;4=H0udtYJ_H_EDT>31Uw$4Fu*AUu>~vAa>aa0 zf%?c&r9?{S2ns*SRmm6b|1Vr~5Dx$sOxBdWRDTafgtbQNZkRZDf0Xh@t!X#bAF7mT z%2p1_TE+_D2p4oE9JCBcCjqN_p0hM}5T8$TDd{n> zXhcJ$xVsSu4MbsF;-p+Eo|65l=E<@4?UA6ybwGWwn6uLqICs$8+D<#U66r4TBHN5y z2&0Gb^J6%Je_LIIJp)ItY|0?uiEx0E*nra-GLB)<8580*!5yF5Px`Q)D{+|@ zfb$2KSSYkPKbc_FML>Q?HpxyzN@~WQ2Z6`Uh8`x5k9;Utnq=&FsxHy&5F1othSA*VC57(ivfzRAliO5IG`?Ft72m z>gXIF74}LrUdn$8js{wGM0&BgA%HYDd)gNhDWRumL}g20%F+!8C4|};mI;#*E4qpf z7ua;FSw+O~7kJJ?D5e_J{_4l7@YRth4AnLDM~Rg0ByuCn=rLvfmla&8 z1ewGw8ABXr$FJYd!c3S^%I0&+V4{i(Yo+YQize;_&Ew1W6~t)3DGN^;Sro_WjKqyA zTzAK3dkRiPftLSe;8nIZ)5`Sc}orm-PJR$uBXgtOI~3<6zMiK zw!zOMNtV@q!ge!Z4|o9yp*~!*Wk=hU);wmJT=apYSj%;)^k?~un%nO`EDEy1pqq{9BuMuD$v zB*Olr2unz+lHWKR!DsEPcJ|>FR$ODJ$(st4DfQ1G5)Am`vUy8T{$zw+aNc(H7{0Mr zf#bg_=dZ?J;Xs7K`xt}~1r!D%v%Yh*y&Me@#dzgD87Z!kn~WXm`D)o5kpW5nI2%_j zs5KF~Bt@b|`ks>9Ea7){lSpQ3fc%H~#Pe+A?5%!6$koSSoK6$E)X|`){2iU?nyg>U z^k~$xVzsdelOraHNT^YG--~72>$BzvS5tkjm>MPA^2CN{!95J>@A=Kt6l;k=lS9ELw=SmJ(am6og9E(>a_MF~Vis7WE-? z>zOkU><%FBItu!qKDhXLGV`p++{z)wONP4>a9gqZz2wS{g(8`MHJlRDETP zHxd>S7#!YMbvBqzD6GX)gYrIxIPF>>FxV*i-Zu9O&Fi-(q!qk=NGL z75+q{D0j|0hh4-J9-#cb??%q83s6ZGafK0dfnj&5;&hqIX8#)7Nae_b{dDawOnR;a zvX35V%D$YvcN;w7m2kdmH5oq^CYdn4hc&iy=Pv2GvDg0znnU)v3|<;bFe1$VdE++n zGW?}%KcgJ#)Gw?F4*IMr1T#LdkFZ`4B|}4T0;0wNcZM|}>JbwEE4Mi-G;LH9@=MQu zu`K`j8~*d9U$68(FvkUZiV0U6@08tsMQX|1q_ebSr4q+aK*-IgT4Z=iI=;UxNW`G$ z^m?-_&IxGxtl|1nO{pq~Vbp<`ES}l+Rjbn+++?t;|t$+P=;Q%qe5t*Vb9d8H2 zKQ`gp6tkdJ4dd_mQvrTs2-C6`>OUAH-+9f6;tP~$0ETGOF?QG=V*6oSZ=`Sy&s*_S zCymte4OzPIB;laDbH>UWRn!nq^kIx0vM%isUgrO_0I^Bm@?j{cDy7JZ5X+X$K#GQ` z?B~UF&Tc+ojSN{b$zfE?HN4(u&OAB$K9U%A zzao^66@7!pAJ_9U{1Aq+?S9g!=P9&T3oEzzvAMz;3BduZ0eWFMmLV2_KuI-1S@eLk zo$a-|hXgV)wqR}9ALI=gW#?3j;3qnKJZgC;+gz%yCh$Gs1$8(vS99k=K+a`q=i@#P zmmora>Ve_BON_6gd)%wg2|Looj~~neJw0+2V|M6c?JqA?N-(S+WEm#>Dqy1B^+=FJ z{t6Wb%u6i3VOI}<`4vP=jV6*C|4aXCiZzYs&of_uOHJW;>4&{GK)teGf{Z5PgbtN< zL+PvdsDabFq55rDau9&PDivh}X2ax~7ongPLhD%EX3GN*iE-qT7Wq*bes%T*|2dnj zmn3Y#d$Y*k*z|-=)ml<~DA{19SvSgAn)(R88@EWdiL4~P8)2|1);C9qrN7Qs18(I- zQ%#chYbw9CHwK%tcOIs>{+1f8Hi{z;+`w`T$Uc4syxWKY8GBZdJPsIOOa z9i1yUH<6Z;Ktd`Ajw0v_fA=5L|8|OhjygOJA-_WQi@B-`j0Ryd5LK1(peo-^*Dt)( z(0}RuF@{fEd)oIXMd7BNRgBlJ{3zF8kNFaDv4zH~Y#+VLD`=W73|Ze5sdp}peQMnW ziX*w6Fj=*yZ?D42)oAE0iUCJtdgrNU-0?X&k%~; z4LXg^>YYiAs1Sl36zrSQ-_7MK6a7lY_IzdGGzfdGaIOp{6WXxSG%3JK^8dUel-u>m zg{t*Sp4YWdgPkp2iRvE;^YxURA_;AujusfrkS$+4kRBgs=veU{g(@sFf-?Bt(8s%+ zos3UqTy73ue~h1ofSYbuu!{fkDVTX~>qjf?mld_6`}uj{v|mwAPd0Idaf=3L!Oo>& zI@uJ9_Gr@)G%CCeDo7S$TVOWJin{qLJM-}T8_n-4a6N86{jap`_B=OHth@6aDL8CJ z(NnRP93+P@f)vNtO4Ow;wytoLM#s%J1jd6CPbm>DnaXm3%((BV3d!lgEfISaBy#vh zgL(FV&?JW+?&a&PVaA6IWj3fMQNd2>V}$jc1kXKeN;4_7sgBUS8~G_$vHYYXU;dh1 zJ!#;lx>i~|5WWuRYk%%{NCAXN{;%>w$8JvAjEoFtpm#v8cJ<8qpb6Zf!vu(@W5hXB z<*VLhWJY-fI-|;MTzq|Taz~5l)U=@F5spt?e&4X! zz;*xxr^6a59R{~L%)41yZa?WTJtkS;y9ub{|1uSG%fiKHp9!9bfsoQQX(2BWqlduS z=oqo|2n%bZFrIn@&Kq8S!J)hQ-r%R;i}4fP?carTuHIL3oXmir*XxQTyL@Caquw~K z-@gYW$k&lNj^*d~(oZ(&#;}QMp|8l(uyOG}YI48=@=08S87vBh%8qEHgZ0B}H}GV5 zk%^;O57YCm)%-o_OB6B8+9_j4jHT(DV8K#$%*reNbuZ;=Y|RnB!vDQYEH#cIz82A% zSFrQu+%M+bzobikl;B9RsXv1^mtFX8-gl?4w=zu>x_EALT*lQrfg${f0MTMh7g)Odo*w|pf0Wc8Esp#YrMe}m8JGH4Tiz@4%OquK zb0w>nT)BU?800^Df;fa3*x6X6P>nqr)T2aVq34Z}89+o^d~0$HOwJT=7=fQ%ltZ58 zvJbz*=3?!;z=S7V`VH|#3!1-j3R`1^Y7T>g5tbR`!A4_OyIVR~f%)0e<4^DzHW?M*A`{7ixXM*N9a+w)2a`Wb>sPQ4+Heo4w{e^wX z0a^CCgNY){sM2#9x*_1)>l5d-YA=cW)mp#A_ zMqZOQGKOC)U2-P7b?GUv#06cZtTGE!hB&*sBbl+|l_cRp$E}R9@7a}d9; z$uFJ*^vzB7V}P|}`-Z)7Cyv4D{__DIa5Dg#rXKzMR?*oDEBCRWmmY18L#oA`Jaks> zF<%UYm7xQ4>fu-{MrVhKRbqNjo5A4EdWmmA=nH2vY%)CvK4vtpV7GKa4I3CKEs!t}62qAR5D2jyHmZlE zopEfH)d(PHmd!UY$RSpT%yq3ZM^d$b0jU|0C({6OhPOJA6tQw)P|mL3yc zlJ!W9%PEX+ioP@>Pu<_hvwu^zP#!*w^tsqhx;UA63lmakm;RAyQf%HTxna&14vb5M zRk=Ao%V=-!8glHET13Nbc#@n=`t_4NVe1R;4B6XqePD!4A_;Ub`FC1@+eWc&R4oHB z(gwksQ#+zuaPNmhAQ+4+$EsX){f4!3`#Xeg4S^wix@Y^aq?>GKa!r|(_cuzY_3i2? zh|x|aLgyP=iFL3ADBNoF&W*lIJj&OEBgPHOLmcWYB_QJj`1O8-qAII{n!4k%j^!b; z5P~&^&WyCE0Y6OcL*-fIb4n`TwaJ3@cbIV!jOSZ+p#7i`Ysgcdn0g=A(5kE-Bn*>A z)4UCtkFJKbo^wqkd(;?^F@cKxShXf3&v+>Sa)fh>5~&`N(F{YT=(D`mNL`H>RC{bg z(t7P_2ojtY(ZaJVLKMsy>&MYz_^cK4CTd6J7oX4U+|(pQamT13X*bjww-U0-3$ti3 zTW#DK{#TnbYGV_oW*VkjyWxA(nVz>sUt0Re^yZ&D^=s*l@jFNxDR(quVKwW$gKz|F zg_)2;$Pf=bA6}Rx3nlZkn<;NRS?hd~l^W;jfhX&C!8A-pE)t{ad%QZ4E8L9yJTlya zDZOT;Fg<#6JxC&1cX>6}kn7~To>l$|1j@4_q%)a7va)DmqjKPr*B7D2WhKtrX4`XgJ?LJ2o==`CDd#n^#yED707-m4&oW zi$r<&PvENc4e-!gqPd{wlJ0>^QtD34CuSl?*4OD1rS_knd3hDpDL#GB^#8eje@VOs ztfN4DRPJOi5eS%D2k&~Nw>8oY40r^&3+d?0P7e;Cw6(Rb6Zn6_pefi`mjJ=u5;$A- z+)|64tnx*y_-P680w^db09aZnZxq1=+b2qw#MXX-{Y?$6-IgzB%=FCj`MjyuxV0^+ zIJfYM-tFQ39BH=q9Rqm!L{g3oI#Y9B5IdXb5L}n)E_S*H-T48JD=8GK7k^%nLyjr| zLt(=lqW4vm`L~}47V#5}L+k7KA_bB!Lkg6TEFKFZGch2hDl>jny?*HjuXjEevBAK5 zwik*3Cx4U!4u-!|&x#etD(z9|Gks{KSTd+zIWT6Uuebkf>=Wmb;}WE*;po~6F0f@J z`WG~My-+D6gmR5oTWb{3(VpZE2CD7cq$XaUoT93&egQ&o_WvCb93MMfA5BAl*JfPW z0E|$(-6aXR*JE)bKsx<(V(&XLNzX^pGoT+B44&J?W{@1`!lDm2g1kfOh+k#qqBEZ! z`XMh8d(gDiM2RO~|GE?4V!HUyix~W@tlcPV?8Z9{BliT)%A`>eac?gxCyg|AcFb<> zV;Q~;3$cdu&wfeG<_K-l6T2T=Ajr~&v?Da_%NYD5Q8?TrgI9ot2H8zV@4WONG*06Z z><{HS>gH!Rtq!~N(l7!(!8=LucA6gPGFP_9>i_=z=J?|u;!zXyuT~)MK^Rnc$P@yw z`yK|B1iXBFKo$BR5O0JNI}Exm=>0~V8_Ld@hp@CQC6i)lc zPJnwr;+BtQ6Eq5n^7S}vP;e76P80p@RH1{w_fK>Z+WLLF_vctEuBoMhQJ)DqH*q|= zhy8`aT7*8=V0XcGBoLVK9T&#;msStx7v$!uwo+KR!#ChRj_jNxvmF1fEA;6|Fe_w( zrqDoRTLydO{k`GC$T2(TeB;7*&mg9*FVjNbGcR{XgzSJf8^e!649;4U1gYW5wYu>4 zd_OZ)U422bZdg&L#D=+vEArElg3hxzF$QkE>*xL`?|)&WCfciOwc71nJtKF=EC5mv z@!%WQv88623>4Lub!S^WUza5QSA7KYbh(L`wE!^}Ol-saoW#33t`CCOu2cank!i3c z?RuTw{ZPUlfkQZLgZwPj15)eC8Ui=(nK$7^WMwFYb0CIlhHD;ku2Qg9COF0e$0z?k zZCn9FB_U#oo4Y*h^^9N9Lwi8J1^>sKF zazbmrnr~b?as2GX5vh1RQ(kSfeTd$lU&$OR;Sb2+)3;fwRpBb#0Pm?E}c_= z#A_{stvUzi=_Bh6cPwLXb=`IS^IV|#$>gJu!A&z20(LS$(El2w1Pq8htuD1#d7BvQ~tW0 z+I^Hu7vxfUAl2Rb{v<3(P6Nw_uApGr(t5)aM53{e6z?n3R|Arkr?&<5lhv4)e8TZl zMF4cHTtM9I+!HZ(4p%O4DKG?3nI)y$v1j$^5jK7URHYjm`?Yyca5orYIP#E*#g$3N z*h8vXxnf7ThbMMZ#mq4nGkQA5#(+7x-?lr_1I55ft&Mrb4k9%VI{Q29jo&NF9Es{;a!8ya{BAXh;=fk2%f_jt@9=JNF#ydLY z^%Yl>SJ7rU>Bv!6R4{fiY zWhDLV#W?OOB_m3=nGD4w62}lDo<-p|@ezx}89h9U2A&*~AYtHGKk)@7=Z4KoX8^Ii zu#9Rg`LtWJjI6Aza?{lNLa(f%0vygeJ|B=tila*=b4(eLA@duBlF^Q|GrsIuE-YYj zMp+ttYC#9`9Eh*|1S|Q+e|vYQ7AkGx%gFWT7=;%yhPny=vK{(Z+q8!i90%-6vvV_G z_`)FD%2FQkysk0u#=$A4s!M(^2u()!R(kr5cal3_Jk*b}MWI6}%IKP3NRKJV;$~~T zQ$?j1vZBK-d&$3et8bI8;63fPSGmu27l$(AKIVRhUI}1k>*g`EiNd1E$0vLxM%9Sy zsmK$m@#F+RXf4P2#l;WhqTp4}wqbkzuqR>jaTS2^NdDy^R4~ZTd5W1-LC5ZH@E__{ z#|0FmeE$x3>$x)9fBppSv3*N*>Wq0m7;8olf`x7&69;I?{QBgCPLO9hS)q}1Y~J%a z6Bn9j5~FgAp4QF&1*N-XEEWOq3_>6CEYb43dOhJsEQ`zioq&yS3cR! z#j(w@q2aeKX+UAptqIC4Gg7g)0S3oS({|-KN zq}^;Uu8!oEd#MqXZTBJ`D6tfg!dVH_b|T_i9?VgiXMo{+r9yIBdd`er@(F&lFxNg^ zuS7P{&N3)rLgI~?O*IOd8whwG{N7#fBw67eix+F*8NGSONZbmFCjFR3{ZV6Q-$tl! zWYCnbzIU+!NMJm@oj<^V|GY$o-`@i(Sr@>ym@j&F6#rCUoeB5Is&hYK++iRg zGa(E!toiBTkIz-`CPEKCxSiIp8o`RmVSr8kla*4N-5@O1z$=DZ|AsC=m} z5a~swYOamU+!PW-t9CCq>!Ry8i5DIqu~WB}&h*Qhx%~$o?FXkvnBZhGe#o$Yu69J} zo|eQh%!F1Ul{f66U;1%EQ>Csb9qw#GObElT931%;!AhhlRrCX8{rD4>_!qb_tni?k z@Su#@NQncd782F`KMgceA%9P?o@SMA!YWiC%I0lbMt}u)bE&<(l>IF=Rpa$}RAdAg z1?{(?@hc0xuaai&^}&=i4Bz02U-6Po$1_i;$!d6Z$%-l_T`2z!*lXao=_h6ISfVk44 zScvJNn+9O@|H$HZaU zkcIT8zlA*!7Ou*qV|aZmlFc&kHMJ6Yv@6dDv~>Heu{%b9Se=?0#!LQHXydTBIg*vf zlMa-ptL;%s35(RdSD;R5;&In;6XFO*3K)6mevSA$ZTamjf0??u-VIY#X35G)aVTnz z2~MXtBm^gBCX*xb*cX!beU(~8cgnvb*_h_$z3?E;yZp~}>d>IWBtF^;Bo6rjy#M0E zf2}LIW#6YNXl2G4iE<2LTOHI`D>icOw0S#&NQceE-C%a^yI**NUT|=oW`EQWHY>&Z zx`qAqhcRP6_e53{_Z804Byakh9XR&w5Fhal&*ZcGAV2J+@?mBW^V_>YS*RK1uCigP zWHOXY(uZ3~+>p~o!5|aSZ*}EU-cd8SnCTZWO-;9~*xwqD;k=n!PlDR_dF3{AVNqf_ zR{>)f-|m23_$w1)khRSUMFIM#$B044aF!CWUL6-0MX!=JIx}#?9iV(8Lp_LncTpFY z4&C^(jD_>|&hM$71Jbk<%bc~eimwRhu96v{z5g6B&!Agu$`(c`6_8#yU(wTXioAEQbdlXzqr4r_1yE=IIh zaCW|pOM|R(h+Hx=>bdJHQxccL3bjA8fte@w0S`@{Z?tjH4PUsXDB?n>xE32!omAw3jf@GMwhW`6q%lKsiD;Zj zn+3%v9M0)YU(W9G>+~;1X&X8CcYd`(B zq+7ovFZRF$x1JTo^?!_R<#5ZT{MHFYt+ot|7){nDwr^ZtploEn`}ml#*YK?HORr@( zLa!h#k9h+LR%S<7{m|(oU8Eb1yLRT$UWD}aZjU@@sVvYI-=M#&RG*I<;rtOuyO3pZwp%I})%G0L9#7@`MG-95 zx4B9D_`*n(Ad{O{iBZQPcwJo^E&@qR31O@rJ7RiaKI3|l%24-S(#}OQ{`9#ft45eq zych?gYM)}S6`c|x;Jq}K?tph*9!b-opx(BfrbOx^OM+{7%eHlRAl(g8OFx^{E%?qP zfreD3R5GVLDkTLyiOllROySIH)Nz@ti$P~`d9eyoeS=@ULc7-qVqB@^*ANBTxa>ZN zOk&~W_s>G>P}$ZIIoWrC$+W3icugU7taqNam)+JLs?mna%0y|4A-z2fW|zzJ+{IEH z&0i#@-5Xra;+^45Nu`GF_>*>$UbRRual7N(P^7N0#XdBMqV=t;lANYQq~-&vV% zp5W+?o%4OG;mV&`CqYiL?n$ifNC(%L3rS~tb8mB_)7f9q5W8UF*H z=O_%}S2Zr^X;MJ5e<@Uh&$z3n~ZP^8<)p|o3 zMR0Toj|SFqt`>P8m_Z1_p2XHeg-cVlUp5kJA`XU~a3gD=4h)Gjw4cwz_ z&LlRm&|pC@u8Ald_$r`Thl4V%YWGW(65-gr(bqC(`WGR+gFh7h#szYMjKas()l;%- z`tH(f`#Z^?F}mzc0t$<0DNrjYFFN zNRXEKFl<63t=ksOa{25m8jigrr_xlwteEGXPo=w2_pVJ zgQ{BgPSEYU5%`-PGeO-<2-;PD^H8^?&IYrr0uj? z6AZhpl;5afa#USInn!X&+3C;x&>bb{M0aq}NLz9m!D&nwsu9Y;T4P*-h?T2GCPLfmNq93l0D!)gtRvx z2&M=Bz4dUGz8vRbvWuP#*ud1DBG<>}@l)m&c!kA*)*EjWiyB5MeYLfX0!3yo-3z@) zAK#%ub%R^nEz}g02l$(vcbAa=PYZy|-ky3|-}@SOcN(|M02^)w8Cf49$IqArjUINs zwUH`0*>ZdqaEhh11H3IgY%izno%dbD{CpC{r$eC56YpQJ(l_CNe^}FdwQ_SKIq-Ua zlb)`&q9lOlkHf;k^55>iNhsh&GaHGgupCn}U#zOYX6o6wt~Y_lRAvx>BF7qC=$CMA zGpfv_L|gf5yKcWzYK#O$CT*NRzPqanZ~Vf|OOT{wJuO+M+%J-Rf3wp|6&l!|9j`7y z=y4_E?>tUh;w`4#TgIW|DR+}#J;sDlNLT#pSJ$DBzak&BTiqYvoaqrlDSF2%N45k; z!CpaQu1nVM?5#Om+&Rdt8}Vf$sL0h%-exq%R$S-5oujc#cy{?mp$cbSWXG7GDJRq= z+0c83dR!&q%zl;R-{6l1l<#kd@_u&q|5 zVt)QO)*(%Odz3FzgMM$8*(9uvAMElTAItbtG!cZ0YWD8eZQqBX)y5u&8p0ZM{Lh_F zMg+JXA?w6@S`BtJ^(XTmiZ4p^&_(cT>otEY8dJz_46Qvd)^(C36Q0+QD6`&8>R}iw z7WN0qKT^)rD^C}xM44l%blyHTm$3~|Sa|bh)((;K^xFzWY8*&i1J-j<_8x3Pr2ll> zme#G}F@saQ2omknhVh?%I`22+* z9xUG)ErfnxUiFIsp3ADOZVf-*U_5@RPPrlG*ESx)`sk>85H=aQ(h3bkyBS0|qmw3wR&oypa zBq9kNeY_;6XEUGJx+d$5Y9JlkF0Z>EJ!@NGVGWlr6R~kwkW13R$h6U^lLgyu0hDsR z2ED%MOrklseQyRXNtFe4Ls5R-#dEEU5M*$g2)ZubGmdV1;+X^Jh4YBojWo5GU=dWs zXtxgxO-+%Z?uv+sF58gLuq{w(zd}%xD(liek$?8Oo%|c^mc`1CkNeaOg35^cup0^b zxLUZ@?MZ~`=Z$;586|ZV){Sqw3VJ4yAlc*KgafK_aSK|cF`1VmplZs9mQF~vt0;_| zVh0FEi#&QCULXO_>DpWpWE*CS!R=n6PRW-p7eo;(KMjYLT z2PoUoef+Z)DT2+dEz{oZeQ!ZiJeV$E521J+nQzss`|ezq#1&6T+?Q~d3ESHS=I6f&U#r~tQ%lk2SH z;Qd+D>V<{u?dpkr$=3W=fz!3)K}9xs%h%?k*=@b_-F5rkFQ%X%*^D2SM)5;Gbd-;t z8%4y4MT&O*%FmlZON+_Ib0t z770Txp8U?e1iF59#$FvE(b%*+;o*xle%4Z38vDf5M*v?n(Be|U;iDNH60P++ks7>| zESV~zgo6ijuj%nF)`-1R@rq?5S=Gzz6K+N>*Qm2k9kO;s95h(d-SnDqhbisU7)c4D zxD9FfGZZp=^^-ReFG!~F{z~_9`~4yIHsy*u)NQbofAc)m&MHYdHWhXmQNF4gzjN;i z^AD=Sj=|1|;J8+%a_mj^4Z*A?q9#JKvZ&gU?|`SBq{5W($xovK#7pE4=srPlrz$@X z$1R?kv)n2u29>mDaPkgQ9mD@))9bS-&3*CmQ5SINJGM#8;BN;!ZBnrJ!AVL7F8WAz zdw6+8#KsV$}NMtXf3W4>J$VD*mS8DlLsc(l|N%_ z8Y4e%T+sbHo+)GX6n&bDZ4{RV#Fotvg@>(U(TmJntArpvW_x(Mu|CTgK^>>65_ z|Gp+P5I`B!E!*v6WAa#0vbxUb)U9%qu$|Dkh|6X%)U)+!Rb%ewKibnnDMxbsqU4X( zuq*@>LcX5yK78|6%WS#iDweyw;mBRINa|D6{@Fcu7Jl!yaPjxABg@PSAIuj`oqOrsV)(m6 zN#%(@ETJFgZ5YfLb0xN-GkVS;{6{yfvD)O33OvHV1tRu!_?kcE)1 zqw!Zrqb7N1!a}%8-Dgs04Y<&WA7X0F;i?UWJJ4s-2=uh|*k)Bk85FWFXLjPofAims zl$nlAe3osua%-juEQpHsxFfwaGAuxV90nkc*l zfbaJd^Rgpa=w&wU+l6QB;3SydN>D@u613GDlz7$iGIN$D4Ak|Rwix=|p=e+OI-cqk zwZA~}8pTItw2eEYB`a|vtm0y@OS83lUwnKnKowlSzCzXY`I;ry9p9}}ipQnt)Lk-l zJB;DPA5`)3SrH}Bc6AXYMWT=1!3Vtsy<-ObYYUQ*8qmZ#yTBpsc?te_t^YtQ!%8gG z&|#3*FdP`$m?^}9MV^j!y+&6MKR%^zqnDCE`;c?Y+#~6mV~xMAGxUY>j9|Pbh|ee}6Rb2uZij zMUXgbsH?ZPAi4HjwRgkeW>n-Iy*jk%EW$SFzle~K2_B4~u&^GomdbQnxj*L2acZ*mKEkkFEdYZ$1zXcE`w)TUr2kQvP2s%# zyMB#xqv!n=WAy&0-4%2PGw2&{!!CaQ7WL%a@e#f_i5NLl8|sOX%ff0pB&U%|@2Jd% zt=^G#yjHs~lh~_if{*Hs)%4h~Ie4G7!gtpZH!&z}qf{|G)s@2Sk5&31 zT&66uAdcH)<@PxlWyN~IJ?`T;6QYLg3+Jb!_~cc!)PRT!PrKy#>Pn3t{O+My3A5!?J0+WrbLd-GFrr}H2Dqyd@COYCA zWdH zIqsaga|oFD1it(|dr5H}ZFhZd0OIq&O+|s)kIeNe1-A zUBBKhg(n9q!yd3=SwUij_0R?s*d51Z?TU^YXCdxs$cC05s0D}84HpXbSnj8=wni!p zPj-OIEmA7J3{D=HV}biT7Sc_07eLdH)hOuxP}B2bd6FzzO+rSlNPk{fw#*hN$cKMR zbihr1`lm~@NI#2dEn~OFosjE~@>^|dAG2UKje{In|GuTy%g;9Q0f*P~Z$~MXGTbRq z^RGmsP5c2})%^M+G{_v(Y^d8xxsjBQG^JX}MS=p9= z)d|{YypN)Bi}=+mER#MpDFzt@4hiWSaWZ-jrP!en*mNY$&)nBcHDibdrzJ}KcrIvI|G4w_sXx~w! zON&3(1XDLC^5uEb) z>1DvKzzgV$+}+*PQW^yi-&|P0eT;K_H_qRZ zXvV?oI`UsE5v#jzN!1ELI0L2E`(sJ>R5 zsOFKG1$;`ErrWw7h2nuAy7!Cl+ra>LaLOBkKlg0+zF-uIOO#%j3L;6+^}KU%e%75# z4X4ZTyYUE4rssOx2Pmf7fR)(~&(1sRob>k|l2LEVgxH|%3(r6pqNzW*r52k8mqp&6 zK7`$D3NNW(wcxrtxQ!t6NdlHhXx;MC(}~x)_7ct=5oW2asav)g07>rmd}~ z=l^-^;TuWc1R@(VE!JcV>2kCZ>b9f_y&e0KHFwG2q4nKLPZT9Ll>ikKRs zhnBVc3ul(xl?J7gTIKTtnl)C9ppy3Mv>?sRkx>;6SO?DuD3^ulH7mJdAy z!-tUwOD&{9kQ~l~+GIFYpDhvVLko&s2*s>B)bUYE2tO^eugoNMz`|rIHJgdwCowJY zR&5X;>J2fK^v1eVaF%j%LEu05L1PcLpyyp!K|#Tt#R?Uj`c=G0u!@R`x3@Q()!?c7 z0O|WREK#D&@9ph+f^NP z)gAS%f5-eYiCx;DbfNCjndb3;p-e6;S_;Wl|Z>7DiNLlIR z@ak~~^GhMOKjmrsu0m2?k7TSB2*Jo9jThP*L|)+=|3~ znSO>tTzO}>T*O)dLg##3BbK*S-|nL;73Ttd0t`}kAij`M!$+6>#)|gNLb$j|6{zZ= z_%fv|yTurd?3IWIvq;&m1d^o=LxI8O@8h6CZYZP_b-wjr#W!u=hNKUFDCaZW=&Z!9 zgxzprZx<5#y*rD6+$YFem(xxiDb4cKAw**TH-wIm z)O-?Q9%+YK908ELrPZtZ(q9_)7Z`_VhK(@AoUXrG-&m;m&_OH**IRFmX zlc=!OWtR#gCV5ZH$Wh8XRf}Rz+G=hs4fSQ@!zCl#=ChbFH+!b}eU`FlNnG~V(&-R; z=J(+a2V6bSaif!Uu`0~d4%Z7&)=T}p#UVcdA^d!KV>pOMZcC>lx~$}QY||B{UMdvD zNVHmjVk9ZDlTcl{sw%u|s_VGq5lWy!G@~ec-OPu_N8CR=;_1n{Qm=;*qh#b^!0B{G zO4$wY*C4dt`#p)%rn0>^jNQ&bXU5Qc{a#0sn{55dU;bjznMtr&Z}9frTRc2IBBzAY z`Gj#;;pyoCkc5Bx^PiDY!e9RK7hGNKaXOtaO$lYHk-9z%7V$3vTwU#OdwcB!met|i zY_|CD;T`Vp@3CHQFbpGJUS6V+;Cj8r`D}9ga6F>841aidFei>0!7${El>_A zEBx}yFBr!aRx5Lyy?_5M?n69qdwYvv95G}|b*5u6XOcSnF>+bBeI_^M| zPYQ*U327Lx+ih?@O(^w@kDq?V+YcX*$I-{1aCi3>4__W^kFjpIgL_eU*26MgopQDr zo&5iv4C`gxi~w8^n%rj=9lLaZi{l`P8gL>KdWA&hvc|XoI8Bpvf%k}hekWih9M}|Z zzu#M$xj#%!8Jq3K$fi;v!n)L!<`-iVVJ(wRzMH{&33E-;WKQ_5p^L4x-OTkG!IooNyc9ziTAIiY3GB>q~D zC3-zutJRL|U+eY3C7s#NJ@rAakCyWhdTJ46x+F}$ri1>`W%fq6$3W?vK&g$WBZ_ME z1#=Q$f~Oqw(*m$|so%pei(^F;$Bk&2B0};CwnjyrIIKV^V2#Jf%XI>YH9Z@qFrky+ z84ylpgez7OavlI!2F=G$pYix)cFOT|#A;mO`|tmN+q>J?D>;cbyvz9c?|;YfbjFx7 zpcb_~c)16jStG|9reL;}Es*`h@*EbHX3rOTG3>(D-5#o7U2hVUltpl?q=Ilh@tiPS z7hXDoQI*y017i8)a5eQ_84}A{4cAueJjjWvgQK=%Yp?d@iBhKvUc{w)a_6 zFQ#|fgo@vjQPd4lX&6k+fzUZn+*U@duOj#=Q}8`PSQw41j)t20YZx!i^ju5De>(4x zu+&{&mn(KZVs%>|$Nt?uvOVGJ=(d=URBOeULLOC5yB~%Fa^6Jq;Z)5bLIT!9h9T@+ zpE5LE0mTA&1eW~(+7ik!CvWED!C!VXP%&9xRvNtdkU}(f^Wbx&7GUvPu71wAwpiE$ z{oi|nlRA9%d3pW4Jwe**hGk~!Qr7q1b14v{|4fg4m-dd~|4^#2e@T)yq43XN-$>GL z*RNhnBBmV}8ux&pBB?0~7M)Lda1x`UPA0@E1(pB|`KQ3IZsZz7saE&Hjqu1Kl7v** zX-}c$9FY-rCmtSC11W?cl{x%(FO)7MZ8Hvs6Fz?W8NdAfBMzqtIjwMYwa16=-&usm zFMmhMqd9x3JwFSv_g4s>P!8>N0^(P-x|W~s$eB541(*`QUT?5kt+Cndu^$>}8itIV zEiG)b*?5$vb*X24t(-Id^d~c1tqDxQ`*&{v5uDE_48!12q^pSfczAfg=g*%b9dVi_ zTwPru=N!>DIS+V#c)*xPGp4d&x7}dO2Ef+i4ml-^s}11fZWmqEZCNXBu6B+5 z@T;nO%0;aHQYnBieX|LEz&%DHpoiUrsKJNib66d;se?F@?wBfSE?5ngK2eSnKK}ey zym|K?DX(xY1*>s`o3|hE`22(dOW}pWi*PT9_>KTu8UX!ky#iX2fm9weY`7*Og6ips zA`-^wd78oyWrU8Z*KwPsR>!5P73xk2tJMm(H#Zo^0WU8t-96=OQF|g0bycd>)5<9a z2-a%ncsibtSci$vN;1$kT&t0!b5b)zPXY)UOAKTI%1(+Abo zcn4_n$(n;pLTXMvbl;CgF0?fwXtk)(1VPnga|Q7ZxM=CC0S=vL6W()PB15a9%4@Rh z6)5Qb<<*RiW*jUDwfgD<9K7$PUAieklTI z1FxDYa>_WL3x4_K?;fRpLK;WxuWs?-!@uBqe}%)-6V{tOswULZ9FHV9ps!^{zc$M# zU>b1ZGO*V<{4DUAXy@-KrD&M9-|x-AQY&(@MtnJ2W0>uB1y$fYov_{Q@o)eB?+_9E zn0|Ca!Rnr+llsW_JB=VyHR@`#j-08R3U_wPRh(fjc5fV;ap+}}Sy z(V_;gu6EdrBc5MgupR~o6yq@9&3Fe9OM&0*wh^rjD7M=*w%bkMgT8Aq%gsy^YgyM< zr86v>1+GWtpO4O|+4oG>fQWh^m4ZBEtX2c2Qt|ZkfG=Nu!MpGN1+`cX_5S(}yZuKz zKi*?Nf=IPyAewn%LRYqP3y2!=VEd&Rod8@`&d+X7fHET6o_}gabFG-p-uTK(snFrZ zNY7G=l_K#Bl_<5))lc1QHqkuscs$yevNeww#t{NU<_X8f=acFL|J2nQElp>$X&EyP zDCJmAh0ke*Qgf7v*jiguSa$NvB6>(pM`USnaysNC&keCylW9D^+~56PCs_5UZ$`^ zNVv0zpQ<{!BC#H9fx{pr65^uO$x|SUVOOoK9ErUdkrJE9f{8cOG0VjFm!f*qw;83Y$^r5OZ?9N|e?xR3e6RK&e1o z86XSYdl&I(wv!f~6g zjA3?(vvVnLkn zpYJ(as~qzNKP#%9If)ES8=D6`czs-rXxrpEhYk|EER(1Do=92&SUILRN|4a)Hn+bn zB$sl0`7__cYl-ofzyI33mo@`AjJEgYy5`cjEW<)xjHE6nsIQn;*D&I)b zZ`ZG1G@g=mHVPpnuCywwE{E0$wVt8%425Dk6|9B~K{g{d*=N*4;eqNM(Fj@?z2%+K z3W*Sn?uf|?AKS(kRFB}}Sc* zw$Zs)1i1h5gsS2lX`HK^+JFM3$JU_n#K)Tvr z1^F_LqovZt)i=dLV#K4Wq$zoN zF{432*KwAAXKYLsORcFM5ff|ZMxjMxW^9n~^8A3uhkIPV`CxNd3U>P&Y2a2N(`x4Vnv41B(lSj6cBCtSPo8bJ^*(iOSyp~<2pMbK4)aPmPQZd^6c z)zzX=MZ|@u1Vl1ohWi5u>kwx6((C&*z_26{FA^AfOZ`?>9tfBo~nqD&Ju+by(Oz0|kw-=a)TREv>m z3gG$WXr*4(YkdCnsio?xVsMhzn)Ds;?%jJlKfmDN;U42S;_mJahr>CXa@)-gDG8?O zjO?A{uWzm~E&(55@Y+iI=T`Y=Gm8K(S z)@E59hgg8JLX*p;T0PoO8(HaCp}1pjvmPOG#>3~2c=zrHWU=QN#x?Hl-r;z7alGWl z7dm-}X0+P+8D`48ybx(5d-u#D*6@zyQz%g-rvi@6;W|U zDMzSQoKDt^6{^s3GCKn`_Lqof7=TV!X=h8k*8+n^d=13Y+(Kr@sw#Izt5Mqq2PK~u zQGb*r8Rx0s{{AyQe|`Wk;LV30aeaM4*%u;DI1V!J(OtqyzKQ5i%hI$MXj%;B2(0!TVD-Q4FQ zlrF!+-kVcKoDct;c=m=C%6WC$v&jk7!DWK9eUnT+LK2b;P_fi$6?kOmfSLf65sGZI zW(GtuvNvhsTJel)RiGMaDwXTwB)ZprcBJaFonj5l2O^G7xT$W7fHoT8V z;MQKz`;76so8w034qCpsdkrFC%h`MqZwjIjU{@2Ab}PxpAh5xVs-~yy+4|4T4{+cg z(5cO5CjK{^ZTIykP0u+MzFE0vO@^{;TF6)cA_cW3oK8o)yqL~QgGA{xX3sHN)r=l^ z6s-VxFkMm=wVolV^+c(Xy%ZDI(d=bq83rV%m#L7NqP8*G6m|RHwSBN862C?$+Op2m z*nbPI|JuFdcY!qqOl^<+Bc1a#61CT#OP$ouL401RzdQSeYx57E?DF-EB>i^%>eYj$ znSgZ(Wn_VO?bS1CIiZvZFNbHmsN!b7$B;;J!fVX+B&GqPr1Z)VIMxWjG7=fx?sIW9zH)JRyLtGEF;}onz0DL48COGj*%lo ziq-d1$|K6D;Fq8OhV9Ob_EHMQJYc$Uu1zyCy=^{x9Lt?Gd5;dq9O%niL-Sl$*hyiSC9C(~6 z&PDL{{rA}IuCZEK!=R}eSyyU-jsV06(vzP#Hk+`t{|ocK%s}Y$m1^Zw=PI^q!*-Owga?|FUSwR*t z>8FTD3Fu_}Or|N<7|jtX@TMNtFeKjV>u9>aBd(Pz*ghX}P)(Zj>5Pr+nq#2;T+MY$ z!_CV&!6MdJ0!q0d+?@8AT9H=?dB~lH zAO7$LSNj{JJb1EQ!ujm)b|siVQqbxnuU0EuU*F=d|NDRA;mbX~e{&O9Fl3WD=JUXT z<@)lyT6Ok0rL85l|Dx_Od>wgCNpz%SBoWvQ*sMdwC))mQO|V*41n0gHUe%o@e80&` zi~8&XMXSQ`MFNsSJyl%2-R2f|A1{gYy6usYS#!#dn}vtUKZFoQr;LwRc-jX;T$@G<}$~KO6ql52qZjv z!QlZFqMotk`>8r^puE-BGSI%$#>d*(L-tY$RUnd^E)k0WC9w}*A7B8|78MC11(FBH zcsWXN#kq<=9{`d)8rO>eP?mi~?k?+qE_nsSEX_aL%kBOimu$JEt^Uex0p{OD^%V0t z*9Xgc%|73aVX0r1-`S6=|NH#e;|=&d*Ef>%+x4qgPtpMZJ)A{N$RsVO<%n7i(0YQ_ zGm=)^>_@yj9`N#bkL#P85NAmm(Llkh>NQ6JumU=bP&4+j2_R}oG4Gnyn>H5N> zsf&D{2){$TQ>cVcl%&{f1iPyNNEuZNPSb=MN*e$YL^IMbxM$iz`bo;lLg4iC))OmQ zHPSSJxu9AS7yZ2Vf;(`Cd%(6^^B(WkYp6$$TFuA`)s;0g$Qj%123K24qs)1Q-5-8L zN+fmaYoVgmI_!={HfovNC}<0pU>$fh6r#|YL8#nCI+{Tn1MX0IJ{cL;E2#Ng@LJ9f zU+W{H2=K(mqsp{2gwfmfp6?BrcO?Y?83sUsniBGMi^KChK7afx-o5_;<1k=74%n_Y zR=@Lnz-GwN1zoEd^NgmUky>gEFic~Jpz&(A!#b@|C!6c_YK84)gK-$JySlQ@x{=bD z1B4`aG&5Q{T#$UKo-X6ySBhn>_e#{kfH*K$MG%h2^BSK0d?Og+B`er zur=q{UK?vmQpo<*h9%vYq){10q!{T{eczE_jk;p5lHoe2 zMVG)z|N8H_Xk#^itqy$s*~$^92dJK*<&30?o81~uPfz&r$DvjRc*#lt179 z7KEITBxCZ1G}XHu*V+K_C3zTo6gBE5a^J-IVZQHv9r!jQYO~&8x7%SHte)C1WNg-J zl+g%FI$t)M4X*cloX%$q zv-k+30SXU()lM<_9%kSL7f`zSbAuCA=P9CS=cvgT-x;xgxLd^+QNIzg-VNEQhv<>_>8 z;J+J=s$#WT;cB;odPYJLK^{kJ)*EcM8*IC#K|{`fh-WT1`U#o&bs4}f)LNjqIR>Rk zB`27<_W{sp9oVOl0k-VwsfxZg+(-}7L^X6C37e>8%qX&$5&=6(`v+_vgHc_M^7<&q z3p$CzA1$$(ydW~pnI`lf$B*JObte$&PKWtSP$4WUsA%~hBldy9A5@0%KcMywx1Y<$UPux*)k-fBAT$m8ZU{- z6ARZCpVMMxt^8}0!bGWe1*!?v=TWOqx;SB;5({qF?~+i&up3067@$c|)Ot@C_H|NK z+<~W_eWoO>Dzqpx+ZxtZG}WFfJIUvBE8GKtbNiaW#4i93d4iaz^toXikrCh|w0R#5 z@g~vG&+#RiuA32aVXw74-3UUzhcp6~cu8Ouw<^mov}dzAwDuf*#uGCDtgM5!`}-%^ zWUt8?1SW3dX}Hdu4=$r>(^W1#(cl{Qi`8yQ&A;NM5Q_MYOoML;!G1JzS~Y8dV{++cUZ4RJl}tT ztjDP3dOllW{BanO07(U_>C?&=2oS08fflqyCYLhB{3u#gBfx63iYN*l z1zfXGumlp#NS&wM(wI%LN5AF-2t_ngp71l)#?5E2t>jU9z6p8-|C-2wkMojot^x9Z z6x@aV>mK`s(Z@a8z|=g7rQdg#2-NCnXN(Le)!MYoj4?kiRe)5{5ZJ4W=cGApmcXMg zJF%?IBi*@*@%8lz#bkkjZ$VEKeGOE_>oCVbtiMP3^+3b+O`bWu{@F_eQNPj59t!0N zq9gykzoi)Cr6U-S2M^6a+@`ePB=9gxp>~?oNE^?(KHFSrlm7Gxi*%GEz<>lDSB0u~zb;rf0jgz&vNFR@`eqpiR1xzLe* z-yq>~+^d}#-W!1Ch~}gIsFil3KytQhL=_Y@k`y^%vM&JuPpvoHn-xfIdlm(h_03_p z3J?qy<`1ZN9qt^_=i+wl(yr^}0asDoxb+O>usQ*W8tqMXiIM#-qj;tz7)+9lHqK5h zhR9Gf0u=B-Cq}dTZquf4ZO*B;{oE$Ul!njy&$PW`kJ;pQ1TpaY!Fr%B$K%;O@J8dV zevjTF*XAIW7JOyjD=}`q7Td5BqP_D;wdn+YVK{B7)l)wnkH|S=97mK|z-E_$r@S5} z^`EaG2Osy2X9yhc^MeeC*WAXu$u;7Pw8mb*9BcIQ{FNM*HkL~~LvQn3vdNYy=UkHY7s=NJrfsqUvwQY7Er2M~gbUyETdr>;>9^}2UKAd&sqIw* zAFwogkqIeTT1tXIOTzK+fIN(Nc|PFjX@l$Q8#od-rPUEJlpZ33zn&}tP|O%r07(=z z(V&IbL$w-*lOC*?cyiICo_J8%0lNV_6E-kqV-m z=%_bZS(A<3d0Erb6qq380mFKQ)thy6;T5s&&-?ui#ssXA)m~d~w}5($IBAhD(#@Hr zHT7gcli&TmDBYX_Evk?P0ME^Qt%0aj<_4_z{*06pT>{nyPhuZ*Ma6qy8%5s3fP|mT zw$4TdrC22zos6aqqN3YRO9O4We_tDI_G~tY&THAN^`%Ik`Tp%9bh^(04Sd8t^YREO zC65}g_fi&ESqbZQS_v-W;TmA@CF^Ygkm0=qAo>ywB*}RX@%zRz2IAyv?fYJx50{0M z1Fi&S_#ym?j zpfCvKQJo=*6>M%Jz$}tBNHWDMBCN*_>X;|7mRwrusir!NJR~B}+5P%GS4wjNYD5UN z{m1*x$Ww^x&t9Hurvp0-=DLyJ;iH&68!(sQ#2!_REK9jz%rcoHRFv5eF4$u%6qw!6 z7IV-JsCFeqI)|Sdx=TIBx$6nvSRd3^a|<+mNr#**y*ZV#f*)A0f8)e85ICpsK-I!gTwi<;tkFJkcLlxq<-qyO* zim4X7d-o1`81VS;gjy;F5PPySIk5pkZjpLU9 z(-wv@$$mvuWFH5yWJbe|oZkw2AJf*WWKC02EP3 z%1G)?2@w>ZXj|i+NFrWpglF#3%Gnzu@%a_4VJg92XK#VfEo6r`GY(y3ckRoXNXjN# zE7SCe#rw(ZuVj0W_M_KBH4@!ch)+cde!r^A{pNEElF;*#X8*{3c*T`)+}+PHr~FwY`i%%Yz(v}g{XN$= zlJwj4t5?5C1vzT&Bz42C7650UPGA$J1jTlhG3FJfQn4O04lnoE@Ap`*Z*YoK)h8L&;)uYXfahS03o`EZ(MnM(rfYx5qT2b}O_hsZe?3_UANP?9tPIs(MK%Qn@FT$meE zp+M0oaK%L-$#M42*8hF}tbMee0ggT*Wp?lG1-qpnWuk~KRSa$Klv;tV=2a;LCnrRw zX~Ow@@-)6ic2N;*HXE$h>-hf7W`iMT4C9Dl9Kn>E)i6M^0j;SNNFFhcYfL#Kp``>Q zvHpd%u!E`zZ-sX`?TtA%jJ$5Vp9=(`n3%ev24Yeu-jFP6y>24dAWggV_5~x!!Qbs4>CTMR_%(y!b-4$0dKk4A2wV7<;b9A2>9?lG?KP}pshGO%_euEM}m zROf1PFF9xyu}lFHZ}ys*VkZB@1GZ9tb*2o*zW1fB0b-@4#;FE))>vzE2AU2OH*{$p zSbgZ_ndpBe$@jI0u2*LYoi19)T)5d8_ZFV>21@7h0?klXOTS~5FAYL-p81-4m)=OE zpx#%`lOGeAk2~x$Kk!0f$a~beldNwJ#5v}#mU1m2qs13m(!Aa?&_x7xbIP+woia^R z{Lb|EB-Z>xL?U`~95QketOZz&E35hGk)D#Q?qu~QS$Q0>T5plZ5rY&fIneFf{`vZ7 zi2}zU9`V&@2V?+}%_&*DCU}yJlt};*W4KJn$!jb+IpSG0Mp#tuB+c{Sc*-WrjUmL` zqLbnMzU=E$_E$U`b%o=z>cmi#y=xh~v8OY0Aj77Q)_xuMvptz4BWI12Q2V-uJ=l;- z1jyO;MJW?Xxr}!-jC{=Io_lGjclvWi-D}&tx_&P>PbZAxk=`!Hn(?ldHN|HWe@?-C za$F(s2oXE-tW0GxQnJIS{rLEtGow};0s6|&?Jy`Y=B2BBhDLt{F}I2t^#AO|`oIvG z$(aNX#?T4YqaB9FRG>)6&c?rM*5z4t~wMozXeK2DY*S>UcK4U5dQ z=t5QXW^?AGBN4&|f1v&mSnjUR7ld_a#qZOWmGzO0@Q_wB9>j>Lb5^%=DPsC=f4#?M zx4~&T<9sf5{%eU;XX-HZFN_s%y=SY`vI)&emmB#9gp&*~EUT%Jf<|tdUbW|Qa#PKT zV&oe35}zqsEl~gkT>~6jB|rqlZ3#^hWvYfD!_6L#Rn>5U zM<9WpFFQ$o_9cNBxV?uYIbz{RXeDdG9o{iT7Oo@%(*&i41>5LG)po{pi^% z>eU3WM^Q+Ecom)r6GV)_(mFVxw@$@C!D<|kQbkURsZ<;eFF?M6BX(==IkWxygmz3wL#>5MNgFEMt0 zC+mTY!-$j39-zov78zoa=nI8j@ zOzXb@yp}}da<9JLvks^V>kM}wzgC}@8US3>BGauy^Xrs!>3&!mlKuGlXJ^TY_DAAqn;b+$f#l5m_1942R9aUP7wLIR`CWB zfa#ymMSiO&Szvo*^oDtl_YW=u5>$&3jtdaogY{-W>#O~|JWExpM`z*{c;f>UCbK2)Sbz*L-n!UpN#Vavx)h1&U4WRcm7D>## zl6AF)?k%ODc7&&@x>N0pVHj{epK&}MPMOcWTA2!xuC?HF zHXK!8du_A3GULBa7_?==)b82)y#Xks+L-}U4WVJwGhkZ8^aS8WyH6e+201rbKo?n% zUSaIfm~T!Nii;2$KF@vh>ZLupOifQ+)LmOyk8*(%nm|P0!JBW0|I9Tu+qBN)mO1yd zn*(uzJ$3VmW{h`xt;tE5?SuZ=mNiE?-z=lET(cRzaF`qN!ifZ}rR{x!gzhY;C`42D zn#7Nh2@)T9txqGGw2O=lS+H>O_df?Yx{xMIOc@6H;+o@5!xJeQ9{HaA9VDp;9R!LD z@yN$&ndfRmkwx+fSn{O$^JFyHrx3gx4%iIWW~;cKSNI;nfQWvKEC`>EAXv;f;g5)x zu`(x{V`Zd~h=}tRKgJTem0>zbi1Rup1#u*FM)aM}XGjv<+}z;&`~^?X&)D2tqhdm) ztx{dCIzF968vEJEDWR5vQb_}8U?YLacMi61Y-XbqC+Wm{=bFvJaTWn250GJvlms~^ zq#+~80LXxIIeRIPjN*MGipw9B95o>UBSHn#_arU>s{@|AZfc6mDX**_&svGw#qB`H zcijK#B@9#n@e&b+Lk$~Kn25`+UZ=%SC<}Zp8YXNqwYMK_-ym=kc)Ge{n5EAMH2KzQ zU%JBygjyU|!#4IZ2{yh&dbT!4agbb&np|cW6mF4;{rZO-(eAacVBh!|aL03}`)h6W zKf5`VkdGu7mn58hc{t|;-RI!z?=I>($30xT^ZAUImxDP}vl08@qe`7E<6}{24leGm zUWal4+iG^t7CMvilsXr_8veZscU&UI8P6`A{_@A1Wdp^!)fu)6Cm7~>yUk_yEV5if zAFT>RENG2uzT^hx>qDpLqMwWE?6v-LOER_To~BcSTX=i^%>SgsDGP0*c zyXZhtf#?~62^oWto2epsg*R2EN>z-br8rhinCcm;VT;7>a6kxf(-qQzLGd6ykCIC% z1cV8*+NB2&pf=a+0^2mz@`9C5XdIFZ;wFI)4KNxDXGuTs8ehctRBk|JrToO!7&76~L=6MoG)TNsd zJN~Rwnc}snOIH*KPUjO2hXdf=yOVc+SHLWH{`36z71_KTQ)hGcfObh7|K5w_RU2PI zmH|*Ng#kZL3 zzQx+aye#&-dUR(`d`{DZ)9HjVO_)w+Ga$60PK@4br6+RE*ladftyYm@Cn8v_EE1I8 zopTO(*>sBQ7;Vp}9{ptv!z$7+m@F+d3?F8TY_^`+a6ADJ=;Ym|FUSc_p}3K>B+GGjlIzT%jq$e|}Z+VrjM9-zY%{k-M^ozXu%yORXd>TQ{NT-yHI6Y4j z)^OS7gap&=72=MGW=Io9M08VF&E5X&#wucsQG30z#44Bc(AQ*B|M#{om-g#&A5*qd zXiKcuKXVC^MMbht0Mote1W19E19Qh*O-O0PN)jeyh)hUQP%@BKYm_pel!BZrID*3s z7|l$r$eYzhh50`Tt%0P71feS8^%kW&2X@n$tc!WlhF_=yQ~bU>2lLO_pluKDwp+Y? z`xgKA=b!N9;Rzq!+(HXl)dsOlJ<3fwb4(|w)l5|0T4Rd?EUBS z3CGhBDX$17y5Fj@G7UThsKt)$hntLH0IDU@=HDzK=g%^o$&&P3ekZeEm*csF6~0D}axKMc{pSQnGT|Edr>}1$ z>9^}wuiof!|D-FaGoWVxCs-G}Z)`nqaz!kuk6_sW$!OucbUhV1BrJu)QQGUI`oF^Y=#U+~}0bGq+ic4udwT#A%UQUqweC4+_m3J@R)HvCsxuqct>S~OQ&(J&y#U z4O&)1w;L3)ktZ8PB1PY~u(#(>H{5ER5q_TIf{a3O9%qdAM92)4i*YjDL=f$<;S_D0bfdKNx+ICB=cX3L%P4GRBGtYUR({uAx)xofw z{~>|cd2V^F=WCwp*>wh*{#!57fk^RnGujm>R4fe;C|)~mqM;&KvAU93u*d~iuOT0V z=?1P$5OkXH0N!i@5xphpzf>6mtUZg?qGqy*0`>9^3bcJVXSG&?sYPsjs-bjRokojD zlGcnyuY$6!c)D%a_8l)S7mGYdhOXH`75fGm_J-$$#-vy;mB?1$YjYh!U~=*)dWHk! zVBq5C^0|1fcIp{Tp30@53sa19L!IWG*-I(dYem~Oi1YlX+YJv752(9E8gJW%ecw>Z z5`QUMM_@%jJse-4zdSE3V4|E!sPuE0y1AopC(NvBvFOv3O2d5^+aQZI<#X z5=syEXi$i}tcmKZtR#A!_(&ed{Ca*rJC@HBtMuvNd(wJSNOidYDp8p8Y(w=YH;I@t^*m z@8Rv^X3>|9ZChc+hRuT*GDqFzCXgZpMHN;pl;f~+9@R^ASSFsQ$pcu{70YtL~oTPy(3~2yRyd;3@6}jChwno68HCrwdQkQwnh8Umm zAkg?+1#r1s@pOB_wr{vD)@5$Nb4&tgtpCXGg+av zwQnfxXxPm{jA`hz0am0$qob(F=24&fwxMpD6^r+@MF5uST@Cn@vfz5X0IGQP@+Drs zer@w_)#^Sj3rxs*L3PCd*hG5NE9blKy8$@|5m_jQP;lTn8wAg4U^Xme`kp`A>z|I#I5WP` zprg`_2s9obfr00QuC34P3>eScFgFKF>YzcIrM%erO?p^4?%mn5XRw^tB7crNB1dPF zX!H5a=YLkH&c<=35a;Lqwt0 zSgEv7*$|| za=l`!))YWqSmO>;OpbdpE5IjM`gk^yGDaRT8$C1q53~=B=nK9-KPRW&^C$1YXR-Mh zYkr>9P$f@i+I#-jY6Y~R)`r{D6E-)9vU@wn%`>sCD_*^Nh3oZdazQn+P%JBEvBn_j zU(AO_40I=7=L?Bn+bb|dk;*m#3yCYS3ZBnSJ1loo(pnpx8y{gBe^V;4JxZs`EA0nK zy3suIkk0qpAj`if4;YPpi0AXOXBgy+ug}JSGkSd&Z=C<0r}tmyYKV&~C_Z83uSXq{Zri^&o++KnqwBfkqdOX~c8T zjxFXn5*N9MOwF>6_|*2;M!=u%zS4~km!|i1I88CfpF*GQ(SkIFG!J&L$bFICm0P_w zZLQ|0wnko-eqXepl?7#4QT?nH^yomK>n^m2*n07Id#eIHv(9J8uLKt2eqp4WkmbNo zXLQCT{QV!oHwxhCcEh*7{cU{w$=C4a&F9w8C>qL$qf>-@WLX&X$X>e?=)P%5p)uT(Gzi^m4smSyrnJTD)ecdgN(SY`Q_!%DFjGwsd+0niOmH zySH!{mD22lXb(t%0L{m?sM1y%=TtSFA-^{={le|eO>oW*RY^}RGf1$A1m&-FTCGXUK{BEL^3 z4~jbEu}5OTOy!70XMQ`sMt*)M=LXXas3XQ6rtkM!)9Fk)79*x4U0ASmm#2Mv<}4M~ z8dVPv6RSJ^`1BY(3bL$?X9|Wopl3RE*748I|CzqyFgLVSN%DhxO03y`9(6Wj|1#3~ z#5)F^BtIvudB&8yZ~uO><8XARvPD8i@0k$ir2+ay-44D#{3(O<3EXmmF}}$4!ASby zdgm2~D|ySTIJI@NFY0Df?cTBsN(I)n(>my_K)D21Y+l!ebu&rAO%+R0?)u@T`5^&? zFj_ei6EbxNLn6^Bk>AP8B8oJFjIcAN)>vD{nrM`D!R@wT-!|a>jtdkXEc@3DTqa;T z6MUBG4d3tMtIgBjVL{ zh4{$lKPq6eGIS6k;vKhB2>|L}6Ij-mE`jBcn z(cui5N|6zCOlK&6b~e8D&zaDj&*Ch!^SqB|lVkIJ>6{9xg0`CxM?DX;_$N$}>Pp~z ze$SjIvmqhI>4=U-r^EZ{{?F~l%y;JB&x{zydyppi{rA^qjYnI}MaE|<0Bsu33URkS4Nveyz^ARdL%*|;l5U|r~j3c(`mSe@2kD)O%!U;@`8uC+# zrr^*p3Ba3WjORETGx_@C(-R&a9&o$eV!XRM*lxEQE~{m2JUl$u-njC5xm>NT^t$5i z?hbc%cTo>CM?OUdaS`05^=N9fNDGpD$H*5TMkk>Rrgh@EkN-O;kBo_R4QxZjfLMSL zLZw)=gr+sRZ8uwAZ!D;VrD{g3z*J#toN08@S{)jE4G}HAU)&?E(;1x%vQ=hTG+r5B zobm3NpHgEvdlhJ8GYFRfeVo3l|lE1@P&#`}$m z;w0B5d95&C5DoIZoK2^nec!|BYsPkUngBUw=fU1gYu<}daX!lCfgY-w$d6jq2qVP& zUAtp!?a8HKAV?;jxR))n8+DS&S9LTjyze#WD{vZ;9i>z_B8qbvQSc(rlAJ*mP$^I> zXzt*yMXk0oi=K~+!PZjf(6i~VY)VrMsr7K@FH41$kVS4H&$s}@yK*RDG~-mRGI9EV zgCJ--@bOnZ!GHG)zlgv1&;JSA-f+KM-3cY(%!AnYnj(z*Tdj_7+(IJ->*b2FELhen zuGbeR>jleY#j>o%!^&do=nnZ!6`OjdnYC_5E)4^@godXmUUL^#H&y}20+p@Pk1p;+ zkN_qMg{XQ%MmjNCV3vIKa~;IfYq~n0HNK1(Rdb$Cz#&>3Gk8sJNMuLaGx!_~=O5a! z_fhXNz))iEovwY1v0nUc@E!FU#XcSK10y-K=1DH(ebbo^e#Ox<8n0>M$;4sQQD(#2 zh+~Pjpd($M@52!TXPGs=KjO1dcd)%Te!}ngv%rYL9<0JD3P3S=p*bSi<-TY{IkIfi zwrzO(_ANvNcXxLqCc`-Qnb&4spXFlyJ>qNaR%fLr1#>D0Y_uBxXzX&s!|HYhh z*@1~!Rv7qaZM1A88I;uYoFRP@T?x2(y1T04cDwbzTf^qHLHB(#&+fisDJ9b3scVe{uGgy-h8Mx=d%^u1E$t})6bDq|QE~(q z%QB|YcELItJUXp&-A1J}f0ow(j7uRR8i2RDG_fcqwP*qWi${LL&k>_WAqE^MXf*BH znKCAV0KR!WvSK|8;=J$qexs7tulaQ~BB^)Tm($BkJGhhf%)v_zR^%B>vI~C|qYpDBdE}o-&`YlqG=W40>DhaeAaC>)6#=vE4S*RwKKBm$`uH*If6G*djZG;NCK~9?c{3EK+wNHu7ytZa&QUb$7H*6Ie5Zjd1O2?bY)Mf!S$5e6+} z2Kil{`?%NYPLXb8uw@dh$wqnt`JL03ZNKL_t)?T9xHz`Ajt?T8 zc3iC<=__6Dz^FI$;17XRF4-~IBL6hnwK10kSY*LcEFE1H_=R8iMf~8e{~B)}Z@7DX zhZ=mzoI|#2RwAo4tDU`G?oie%?q6CziRE&K)tjLjff>Kst71n3o1#N|(@z~}LA-W5 zTvu~k-&l)U%mAqkmOE>kRv@U_0%sLjpjwkr(gJgYSf4cKe~1WX`@1-Q4H|`v4iJ~! zRu-i?D>2@k%hFJ942Lbc5jOMMkk`@!Y%&3tQbMK?gP^rRuL<5nUI`2IXvNn~?D^D{ zl-X&2+H})nEXtynel^& zKo;(aohiC>vjM!z7~iYJphP74rMzn|W*zN0Jz~a~T|RcK-CD;{fF9_9_W_Lmmylbt z&Wqu*BxLj3cv%dl+mkCOhP8j+>w}T>!}ZR~goNdRmD12^L)$l$Rt>C+GYl8N*;!%(05zi>6~Uzx?DhG>H#5il`YZ%O(S~)HEoB+f$!ScxTrN?I?RL9` z(#eb8skP$i=?VMpU2{_u=+o0vM1j6|@dE3z;PLToq~p=(dUsv%^8Oz8FJ9o~ix*aJ zFFM7qU8ty{EDJ7PmqlD@WfUx*--*Iw$2_W0n|gX}XL_Xw78C=Qs-4FZz=MLW8XzhD zj{nX&T?F^78LbsH!;013Y@iZNFjHI!?}iT(cCA*A1W>Do*Bso5)fCiaF@q?MJQJ#b3&@0+RNz1pJyKn|LX(AWzJE@2 z$>XuH6P#!OV}YWz9m@6db|-H7JDmL)9ApqV8zW}ELW4v0PG?%k*O_7M4A|t~&wxu- z_Q(Awr_cQ&SETVt!_t7g0{d-;cKMA&FW3I8lPz_S~^5u`?%~CyGJV5k^y7fy)`hpMMO~d9gj~>mXfA| z*2bo0c@Ji#VK!dP-{Jdn^E`gGxD!lOqb@Y%Mn0pe=2Y9fao)b~=G;mt@ehxWSW3bD zix+r$d<6Xd>#|ssEr7f06)#@Az{g+yvNcU=ip3pim#Z24_ub}y|Ke)$L1+lIlzYIV z;M)#H-HMc`&1nB?7NI2_s2f@bQb(nL1awexorkkvPc%g&MLBXES(|%a^UN#fvnI{> zYEebocC-d8t6&#kDGM&^ok=?9X$u?0$jC={?|DpF_KL{hOqrFAGdz-cyBV`>t#V11 zt_+VxfH^YMf_IL5aHg+3KGmaAHmBYJJz{oFW6W|@wE{XCtn)MSch2P2ynifJb7mNr z=f`_i*J2f}Fh(tMKZk*nT;@VicXt#oi^-J+?`Yl?-r@}%jn8=$jyhgJzq$jyHy{~h zjC%AY`K6)=og|sNA%55CHQpy))x;SmoC7U@cV`c*<&KP>R-p}5!@x^S|H z%%hRMZA4yk}a`>YIlU+o}TcyEO;R=P%gzv6gj;e(g->dY8VywG%&6#-pecB_}cFHL`^sq_m z3Q+~5mhiBt zGAgGFS$KqH@%1u5Kt^odV^NE6JOI#QAfRgR(%9U)Y-{T9NvXJj=&IxQlt}v}kC=S5z zOjB+X7!ia*a|Tk{uy=|a9Y#9R_5^LaD_RuF2m}Aj+va_L4s47Y4U5+2`k)&a&b+%b zIGfX~XRtHS&h+egoVkP2th;Zfp`*MuS$g zX0pqoWGXuNKd<4N_l$-qes%`d{JpvJigHQSjGd2&Vl(L-}7Ku-BjYJje z^@11o_htZn`4XRe@(G@vp3rJFr{20)X%wUgLa{byd0yMLgHdxfUN^?W0d`ridQ&A4 zU(cwd#|n*xkfZh>9iZSEuqLIAzbmtb7q)f_hnLZyeTq8MAm?N3qfs=UyXR8u09U$T znH!NZsixE{mrJrLU>HlLVRKd-l`zuI%)|Q;%u!B9C3Tip=7Smy=k|J6QfHZ!KOai{ zfZ2|zdHuV-mHz$gP|S1f4kjQgK7*k@%r>)Ar#T+%#^Ah9`B{0*N)Ky(R+i6u-kSC_ zNmo|YZ==ZavSVm-@Kz5ppfRtPf&iGZ>xL6(Z!%I8XjU%A)=`6pc7B*0n+RMLPPj-n z?uL_CV(mYSH_|Xc3N67&^ZMBD#K(%%%Gr#8`6$2drE2;KSn{d@x?x!u#l$`9SU^2W zQHnq+jdk9PNK6M9@F$3`jra73G2cs7%Zi9|PNQ}*u=;tZs?jGQ)`xP&Ws0~=k=A(< zuQBk$ubIbq86`+@$GM%AU-~D%j88xP5sL1(zgY96b-iG@SRf0707MED1$%3r8D%Af zs&+k2hqI+nH&k{r5)B;-q`kT7MICGf#KDhCid#(U*l4&(#_!+D5 z{Mp)hDHrME_EFhvll%>GL^_|oEYfHwr?~2zd`? z-RMkL$nyX+MPz%5zjn+Z6E?E%(pe|HYkfNu?CNOBoE4;8zhUTj5*IXuVzZ;YBXlrqNoF`LZkr!*yM`LQZ3b8N{N)Q z*mG9|78=gfAwU4PzCR37C9P3_j_KB2K&z+pmtxj^b>M|&QPlf(gNQ<45ge;5SeG@) zJ&p9SOs8|CG|*F}XW-KsVHfG20;Jz}j&{oTnL!p6p$t^)d-S^Z2stW@GeF}rvO(^- z`gXArgA#kLRQB4iBVft@a%$#0o|w0TKpNW>{rmZzyuvfHZmSqdO zzVG{vB7&E%Ug5H?W;FG+5GY=FO=+IxbzN~~eQB}UbL+ZT6pyp?7kBp{g0-k{qZy_j zvleVu#sx?`iuK(Bn5zSB(js7)0dQRii9RS(gz5FB%0s(T%g%y*EMz*Bni8g>kl~EB z;y&cF%gDe?PuWvP*ST<)DVoF6r=U^;&sAL)a<{W(6vDA&v@GH;*h z>FoEJ_hr7$NTW=T2i`1QaX#LE97E>!wKZ?lmcJv1vDtfe{>|`N2Du_Aj!~$f38Ep5 zGuA`&@Gy^VSaBFRJlp7?JGF=P01z-Ijrq(NF!Cb+p8j4G-qD)|B6Z^&o7lKvk8~bu zq=Ai;KPTfx$L?GT>FLqLLopvZ$Xw}7a?EHLk)R2$ zn*2jVU;zjNc28MF@WR0Buq|)N83@0t;q8JZo{GOL_}VwVY1td#K3RSBy|pmrht4PB z#xaXZG@eNd1@)!07jSxIea_-Wqr9!EQJ3`~i`C1|=txU+7BRTR_T6R}O@nN~{oMI8 z70}`t2Otm6^derzlvu%MCE^)b_KYT`&)DhnJ)kW0)u2o+g{9HN8r8CTJhTSFzBjkYXe9Wgb@!xQm*K61A3<}-IpwS?IV~<454dJ_e4ISh^4QK7K;KJj5)@Z4O}rregVn_@WS6s(F@XR3#Bq@ z(D|bWAO{QrA|KXc`WJ<)-#0N<@xnaC89a}5z+tsdGo?l0wIy9J)@H`d+#raIfWZ9m z@i9Ol)8Z*Ow`~JU0zBPrr_n#Eio5F-m&*mWrzfimdUxkhNP_$OdwlfKM<~mJ2QM65 ziZx4GS))FWESAA*X=`PSl7PhP^?3?sc%DcQi3SKHgPapsZpylQI;?*b!50crUzb+V_KE_g zaGSzXmbD8TN0(CiTFpx1SsG^k$+h6`%Ke%YN`5{Io7q5?!Pfje{>;Xm`4O{_?gDq5 z&sntRs6?Kp)$_fq^yhn@0YU<`QkX^qL@tagf;nP5e}CpFGeF_*0HP7itUSY&Y({Yv zabq`-_DMYjX7u0vJ9Yw-#=4Av}v3p0%96`=WE`F<~5n^ z{-?u!=VdF{bhuk8yW*hsVc9>qzf1h1mspY|FCPT=wojq)~>R zHKRpSF10ydho_B$beA1wrrfHc^I%PUlypM{0fMD4%Yy?7G8bXRgz-0t`*+E%g;qAC8A}roEZ7y zIgg!xc3!8!M`uMb^X8dn&Sz&<Q-!?udX1CJe54TM+hSJv9)e+ zw{i3_@#owm&DP~O-g&I!>$8mPcq)1-NvC7-p|NBQ<(3)VEhB|E#(76HIO5u{<8m_u zxlH+|4OSObMyGC9Qf)rYH39H*y>{sP zU*ZPw2GQN-DdG|2dH>9@*&5xMKBTfhV|!f z;*^n=t$S9`ewICy-SF~X*&rAz=(uj9p~dBg@Eo{IgX=7{)^JcQOUB^cz-4RY#^dl= z^Ii=i3r=~;^mmpEVJLJg0+*#dfV5-%JdPL}wK^e|$=J7(w#nse^hz_NY(cY(Ixo2= z(YJ(r-1x;2Ur&719Rx^p!7UI;ji1T$`CZm#wFLp4sN}DMuHkz(V*nfDQC1m0ckJR$ zi2ZiM!^1;wlvs-MaR2@@dzja4kV9!agYHlS>#}-dzlPS>4D->A@``=ivDb=k{mi$p zE^9cd?O6IDg&gjk^)S+P(07&(!5YMAF0D`MP|tbC9{WeEq!f9Xq@FAqGAqlW9@5br zmCklThC?vWLSO@a_@}%+7)d`|@4nR7rWwmBpidArKqg8bk%M~)GLD022W5qn6@r2$ zV&UlMLTCV^aFCFJxg_y8MU???FxouAi@q2gID_*~P z6*b`QuGe8r3>+w4dg?su@tCp0L8=RtHmz4zbe*A~E2Mz?oqhcbVA5OZ%uoRuV2L0Z z`BEJ400=L!fnOLCg9NZr?Tr_h&fjaXj)FG|O$YP#6yjnA)d1nrjbQ9duYfCDwvRc2 zlfbb#&6FI0LS>>U7OzdUKRtOGlohs@#X1pdt(M}`F?7s<-JM&r+HN#(*uF2rID)ae z{0J{8bm(F%MV@VL(7{g^cBjf^k{lF7kOfS!>40veAFd(Mb_5%8Xq5iG<*=SlLRqwcdVRS=V)lQvaeC&y}&M9fC)Q zZtg>K2U}V@JIjm~FiB8k1uN~ zAD1mAD_ig^BqfUUC}RA(l!8_jfAcqgi~s)TzJ*1b)gsif%*wWHQA?Vc1(dJbZNs{* zc=_@rR28eA7dF_VvEy>N;G>T|ihEu?k>#M2b;DU#Y~XcEEs7GQKw86`4$kq;&H7q1K4`Mh zjb%x$9B4TBHXu?!ds0?*&dyUPpyV&AF&5PZugQSD?&iqDk!R#RYpvmSyJ20|1C|&J zSD7!0VKzpC=5sSgIOcU5zklL@NxUY@hqJ%qcu3+!H0r1s7;OK$<16oZKEtDNxSDb54E zJG;@9K)nvFs%MOZZs$P|J}>Vd@3hS`!7>DJTtM0g@z-T1=MDsa1td~sslzmwGtuU3 zud!ik@MIm&giWydcU{(s&yQzGJ@`d{B9XvA|9a}@-iD@G-=;wUaF*^NBM&dZf7{>F1zy1M!_`|=&Pk!<_ z-oAZ8-4zcH5BTh}&%*XVJ?x+V^WVj<|N3vBR^qhoOgz&+<}q0My7O*Hw8i~Or3Hf~ z*YgbzG0W03@rD_3Wfs~8Y$3XMwnKN%TfnoB}W^gq#6^Pff zT*63b0U;fgU@$~cv5o?^WBt@#JMid2`YRsTI_QIJ*Yt2(m-K(0xG1o5k zrl+$B)Bq&NP?lhLLZMD@nbU(B!A^;S{|CbZfwHis835@D1lNeg&H24kgOPSnWXw)e zYU!x7aL+;*0nW@3&z_lRzCS>L&-+?bSb=pj+-n8aUJG$?PcC7V!01ZcV6aD+KVtoR zG^v=f!-z=#e_2Yb`Pq1xl7CFg$;U*7*Q5Cp1&!0i5UonbL0Qs1WChfqZOE|+P{ews zG0k(&U?hVOQ*7&C#J1OIbk$HU`pEho+jm-z*zngIfl4ym`qcaQf_5YXe~*qmDV`33 z09P>tpyyh>4pLwHIh}tpR%cqB)+?`1-upa{{QclJUh|6UmuY7()|6tkBc)(Tk?IzW=@CJcA%Lu3s=~pu3q2O0MIM}WGD3lKE}gKSm4&hMcDYy=^G`qh6i<>fF{& ze6$qo)F>%Oy633Q>-CCPuU_MNx!_A*`Vwy222sWJa>3_yNC*Ms8);6@#zJAg4aW;=1|S7`W1MhE}T9AMc%P-0$aC7P1h_nMW%vK5AE z9~ZygWOSlXE;0?-6kZAKIHKb?HXv%ptMgDP{oDr)7BAl+V?EO^dKsCxaWinJjmMg@ zj^!p609DkCDMf&)fLuWb4x|_c)^5a{@eYj#yl)r@Vqct}_+Y5yYx;XIv_QR@t2_CT zB77C#6GUnBN?3&B5--s}oXxRuUq>WM9ZU z>QjMLxHe!+bkK<1yP?S9d!VkLDOiR?(fNEQ5jTF4o)i`Z>`vdlHWD;o_}Q{iEZZZ< z*X_!RsACEqStHVJJf!UF5%0Eiwjw< zgll=J7@w}SWAaXW8h?Y0q(MIG4T2S5`2+xitPD9bU``C5n{jiT^DsIhnr=NkK3E<0 za_@62Ly!;Ue8?N;6_HiLu_YXu*W|}P{tVy!?tj1!fB1LUciYIUAM)O{R{X&q{2@O2 z=*#%WKmU(VTXlM+?C2PaKj)0V!`%H{zE?5;03ZNKL_t)LghfKrXX3s7v$A4u#x}0Y z87q__dfUd8bsllKhm`5i9XB>6F-IYr#7)?qSYpI*UtGR?Fp_?_{(;Mg*XoyTo-${Q ziFIj&>86Q!+CeNRQx2&{z}c~x-8+p$02kO|O0_fL#m}zf0>2?V z;GiH0dIzt;DEu|38!&iim32`~8C<>L(rvFEjnGiH-Hc$an2JY3?%RgfAAJd5{p1t0 z*6`V9p8-wr$ydJ`jT-JQ7f4wmbrGswtInfzP{AVi+Hyf@TQUMu^*U03MxQ;f$y6QUbzw6a@fujO)w(*Diw01=TwVa>g60YpYm#zI z*>E7zBEpL)LOIIGhRb=3HA}OBF&n|Ng2?@&GRb}AeBfsY@!cF1Vjs12K?1j$=3@~T zGy>$c&c=*vn9FlGGfd@mQteTZH2NKkCj?Z(8IC*kXCdJX)qyqiV^2QebCph?9K&D) zKw1-zv?xx)tnnilK}KKSV?+a$r13MOfX`#eKhLgx-z|bpPR2g1e*i#+zd4_q_k{)> zRW*eb2(Xmf>q;YQCHeUib4Ey6P&Z)Tn?*&}h8v^J zJrae+iR<->uYc`pD9eI3pM8egw&5G!_y)8!)Yfo+y+Z-8uBK@2`{o7$O^zEXXp|pt zL!-+^@*ieiOlhsypPmMVWL++n zCilepZCqCw)*>r?cXxLaKhH+Vt}JAEaW?jOo#)qQo-}^G8#6hsGa1dju)nF~X2;>! z%&$MYuYZ>DXJhR$#iLPZBr8@UFvjk6>Ssf47*Cydv##y5c;Z0Q&(cV70}EI(tDgsh zF-i7#L}o-+dg(18A98+5S^m?=6)7+WrK%a6Tt6VYGJRz6bt_&mOQBx6rK}3Y)!Lc} zQIqkw8MO@OJPkE)3Af8-C%e>h?dS;0OFnWnN1iNhIWuz>J?F{r%u= z{@F$?E_hPu({RI;Fh4#;C?v9l^X}17!k4hrIhy4Wm#!3dP%YZ zu;;PfaiWs=C(>ZXpB6rg+{DI=Q}8{(;p*72V_weF#?g6MLv{Vu&sg(lVq*B#Nml&~ zU^?gd{1M}@VQmCP#qS-n#dmlIcluDTKoh8r4U}#99k)#m(GtzA9A}iQpY`RAOcl~} z!f8Nv&M@mR^D%XLCI6an@@!1xxkc=Upqm~9b*p%Kc)(H$F4rrf42+Ik&DO_hUivxi z<-R0pLI)OF3V#0Q{}F!j*=KnB_Pcod`6EOY=cOPZ0$`amfB)mZ$G`bE{|D~>)$if! zU;jE<-CfpcI4ejhogZ~>qVFY{#NTE) z6Ir`6v7alu)0m|siGDJ645o$mxjq<4KV0v;!~sI96{uE!Pa!B^6f zRy0pdX001~7>hG_riixIJfnnZFbDtz^kWF6;$Q+A&1;|3ilr>xA(()KKs$j_)ztkk zr9SzgtVj_q0NC<=Sr$MF9&bAywjJBU6ABtW{_@9Q`g&_SZnq5=kL*!Z+-@5_`SQnR z9Nl+|q;jF&_Uh@5CcH#FGoT>SHvOYeSXvbz*6G?km{ScBHbCA5iJ`G*!rA9(aG0sUN-Y z{hV$q?(Gg(k=7;C$#X`D*#J9(y0MPj`S;K6!E4?_iM1IE%Uhjby#GbO&Uq_qH!-$^ zG{Yf? zz_hLb%uTRBi=at?mI7H8)GBy<+E5p(C-u?mFIhQ`V$rrwPaE#;uDHLy$GTcQs*gYZ z*dk3C0mwaW4g0N^V+f_%4bx%x^z}9%sll_w0jib|qX3SMDG@-WdCgB-YmM58bP7>3 zMOVoE%jycOrP(^)q;o|^S|wi?&i4f3**J ziASb$S_;rw$Xy$ILu)svr-+h9AYMXZMF>xA>YlXYxBzBVG;@?-id^+8EAv^#&U_^A z^>chYKf~VZ%57^ptmAWhh>B07k5B9T93MOzOa5G!g?%50L0E6vrtgYbQlhdPom2WD z9W|QV%Qdy(!24eRGy6%yk_5M=n z`_cJuHc<5Eh1tO$rznupJX^!loEwIyP*r{>?X~l9_&yo^NP3O{XbC6M;36q9)UXko zK2iQK_!^-6HxVQXD_13oy{0vH9MaqYSoa(DeG7hL`dB}+hT$5JjP5kHa1V$jY)uos z3E9szSP*9i+6`9AXfRigPPDS4T`mGF4?_Aj-bRC2#v6bPwdQ#yir44PG7v5$ko36D zBP9%j_NTf7WUTj3tj={(bbM=(<=F_>!j7dbe=^pBm&gEMG|>9oE#)27&%+m1L8DbL zA22g5uWQ$7Nb~Ss6^JZG1deu{SK-mCC7q(<{f6^9(LO($zn5jubFV@A6IFoicEh$V zxU5Upt(`B#w|wkiWU%YpR$2pK6Y4z9RvYf`@9`_Y@+)|J-0|H%{T?1}H!O5Q^Gus! zhUI$2Uw;3u@rU2}4*uou{T{CC0@@T5jI?IfqG#hqNeVcg>o^BM+86klBEO~_>#|WW z1@|P`>|eLn!f{Z7ibGB~ZQI}3f!Li)h8srb#VoTl@AZ3JAB?0Qu6JJQ9tVh^log8< zJ6xy%9w3X6bpZe~B&w{S$P`1RU?fU-H$6{ojQZ%qw00V;>1V{ojvk?jCf`k|V zc|2-{Q*nc;pTro7nN!Ii8ur@_x7!o07q0~e09vta4Xj7xK!}2Y^Ir%MeCb>Wiwk}UfooGbD2CeCDl1kq zgUf3>E3B+>%01}H54}?--lRz&^*NqBryCn`-OJX@Nw48lRQeey_9j9p`vvZ0qmk&jLb^ zyui>v6R-V4AUsC!&e2?>k<=nTVzB$u>9%sIP z7z}}~MsrLN&2BYFIVYa!`QFd1^*rvp@AG%gz}*bmR1M4))*L4Ros|CO=sy5T+QW@%a-o&>B^t!VfHZ6uR4IVpbh(M zw8r5&_fv`jfTsUexePG|{7sVGS+y=a^w~iG5HV4TER2o7bqz2LbDMN6kp`Z%js@ zlXETcSz9|A_l%#mP}oCp<36064?cr(i`RVCpZiYcqw~4RWe)g$9?M}(0MNLAprB3z zj2075o8I@WuZLP=1}R;6htEmUvpIx;SCgg&nceY@?FT@G=8X3p6&acCH_FQVHyzTd z$M0nt$T-8EQBLol$CIB4jQpv~1BC32XO&R9?5v7?D4%u83clBxIWgx_0mfS!nj{`B z61ACosQ?*d{_Yl{X)5D=-EI+hmG7r#sdpG}yjgQaThhH%y&il?d(Jb6F`5bjNQ<=S zGnq8Yr+NS9vlO2diP9-~FS*A3ek0BGXtDRa)b~o08l98}!px5aUicHGHi%li zc;aOaY{o-*{*;S(ZoL`MNc;0SpnS>e7JNx3Y#pEJ>t<*A$Pb~aLqd0`0$-&|Eh1g`2)Kdg1f%a(JMc!pheaX^#`F#raHYn&m~`XJ3ORz*KH48gr&22^mWvl(HV~nHy+kC&Bw(AB?0Q zu6JH8=PXk4a_@{vDc^!2xc`tZ5R$s0Q#{3@d)34buzAW`q^$Py)0wkQOo|F;2MZoi17`(&el5@AOt>HSPX}R^mDhf66P=Nx0ZpG7 zjVfnjn&|VKB>|y~(gZ>uv@*gVQclU&4PX~HM5%a`rSnMuSfoTG z{0#VPuUu)Aka(dT_1{OuIMx-WR4O#0s@8SIx-6)z;^Fp$`^D=wFM_u19$~3~Ry@3Y zh^!0KSv*x;CWWLRQb~E`=th%awl<7*0Wc`-@cR$1O!CX_AQ8do6SbBe;uwJEDy@_7 zb4e~{S`9^?77o?^UDBlXj;Cj`<;*bA_u@#;`SWv4F3wh=&pJQy&sfi?_Hb*p(|F@K zu=(9?o8c2zTBH;dZ!};^xP-yj?tM%}2Y|8&3d+fO@5W0;K4v9ijyOG&MQ6N+KhNYU zH(MMmHf^W(%b%a0k?(uzaLe~~rl3?biRY@0>F|O`mFJqym|`%5q^p$T5usx}*gY9; zGUf?~6T&Qgm?OVu%{2@=v}#7xA_WcAC+572I8aTg&2@nl8f8NA*k@T+9IWdf-?O zd<5qXW?RL6o$;V~{qlO8VTAmC9@7CUpf@*U5;?JzXaO776a}=1QB>MnIyVB>WnKwS zudm4&6Jui59?M1nJ&GP~4C-}NO+NW^RjuDe80ZTwUU`h?rIdnoQK(uoLeUMO_5tD*D%8&rONbnKeBTGI<)n}K@3{f#jH#lvZmg@-lg-_l zx)>Y{+g%~E8)OQ~O@i_@*4eZ#)6o*mg>3Vzd6+2BD$F=qIZ#{g)&N{tCk!GU(MR6v z*(*hhmuhmH;_KbeAYKEN^haBO)lTNvi3hnSuKRi2VC7yA7-FRF`HW?J+u!rG$oy41 zu2Lu#Z*0brGLoMqz9wqtpjO4>;}goV;Cj7Bt%|+X;78$f9cZecEanWYbw?NZ9ftr$ z#~*$48o&9Qzl9(C?cd`2Klnk=eZJK9`|Qh}Ptjhvz4Y$Xq=rBy? zHP=4N29jZJAQNa<5)-xWFk)z&54h%JrfKdOfM(Fg_gljdB{M5JgW~Dw_cODb>&A`y zIf5td(YYd4Lh+#>o!2JTXHsnV`rLqG1}%B4vr+Hp`LcD5CQ1YdRJv5XbKVkOJSpl1 zxhcXEecgj*5`Di*VN_)*{1}-v3!Zu1&)x^ljbnN5xh@0=U04!8+g`~4xXwMXnMOM> z9BFnQqpC(Dw4DBZ;0Nf@c;k1+nq=H-HqpAIT90|H#TCZ`9g8_0ma>@PR0K3S{OCu2 zkC$Kj952880^4oJvY4XMeB)*>=9%)t=gq0^`SpCA0l*pbSp?{tB!<9>3oT z>p*{dd_pN^qQ4E&Ka09UAVsjC#IG`a&GeYZmG6J145_EhGeXB2hb}NhGl& zG~} zA8<5ulMccmgRYX!yjj&tYe67ayI){6)&ll>a}6!tvEgY3G}&oF@)rLVC^U1tB+> z5kQU>nLg^995mD;=+EW=^gs*0-=mKm2NYPw4mXkLF+~n%M{w*b978zqMi~G%+Ba2f z6?objF4uzfvS88foXlrE|9kuSTP$V4ix)4fNw6E5TO-Y{hJW@AU;gr!@H5~3Hvani z-#?{M_3{(N2s?#nFGKzyk%c zGnP>~G7nO5#W28+^p26|3Ojh?Bj7v%FY}?9LEYK+;!yh4i~ReODWuW87NsnxtzoY> zti_Z&Sr(MqK;JZy!4ZHPf%}1<=aYqYFglTlcEZ4H)P+nr1ya0cO{rpSQmn*5$DDFU zrjm^`89dltOYGsGV3S7DGXO+GCZQmC*M0o*k*xG<@O9n&J6pYbn3`>`I#Q+ zO1glRhp4;PkS!2UfFXbx*NC3kca3`<=S;ifce^*c8@KzO&GVY)n%|ovt>*Xh8g`IK zuqN?4FoK%Fu$u0be}+QPj_>vHPDU4}$5vbLmjf6$0|?=rw%_m_ro9ICx7;TYx zWao>mc^Mol&pki$q1kzG_^ePF{V9M4l{p8+oFC5{gz9uZo8Y6E`ZuH=_B|q~mgzi4 z8YP?Dbu1kBu(NL5|BOf5@BOos6DmNlu5Ij5V4o*VHI2^Xa8m(G23(c}ch?J+b-}i8 zXu3jlbwlw2Xhm5Tl*Nqmvr?VurD|_@HuD&cxzDj*d7YYczGa{9$|R$zeMjP1^OetS zrc161WUd1Wb1I~>CFyfigfgAX^qJ?Izv}3>0qAIOox4J z83UEU@O369^6Ol``7`n@jLogDeIJL7w|8x(VRXh{`QCYM{w60J$|cw0a=9EL zNoPJg8>INTF(TOZcwJWf<$wLJc#A83_1AwZcn`eH2dnxR?(UJKJS%WV330JTaxU&*@_Dr8d_mZ33!N{M zDaN^wgGd|rBl(6LvolU+@b2n2?rUI1vM&Fw*K2$y9C1r=r_50ggp4&w^VpB) zPQo$l5a4hQ^XJDolh<~d-M0-ZDwd@H*rB?4#ApqAf-2C&8gCY$NCTET$5+0e`7s4( z+IwUe{)6Mc61_GY)kRrO8?=2U>Y;jL%%ICc-bhHvGc@r?S{8+KgXLlZ}9fv z0o!fE=bwL$)+&DEH+}=Z_G`atcyWqk7FZPS<#LB#`}JSLr=Na`KmYSTPoHte1rSE_ z%jJT<_%HtjfAmM+!N2;K{{qWWQ1{w18`X3RIutYJ5x0S4Los=!IIiwClF@ONW&atk zjMr?SgHAEUjha(HK;YyD$s&Ctd2!;|E^R=cD`JS_K6v_l^tETmxQ^21Cl2icZNXh5Z zjThwfpbR29y_f(kV#bc`cEchP%>XW5Z?+YBC-a_;&&x_*Ry^`^$2F%=AB93b1NThl9_pX<|Dx9ESTxQlqrBb?lJBmaR>k(gVBgZEaEU1 zi}H4QS{LlM4Z2s9i#ab>DY%pi8XL?gY2wJoGp|2O`JUH|(G`>%r~H26lbvUc`{8?94Vi001BWNklB6&|nrUXn8?pXw%uqhJcnKd@ zzzff&jCA`&uI@bSbIyCBz>onUBH_rIdDe`D;$Bg12thY9zsdVLI33yi2S@%g^Rjcy z)b)uzE`GnonYMcnZ=}8Aywdks1AaK~f>FE(~-+Yd@Z{OnW=bz*8cEi3^Y}k&m4G#}*@zt+>6+i!ve-7+V(l6@pJHGz4uj6-r_jmE;%^Q6G``@=f5Y;H@ByhX| z!;jzlvp>T(zVUVZ#&7**H0OkP6Fb$;N3-loXFSSf_*tfo6a1`k4 z$t(4GtbsX%#&f47$LaZO#V{ux9QZ|OxqAQWgOT*Z_0CJ6)~reFAPdlo6O+L>5!*|X zf(q%LBd~ds3DznNi=KJe8&ynTiulL^Eh}B@7$1s@GsO_PB9Z1sP?_ttwU!Q?c93E3 zDR#43;?=9ykRrHk70Y!+RajbxRx2&wa#_R;b=p1o1ziv`$|ZPYtQ$Plk<80L1TtvC zsQ5LH@KFc8DgYMSBNlXCn5v+xjaDW`DATx7y&j?W1`fJ1AnAKED+R2vMNq&63#yVGFJhB}dG zTvnUcUbAmG7*}p~rxB-f)(loCq|kU|=Vb=|XLIB{XJv)Y=dYH21XPK4>^^1jy}#h? z!(05(cm6%T`OTljw|?f^c3woVh$Y^u0~D^snK9=8Ofa60A(}@7vUH>MnNl|@u8b_{ zpz~}!=8N~p3f}-gehS=SU$b#61*rAhKx4c>UCuc01q~VKo@Zx~(4&Gm04--^>}+jE zxS+-vpQ9`ls@2aQYfG!k21X=y{MfwSl!(=Y^G9oc8f&A4AC zmwPiIJ7^Y_QU{}S%moTX?Z$$|j263YfG!}@5WuW)5QvvsGJjYaAGpk3o&k)MaVl+! z>Nt})?`&=OdyG>go^wW9O8ka`>*Wrg{p54}(RcnmKKa@=@$tuBLe&aILDdFU#E@bJ zivkRL2T-p0zQQqL;va@TE#g$eP~el7P7itSX4!tWpNH4gaV-$*$W(3L+6gc{FO#0V z0v|g@bz^s&Po?3>?=7&@(m_rhozVl2n1$yw=b7j6bw*R!J{;fA*fXy;&!5qu#=a^8 zPtx~+jAteuDOTswUT3HEWE_rt;aa452i}ngKH)N`m#=});EXWdi@5q$IDV%AFVPke z#Zgv`62Ruzit!Dr72Dk4=Fe>{9K?Pg0|tcNmF}J8OkZy^$f%f;KbmgQsOsInArdlI z6~nsqPT@AWC^;aCrIgS^shimON*M`ylp%fp$#eTY1bpM-ia5PX>~oweXq-7C4r?%4 zoWFHr7Xr^06x60zi}A*y4QQ4nX>x?P$L|mFKLB+@D;2Udh+GYaz#@%=lOfGER8n(Yo?XsYz*lESRW=k;7iRM(+tz}m6fDJ>xOKCwU~fiy+g`CZYZmr& zd%|aL-r&ufH+Xt_!e^ho!B5`2aT(fh+cs1$tDxFY_u9+Mz+};~nA5E+i_u51a($u} zbVd4E*A)*BkNETd{Qu(XU;hSPzrM#__Y;2Guy0TJ=GVT8fA&v*8-MVJe~2Id`0s;# zMhOw86O@9tPmlO_fAk%E?OWf%&wl%7@wDC29%!_kh}yJ?CI_AoazN0@R6CuL2PD2Z zl8g!YsFq$q=N|=85x{ETR8}HWny5K9bI^xHfQ!CA&@VZE6^IA zYIT7>M{n84snFzWNP`Ti+ZFiCK>JW#GBC+tKEFnVHfToGjCtOi31Vp%vMjV62H?xe$ZQxe#gt>WR1Bms=XINfNxnFj z*$B~To@+811D-oiC6q@Q);WM?6#5?b`FVh!_=W4e5nUG>8XKFyk<)N9g(r;4B189Z z@|FN11kBGUIBKNSE3>2nevgwqQ+V_5*$^=(!m-DA@5{!a z;XKRp8|hNh7Z6H*!??FV2X-uWyzGX^5RuczC&Tj~uACG$Txb9$S{}yO z-xuj?E%~+SeA;>extl%Z(%E_#Mp2Jep@MA&c?gvnt92dgT1qH{T}YiNELlFbZscCq zxYyBm+-d)qGCs;MO}r!T(Q^jvyni!4KJb*dpRZ-YjQp4_!?7etV?#73n2uN6an`CE z&fFoARPDarZKO>a5ZK@eu?`(`(I~0h60+6=BC;{}Y;ETCQ8h)Dj+x8d9scSE-^cg< z>_6gne&=_rQK$lom;tDdH7lkgKh4h9A}6Vv0;rZ=<4^i~XZtwsSN?hSd7j&h7p%FQ zEt=U_6ds-!IO~0{n7i~d%YB<2>LTJ@!ACxGid)j0STZbUgFJ`P<})97Fv%7E%xgOv z|IJu7k8Re0$P*<6H1xCC8{_&p*An+GMIh+WVCwo)%*My9&JP7{Tr6IvUv=P1B8Z4v z8pr_Y5vM{km0I)5rkoQ8sFiMOMP7Ht6Zu}J14D~M%@!m((P^YWLbM0zI+FP`#?iE!l*6SV0vUYu#cvS>! z2`Me%p|ozHuS-8Of|0k)j=gyuEpti(H^OP#zE;p0ux|~I`wb5dZ}Ilw0iS*L89smW z29FOn?6u+X=@C!24Yz&AzHiv}9ox2fV3K&rgwZJ}V#egMELdbQzUqeiEImyJatu)` zw(2DW93R(O@h9K?6MXjBkMTSI(?7$ve&$A3u5X z6G&OP%Dz9IxpckaM}Pk*{`gP+1fP8MYq;KBv2UB}uM*Mx#eb)xl68+q8twP?9Za+> zzTQV2Jg?P&8Ahy$$k&v(d;0try*?O8KV0v;)YH5&_?Q*Te9g+w z4B!WF;mTyMuhc;?FFQEs;3>U+_I%*~XYb9QEIE!d!OtTy-&NJ!1VHKlNP(nmc!&hR zL!6aFnO1AFT4^MWZ2s3Zjg75VLt8=s2cYe&IFv{&DN+MM0EmlCbXQl^dzlfwKe&5@ zM`Tvx;QrVNYt%dPMMijdxPR{9?tx-R`R{LxgzDP!uX{kd*=(@cY>;xolx76lNq?P) zKsR=%Bg8v)JRO)@P(&IPs}j&DI6QQb8>lfu&vt>tzy@-fOJt{?qbh7_+ZL7Rotih@ z-_z3X=GpK2x<0rdv4d7cDd zmqQ{V#$mw8a^VOH_=U#}wAEBuQI*zTd&aDFWbII)V%P*KhE2b&JaAt7uF|mbil>2} zI|J0>l=J{ZK?)O6u5I?lUvFfrrTl1a&mvW=F&ed|r$t`~pA_v_orgkH{a91~A~fZU8P~@n5@*D5z>k0YBiz1y2VeijHxPyaY`m&Y zj$(+Sf)tuLeuI)L;rqt=hNe{PjSHQlFBMU6-Rdias)gc`9^ zPjIbsI1B@}+ilq}W3)!0Z73Lkw6T`;*7e_?R?px@R%XuSP(nZ6o8(24t>7XQ?Ot=J z_WHi3v%l9;b|s}u(2V&Yor2FLpTI+0(l)q(Z)ouEQtOx+2=RfN-9`z z>$8)YcAxP($5hHV;WusL2le)GT4vD7{;op0q{f;wuYjd`9io#vAM`Tg(z1J2IQ@a1Qo zahoQ=)eiNv^w=RR=FZoOt#gACVdnLx*YW-Q^=+)_ss3|6&-Nml9&rZnN75_iyi)oY zcJR;dvC9(Iw&U~PmDKJV^oOTK|GLMWH|Zb$o%LUSZ_b9Ld^Nyn{AWQKWxf|#V@~G7 zWQk!a{ZE99@U7lQ`YZ+kdYB^g^mx+W%065!j#RPTs)JcR(5xrbaWWs~9Fm!oVe8yv zvlFyjjP{Y;hN#&MZ2$=%r>)nk$;Lqj1-EXCKD5tT$FhIj2QxIbgtcYz22|E*D2|?1 z{whI=CFy03&^E-ENw%co+RbUt+4u?JN+_{6zrq;Wr;A^hy`WVdN9q^?ueF+yA7x=F) zy@Ywrh(j!yra`m*Y;*euKllO8&(HCDzxR6>h7rgKfqd|ZcCtyYH=OBkl-hMbDX0Q-9sRoO81L*{mvhkqU5Rw8Y3u^5+d~yu(6tP&GgSltU%_*eZ?tdVtII&>P71*-gCeX<5NvTb4lDgXp>y z@X@cE3fjfsGlQ%E1!j%F_9>sv=}FW8#nwm&WwW4{4Jc2kS0e{hk^9dUY3fBD0fO*D zF(Ryna*1%TT3Vce#NZ^(@-%1s-~a8uVRty-nP;BW2<};<3Aq6AwK))jq&gvc;C++) zTa$;&IRQ9uISejPON;(qdtJZ`7y+7AMeA$tgI+?@6(IAFafyS10k%Ub9PnW-4n*6S zur_*`xCY9+T=e5N+1Iya>Gr0h%~axH`Vfo8BYW>GVJ{PTn_w7304vzmxxO3 zcg{#eHGR*<05p*pHPWL3SPxxgy=ZD7p?qe2so*sio!m!Cc)qa6hCW5Ur?<&+xM%jb zVO^G>ZkS{#mEaF!S~@$HI-);p(CaCpy1BTfSD9sP`}aMc^cbh7Su4l%HIX~4LQ0Kr z(T`>XtNgLvvu;?GnO7MW$O3yBJ|?2J9%qNU`p?_3SKb4mqz$fNhn#D@G0z|V>gU(L z_cQ@l1F}81M4c&&dN>-ab~g&Wtb~&BfeD2Vf=4UQw7j=QH`6I)9H>sMHF;`d@T6}_ z82El?+2o#+L@W)%fUC<(y!6sbI6FJTZ-4G{h#Y~OO1TDe2AkXw`U&pwdaj>uuXl~A zH|h3X7xitf;SAqSKi|!79RC>J`mh&Qb}jPJkGIhU4SQ3gGfI0m@QiP_kK*_DdpWsw zkC&Id1G;%85jYzT4hzSC>4}H&sl7H?N+3-y7bgZ=`G!ECTsQ#{67`ogs?e}!B_6Bp zs~Ed#V3S^?3SWxP6rIY_wq@+t_(aCF>&WZsiqjMuYmm(vzsg#!c8aOaTAIc=2_>Xi zbf_!MQs<_4eM@S-;V6RHfUt6%qU$?;ud=M=w^|Rio%_l!=JXT?Hicky4Vv+;@mSBZ zc4f|(PBZ4?5jkfJAz<8$7zbH@QDv}f)avvZ4VCWJg`jmjnG+}gVaG`6gp{rkV#E-l zI2$#sT{a%o-ccRg_Sa-l>3B0HqQVBKwU^iNqu?-^pAZ6$$0L67)1TnM#T5wVe3aDp zVT@8*z#ZX06m!$uP;a%#&>nZ^jKa!-&mh#GN~L@YIt};_=6yz~hfS zhTCUn$`*o0x7&@_56A#5ZM$H6FUk)&&lomaeDMpP$E!bk760YI zcfb2x?Duvz2~EuE03I{kFJMbRRGi_(+eP=f<>=KY0`YUA`J23n=)9o#7G$md4iTpTSzPfbZ$i3Bn}wdZ@_-a4C&*eJ$a-#;sTP=Tm{ zW=lzhf}v^@c`(7!$qFoB5F5q${?bZnu-P_34Dn88Ji* zagfMzof`w4tiQ7|Dg?hCMULm((mZiToD7bcr*03Oa7^RWSe^4v0HU`*1E@y0q%Ih>zYD4_P@_fMu7Fl z#_GpW`@n^sg_pEWu^ED#t-OM^3&t1+S$8=j2Z&R(n{$hjuX4{E4eOB?Wy~vhshtz6 zpIpliEQ}*3r`XZFI&qx7bhPxm;d!Dsi3wE>=^tj&)0P2nJ*Avsb@J+gNMNR+xsuCdspoCjOfs6p^q9BU}2Sf33YT+)B?itmeP(@qN+TdVq%# zX64y+ql;V>6L9mu3IO)ZQymY-?Ulc_N4=}Z*#5hHm8P9 z7i|$%`>Ah=(^#TCgK;20EDlkYwn0EphY%Z5Ba&#*!tR|sDPo6^k;IW|sr=Br8}p=D zy?&CK{^aW|v(cdHX2V=UA8CE#u8iyB#8{4(d$R-m)vk z0pl>^$Qf5xS2#_x;*TAMH~^G1h%oAgURJCCP00=jMGxtQjFt)-DS!tcMMvLI{UAdPYWSnnkKyb^2@lmxWL!H@+?07_~S@TB$sK69)ARR2{2ow>;$854#>YNgrJgz1TTE0A~m~ z<>DE#F?1Az$zpMiNoSn)AVJn-J*lx5o@;>KU&Z)?f$Qatw>Plt*?GMF^RY(b7x+S|@>w{LT3JB;$X zI)1wh&oWTveb6Wu&_vFczytyL*5$RDr<(36C?A4xj6GB(r=>%?MvT%36~Ep z@bCWkkFniJ;q~e+(yv*XbyzJ;dFV93qJyl%*DLMZ2`p&m6bg-zo zLLfj5N}Ep3R`-xfWH2$1krCKpY3i6pP2I{#eiviFX1hU}P9RpWAL`mD8)!Kr!9}x> zt@oBs>PC^IDtoY6Wueg2q6qxD?d6flMWUsgu&a5mYi?=4uH5V9e371=W$ujdYwN<~ zl-EJN4Lfb#JM4O_(XO#&olf7k1{P~uQCMXS+<#5=}}7qs0#&2_e;!? zN91dRhH7v^Z{#fXQ;CXv9)|B!WZ@X zl|HY^n5E6(f7jBD%YQadtA%RmuU?+?vc<5GoZenbmJno{B>)DVZti0i{Z^gG-t8bv zS?o96ylF6<)?N3{F`ExWateJ}FSUL0_cAI)-J-^o$6ZFNN-rktr*B|6pxC0=hX8OmAvYX0wMu}E7z2B#&kR)=|NdV z|EVlCUN)@W>TjEK9dn?fah`tqX?&A``S}@dzx}q{AD|JXT%J7)11>Kw@tyB{2ls#Z zOZ?@Z|9fnAJ4~lZH%nw=g{)8RlFdht4bi=>n>s}*aOK6qmuTgd*&;<`y7l19rxt&h zoPo(rp@Yd%D>?E}u18MNN7q9yasmjb%q&8TiesWTfJ~8#B1MS|DD4Dp6c`o7W(F|I zb9!T`QDgNF001BWNklY|YgbmOdDlN>2l4lCNszWazT1Kq)Ids4EhMLf^Jz22@ zZJks?TLVOlmfF7kT?f}zFRzW(0i)~~_aM`FDy16zV{Nt(X0DG#sn!1YXokuIRSMTS zbPm{ZYdA{uMF!`DG|fQHpg0s-48s7~dyBf`>y2l9R4~JMSre`wo9FM$?f^7U!;jUd zZtKw1@$lj|o>2X|C|@nsJQ;*(B7vcD0H}w)cs?qT!uGiuU)dS%`jEQ0;rc3a#?s!o z&V?JVajB&cQ>Nk&wQz&tB!vPmKxBo@jn#Z5lo~!geM&t*$`UOA213*#^Z|1CK|p4y zTQsMHfBMmn@$}Q5#^gn$}DDC;S7`g!Ht89^D>+6;j)lmr9869HI*k|#t;V#aX`+Kl7ukNNt~wECR-HA z%Gxl#cTszOGfRLvsWRsRC>xMj=w!M{PIUG4C0k=s=d0ZB*5j)DZ|Ae&<6=a&myhB! zU`@_R5BF?8W=|ix&q}%!mqQ48GJM-V`;8gnec%1KY}3s)C$0TfM~NXALXF_CTeFt& z00DVU$kWtdtq?`-Ew@RRPAETiPajW*x~5Gpw7)M-5qSLKp2}$CLUEck84kQ!4#CsV z?(3u8ecviyXqg&_?#L-2MmvP6E45&{#WEDwT$GHcDaOpTHgzN_ddUCl`D+c^w9ep_ ztPAIelDW3B0M*c!{@cm&03cCI2>^uwi6zSlCYy;cj01AY_{Sgq5WoG|&*JG%e+H-P zD=qzGGM`H%X2l?NA_J;EC5lC^fT`4I?ALJnS6p=EKC9WwCicY9VQaI=eo)z8#3Pi) z*mNkWGw4HJHvfL^%6I+T+PXK}M4b+e-sL4e>gAvRtY3dbRLVnm-D=R2yLDXqs!`bX zrqHRCKSA@%Ey~k7A*d3#JTK=g4z^5cufWPomd8{&6%q(P`SoN61VMS&##r!JICii6IvJ4`lvzz_R?gT(b_P&IE2*YZ0p{lU4zmW zTrou9(^lqLL}XNlbDk$$T|K~V8!^NP(sXP2Z4?>>6KTd%<^ZJ1KM2Za3CszB2Gy^I z$*Vjl8w7fg*aBb{S!ipR%DOGMl8jd6cKu7xojZK?GoQvgZ@+^d{NoS73?v5ToQo}* zl0E~%UjSnqM?CY)Gx+RhKa1^li*X2|S3=N3j)Xq4)~sH;uFI4FOi0>4+4v5KA%JK= z$yAI6C!Jh{<6p-&LU*M%L!H@*d2`06pMDyL!=K@W7hl9b|MZ`Qw{-1fu5!}s*MItd ze}pf5?sNF+*S>~%N=Ph$AR&k!A+Y?pWs*>P=qu z`WaB0nW{e_P-titoXq&J*CQwCqwC>U5mYtGq&L7lI9W@HwtEX$%Dl2TG=`s-zjFczT)JiqrQ4M1Q zkOdSufRVr$5CJ>25e6c;3V)ar8l~-`gmPBE8dRrN`uG$|1FIg4#d7G4(W5mm{hV7n z)~?X9MrHUk{c6B?fmRJl5vDa_LBM2NztzvJDb(I6V&m+M^uX=GR35wg<#`*=)87_96(WDRIz5&$x(Ndv@PXKQ8G6-p6?1Leu(Bd8H}M z(Ec@LwnoQ(E{FtJmM)dD1j5Ir9D8~Tk4owk>-V`cZUubSHE3Y2IOMrCenpW|i7*A~ z`etTvMnZt99Tt$YMCLG*mg*&2Q?|`>;MT&N#Qkl~C=e(zj!8BsSQ?h)PK-DXI2})T z;XB^}Q^4uLLouG}xa^)D#F+%H z1`I&uMEa^9bt8-H`)-Y>B#$v54iVGkHPSqTC?M&fMhj!wmL^w2)W&J;T4bAdloo>v zm8QL(bu$DrnoRGQKropi?drOBbJ9E4sq0&DOz7P8vRV3F4<%^JOSDe#h7a89A_v@t z=~{}gHPg@uOQ)Zg4W18M{Ur2|wnT3D6t_xql(vd92@K+lG*4P*l96*lh!GSc(tJWj zjo|UtLod%gEm}EN^}JGU!3R}8^J0v>9IA6#dBeul_oH9Wy`J;9!)KN-8z0wff)K;% zd@utV@3!c#l$&rHit4$t18I6WlQl{#GdG(AJ*Mc_n~b~GkrkOs=A#m$Gs_sEeIX>| zOs-@?D7tVehJI8TB950h47hl3iEqE~BEE5&@Y$z-OAc}2qz)=ur>zlM4rI*LA=S*2 zI@t;(oQ(ByUr1H4VO=*i(sn%;-Yia>T2{dvfYN7H2+eYG`iHzMs;#dFU-(?a=XuXe%drIu#y)Upqam^{)XA=+LQn5_H@>9uqngxvy<-P#z6O}eIHksc!zwxlu=N4h z7EXXf#uf*oHXmZdxIN(d`h>gh-NT*Rdu%tc$QE(t)*6*IE|jQ4=v*^2aa%SODanSd z*|S_Xc>TKbSJfv}#&7evw5PnhY1bqZFsQ@(aOV!b_=PXxUtfI<@4a^qwgJ6aPrzD zi0~l4Z~Hf0kDR2BuJ^facHrFf`C<_`kkuI4a)aJy=*$Gjy0g_U3h#XK&M)b;2;l76 z=nbBJ(Ui!e%*C*+AX?rJ!-yCoQknsf*0B*~4n&x?lOYE+zjc>Sfq*yKpdda5sryp< z=!_^5$C0I@Fx$aOiF1@z+JoD5^v+Uh zc*^g7_x$ANpC~T)u8A7!9X<9uYWqZFV1DU{YWn4rbxH}y8KZ)P%ri`L3g0oJGql+Z zh|u=McDfi`4*jaSF*kGBC_*(Z652jCB?u)S_KJL%a%TI&1k9khPa%oig(|A7k~CAe}d0{ z{@-9eX&D?lOh>VV$x7j~Q1C=QAEaXz+2Fo+Y$S3?Y7c^oi$=e!czKO~tWKioeG7;% z=cSbaKzO+9zv-%d27ISmo)kmhWKTw3@X1a1cu6ZX_xMf9g6oRc*=l%qdI`B4NC%@P z6A&a=gOnGuITu-+I0YNPbPn_&o$8E%8&m1KZCHbgbJ6&b%74PcVqdg15ZB~`T|IU& zJyH_laDSU!bB?749l>``Qk${VG(Wz`kuGgLBIX$$QoAoWOt(_5bA zMAX#t6&joUVdSdc&uMNp=}mvcD1F$U-@D7$S41DTSpTcv`eFZPR_#N4VjOJ6If_Fk_>GjV) z{xLrJ$xq^|&pj(P`9P&UYsKqsn#nuD+c8QOCqr@v#I_6+n=&A4ev0}W(H(655a$Ra zh)zxOgx~n}U&C|HJ&Wg`e?iU(iGxIVcRrIiM7;IRJNQrk`9EXM319o_*DxzqQ#Y_~ zco0CLl#a6X<|Cww%n7V`wd(gZd!?DH_qlGwR=N*kGPrC6cp38%u18MNN7q9yF3RcQ zAlqNfBDvunXMo+5I%wm_Tp|D|*C-?ZykhXV=sI-$w!ui0Ks6|GuFe(1VrG1M=O7U^DR6Sw zR6S(D3*%N%85Ng(YUgFS3s}df2MHDM*f}a3XyM4+Zjg;%?yp9b?j}2a@J6gRYL`Y3 z7IRSVseSWN5Yse)5HMn=2dS_)x)gNh%%B+cw0lbj5+@w#b4&e0^a`PlXU%EU_s7ra z+PbiLPMn%KSz8}%jXK$wXdEt7pH+>B>Xb;D`WPaKG`y4)Y=Qd8qQ{fBa-vR_d#b8{E z9#u{)hVL4`lsQBNTQ@m+`jpuAISS2*%3%cd+diuAgIAZZBo3P5s8c>JeUS!H90RU>W-cl1!!RP{TxxgK1J_oJ z5Rjg>N{jZqPHE(uEj*%PxLc3<2uV*j?|?L3_59P;=3GW#`FZhl^t{v0oB!TtK&2 z=7P{9rBn_h@_b(%m}vUZd`<*QX)m(d=s{X1xY*gYi6YA>andCv4jsW|N%WkHx{+XY z#;jwL(l5H^wBBQeWddc)GjPn;xV*jwh)T*Xm}MVaOC)XfTO5x^{KG$dAHV(EpT*&D zj%hlo6IJ>Zf^(9xm)BK(H<;OBuSz$yJ{4nH{fFXWzzeZT~veht@ z0}}})5Bx)17Hwn|Gp(f_-#{Tp;szrKuz%l9y8!1iPLj!`p?3V(~9wSaL+ z-6rSv>ufM)t?`(l`_}~<&2tjR%Zl@;Yyf-t2QKxqOSZFKEmnM=s4V7!ef?#!N}jJ% zCFBr?6j|gKU^TdlY%4May7{QIQF@lCXGZY`>gRUQQtN=U`Ea~xG-e3`prEBG$ogqA zw$4Mr2(U4)=og(=B5Ol+u;(}TTaiO3{8>BP2A=>be~FqyMti)2j&F@mQ%X4M$@bgr z7BR+xv11IioWlUbIAaJ>W=v>io1Bg&rH-&g(bkO#0wD&Hd8LdH0EDR6zs=t0GyVK{ z7C5-kxyy~!M&}VU*FZ5yjQH}Ge+RGpk5}+7Kl@jVantem630yQjF(@28J~RWNqq9x zKY?jJ>NBl>7J=$E<&9qmP5*0+5TL_vP>6^Pl@XZr{Fz>#HN`OhaEe`@{94og-bhPH*;ecoVLB z*wtgWe!kc4C#-+>L9Rzm(nr@rFEiBpT2v2Hl)Yo6Y0on_dSzAgE4-1>|Gqc)ZE=VL zr4~20cvMT(GKFdY%15I5zD5#(S_|B(Q8UjNh5_5n78mc`RmaUBH4IImfpqsti}3s6 z9%o>2yNQ8T64dWJ(0)i^X3{590&$e;~{TOTid!u{J(O`7A$Y=#a~O`R&^ zP_vU*fQ_7vEIYc1vp7n#)TfI>M1mMC;_GGPWb0C#xTn)e>K3s$p@tA}etrjcZr{N# z|K$~&P7^R}rH){Rj6vs}!PxBf_{A^Z!~gaC3;6y2>EGfLpZGYC6)d9iM0riE^T}Rk z&P}=-s2Txlyl(T}JDNN{^|HNur^cnx+Vf0ZvmXrD_)BVh-n@qUey;Y-edfp4tSPFg zc>V8sI#?V2IVD2hT`~t;B1yUHv-mKaZqd&S3=`Tln>C7P+{j7hDQ67hMs!xr>X@zu zQT^R=K770Ox~}(H@6Qh4Dn_G|*=w}+&+X;Azu%l`ZRwIq*Ljxg3zLCsbMO1H=9G9C zkY4L!FY8QS*?RN(%hOTXtA@R&_f5RyFN;>~b>=V(#Wu`>ryE>+-SN-?Z zAd`E@(?Mx7BTK#boB^(zZ{Bb$?UKlLfb>u>_1dtxwRCgWKGq}GWc)yyGngW%oCeOw z^Nd^^g(&qXIRlBM{_{Mig2(1LVVdQDm!P$Y?>zQ6_F=@`%U5wqM}%QpHcn&_2ZSMl zK^V6?y#D4}_`4UsgKzxq@8YqK-N8H^OQc!JEMYE@Vjeqs-0bH@4iz%|6)F#EWEBA} z&0FzyIv%zneMTb~*Pf#zr8{7(tRaal5mRNlY^Bgk{Rj0`uA z7Lg91*kh#anX{iXJk8n=Lh-Y&>O7ova_n5%WCb{>6RlcDr&YF_C0Q0um{CI?lLv|31$4z1H<;u$ZMSJGa@T&p*=+EOyLa(lUwRq;@h|^9#vx*!XYI4Y@9x}* zI$vf_TOd{KugNW&PXEl>7lzLus%=<5)p=do(2b|eI6phX*T4RC+`oSxul(#)fP9&t z77J{*Tim^S7k~S=e~aJ${oltYKJf`)P5`nvnu#zFz>us3DL2~Ex@NGU5nP5%Y!lRU zQ$N@5cdg;XUS@mgf)C#G;(FvHeRMtaGJ&*a6x?L6tO>4qwcyr?0sZa6`{M;qqu|_k zb$IdA>p@=}ab|^tlQyORZFW zb|BKIIXh2MJbhzyTz}MVY&LB$vDp}tG;D0PvE6WDTa9ftwr!`e?TOLYy7PbEd+%E3 z!>su-Yi7=GpS_>`poIJ(wq>P)v>?#|$^x6*xcCa&3LB*79R1hx+eT~CO!2H5fERX# z082pWgwh8f{^g{FKW6!d&oI{?+-#C8&=Mo*mcEtexwCJ~M+IWz{i*_6P_japGK1BF z0o#CvqUWApCary>Y1e+5&ST$0X^c;&B^sA=)492w(oaOF?bD%E*Umq`dNTFbvN$L? zco6;nZZ*=0IftCO#Y;?T`s5~p+5FZ%WrX5E@Tf0 z$nOtfOkPHuQf|KP3y@Kxi3*2_%o?m~8NvfUE@M8zntk3KUkCLe>E1VKipG3;{mIF< zIXWity0WJ4O6Z|5YIp`^Z|yYQc3L>-z`I;0)6P4q=Rmz{q$>6{ZAbf@J1ARn@DdvL zcaUu=<@C4cS4WTZ+q$7{TL>1=@}~wjcjEy2{E$tmK>{DfrCmTpVT9MPeueC?wIJlq zX3bo1cIrX?PX{#&vj(8J($vvln$Np(Lr`Y<-+8{md1K7$&9$$5RXQ3}GNGu|!>XgV z+8to(KEs=5Cy^^_cdfz!n-x5GWd87=yz=Jwtj6tG<=wP(F{oj*A`?Y!ke%rjcytRy zqo6fJOfwl+j<%A9<#b#a59ND5^Cm^s(qG~}d+?ddz1IA7P=TLcn4DfX)dx@`&0W*1y8b-7WyRFxrW; z9~<@i&6A{65dP7zp&w%$6p;u}j@RASuoKq!b z^V8)r+62ExSLLfP1ajJt;tW+-z%YgX+~qIO9%pzjXPJM*eBE8zab?H?fpf7$JLOj-UOboafqp+#IrM3tuS33iGETO!|!UE}X;lGJ315 zP3u75+(>7{D$LIM zp3e^+e~u_wUsuKKsduK$WO6T;Uw{yYPi6|~(r)h;+^Xto5D4U7Utb?jZ|DfHfUD`h zyYp+m=!|%*h3tyCjShp_T9tBAxbmxPN8k!sV8cXcs6+h7F-FJEJ@mJg2z`pnZQG`r z=jP@u2B~(4=&8L9IC6S(-tBw?AcnwRs1Fw#c4tg2xtN~sF7>^bzL&6G&#H>M8Ql-) zP{Vx#W}e6gW%t>~d@~@Qw^KVc?nF_w3^pvI6|ZfCC9Tg^WH5tDr<iA9;?G;e22FVX zwwM~b0lyuNGQDW-oKZde^~Z%D^wV=5nW%)Vp`?p42( zXMY=;=hi!z;%U{S3iZu9zZl#|F0VfU8>FL#Z`T-$deEyn_up2m5RB|9s*&gPpfxkT z8rYzVfyXkbuI;l2us9@nuy55ykQNi%eoLX{9i**B!-{Y6>JqOYB&L8p@hu)6mfa$G zmV^`3Uk{|%1jmyx3PV(6s{S#I$MtNZ?f17iR%d%f%_n_56B?}(H zLG*+3nsoe%88^!mV#hXd!T}4-q3xt0CWBn;4x^#4mw5nr5pP}`Nl%?w6hzPAfJ@0; zauruE;fbhHFM^(fAFD{Plp4o!0iAX=x8xHIl+YorrgkR%MEw~iW!|SoHVvc4rM-9U zq9f`s=i?hhc7aOj`)Zu3Kr4)?Oj$-qFA&r0S2H@IRow#bxT(DBYi?j8KY5RlFM;87 z;mLd1%kpbzrFv>px_M};v*LQj{|AdbEKR4E#XgY%!aE@Lt^rL%_kzhW^RCgZ*|kaf z#w=5qd&`NKZO`fD%?HzL2=a}M6Ud8l#+RGMNRjqUe?*b(MGO834O3dINP*5)OrOP^ zCvjPl{9OgT+ zg^%g^Zqw{g&D>l-3~qwxsp~caTWqq0s~>woGetc!cNTBO{HlLRO=e7uP(LxmxF zCX?N4(M^$NoGHW6-#IIuNQ0aZDJ0({Kk|-XP$V0cZeE3TAc)rr;kN{`d@;dq|4jCx zM38qT>jVco_5p8et5R_*tJ{8BCYvqt(*V*9vKQ!k`c|)^o;xw8gpQtmph#*F@_3M8 zNl0m|JS%Bx&4$g@vsLxZ#rr>a$fV{0aq*TtO=`CBuw$TZ`i>r798-@|fdXuqJl73fTUxjH zm$oX@)Iq=^W;x4WNdj%YPNryV-qNy5rct~ynF)>OQbls*xmIcbf_)gDx)13|HtPv= zihT8DQyT4A;SViQ&>iuwSM+*C?zp-C*3#C-FjGL*e-|Xb4!+N#wf8y|F!?!bUB<0= zjyTVIICi2@nyi#LOFrta`ZGlS$Y8l)u+1u?ga;nHywJ^ZOUE$8JCp|EC%G!zdipdp zLE`(C^A5P!Xb%MuwR_AvXN{&&A+x-0pg#V`i9X(X{tT(!Q6k}((7EtUHS+Cz7@GBL zVsLl{0InVcv;s6a)$i#EM;y+53Uj3f<={K)hksj)nz_8@`>-81 zlkJ5AFk~)KCg}6m98JotYv-4f-!8V-wtPrp-u8+4-)q-^^0Z_!_YuQvog@ZTq0%Xz zVMjDj{YS}NWSZ;VEuVa8o1d33`+X!Ff31Gl|L>kS4=?YF78EYbQNM1H8iBoK6rXj+@xLWLB1%SR{kZMtB;!HHoPnAri&(NA zT&4bBy>}_#Du<#G?VyCo1L_J+5fADz3k`g^Vy%mt0j@@3!lyZ`<^@DbzfuUGjBp1( zYY=Dt(5zqUJ`xpB|F_Q`EtlMOl0m6$T73ir|u?o$yp-MYe;2MHzEe9rVrxFN1o0_&M}>W6d+QQ z)Og@;+9<5bA#LGFaLR^B@3E{-ii_oJ`*X zTDjstY*dV4eJ>*f>c`W2#du%xeHdQ8a7{Ij^7^#nzbrm+hY(0W#KX&*ED_IR5y?`f ze7Y3!R^`g{)EGCh{3O+8K)~iOciQN@3j0SUVX@Z~VRqH-&F+NUePR0E`*=yabmEsy z9r_$Si$lRG4jAbrNzGGztATSoRsfta+HMS5nZ#SQ?DKTJuZu3cZeh-uO^L$)peDda_C2MHwomyKxXgW;DUNYq#n4Yi= z+}g4O_MEWdcJ>R)e>qp_j5-vI7gV18#J73=EW!RD6CJuc9eS)s(|r&`L(dD~2u#J+ zEct;^pmpmSy!os@4b6t_RIDvSSK>|1Z;B%OVii4E)%^wxPr!rHOhaBcgxW?WNxG}} zU|T!Lb`1k8HhfuH)$0AHYHsKpt>)QhoXFK_+kl}p-azqFt(sk{m02KOFj(o;SSD4b z&-$(tb`)P^eUgyARaJtD!OD*LhGjojxL_F_3LY+A)Q29xX?!yuj3-T?B<*|l#P_GwRW5pAR%KF4i;P-%AxtUJ$_V{ z+&je}{6?qjNtSvuGW*}7{PH+eRWYf>(t7&3yH0#NPU-d!|2*AJCwL$_2l(i@QtL>$ z8%W*qcO1$jC_c5KU(35y7|?o2x$99b;ozp2CUY#}LWULZk@@B~3O(08fm_{q576^C zrhaAlxFI#HCyrB%=NlouXMEPa^VxW;+phlur)*=ChsaaS=%RD^Hp+qL*8Ucpx{tu{ ze`RyeNmbcwO9YKi@C?7s(0!l&8FsTsv~lbLc1F(g1jM&jaWtnLp2mABNM=pQXf+s! z9HrN&R8G`2DI$NPY zE5!4vhidM44yx00NGXWUQr%_jSgVU+OTnN8f<)){WZ{kgAgqckSvy>*jr?dKw#Uui zXe-M`y_$P$oJ}^RVcUy5=jvKDSN4w$kAu zqG`8P%)tnA*wPnnAC^QdTP|5t@}_b$Fc)7L?C*|io|cEeV6|3I1}tpu2M8_z)oOx- zQx$P&qA=uhj3?rQDm4a9BxLgC;6y_@H-?2H;(XTtpps(fgzd!(@7?e3EjA05M*S>cj4tDlPi0zvG*Tfb+*03MeiEW!$nB+7or`Ze; zZTX+eawH)d*zee>@3gu*`ojC78_cNhjsXUa5)IKc(y0^S33H8(=eGPkI*(d2XxtlF z4934iNPlsj4~!PP#yGh>mp{VvAebWj(EdP&ssNv(KrDAuq&Pp1-|y{(ABUHIPTs+`ZRl57DTj?D`l2>8p@DgBQpa9H2!wtn6; zH;M2~hbeMw2x!A&*}+sf$@Q>t9cmwmK3N8a8Lz0`RID_2XcC&1HLaEBeaV)!$8l~RNf96(vatMCz($?c2g$#ekvNmc2*V{gu z4SpAcmL`rp*dV)etKs95_nArq$#7{U*7I^yRB;(A?7k*iDE3*VgZSh}GTF3C|D43!stU1DZ!+=wYWJP3c2(gf0#;$e1qWc@-j#VA;bwar5yYX*^2sRY6h`ebj zi*k)*Bydgd(+(P#HJl^^$LE>lBj85+(CuJMf5>cIcuLszad7ciexE|F=;+- z;Ch{ET0s3PQpw%VYVY0Sb4#?)*a1H5CsxCG%6Qmx82>un{9j^hfq1~&l#TI7i{dVA zCvK}mIu7=)s@K0c^Fp9nA%-3iTf3zA8u-fDE)BL$pmgy zKw-KR`s*P|5-WZ;U=is%S1-ic;=M*FSv$-+Yv>{~-mD`~g-$AeTh zMVzo=%hs+y-H3kI^=SM6VpY2gZ+38!YsZa>P;pqn7zG?mpVHB^G3Q6xanof4(V4(=Gnd4cAde#kG+^!ebeLc^}LsRcfjb!!<_feEIxmaTAP@1*<>XZ2dmNrZB$cLJQ+>MzTcrtM`}R(v7EU06*T-+D5>Q1&!Fv9==` z*w40V&!LiT{|{99CZk>tWeY=h&a$o_fVVDN-1B_n(Yu7-DHf6F@v}d_@7;sl{@7o8 zuh51a%PN|v)uo--D6*xiOJWk)7|9Ps{3WYU)WmG>i@7nk$e&>;6pQkq9C1JeG$LU_ zq)OHi<}n1_5W(U1tO@c;8FG#TP7xKmc|%+ZBP6M`I|yhJN+!cV zoj4USM=gbt>vy4LK0?U;e&Rp7YDJjf1o;RrkYnjS1Jy3&DRg&G#Sq{$wKDq;0lrBz znQ9Nhx;%70k%jQj;@W8z%FxK)v^siO_Rjpf&z!$SIjJ)hN{Ng>=`;mu!`bx`C#l9& zboxiYhD}u@kA{##^*ChQNfVc*BP~a0$&H!H5P2?#+|vYM%`s!A)8))h*Mj8HLBqCL z#?2c$C(kJADe9l3Yc`Tq#a!2jA$n80jw`-wj}vMByLnYp+e(t-RSBivVon|Bhox-7 z%YL=Q??comLw===KNi2_Ly5q?ykDQD3X>jtp=)m;xOGG_x~?0rcI0Gh%n^3>&iJZ7 zA}6`}nVOvU#RjJFM{lBSOduNEF;r(EAPJK4Zn)qj~-riMUp^T!A7&NhN}v+mhb zFC{aL<}V|^s>=b!<(@^w;MIi~@3h~B9(6t{$r>{o0OG>aue9n2-(Nl%s|B({5$wBW zb9Z?K@$6btG6uCJzxdoMe9jli%6Q-A(0c8%l-%rjhnwxc)WGj5Q9BGWu;-;4P{RG9 zLzSTx2*w_wBkbdqWuW*}r68%Jmtzm|9su!?bFj)sg72sZPP`ahA-jKh|cap%sM@!N71}F}2Aa3aV|G(z<8VFJ%^t6Ih4lD8(Wz zC;BIXfJB#&#P`57khA-5@KqQHA0pDIA?B(19O9mR`FvUp{tt#r=)O9YDg`|FOh%F} z68%E;nt0<2MquabPlS+%CWM-*&z>ZNnwyd;cE#dG*d394Q^$yU%j<-f<$pbt)@#|z z6C$6RipF@$s@k4EOi|3XJu}>ttB4HZl(081nfKba6Mr6Psx2M;PROKbkgIZ9S3&HJ z`O?u*)r1i!(_LY1{o&dqMH!Pee|#}gwj3(FZ@|Lh7$IkWev1*s)y2erC=)($bH*L0 zgh|hyb$XkSWDK4j^FRy`(0wt zO|5s4=p(WiB#+ky@80B_TJ9$FoxY5MnuhFGoxh_|83+i@7phS zRTTw()a8arS)+{MYHH5CZ+!}FP8A&*an`LHs=!H#MCOgGnaum`Pi?kfoF*lJ}mPZrC%ZD4BMX>zQIw^B*#X=3!4@f=r;>$kK4!| zM=};xaAfl{roFV1slRQMSb#e(E@E0fE+k_~k^MNggU$~n65Tw0K zm<=Qoqlu(|hmGQNg@2C$Ga*mf76D&biOv6$%x%&h&=Jzu!amvY#?;Ze%(1&O10B1+Zc z?mI<`bN=>~fOi_0ibmY22iHFUy(Aao;9XfXIXCpuf*?E-!g8uzv1QZEGMSvPcfJ-G^{oK}p}Xjh1TXrj z@E&pFhtE-2xg%-KE^j_e$_eRn3Fx5}kRVp@0=^4JO*@|dOlz5!blK13bZB=KZt5Tp zQRWh}S$}`OPwTX{$v?8)W&F_jcXY%umvMfBoS0yJRtCl|OR0OVGbX~afT}Mla@EA` zBsnK$s|(74%~-A7Dv(UMF{ky-n9G|*w-RGBB3=l(SDGhTqRC%T#Gha znrB8K^@orgy=7-30UjnZ=;Gabz1z(XaTs}c;EyM}F}{Qn5>P&&O4M2K`>)#H`J(a< zP*{?x04NZzR4lJmAJP}|3|<~n=7vquzeRC{GI)|D5~!%{R%&Gm#-o3DB1AQUup#VH zR=3Y#asgZ?Xj4@106JL$j1DeuCJ#Y!#xJ|WWfh10lAPs*q3-Uej- zc>0o?$rZ1;Xf-(47B@Uiw}`Qok(Jlj_4OPw%q-L{jlSNmP~2#1wvDO^mu8&j@5!=C z)UM5Mf?V__Tdfg1TMvkvhcdvxMDxE0*$w0~dAgi7NW!E0WXPFFZx@o_Jq`}fw{iTYLLVUDE2cN|75&S=W}7XcFf z7O`{%VI&BBZ0O@jzbp702pR2Vs4QfDF&;})Nw_1FHQM%L)e`(k&dja*ZQCJY;+1E$ z;mM%!G`xrptpboc=(ARcz5YYO-1MJqmJKU|uN^lfMDGX&5@9S`OIU|0*OaV&ec8b1 zr;D2f1Gnvg^GtBIryorjH;cv0El>(Bl?HNzIvY%1Nt2vy3A~#MnCdI})t|J^xF%cz zW}hf^{)cL=e|$adtGnP`b4mkiM*h0)s3kfb)Q!^3oLk5i-~??B&l!(EO&RO)onqQ1 zPt|Xpn0kdboQ(pZRDI>Fh*9ZMJobD=_zQ*elAKBqfhIZ`;%s=XPJ~J+m<2mEnok}M zpmefKKHu-3?7UpT9F1e4mUBVrI_|$Zty?W9ULGd#E7&NF2SJ9*?Mu+Rdw@KCPbUngx$yqE!nw;(#_BVN0(a~EHeQlq>6?hMImbWubefSn2Bt#quCUb@Sj&9 zl9iz%jQ%p~>G1@AhZn1T((qb;?f@wlDjOaEYp9`;J@;Y3TScf#K_;7g{kyzM0zw7X z>TL~5vTEQV?{ELM6$&&$EQHARuNa4v7|l67p2O<)7ysaUppjtNVViBYhQKl2Xb>?0 z>BB#LsKQu5851jAz_mySAkkEUI$UHYi$t%eeQB^aS1!+n#<8KLj$qRwAFF2WXbPgl z-|&ffvkkq`MuhM#BK!TcnpFgJ%vd-K=6m`0!O-&6 zv#5yxkI98;)5rP|xh-l0w{U6mSB0owEsJzH3OTqQ*g#obiJT+@37@R7U)xR5v2D;A zFU2$7S%!O0e`2f~)ZTs~BF{hyz*>@B?tib)zt}!~nly>LE@O5a+iU_TPVLN2_ec9#Mytq`Pk8F0Q&uaAYiN`y~9l z&o57KI$tHWs`9=E0BHL3RqS-0lU2XVe9x!nP$)+J`SBz34-SoUhwMO9B1Kp~F26Na z2sYR!W_U_4Wa0^S{q0K89^{N1P021n#wvJ!HOv-G__~XCVZ=8{c0`jQ{%bW|X*gyA z)smq@tj39xwmjCvlu5%WEqDopV9FL-Khqs&cF1HO~}*Vrfj_9NOX)b zICgk6yPZ`7a9`<;ejZaj&5C#Ze0O2LM|k?E8G8mhYv;qx&m1YLUA$OLs+L4DaRvwl zmAp?bD&!lFz5vk82)DA|1^c?DH;59(yCR(B6OsiT6s+d_n@Z&YafBkktfEg>$p;?7 zUu$i4HCaWdQC3#%Q~Ms;r(3o?!05#O&6IMVTb^Q@rl${RI`@Zd8yJACmo6DU3?5fU zf50`g{n;iiQN=np1I37Yyq`WdOit>%pM4w$H*o2yrjbSM6tn3s^`x_lAvdry3+T@jwZq z67(lW;D1=>aN9Q*>W}$&qRlPgmXrYs2@RjGHG`a;gRP>hG1vkedMp*7#L+Usq(1dv zM?OFkGx}!<^o^_Vi7tIhdAB4=vHg=Q$av4O$^Jqiv4X#5Epg`R`QLT#dFG;h*7Pkh z1AP|@gC7jpte1nNX$ClIO)ZU^!dZNfeM#&i% zlgLdGGq3(BKO$G%I`7p^0e1E->&p#%tXXv!JW?l)tjn|T|L(2S+dP7s5Mmb-6@2f= z{?YVfPE(%-(^dMlIn#k5ERnO^kZ|!k0_O)B{T%QBbk1 z2yM?pDrR$1i9fUnw1JMgD;KEjjIq^1@!pE=v~@i_Z4pOm_CELb&bc=>{)|x8w-p;i zYWJjD0!~7bD7{KBqo17!-rP-O917y?N7=4Tr)I^de&e@c^NQiRl*bbmq6th0o_?Qpx0{}e8M%~Uvw-NjHAu#_R_Ghl zXHZ8MbDW|zU)?rMw|1$O40Jug0sD~7EH9(t-yMT~RwEv%E$$5TdkCK2E^zO8{IX*o za&yB0+5QtkPAcS{Nw`9X-DNc(Dqv1}f-`wjj-&lK2{k=paDP+L!z81hR)FGw{mV^xf29R5NJ3>&&Y0Nw$hy|S?J*glulQsAOPew z3dHu4WW9TU@dIrB9}N@YNWhr!nShy5JnM9xL_t!kx*jNnYAfDLl+7a6)Z9W<9wlBz ziPvy^ARRJbs`DoB1|1x@aLc7hvq@KJqr>AFc;|%QK{>HV$k9IWfFAg%%1t|96e9)jGRS8juS=9J zA+k(0K!}AJ#YYHblQIR+2BrFqNU44=BG`^3M}wlM_^gWthl2ew5q8o;YZ8vs0R0^f zolt3={3c9pL8L6knw^=zEYNBMAHL)cmC}W}!Q|jyRC{{Oq}iaG zdRW1iG(~W+&=bAGD3UUTz9>>Ejda@9KNlqOZ8vY-(WDdtl$*AD5#8<+M$m-@l?8ubj*7)W6znw+%vp=mSe-U34&z>xMg10;q7yNe}m zz64*0;Zi6&nf?`#7s$!Nku<{opu`hXnr|LckLyDeMw-{GuhqdaRd$-BJc`U7zFE>m zoF)5`%>jh_%wjpCOuF&Y{Xb6Yn+#s9`4O)D#;r$V))#}ugI9LgMdt4QQ86vl!9P%t z-Fo?ztcnOjP?%I6odd6>LbfwM1k7~*?fC$)yxnMbyXbs@2!H+O?yxP>S!3rN{@x(Z zaqiS?&>NH~dqJHbPj5WRk&j_S1c=+ZQlfh`l2rlj&49-n3&^m*ViT@1B%RFO@wPEQ z3DVK3U^vu+@-MS-j~<jH`)r`=^ouJ#vCku zVSS!lPji$wpd0~QIEop;9~0zX!s)ZzhuMwC$2&cotxhf?(C{iae%2_N!9sgf?kd!u z$YxT7bCvOei_#cNGUv&%>I-NmJ%q*6aqyv~WyMAmYQ%IyfJR}6M7B|FFF=EK-tDtj zH0>y}-=H2d4g&}|G)TndJNh1cxn$5#8Y~ou=xUxeXP{Es9P&$`!oe7k@w?eW!x_jB zn1>1s8H!~m5G@z@Wk6MKq(}WW8ENyWOvY=Fm?)XqL|}$YPLq?EgTRdoOh~Qn7jf0b z3>9$sR*FiGXfBpAn=gNwS&$jmn5;Svf3J_YP|Px%22Y{i?k>R_#`K*Z)xOyYVm=V}mWQ=VN!O^sm}# zPS_P;Z<@JNNJ+!5#e+cfXjau+EYe|IzqG%^=FRu4^SGXB7)1Mc6E@zaN7^EV0w)Fo zM;-o&%PjufqLI;ZY3P3XpI7=*;INC0iw)*q6Atz?i9bD}fB?WJ$$Y}M=(5rA%eQSw zH?e)I+*O&l!8ON=#*>imDt(32}E3Z z>kyyXmj%>x=>a}@@EtjJ{jSs7BFH||<1Y$|YfgK87G%k}^Ub zbwF|bYn$==$^~bfM#EH(&wpsz%RdF2f}hh-5+<=E>yKkY%eQ8V@;s~N#vj6loY=KD z60pRq9K@t-!iAC~Ui3Q&0vp*;NACpj{O5ywF?=J#{$uRmr@2FX z9zs9lj0pv9`bRo%)<32t=Gk8p0@xch#O{UQ6Rf#z?VJB=Bes9}_AKo9g{rH&Jsx3K zRbeb2ORV`cr|9&9!}zJ5GT7ti@+NIcficC%^%Il^%7IEIb0a?s3Le+^5&K2XLS`1r zZL;(qPC0km!oHej4MtI^>6tpL9&WOxR9Gzo$c)qTTAQlk-ClgMC zia8Lkt$q3~w|jV7y9@h{Z#xI~xR@A-UN2d$m-lvFsN?m31G&VS2SVWuC`b3+DCIJ{ z_8UYf29X_-OYtWG_^049OtCcL&KIzTgfU7@g3Og6Nmf%QGb}8=fdoxxaESRI9g+J9 zN-Rr%rqhyr4H6^=$`>(hzD=lV^a`tF0Hv-dK{Ln`CAVfUC7&yfGzZVFQ? zz06TEd?wH9jL@zt7*QQjXKOt`qi)^j>Wtt%6c);$eIr1nkAG_06xs?~tM?||p$h4v z-hf#4$*6@XPAo&ZtSSnadiJn%%a{5UKn%}Hc?>~CJt^;Zp?n&up ze>UG%S1J02WM19{uzob6v#_Z8sY}eN4}VPM|J>+Q>sm_8O!07O_DfwsrAWKJAirr+ ziu6C>+JNm98=*I*k1STq*?F2kud=hX7tB#c0rO{p9K9p{JKy&QxCtRl{`2^-eTKBz zFmq1Dh6Zh(=?qc~!6K$tmw2!hT*C(FmUmf9R^Rjk1faSC=NJPJvddrydf3!D$>M*d zqSTEVMM9Ej{t7vkJT8as4!Lg8hV7-N2Qo1XSw+@g6qiFYKzlwPqffQ}y`>lKIiG-lmtvzqY{<*H$?!T z2bDb~4bDmM&!Q)PN|T)1*WmK|fm?F<`CpPJDlZ-^5#!r@S@D^Z4cPn%S2k|692<6- z3qnIvtRIU>$85vJ3xBBii+BS(kIKClJlJz6juy{t7G_LBC|fT%6*;`qi{Ws4fu67< z{)H+DF-69IJfMtR8Z%S&cRS~(r_<@*l_|NwSzcbCi%7+VYN{GR!+}$7&wC9WXpvBx ztAowna@8CtH_-|Y>Jd$Hm|ziLfv>my8Kw1?w-6e9;MWgkw02crj)a9E&rRRr=;OiG zfg%FpHi3)7^vVezs(XOk_hskIh}R**&ZIOp48m84@CaM*d7tHKN6{DK`}avo+l%Ot zLk_6En^VH80~uHc7=%g%$p6oaE(NHfd*bJTboIcqCb!qeJhwVq?&XW7<#Siado8Q_ zhQ7{);t2?qC;}9R$vzP_Oy$j!?1~x($RSqar!r^o&Z=KE{DYbxkq8U7K=J+B0K~%L z?OI}rPt$Y}DIsl*jh_}qCCSl~!B+@&fMzaC#{EG!#ROAhz2eDVfZNvR$6dQQ-!doYFphqH7PsrCL$~`u z$MwxkBfhCr2%UWnd5MSTaW~@7&F77%c&>GnNvcHvDwBquB!S)VXMUmK7n%)gW2tb8 zLTV=`ED)5E!0`_^sPGt#s2gU=Z+aGWf`ZkR2wRiNgwl&weDhHZxgI#H9P!<%Z5i=O zwfyCPXC2%Gf_J3xKTG8BfhA0{Wn;O37__x--gHfh^y)f)3>R{bl=4znE&5dI?L~Ir zA<0IT*<;9LeLxc|v%P_?v>f(W#J@2)Njy@%=s6Btk>vez^+)_^3UtpUSEK?{aKhnu zQQ=uB?g({_-_n{6l9>o4k7)R)5t6BtEggGVkw^n2CdB*yjLAifljFXF8}@*Gi&BI1 zRaO-vTkov*3_OpGq@B{E$-VbY!Gnl@JzEA2O(6VW9VfKR3g&tIWPhJu-Mte;3 z{`Cdhlu)f<50;ZE)IRMS2HhzQ^q8dlJ(HA6_xL=4l3VAPh-Xa{#@yheR#9(bzw)`T z0(TtICl%ZresZ>ZZ)KD=1SVQetBQ;TQRKL9g8wXrXYqB2X1KBsPOIlw79S0CE|QxR zkozrVP%?4#`yEur)Uhq><+}*pKlp|jDUZv+R-^*CS~#y(s7K`_6ENZ$Jq!co6r||7 zNi&kLpMhtSs(lchF~{q0_mehJv8E_^kN0OD3xgFsI?8wCX_?hTjv^I%SN;G}p~P5| z`E_8OAyq&SYQ&fiR!HS=!m^%qhezng-Y_tX$gc@tI3qr0lH(RIA1Z zg2S8t?#?+CgCBW=So~qog6Q}>l-yv1_Kh&mx>2{U--KS@kht`hsp&+70&+^s6<6{+ zCmEtIDzZFew~V@U|NgE5O1>l__9(~JS^zyXHHLm=gMeq3`X4jC!TP?hY=WB$bnuHT{D!U`dyk-zJ$eb?i-+PLn@b0v`B=)^=~Yv|EaXU>YOJdVW-NV&6e zAfT-3q$ZH+H`GtnH6=KF`OECS!-HF$-W-A%lkTuU6kXfT_hIhX#xc{`mE~nv%78K^ zGUbw+SpP(ONAL2wlEu!DFfA~) z4ym7$)>`@SV7eS}S7s%Nmm8Bu3v&8Bm`CPWTa`goqs=4tvVj(;sgx794PVd;K~c9; zvEL;knxm}G`y;8HX6_#qWDo08>&hf9i!5@kMUbmm=uVUo&|ML63DMCHg9s;xJfTwY zaQlmJoi#=SOwHDbVt`o+Kdh-~Mu> zs7L@LS=>JL%QEU}44T|zFWiXl1y04xRoIA0kNk3iV}nIc31H8;BHZ#q^}XJD=Xt#S ztLpW7j5CO{JE69w3W99@<0g2_Ubhj2dR{I%WBQW_L|yTRAbaG?yR1~M)&rcpr?GY&h5fd zYn^D8Xb~UAdxoJag;=0);%}EKf`>0U+My~>F55!BAFjTk-R~J6K^g5hX7b=2E8I&? zsXY=?b}Jnd)ek2@aDR?h7{n0tt94U;aj1h2BHg=c1?l6DaYqat01X^$T+s~YN;1?u zCwcNk=P)_m&~Y?^=M!^YTV*Enwq6M+8q8mO>B%T*(z%b7WFE56cYwY2LpR21coVvZ zyF+-7i^YgUxwtda&_yqSgT|`E5{;Ebs-@r7vCoIYsy9D~oZ18+Y(Ot4Dcu~;`A~+d z`$^|dOJL)Hc>EMApP_g=H9nC*MEN)XAO1E~0SVLB0^7$g@WE>BnwV%1%=_m8sCC44yk@>Uzt?%8Qzvr%PO z!ZmJpgItH+!iNxNek;ks_|y5zdt2M+|J2`d5}H^~rFw^3l*)CV512DN`HxJ!l^K@a z#1#fHJUzuxC}JjdFgQkNXwFQ~)Q?sl=)2)PyH8}@dJi{`R- z27P^(4C|L2p;Z`e_$}%ujY^cTlV-Q|S-RrHaAaRHDB;b>65V^7yRPJ4AAFy;b`GAt z3O?Q9*puii)Bc|MBp!iJixZBvt|K(ev*m$$(fQH!K4iQ3c|-1IW5OIFP`TmEXG*~1 ziv^`{c{nc{k4O{o=k@4G^B>4Ya-vcwjbgB_&*8x-DN~w<{P>=%J#Jy-3y+s<0>wSc zT2_m!rQ5(rQjhSs`_Pg>((4U7-`_Tu9W&=%`ATXGx(~m_IQ{@0$yXY$vykD#bKia zYPBQdo(Vk6Yij@9II%nP+uzW2M%MFsXUE9thFZk!IA%{kl*EXhLc>ioD`I1oS!$%r z55*hq!*`6Xvy@uCQ%_Ik%lInsWCU}3L^NK?!=TFR{IxZ0KZvqQq4RkML5SwBKr<8S zzkid90-1^`$UgM&j+*w_5uOM0Y=m*c&@bhPpOka6AKayYXQT$@gCtaC2EvoD4kRL$ zV#+F1F>Ymcqcj><#=dx)B41tp3;-j7HeaeY1{FbzUvD?$ z^|%xIc#bL9gV=rNovGmZUZtmy+O@aE!F2-$%j~vVhT!e`rTy(I3{F-(u}3s<)KK}| z@Mz|ZBfm8aMfbPp&#ZL9uu842YR@bUvz+N5+O-b>YL#Q(L8YCg;5N2^iNoL}*^j`C zZ{p|ptyS;I~CGlA9p1K?} zGmxf-2L|1O<(s)&kKFVz8QCT6JqYCo!9Qr*niI^8#z-oKEm+Ue|$9@OM={Q z_JXn7$&G+UO!SN@DvALB1^pS-ZwaPHuR@>tTD+*StLudxd$lJHA*qSmi_R}C9pF_{S z6ONy(RV>AxH~FNV#HJn)C+g zHFtdlGK~k_J%gEZ{9-JobAb44q{4pZzjQIDinekFcFcM&Zcw?G4R>z#hanf@T9En~ z|0WiaTQ-kiSx|pO1LCBx=~%_R;jx_8=1g@hRd#Ux5VSlXN;6Dfmy4H3Z}$lH}B5W{u-5l~sKV zbhAPzoxZZ7pK~j+vcf8_JK@FAo^Qau<-I1aS?@85!Js?GWlQIWPoR&XS4{^{fAagQ zC@cmM6j&#b?5lG3=M{y9e1w4A>&E=35PJGQH=*neEawbd2*8U)Otl=mV%e7DB(Sqf zg!Z4TMABT>+q7!bzHalht&r5E)^9*(#wc-vT5cG5e59q-dHYQrJeT{&FqM_)o>%rv zkBY{CVilPy6)zo@L~0!6cdO>AfKAyfn{jX05*ZPyXX3TD@QdJEzoO89@LPYlRtn-c zBe48{q4YMeQ1&uh_@8&jzhm-$*J%IHV-3Agc%xFU=QEE$w+HMSn_GLbQH%tV^$k2+ z&GQ2LmzSu^5Y4c%d8^O9`R?Ix<+t9Povc!Su$_iS2b}sAh?O`9VD~82sa1~={s6ER z__BPuHp?*ZUcbEM891nR8SzH`=#wPm5$3puMDWNa#VqCJw=&LhmV1VlLc#Dx8jGLc zux0Q#N_|AWf$Mpe{GmZzzdaTT!RX)gZ@-fZy&M_tzx;*$jQ&y@;LD!>7lT%rlY$+Z+Wi_%DGmh;7Lgr{@hEDJQ^l?tVwxRz-&GD|=qF<<3~YWt=dv4MC7v~x-P z$uaCb^DZ;oYdKtn@^&P#f*Y@)O&4``Sbk??&Ui;~^?um?bg}&cmFstls8B-5VrJ+- zF;*#Zc|O<&`4ekCMSVPe^rm5LfzITI3y0@1rgMY`AMR`*t}i`(eK-<0LPV(qdti=J z&ZVRGJDh>{8$Q|>A<?A0SAFxv zRHye}IJ?5OC*ubX_r_VCeR+I49LR0{pBJEV(yg=e?Pg5+ z2-wvGN5KLM9u($ZjdKNtC4{ck*%CwI#2m1$#nc zvSONz!X+f&x?+U+3XraoC?EToB9wXrD)XOu?&Sx%+AX(#E|_H@euc!jrhpExKMg8x z_2HN>@uL7sKhQ&yEmo`SVYhvC_Z<3JBFN_cNpJjVVj`!#q)Zq1OrL?6pShn%&jQ%^_S0jj{a3QbISFwC^_)3$1P;fNLXMQ@4VkUYpbPtf6Hs`p|GQ10IK(l}lN%$A z4rkj=P_t@^0-YSWC#lP8QHh)G=b)lR4o~b08LU^i4LA8 z{30VwuG(dg0$(RhK2=K-foF!t#=Zt8!+xmw^_*iqFw#KVKvn1p=F2}kL%aI3@-K@$ z#`i8?XxYs;36BDnK<3N(O+-S9xCWMC5i842Q(O2)9b6q^maNx!(nOCCKX5zB*t|A? z%#CgCzUE0!<*TbU?!=FwnpNPEUjIZJZ!fr2uD2$HP-FR8&Mb9O%QBa5A4JUV&MXF{ zwdSd@HP0}&s05{{pkIsXyqPJts72Jxt@b@Nr^DC#Dv|Ey`F#l3!Tfdimw7i;gCyXY zC@qyu30{ZUt_;B3w`i`EG}gUTl@=y(Xkt*9WFg3M;mpICAWV8O(Yvam;!wljc>K z%A!2K{sPW-x45e5e?ZYq{W@)7Ff!<1T0ASAvm$ZPRkd~vx)Ia0K#7m|95-hFERRfL zM%U7|wlCHF;SIX06^ed(9Fy{9(cLVk%R4dSZ;AA3TS_Nx? zHA?mC(C)#6e4`MB65SZ@=oOYgKDJk77;XMwksHBBApiLgZTXBWDam1lM@;CNLpp9mG<~L;$NX_KE5jB!aJcxkG?&`UB}O*Eixiz_q%?-`oX$d zwDb2e1hQ5$>0aNRg$zU&56ez&JVpk%;-{l@zziCnzb7SW#r2XoIp2TAC-TfoA9o%z zh{@tN)Z{*VEee4IkraiVVdp*jh#&x&??k=#{2yv1~`mQelZhVlkJqveL6|2sN^R$}&}lC=1}%w0e7 zSz=?Xd5-%BqQ4I)wczGm58g&RE{CE*&7w=Cr3PKN2QM3VlPKo+lIIxF*$k?x=LgM6 zl~EzOP%{#q_K5T3THs|Nv9mSW#qrCLrSHlN%lFo6*4~rwwhmWapiq{F;i^eeUo8^r zD1B{apQ(a2h4QNgdE<}#G>`>nB;=U|-FRPpJ++fW(i6dKW2%Q8PEv-ZQEym*qSd5K z=uR!iXp|1{LE#UEn}pJ%dJ`;REQL)8(heM|$l(n|D)#L4%qUc0#!GjA4|58h+yyvv zJ>Wy?$WR1)E?6OTibW$a<=|7qr8sXzYzuZHl{4#wPWoG zgM1ZV>6&rAOOhnll#uh6kgLKOK7HVrWqWgy2*W66ksVzM840HzYO&B~GO>W?>=y=n zfIB0rha?@`mES9g&npBUZa$gWJV6Ha`VJkE(HxsiYw9<3#146iPr$b|M#P_OrOHzf z6%CcN`hG&+)Ud@W2V7t8!X%ju{U_5ycETO6m+c@&x3A^HV2+5{wyUSW^|A()zc6pgk|V^ zYqk7E*}U9C50p9GgOn^v{Wr&$^w*hD(WUcl2EKgMp5GE}oMzEQ@L z;X4-5SkyRFk3}AvLFk3Iu(94(A6l1cR+E@MqQiOkV8u~6I56NN;ptnwv<*mMH z^_;2?(bju%17f+0`X^waZ2p;!dRw@XkqW{pH;S?1gyG@jtLepz(%MvMgtd*8Z?L*E z;hrJM8Pi#tlgzg~TQ^wwOB5nbGcj6`{WlIn-G}?rz8P@yO|DxI4~v*2%!NdPVzL!z z-aQ6vo;lB(Ay!?O6wlrpSM1f^icnZQwC^#k7TcgZ`K%H|VF>^FKdds7@qvEW< z!uwt&DXrv0IqR0Hu!2;<5iWYo1F>y$q8}!COA5@N`cuR98igL=PeHlYnA~^A8!9e# z$?P%tEYpeIHW`q!@N>t%wX>)5yOQWB)8mxH!~6w%RvF=gC{S>$*ieB~EK3Y!3h(#G zmxX+Jwl6wQ(q>SZ;oXg~UKWT}E+jP8FTk{tE!BrwFFTTLA-5P3-Xo;8=%Gv5+z_Cp znGQ4BIXY>w{w0A1*{BOEeHf`*OwfLKb8O&+IocipM{X!} zB9i&w0}jl{BVz}djj|DS8ivlTf_1Xzw=K&ay%b~7eCTBPM55*IB4feVH1fO_ozmJ) zftYg2>H8g{&zK!br4q*YtD7DxAVmM_j?wG*=tMgqgN@gqX~8A%nUj91na?BSGRO@n zL{%E&kw+@NBY*_v-PrYFYUYvX6k%2`65^v$QsY z`eN1l{Uok@Jqz4d?%y!d(Y7vPZoR1F?RA_p;-J zGtNGu@Ye_7jc*pL0yStj=Xgb-EbA6M?$HtfTE?cBm$BvjI9=~k>rcb6en4sx&#HeH z9x{8pKOu?=EU}^mBjXV2dKxRVJ$wd4E?`-3OieUZ*v({w_MShJEz=IcsEi=1txdx$LG#caUw0 z^BxAUH4>P0B=ji>jd~D06hw%Hk3wMPS1L4dX?l{VW0M&vI6QIH*P%F!XpE zdUygpPx##ry23pV578lMY)TvLJ%>{rbl_BxXyLLfS!}EoOiWOwe2*0K6`yx4AC0t% zM*sp6cF)S|Hc(4{iHDsgA1KnV3$8)p2H* z2Yq6TRpms+Mz@c($U4%-#w0OO@71e{^Ai72_Srr3dr#|iu((?yS;;xhM5RBgYpxrq zNGUGXT;yHH0{U~~%>z2!ScakM$(Om}eE8A28hWe)Kp`7C3q$ulz5o73%FN}s5+h=E zN+V&C31;>Lx1jbA`ekQ97$rBdv<@oOsMwU=g0~*%m4n$hfHpzVHfNBQhyO1Ehum$2 zTtWfQALz^r()G^;n%>jACf&kD_3J>$d*hrHOa#u%#urnajJm{Rr>$lS&tFN=#;kbC zFm|tIhxc@f%@=5m`z_a`ZKV#mNicVeEFkm}?%!2EkQL3V+|}~Q-Acg4*^N+Ze<0Ki zjP@W;L~^R!vcfIOyA+VPYg75k8YQXx5XA_HM@XvQFFCPal1E$*!GWm**1r3N_XDd* z(Es54ga~CJG)ZuG9UMN>ppeFk%;8q@ON3W|eP@O~df(qywLV3O1{4TRq*WXzoB?cMFI3-$hjG#U0M) znQMiNRx}S@75idgT!& zsQS!6;)_nWg~HETu6N(TmA_vS?ej;$mS3dfE2gvqaq+}IO(0=Yn?O-yo8Sv6>q(Id z!c2gqGXOnXq2>lmPb$s}R|bU`L|6n}?f15Z>|+lQOGd}*y=Hb=q)bFlkx?dMd%wZ0 z<}{YM5Vz0NP1@LAzdfE~kw&560G$Y94vS)eKk3o2{C0cB|=2OiF zr-yegm4oe5&+aVKU?NMiQ%ykw0vSURW`PkfbXi5`2tF=c3Us~uuZ93)l%37T)qg|8 z7Vpm$Tc0{9CK*X#HGXo$Bg8u;#cix6iQ<}*CI)H-5KVf2`gF^)bLcwI!Kkvj?!Ktz zm~n(0K_w|aop_j}t!7nX3Xh{qF(Rn+HQZ#5ixC|y?6L3exAzy>lAdasZ0W68HELcpB9=lvHDimRgm4;^5*IZU zDM`5Pyn)L9-~{kWnv2rH#c$3!VZ}y1<3#hMnrIOCh61Va#ZQZPvq?A^;8=$$ zF8PEpYJn{Yu|&xWEVh|Aj1uW8V=b+ngC_#O%+Qa1kZYN<0wEOH{9p^d!;Xs2eo&*5 z{3$4O+Cz5CpAy1Hzf>W7(!+M)NF|VKlf=(JnqER^yb?7&x?zi9gvu!(f0=XaY(mYj zNw4h6$I7_Df*0-LZOzLYlRKj+*WB)dL&Cx}D5QAn)4Jd7XOT7Ao+I36B)#iKA#kHLhs_8xS+Rb7A z(l?X&3ynA?35BiRpn-73=ms){1I4OrtSmm2E;o&tVW#h&QsAleH^dZGawc>*nH&Y$ z`RD*Fvy}k5yZurvZFML*H(bp}>clYI8|>o0uONBFvyuqO9~pO|(OSKG*Tmj1Z?lQ%R+@Qlh&S zIWJvCp$|i}(Km1d75kc~XDc{+-O-&ZC4N-R|*&JhuMP-TnBV$xQ3Xm=QFC5g^_%}Qn7rK75n>&l)3ws zgmV7mqN`GiQdsTszZF^Ayk_KbVEQecAgq~ZPV`=*7_$s_K=}%glP0yXpC#s2wq{$MqZqNC%TihqM5&!wu>|7wxPq z)V8enV*=Z_*gbgcJ+L)-Hk$^gL?~#Jj3R!p0 z&$rusnW$W3xuADXFyw)9h^uy_jlG(CsacUWSLpu{o0`sbDI{+)v#c`q$7Cfi9u2?v@Q7cbrQ`A0O&t+S)pY#gRr+{hx+D)h|6a?sPl0v5bvxf6 zg%#S$(y0rS$}yb0n_3z25LREtFK_z%9SUx=@j(r;)zZCte{OtT0++-TBs-cSBb$^T zQJCEWrwmVa_`cY!KNNnze`wbFtuGz7l6Fq6S)8sRhl%CgcBse}R4=&SeoYb0`cYu9 z8^wzTsjMEM1Lhp9p`!9aP|Aa>p}Sw;ARE^yHG9vU93QsMq$$7m~Ph>i?S z9dfGaYBZT^>h{V9e1rQZc7Tdy)6#eSYgXZbzH&&l8;vcja9!9yamBH$qy~_-021i! zpG{vBp^kRyI=&Bzi`{(L<1mHkjal;Q>JjhiHFeMaa-^_;yY5#S=PZgza5LH zi-%Jd3f-=VZ3%bJSn$KPg<; z1Ajo9g+i~pONJMw^8Rn;v(~cIpAnq(OV8KCW7`o8>1U#%_eK|#O3(GOm!JleiFWu| zrq_7~q#sd#nuig%2NDmCLuBPmA9%cZ8Y z+@xC62`IgD%*w!Z&vf}PnO#!JeJi7&;l6oUx-`zW>Ked+nT7);hA+eqAIUzg0*n>^ zJ==!^^&KT6v zg}>X!UYJu#&NvM~qN?ontPm*9(09?puT>ai$~9oRIyU_p5X)_TyE>eu3ng?8xBM$v zdqE+TK;uLTW<_xaoz^vH5C9#eBNV;WfUN5{V$8}z6eX4fib@qWm^`|*y<7CPrAf}y z9!?Ko7!eToT>!?iA_qEjB2R)T=}&6~;^1naZD`%6V;RA0gbb#jGn`8w>*!A*0i4ab zmC*O8E#%Er5Zg{SvNHD{wG1_UX|;tB0%ue@Up)K*1pec(Oo5M@KpP}YdiVpTqZQ}| zXg=Q~Ux0-g=8Mfzz>ha%QIqpy=oo(mcq;zE#)8CZpSUrc??1bObP5WHQOlr87<4Vv z(~bHyy0&0HOSZy1<|vkiX;CO|&Z6xv!R+uXbs8V-f4;#_1RUHDpjQKJa;IvWHA8SP zP49;Lng^9jTk@AjxU0gh)G4L2h$N%)18#y}^dK{Zw-SDyN?>D5>v(k%5nru5m(rv* z^1^9r#aM>AY4RiuVr8|YBRRl)E~~3Y1)mO!7E%0L6%WnL?>P&mBBLBU#&NJGomR27 z%a48(1UjohEjE)S`0#R)s;VlEd*7%@4N9a1+Kgdn&y|1#d|MU5Ug^cVI0j!P^FkA8 z+NQmLv9AR|C8VU(3@Y!ok)E}*M91xV4xFU6J}bu^eviU00*Cnkm$eFm5N>y`V$m~vF7J# zR~fFftR#DobJ+I-!HK)z%TW{`U{h<`Bf^$#U-#2*X@yrH)Re`MAhocUC#-&A7VPWs z?*gc&y%)ltY+*^sH%n_M6Rg7=_wVZVO<{RjGm9$G$AVA*>joVXBI_-)v{9~c9Z#ig z&6CMBY_Ntwl1#ROYqrLV^3?gL(cFs!hkp$W$rVtUx4>Hb1_Q6lIaWtruVMVgH9OKW zg3yk0pVY`tL6zlz0&xqfv&`8H)`o+4R_6cNoIovcP`%~HrFpDX^H_e}mTPd>c;)Yj zoC##4Smq#U_mmOAiUB0GzML|cM!-;vmHMxOPpgesv zZ8^U#iHb8iP~PQZSXkq$UePmwC*6a|e~@Rvijt>TSFuInkOcvO36M=Gy|`5pg#i1w z$&rL}$z;Yl)1L~!3B)3*foxMDfAs&n0D0}-{_22@+t-2Rk!LKC%Tsy43Zd=uf^Xzk zDb^xl*GTEVWBVpyl%Udp;@@M4P!`Gd?`?Ny4(^%w&j@A5b$IJ)!sL*SO(q$r(2^}^ z!o2f47G@D7;6#PqTz{Dkxt%<^aMDZEAmpiQ>=ROp-p&kBSrPLzNa>lhP48+`KP`~S zD(#ngnXs46{d%q;-2cIW`h8lgvrN5|t$&G4Q9d^d4GPur`!}U%fqaY}=n-hnL2+LL zt?D&}yF+tDImMbJfY6o<$dK-!-_#WwMd5a8p~BNbs#p$ zxv_2I>+QKi?qXMp2HSQwcxOW@3(LmUqnR~iRvAgI_bQ4Zt!Xv^QBqA?JYfFL5hFBLSnb~`(ROy7mH>Q7HtVe*|5qPABo>`7(aFy~^o|N? z(re!&g%q}}U!b;cE(wZouYYSI`pG6usA1KSi_{Y(ZW^ICTdQTxD80DedsQ>q=s<Sde3O5J%-XFA!ujP`)zyWy&)jda(? z(y_P~TQGl%6qr9|-q^olX(c>asMUZB2GhwZaq%MQ*v)apdX%Onc=VYB0MXxs{Yy`U zQt@eWN?S@ZUdKo|w!`J=iQ;vLlBocX;MjNXn+LHFr2d4_C)iaVY(``j9P#xQ zHIvF|o3YbVPwt@mumlaR%2_1`s&irQsotO&R9b;oKIgBtGu0jQDD|5TIHDhn@<-v8r)1ak$yf7XW3uFhLhM*igr@J_=dE%^S6(`?nLl(DVkA>)%>dX zz8c{5U($+1apeFxhh|w(T(eYCMI$StUZd zvUXea9u6t({=A0WRqZd7q7hz=^YExHU8)4%E6*!JhZ<$BjrH+=LTq4Pkx3>a{G>8l zyF-Ty-&FklpxCWDk4i(E>DX@1`z%K405NM}&jeh`v&+V+7sB9iMtJ&|pzE}1ob3Ob zX4T~3NM)L!#U^M)Jg_un>0Ljf;w(0VG{K0sz!*CE#r=^#zuX<$8$dr^&Ip`wcR>6x z`yQN?tqmkIVhjE5rCJKDgh1C zbElFn$tso&+La045&hG_NGrE;QJ0e{DjgLTm{Du5ZLS=HH@dEoHaL&4ryS2s1YU=L zFa9IHK&;p}3*V|p^?=>mlz&3LBT=P8uj1?7|4zGqb`RW%&%Y~&T9Pgwt;If0Ye<8u zFTN)?CE3S(<~W;5iV+MfoTDMCM7&9#Ym5^mL9+l>!=9jV01K}Eu_+>AK_P?EoU-M5 za&|;11g0%H=}AcyRHXVt0lFh)P21A>xZY(VLqk1KfziR?(+o|fn+x@_>4lNv#7IP5?O4&3~^sWLbg6{qa}`%QurphQcZ4^k;del3FZ^S;1dDp_Gm(RtHA*o#g~$xd_cuWq|R`O z^I~SOqc9SmcNNKig=3cpq-;P0LU2Wm3R};JC&?%aO&ctj*>)-ISRiga8%re+m#cLR zRiDn(-jU!P+H?8QQLGwi;uYC7Ib;?c+vKY?O(RXeBVUX#Roa3s8-7?yk1Tq38~MX3 zuE?4g0pKvdJts-sQipHa+PFNGdDDNL^T+KRrO1ASjUXRTF-y17G4=3}(Y{vG^e6lA zCgipU)n-0Y8GoC zliH>SI5Cce9Zjkz$SmL@NLqw$D`|x zUVo5PS46Xk{DhAA;DdFFSuRVFdK^$ zz_8m&2;?JB9LB(j64GEY8lD1fZZy}(*xRTFSpz?`G8!$fDMVE4VKcxFl(u6;wh3jF zXwq&9`*6Qqjo!wEZE^|J+`Nj8R1iIrrDSjT)0aaT>}x0`MIIyvpBT;K9kgHV>y{$5 z23zexn3^3|Ch`YbN|)8}4w^Y8 zcsvn}2FKj8H;kLn;(goGc)R_dq}O#Hr|;EbtTvdN!_86+F8v(i-jFt^VT?XhWmn_< zC;dToQKmFSmkc0Vp^{m5NGvB^%4FMwN*jP{)*OHj`sjST*+=t_w3zPx-8X*_i3AG2 ztBL%Rz@6xrgH*f^vGn(P2CJB(;Hm8x0D7X>!;0g=!%ndkpNB=#-G0%0A%c$STZ#O1 z9oi@Ym*3tMBCJJAa25l`p(R)7aFOmlB92k`3=NSn4K;;wMB_5q#GLg~!so3Jf zRB2mcQQYc?T|A>?%->$9O_ z!-;o@-o(cxdp~Lg2=qpBxA+CV1Q;CS&#=s=Gq8y#-1aOOl@!#N96`y4Rvb;X+cxj> zX}}c4{Pe6Ft4RaSQPnorooEAjvORHtL?+n7Hxxd&611>2>dA~{aS7E@bI{4I<%?-w zqP*gp6bl?1g>Qu=k>b+u49i8}y4;RUHM8V+5hDX{egW~zcDRMic2=I^8O(8P^`R;x zBQunmT}zdDRU{T%UTYN~G|f@L;IiJOB(%Rjokg~xi&kpQto(&wI|7x^RNbZ%5@fZBUScYDC3xqweFb& zaq00)@!9kkPE=E2CYzPMc;NvUI&(rE~I_~ z*e=)Ac!KFI)w{?8xPT*dbku%@gq6QC&5?gHwRH0DLFgv^;b@ND9-A{9R$f6Btxa6( zFz)T&A-gPHVpJ7dhx$z*yL}v_Ruexi3?p6gfSh~lw|QFP9?KkQ0USG(<};rfdA@9@ za(bvR|J7_G`IHLsewMK;N*+mA{EoAPz0+Q~1cnSHF8ItQoK)j%KfbH*gOq$Tr^W z0BjAU{2N2@m4xKpT4KWIih=O(kjPY5c=z-A2ZS;DjxF-nO~s|Jdb++sd60%~7u3=J z>?1lx(4i)m&q&(XQg~DMqNlAWyARZt0*n2|K#OUXQz)ao;gF(ht>r+G>5FXa*;4sP%Tv1$S_$-`l^A=Y;4>w=A28g5W;2m&bG{3ZeqC~ zbO@MTbxMBlFPHt&AuT_~RQ0jc?&BCg zXKxq)zA4TfkCQ9RU1&y`q}YC9{khG7bQ#rVKPn$-X>0ySsPpQs>@CO+yq>nfjA!8b zKT{;jfQuAG{pbK4=6VdHnkDw*zq4dNf82UN)`(Bv7^h@0W(+O4+3%gwFl}wi)`S{O%a z@GffcKRJr0s4d z$j+xipG1j57Bi@VY|`Zu1??KHv+1-n?9H=EKO^>Ur67D5Yy}rshm8hidb+N1n}QyM z9cEf7;M9xDq`lKM)8cOmGZH?_nuk2HA6L-v;SP~(B9r_k7@T&{U~cst)xcsR+~nr8 z*&^(K1aKBFdE?K1W|YtGRS&)fYCjW>^rEI^<0jG8E6pF+er9UDul?b* zPzH!NE1d8a6NJ>I1^&$5R%e;+`YTJD^IK1cYvO-UG&~QU!GO8;eYK%rOp}2r|1*9uZS}ta4!EDC$-uAi|4HP z@k343M&{M_UzuT@#zg`RyHV}2{cj3+Cy5Y3^KwiYjC>FOV2}K_<>)Ee_BFk^Szg3XQ*cs;TOK7FUZZ{v}_a77?IAZ zfkn648(P;-+0!S>hDV*kXl%=<;?52PrB^^28JG=<-L)PZ z(K}i`te(;xMr(UCJpJ=6_Ux+OB--HB;=$SGBEn|Ga_NCS?5N;_j|~oFM&;|~Gm4S^ z>zli|<)u=fB}P3jgEsjXf_Q-v3$zA`Ofh!i8G2;#122wG)3kv$g3N8AT2bf%yIfE2 z;$kwDV^da^T4-UNxY|B`c`(W@hy02?{DD){{4>~$+lU@cjBV%lkZjtXIAPZ$sR3h; z1ZG+0QF{I}y&UKLbW*&w7$%Lm(wJ5X+`OwK9i$%FiEonDY^V-fE|E}}Q?OUy8&9^P zP*VWN7&PZ>YP7Pend=+44e|;Wew`PFbog|U1JYx%Jyj7B@dlO4y5P;JLxKlgWxs+O zpX67_g%*y05kqic$AQm&}f@CUGNXR)+<- z1ybKBxlk_6rv9pWCcNkZb$cg;y0~}A*j9BfGb-cA)kH@<@BmJ(^5PJ}(GJ3(=U*MD1%v&c)24zw$M->aYKNIOEfx zlT6}5zTPt+LVEbytrpeYhjH78nYYyj`}=ds5tN3+_<_Wy)~xu5<`jbf>!cVPeSwig zLOdNp)>3m>k?I9q{>;eV03Uf7oSAV0Y%2&gbp$4*4s@IrXlJgw*5owg90O_o6Dcdt zRiwEYVFU+BRMqj`)Yc1?)ux1&{LHr|jrk5e-@w?XDxNMUla$vAl~`O!J9ztpy*S+| zgGTNSY-UiC1b1|&jf9O+oX$FJOl+2S$aS|Uo#)eY)C}pjnytRJ@c&x^`rzO0Wii!{ zqKkC5XenYTHdf!3IK(xlQbRL}AMdNaR7Kq<9^;GpbxeFMownTKX*%ud_Q}z&QlO{! zS6yyi!0B|#QowKfCGDKUv2jF%(y!>p>$!N(Aq2hmTSFqN4BSH|ZGS!eKT)?UdF^df zTwD4ZSP4GoJKLkx1tBB&)_OFNvK85tAjL&as-e^*G^gR4d1vY%@nxJEJJfAMik zl??Ezig`6#BivSld8;me2mZ^KyYkoN_rLM`L&U5SVd%O7xH!?AQg<*oQk>L_0!!=A z+S>_oxI$SL#*WebIXZXV=2Eoz;+?+ss47JLfhiS03v6DOp(0)n3m^4zj~!a9WhY1r zD8d$aKCd4$REudt7VpvE`tnjRsz1EAza=F9y@bCcr zJ?H&*C;X08RqeoHFA2$k?jF7nayK{gDAtcawln(;ini?9!+#wZm8`xNBO+EcIw70+}+1~kp(;>{qgD&{pitQDW9|8F^<2c zQ)zdxMzRDF$Y=8O^c}Q%5VEhr=>`XwEf(ZzbCbHhH$dzZl4nnvzN7nhzG4>%RX%zP zF+CIVPhEz=DKQu7L%9JfkFTu$SvHF6*rsm&oxWGqC)1Dj?L+MpBo829WoP;QAJ_Za z|Np21MtUZFLm@vizR%}V+dPm*r2iElawfCp71=8F89a(_QlIAP{gvBj{OSbLPZPZ? zOyHq~Z8|Y2!Mi6S^(TOz48QD?>aVh%7S=c_!=s5F4)zHn*cJO4k>*0+1ev7vL2JGu zu2w)Y>!1o%Izb``k7ODP5T)Y9m+j=;(QlOjjXC(}!`JRK{7?3^tQ0SY*!SLXO`J-m zlXBl;ROThs|6y4RcW3(J&3~ZaGaAdJF;vqVKdk7i8p5c%28wucUYyPd#*S>^YJyk4 zvZ?EBi)B&^whukZJNx5NP>%=D>fbfjiUma}AChI4@?@onq(?g+KwjE(=V~I+Ug)?EJo6{F4 zUDYkTMw=2KIa6S z%xp@buIERDELuc~oD%hOsKm!aB8rS#H`qCDGH9tsOG&~+BR|Asy+Jvr-c#Mjajew- zN=e_`Ndv<5((#J_K$<^#ECED{dnF12yB1-p$RB{pWLu_+l$bx{QR-B1g=#^%dk=X#-nCZ9sx{ zBpUguJIUL-qJLof$@aeC$MZ+XWA`i5VUdW+kXAc`7T%zmU_UrTW+>aOvo|@?Iw@f? z6r2&&QUYX;sDQTTxrl%UYf3KX7OmK>yJ4^C*dEYEmVke>x!6aw$T@=`K-&7Rx zN2JV^%&A}0&s6NjDcm4bR=aETo4eb|GdSg{*mpnf`ro+R*<*QU3q(FX>uG)Lr4gYm z8Z2;yIGt2A(y#oby2A&*gPs3Bn$9w)%`RHo!QF~GMG6#mx1z-ziWY}LaCd33V8vaF zw75&r1}k3NgS!U{`sF?6e7`c2$xJ4*^Q^t(Ue`Tt_m(9^;)P{uE5NC!Z<;2OKiNK8=m1IVJf!cN)|Ks1SzbDBo;usTvLjK=H3D+Q;Nrr7fXYzTO18s-3WhRZJ% zcf=J2B?$&=fokjed~(!@isG}h{ydJ+^Np1hzj*yzM_Qqau#?A|K(MgVv z&LkA; zdgjY{VNKyVky$Pfra>Xba=*(L#&r}HE-Ps~|BfbaR0BMXF91F+?8fd^H~*<1aBR9N zPe%B5{&(mP1BWQ=U0_M5zylKvfnBOL=*L`E@r6i>$j)uqXI)!o?y$I`=H_Vy4qvAZ zB$GteY;`y;W70s3vs1L^_F0nJ_VnP;D$V6?u{0ok7+V<9buMvrzH5Vd@!wYVeKOcv znZdULYbdjfSG}8G)fK?`4jGYB50$wGbll0VZ|UpyF8u5KtzUzx^rsrdjr^w|jN$Ad z#n?vpTHbdUJcog<%@GIXx5_4A2gMC?myJlr{Gi|> z>$l`Lv;8Y2IvMwSh5!zCo8h6rGaUu1-u43nPS~hL6~c&q z&_A;ResTRQOwf0WEK&?m6FtrQ3iv3cWraW^KQPixqhRY_$!lVlk7GLH-*F@h(_7ZgbvyA^FF{6w-SG)s3+PFOhAEL%IKo1tlfAVy(IdJRl! z159U_YK&Q4pG1Mx4{n&KwG7H{kmzmD1jHc9ptDnadw2H@P>iN^xM1LJJUXh{9gxma zFww&H8HnoVL2Cy-%>I+eD-i$X#zfAeYoXVr^w`nM+!6HaAxzjY;#!9k0hB6>O3ypx zup+Ny7J??-MiMy2ERAQ4ySGOmV#>j#lV?YKP?CU`%=}2C=GcrhQgL&%lN4DN3tCS9 zBc$Qt8sHIecMf4r^h-rZ+7)8}UoozP&`wSY`|9qg7>E~$8O<1OV08%KsdLW#e=R^t zCFw%ev{-(DIkqO-MWD#`v(NdZyI-IDoHs#W;Na-4<#&na@KJd;{cppl75hJNK{%3k z9EnX$9P~D6A|FTkKF_W!iH0Pe(Kfq@=eo_vm<&DCd`AAqX8AyQ_pGlWohJ=`H+>0R4d}hq*fQjBxn| zzV{QPim@}Kf}u_f6h)D^4?bvE8Ta`Xr($@n|EL+2eOoQbDZbDE^Mg!0^Oba8x9^7q z3Y1&S(Lx`M)h7=qGHg)=29ROvULk1)jFW`=^0YgDRqzSH;RzI`K% z3@|e@ySTE%qFZT^5tK5iVedV$VHIO7di-KG*DvSFOjka-egK)-o^cN@jjEMsrMP>5 zWv{P|Yo!&%OP%mW^}bJTHk%{L2fTFgRGfb?xnvT~LELtVy?kHJ{h;{R}=y zNpnCPbHK`nd4!emzLm^V;N}k-$&rNhtckIF5hqIZa^uxCsn3pxr=)>*YXuj#YYdSn z$1#)XO{_g2-rf0NXWdUC8#n;AZpb)T)QG40jyELVZpl`3lH8%a3uTRoQ(!e6>M=!Go~Cga8v0r9Az6OBzB_ z(ydre$)qHk2`j--cnQT8yu7p`eXur@+Fq4-%`(>|_r_@ayR0_vz z)njahYi94hyy>fjLmN6DkEnz1eoOsug}%xe?QvQLAb{L82TIwDR;F4hb5}UledK!< zEf}A-$!R4!6{UP8h3*KrxVWa)F9Rjvv0%VG!h2&kP-X#(*S)3ax2sciUt%Hh6kQIr zV7*qRqt<~lzN!BZY?Z(mYdnH1=$Ld=;NklEt571IFZ3d`c0K4@ln|cp<28wS$g{wD zXHZ1>P=NR0|bdJs> zh7`8`=2gd=**m*1sdR~;gqC||L^S)0tnQ94X(^$9BvwW^AMCxSyEH?UT}IeGg`pt$ zoX+HyR3Wm9xe4rJ;Mph_+sPr-p=CFIs8&xF;o8R*w;K?;R!r`;O?q=e3T_BZcYNws zN;1F^NBgi3B_G=6={vL5)Y}i-Nt_dw{mz7z_r*9;o+>)Nh_XE?DCd3NkqbVC5;5-f zPZzc+5%UG>o2Qqjgvi_{Hv_UFr-0LPeu(5^S41{QEOb;{OuSYU4NXK4rrbBvLSv5pFu{nlEM9>Fl;3-%)M`De_xpW5C$s&1}#Kps0_i}TfU{( z0`+^Zz`z{EXb^4hE*9`&xGnmq#hcRfw8>@9wAt;TzB;b=^>Q4kJLmx;KYxAWaGdbJ zmmHVwzO`qGb#d{n%2t<)y_a<#+8@DJ{T#c}=elEu#Ymgpa`>j%hGu+RC5 z7Q?BIB3$?R5=p!j-Dt+#%|IycScIoiRSCPDX~UPvk>M(Z>}W1J-n^tQG*v|Hi3jY< zis(kI{$=E`ko%_t!@NAiPYI~wnPt5)dE;C>zQsZJ<7_|LWk`F-oL%_CE?+Bz)! zG&a!I4wjU4Ar;+PcDc#YBB{CY0W#mblwbeNZwa8ffbXy@@B?x)i4;h3)(Kpcqpy1`2%lGy9&Nnz1PB;%Cbuj3DJQE9qzr)IavN*iI66q}}4WLpE`3QoR%04oA zGXuOsozA^2A2#bYUp5iW*So+gLqfj(ZQvO&Qhv8TsCGR#erO0yTzqx=@)8Gk2#Iqa z>z7pw?|1(KgSals4U0kK@dp1v7j}mGimlFGb}9odT~(h$^pz+Q3d?D+y<8pm$7o!m&#cXv{2y)wP0%R zGlYm>&IH(!COObg`WsT8(X~|eOg~YDXKU8Ij2kCz(lhB*a{z5$AZ0$xIGzKkYrVbq zV#2qS9>69+n~SqA4y{3y3*}b&Ii(}bf^Xc7&&(pbihstc*;c(I-GtlDbj%okO5F9k z(Wh~S094o26ViL>IwpuPK+ew^k1>Ww^7i4b=T-4(Tk07D@;vI}UGdFGcM|4QS$$e3 zKMNw}7=AXStfNNUsaQTzN+DTc;xl&;VV4(pK=f1@pLZhmcErJJ6@qVb3+Kbt$7g45 z0ReUi|AbsFZchojUmhqs10G56?tFx45-z(x0J;hb%nSGT$;2qosLU~q^RKAYQGfn% z#^V>}1nYB}3eV_{_His?*t8V+jOr<-1PD2&aGS9`6MP=~;|~&-lX%#3z^;hLms#c}lUE{^R z!uY#9yJ&+baCf59Nc!-gRmw11>;&OQ^1liiWeA_EFRBA42bl$s*;vf7L z+=naT35#_2hmJTfaG-a_M=Picw&36fZ!EWLlJ}eMPvX07Lk5^$0__PVUM+XbMo~nd z77azCDAdjhS^YFy9tsxjir%N3@mC`0=bp1Bxokn@*|^k_GnwkBC4t|Req>gxAgU?S zCbbV#u17!xY+CQ{mn6wiWny;1Xj_KqHa1E5ugLWJMT^>R(twbg`UB;O$L}PpVN|6L z(EheJr;SJryd$pS0B0~5%&;y=UFD$ET>-3&JP91wWHuIPzEDy<$m@~9;~t2}Kln>mg-K{C&1(Z?PZk+&x72vIuM z9!kDx$WNAJbtOF~R74+!(1#ljU1RPLLywB-* zp`>cXX>D!2hX>00-&n5K?3&Nn-n;yjn9+z$I8bf4ydsNpr_ra_9GW&OUrE7XCZOH~+ z>@@I#VsAVr%={OG;ZSVaEC9~UVj<-g73rUFui|b3?ybT9Xc6>CbJi9m<2ThOW{CQHjcG|GhGv%8u;lRD}qZCcjS z^Aom8gnYQ9?63gUUMhFqXfaiyV9{FEk4OvD&xphGbjxnZk+RT~_Y!5_)PKpaB78?n zQV2H_eR+9(L~420y_<}wT}PcDOvCXjX65w#K?{|0+!y6gEWHXdb{~gO#*!FsxDV@w zX9t{4(r@AD+xC0l`57rcKmQ`7AP_zYX)M^P^l@?P5ZUw;-GqN?{L((ufMVHJ;jq-_ z8cLoK+&7eX4s=w|S!69D;h7ab))p?V0jSxF@@oN`HokQg6l2z%*&y++VhMki4%I(LxA%XXSit^Sj2#@7#r<*Upbe@p+0%S1UQfcg;xR0c33ns7P*Fk6kjUH(SM zY#m9&^gty&GS(p{NXHaf!7pG4p(|X~f3vNRfUk*XN-3kaXNBDXdjj&KS_agMHL8U8 zKDhB$C5R+_7fIQww$i0OVUx96Vclw=V~AU<81a+1rLxK)qW;A}?T?J4HCNGuHpNIL z38gDdYb-W9vGW3)NKb_?AnX*05^{f<6MzPzFxN6!zvim+-$Vk`R+pm5{7aCALqg@# zlW|x-UJ=G_za3nCBqvxiBRQ^i&oh3f(^79;W=fY-HnzbBw10$6BZzFcx8#0}G8`sM zbO!!h`N94UoxLKNP)qP>v*0CK>O~6xZ0pMm(%K}; zq4K|af%AXJZg=9h63atl869ZI}D?>c0W~EjZ{ObA} z*;Xw(YD5a`A!t@nyRdWWrF0sFn6u;D8}u9c`oxS0`Oszk7L{WN_ui_KmYO0fQ5<4| z-`157F8477_UzV$f*1AtTN)duppwqJhuPL0W$SM?8(*>_5KICCi<$m;JNr=Ktc@2O z?uvwrLU{6Y@(LwuQxBa7f$3TRzi{{IpT;m5BTyi4nsG3I?6p`iK35+?V#u_zLjfig zPeE;DaQ5z;b>z;?TZk`bA2Eu~_zUlzk2^k+x(Cu+qyvQyor>rd6Ra% z8m;BMU#7>@MQGq~6At*~7arUSE@lc|kpGAA^WQ}TKO4BVSV%}{aXAuf0p7H}jXh2F z?SlpO?LNh+*aa_QeMyj+j)T%aP=+DP>xW|%ZfC~4+Io~v5rePY8XV(5IMwo_9yNUB zU)Ja+kqT{}22c#xY|pPhu9JB!e>t1q-+wH@Y2>nV**_W0UiowPE5*;Hz!d!B2ab=L zZGVVml{FM-CFg)@XV1ObUCWpEbBLD%Z(ms)q3m~(aIVJ2$^gCT8|kj4J``Ach{syY zs}8L##AN8LPt-)ya(tf0m$ZU~LA&ljQ4<&L=9RcOlKUw55`kEVH&tE3U;XoO@4MB4 zGzr~Hy`b*piuHC{uOPSN;C8dFS%Wj-tbudZ*uwC|TUQF)0liWb=}fD?%mCu{wm*07 z@|5gBrAQVOiMN1X767T!$rg7Y{-y=np{CW>x0n9g$~UO?j=pziIKj`y<{NOj*6S8s z{@7|B4Z2my6M>9N_kcOaaXUO^%TpJ2#)0&NxP;T0H2}xN>-s2hrGo-I;zN*ehZquu zkZ^(EOW)q-XKHvdba{Ut4Oix`uCH$XS2;Z#v58Ac!eI^(k1JxUtGVp%*9R-_C5F;P zz7j8+yNa-JZvBg4dUbRpAz%2za&&m&wn3t70ytdbebLH%ivX)TRb_mTV8OlmpjSp8 zT!)aitj_uuoqo7&L{w4YD}gYpIwhXaYtuJ+vK&n&djZb8JG~N@^voO^3T{g3N=%yU z?>1Nm^mY69us4&XePRVp!n+lS25B6vIw-jGh`{*;rDO$)RG#P>VLXi=t#g9?TJ>HCzHjQBB^A!_n{SDC&4^84qcMsRDZQTso%AuY=|1D72U;^cOfC2x z+2a(pz4uOFs&Xo_k_-ASGopFg%zMZuEYinP(FJXw@Zh5}L`blpTGa$iW{U)Vf!Ipd zBQlCzj0Q*{`c=%LGZnsjPdEA|5Em$&__I(_sTjvpG~4sqthjWMbA*$0NR?bWEJN1R z$>Fz=u7seyOYb~5hWgj=s|!|G9hl1q%^G~V#t{qy6>Pr3dS1CawSTSOTm=DKKad4wJ=>Po0A{so;$gt~V`LkHKx|~%0 zQO7@~BjQsP9^%c5y{Knw-**QElWXKx2f+D5mr+ySWGOr6;8b6G?!ToN7CV9cUoWwc zPx-d9cs;doiguV4Wn+BU19{}UpE-69dy`Bq08kO;NslOiD{Ej;X~_rs7eccRuZ7Nooi7IlsMj9aG$K*lh0F;x;AR|np-_s4`iDOxz zTW+V0`QLjp!@pE37#GoZke)kRBT4Np!=#}B23}U)%n77t?d#AjU-7NYO@tw^?eB%N z^NWjn``_5`w8_^evAosga_^K9ZZh;=PI0@3I<$=u1qAtxrHtzlKf6cfbKT!R_3d*> zW3&8VBNH)mlDYR_Y3N-oO5h{J`XJz1%e9$7-v+RVNQM!9;v6AUe*#$gZJm>KZ?-RG zH6~C{yB)_NMKEC%U=!?t+?e;O3|%B=fqDzS*pFY^BC3{cy=WTNMV=$OtO()+hJJMw zVAk~7qP3jY zfT1QIGV|4id|zK=tIUjyCzIw~g`E}!RkVYJsm9Q|1h%hVUT|G#ARC*TeZAjY5_^7k z4Xiy^SJye`0R5aOe|SagttZs9q}AWqb-uddYH}xPLBS&Im>&zjMrHCjZmN3e zZqV#=?scZlU+IF$b4f}G{=_1uyE6RV3?~}HO3D#$O++;eJMpD)CX#vEJzX8Dh|EB! z|NFZ|r{kalDeFXb@n{>~E~1XIK~yOG zBLiJ>Ws+R-HzH#r94>KuCZ|GIgioA7Y1rL^M6v;hJN--a?%2LW!xY&%wXyjby<4_U z5s^U%Gp~C*Pl*IWJLN)y?O0bc^46RGD}Biwz#QbkjKF}oSAUuD6_@?;F87vpz2`34 zL3D~gUO*tbA5mx_QXYFdsihm3^eMLC zd+i?vp#Ba9km*vJ)s&%P$diF@n16BED0(~ONxGbdfwyxZZ=#+KE3;2yo*u6b%LW(w zkg`J|l`(#qe5^+hkHtj+mbW`#I&R16h_+7HrXvZhpMEYSHC2#!s0Uv*6PxzdS1gu0 zPHXq-tfsVh+VZ)#Yn+zj^8QPAc)!T_mh(!yXZ6<5X40(tu$NDu!;7l1p;wU7U`_^? zF)z1lJ4|VogXuw${V4Cd`c@$msp&@B3{Qnv;olq8pECXi*s_upLHRd9NsCx|w3K0^ zo}z4Ye=85(F1+V3oakgBX>#?`%VVm%g9WYs({zxcCG)Ee@jza~TXzcQMa0u!BreDgs9;!U|z9;R2$ZbGbfT+UpCN~m?JYDrBY!?OIhrNb$;hhw1 z^CcXAIp%i=ZZ~m#b?tvVhx|4>oEk+rz+4;SX#=8B39h_(bqz^;gr^U=W2_^I_4x)`(2WE%4BpgX?M}9jZ-8f1^E!PMc8J#g4y4 zMJa3WD>9;uyjwQvdfL=;ddiB!kw5qd#XTm`Lu^-L>+wsX99Cf5;(X^HPAF#;Zivy} zZzGD(eLruVC9JD;{Lf%5&e(>x%b$l697P?!qOt;5>7W%^8u>0MoO!KHgJ!VcnGBLahv zWpaL*?+*;i$0(vAQlhY#h(XjeQH}2AQ-*54k*{QY%?E!hoCJ{Pcy1m<{BO}4_*f|!IOJ4I-~ic&nd)HYeD+`%9n=r&uwU~&DCC=m3>saRO(f< z{(oro1{T-FU|C)P~m4&nK; zYshQp<8NcCgfbo6D66p&TbLBn1hn%uSAP!SIVHdO$M)w<5^t)XYt`-@>kUVFG8Az3j z8)#r8Jt;98AF0Lyu9`*-<0xcg&*GuqP<1b2dn$f?FJr9v_<|FZVAA$Uqx0)lAbN+Q z)rUkvLV#yN*~#vGLuaSKp=w@s!;VqYY#djH0+H13xcH91IPkv&dY#y}na}%MZo6>p zRbU`F4(){=@^*1!f7{qY#+7GtSAbwmRPcLjQWDrZwQwQTRU(S-52UvkxJfq_Xj9fkrPH%wrEXDWzjcTx49QbV8hjD%m|g0l2ZifcZ`gMOP4VCK8?YNa%76jQBx`%)`>g6Be5h3KVzEMQ= z)l(E+cG6rPU;%~7k#JY~W&(j>9IRXpVwnurail18w&1V+C2eoyb~x;;R*X`=yARpV z2L$Ikq*-kiunjQ3)EJ81NKlu>gg`&Vx2rJ=4poh)i9R)SrGm`J`8_|xX8n6>UTd&V zMLcl*lxrJyXW-tbka`tRx($E)Ve&fb-#H&!42<>;&wri+mv?;2I5!3F>AB>r#%vEW zC-=f1qV2FwkDY%dx$tTItg}%(_Ma1ZfKPDF6G$6ZWKG%HDXt?sUV@+N+JgW^Y)}7R z3y>3MNb;nguZTfdG)^cwmw#R@yTOWGz7eTs3_GLZ|8rY?0=iZ|*V+8oriNVIBCbNdP|UDZJx*nF)DFyx-*t zIaJpMAxluJfkGBXmW8!(ctmc%UNRD;>|2J zOks$oTVO4D=3X1Qhu;|>9m;n5Kw_E=Nyd2qN-qtQ{E-m-1)S(Hw?&|iX{E{yk$lZcc zJvs#1t1fg_K%ewD2&i8CJa)&?>lR}V#qrUSPHV`1-sdz}h?9Hk7H)s&3&dd5Ng0~g zR`t|m6s%B&6CHh2lpq+wgo9TIJ7 zdsB}e66&LULS6$OZiinfn*1cZotP#!jC3hGP9WLN^yn)@gh)&^Oj5&nchss_1Z{0& zKbL$nHq7JqRcR+wF+pGJccGEvxV4!F4#*lycEy#O?r;OV$Mehc*R>vS z&vWZ5<$tq>0FOW8ryT0#C5oUK38jwv;%q}@;!{#um5jSD5B=pb2Qj!`BdWE8v*7G< z=nuR=tMi;O_p@dZ&bb1sh@C+ zycjWDp81syKHmWV@)N}w-g)%lDF4_uESd48cF>M@{vhneKBM>jkO=4XYaj>EMC4zM z$juhHD5V}lH5N>sWH(vD7HKjc8iCU+YC8+viht*|YtcjaoWT1mlkkrPq!6JkoDoZt zGi1t7odq2LGqRTZ7S6{i{;Fwfu^*hgSzG$+n7RK3EurSVNm24|*AwoV!pri_(M-l4 zsC5TTO^|9XeQ@ubQAW+4-*dN=@0%hn!}VrrdhG`ZG1U`TxEIgWk6+6l7Ej~Tib$#o z!$!q})UsN=Xp&!^?w+0qUN5;`-}Jyh5JRI{W2{wSr>In{Z1>TlCXViB_rW3PDBY`S zPn_uQrB}e^n(VKQjvwgsc$U-o6K%!+G7Xl>8)P|ILRB=32z~r5kY49_w1%F6mre&m z$s}m%Lw*4d>>&|IX>CFMOt7V!pREyIlWndE6EyDo+8QJQ5uGu;6MsR_+hcOP>YXpA zlm*p6b~!%K(HjiV&j-3eWY)yW;9CkbCtI8ADMD-HFAs)$oS;m4N=#NCf_hnqd@RJ$ zStb69sX1FvQ!9AhKOjnCWZ@HJ+@|&8WV>$2UXT0)(Fs=5|( zvX=5^M7*CDwe#EMoNU^19n!WhqEj|0(PFQ?u=s)rt|{E)Gci4cS-=FuK?%27k~j19vh zq;IZ{=Rc-{uAESsb3yhvY9Hsmw@_Gua}D;Qoq1jvl{Ka^dmWIcZj3~5Lp=*?;(9xB zt%NK0{C2q*a&1;V1W-buy%7-SPuWDYAEdZc){a!oq{wu_Lus1f8OA&LKTRaDDql zrTG)$P!0oU244r|uM9x@-?cY5mGubo8*qEUls~xOqot^r@^CKvVyaZhAI(Zfv@UH@ z8o?YOLrGKxWoj8wmQiigc?wyQG#`82eG9MkuZw%^Jeog6i9HMY$t(gDSMdl859xOA;xHXm=6tOCJ|`y zrjGIx%{#|v6|2Ue6wBNJVsTX#RM%2FRKw?;6x%(MId}5AW0(vaFxgB~tju ziRAlb5dU_1%G*XEVJy@%JJsC8yZ@9MkJO)C>+1T>OpF^k!I~1I&iqj%zxD+7H##ah zvmk!v!KLgm39Ej#*&Y2rZnT}|D6PG`z~g6m;TB>#gvuuV1j;=hJT97Yx5uM42M9wb-Czo%y%M^^fx}t*W@e1fb(Fo>_^7k-H{9F%`$GSb@C?nv5etuZ zkZt$&|5WY!Z6*`-hTiSD9JL($`=Yo0!uB)B7rG~cOCFaq;jG$&;T_Ab?h}!{poX<% zO6%y9{zLnw<^7;InL**Q+*DrZ84ch6S8h@4CqZf%1rfOOqTG_4AJrZ=>BN1&OKnjEk{6YQ0)z-N#?ZS&mNyZ!2OzV821{ zwRh9-N@$+YkB6!C;8A#n6`&`UrLWMJt6sHwOWG8OZ3&XNVd7dnExC@ zwegkQ zA#!V9UR91b>ScF^p5a?H6MghBv+16214$RBCx-#yi1~-r+&ed9yY2lst}Wodi}01U z{#&jDiui*338-kx96Gl2HUSqg`D1>D7n~knz5KTV<2KN+@!2cvIORMs5>gaO|Ln4E9WXjjgHe4+e2F;~^hd|$xE=oQ7P_FF1FX&0!?~Kiqh_Jzv_+cIW zN)0y|Bf9agC*l{siJiJhdB(E02^4YCqC3(Q^L{RA6__n*WdX6`hgpC9eYutQ;#9J< zOS}olezZhseXKu5D5256abgH|MFh~<|9X2arWdO87fXMv03juwmpaTQm$W6WBX76O zbqFt>b;9A?jF2?}gZ4B%VQyYcqzHd2hi9iqM(1#Zh6D7(l+B<%r~AN6Y*RTC5zU~KIDK! zH;I$!rZ((_dAHj4u79k^s&jSy9~Y_gAjkfuFvm7^8#LwLrob6Wh_@k0@n`O`ey{7z-k+CJ#xDB?+5 zts5U;axaU0Cb|)UAb74ytriK0)j#`s^jnB+`3hT#QM1MeJSELw zDsnXtV)Q8s#RuVlv>vR*`Fh$$%_?}PG;v&l+(oR$J(HH0I>EV`^4o^n?53S6l zWGqQ4AHZT@ zNb&IJZM^vJnJ6f1pu39ZIVBW0H08UtiEOxvZ+JE!ajuI?Ze{em2n65G6l`5?A_$ce zstXAP3m5DP0jHudm9sJ$7?EAcN+kr!8we)`2m~xAddsqN2!(xMMw_8i_dn1!aETF8 zS565$Lq|#7$eR$r2!OmvT=(`1r|-u^i6ZkS#)hUb47v2Ww_EPz-vD@LAGipZBV?KA zLN;l;jjvg7z7U>zcGeS909#DvT`vvtif8pof{&=}fhJ8kyRt|22qnDZQykV9Z`>v_ zac%QpIfI6~4g=^BJi3UyII6?JYEGraMSSuCxKeJ2O965GCsoGML)OqdnYasP+mB}g zrpgj&9TG4->(Rqd>mUk0hSR4o1z7Giz*?Nei3b&)#6I75S>ks?);!pWWHF;zNnFG9 z)6krjErVpMAr2^BRbx*e3BbSJK+Eb@`XaoZmZbjv><-2|E2KC9-v>B;aTRj9Y3 z4c^n!cu%9j@jAx#AX}aH{Ofh^WrEj!_aK_Zc-+4eEEW+YIUX?Im!ujd?N^dOyv^@* zpNoi>P3W|E;rklBZGoig>LF?=MpZ}c>?)q;8ekRmF6icrI{2p2e3MxUhVftZEKIY# z)Iwd?hx^=_J1J~F5xTfp`8CvS$|21$wULU`n^jOL&GVCzWTERO7gCQ12Y!fy4kFYU z9h08m$Zq75F+W1mzbjD3tq0#r#w1^wA$h>u>c`A4y*Id{^QuL%t2~ow#1I?fK^XBr zOx_l&U{2TsP#~k=(_QCOdPjI3PyHBG$Kez|b)jvJnZunjjjcbGYLA;8m>(~w+je3p z7RBa0bKCHW(aIidQxiBTt_0kzu>SNj;En+NV=nvb7>-JM$*##{Q1t6bH}Dz^^&36+ zX!i)pm9M5zmR}EF{?H1DP4}QJVGx|wiaFmPsF(gxw;!FyGmQ~IT?c+hVA9;vXjbvQ z)s0)oeB`8@T1m7G8*v_X5gLNsz$j#E+eLvg74Vq6XlrbnAmB#gISHCl-J z+dt+R?{HV_&PQtG!LJoDGhd1PMJ z;n;+5JEI6tFZ9WZ+fT(rgtVfuUxE0weY+VX3)ucX>ii&NEcMGP3^Qd;t&@!$izZM~ zFwqSax_FO`ydL7r%S5+|XgIF*aVG$PcCHC;sl6m=|5 z^xrjny*X=YO6w0AMz9UHHMGQ&CFQ4M`-2+_G7DWdQg8k7JLLPEg3x$Hlc%4 zEB6=*^G1WKRj0^aczPp1&ir3JPc*8_MQ!v?vHdOh8MpEQ)jIozYabA_4?n_4=+>Rf zO1|09_m@a--En{ZY)l>UFjKJE^R)jO4&Dr1`3>JnS>L>UnZWH5rmCkFq{2fJ!&vkp z&IDnRUN>&Zi%|p;I6&KpR`MR`Od~(p&X-RiMbB%uEAm3NEj6Pw+C&{i_2TvNo+MQUAlWn4(d#M$4InS2Y+%k zoWRnGm&1C!c|@yPp@7S3j1GLA&z;42Wn!%7SJHC5EyE-o>DAf%>g0VQ6bYduPI8^8 zHXpBD@>`vR{@_o%EJMirG&yI{&D{|z ztUwF%dml$|pj`RXHVu3P zSEe(DJSX@2q;byqeOfU&F3>=zRZr^`AP)HbRQr%SIjNqtG&R|zFma4oA@-RV1U3Yi z%yQ3hy*!cLSH3(&!A6j=zWL{4_AD~@z$UVE&TBTdjqqI$+`9BF4 z*9cGZxSXA<#UXowj+H;E0)s96!t8r0r*~CR?F`?@{JU*MxMy4sGRoFyJKI>G9<^NR z(_9P32E=4)fyZ7Fg>tC)m^;?l%u-<{`~9w!Ou2$)k?(Obmg984+5{2A#e^%#p-y-y zyDeg~9jr$cJfGOz!zM!#ET=_6<()Q<{QF8nu2X`rU1Kw?cyTlB`QHOV%dd?Js-9`& zm6l_0zl+OCp@l_q52qP>uCUPgHu%O%^HJbO^AI%VO#YCO^UNY7waLv~`PeI-m8F}f z9P6qvb+B;Fj>W%cn&p7Czs8PUTBjLWV4p*nYU7`8==_aI$_?qKEP=sDbgoyKV*JZ0 zr!r;~-NF{~>Q3eTG(!?EfQ0D*@qvZ@2b!AL%))Q3e9g4v?Kb6 zo4b#3BW9CVVT7>;#!u!=to8ASDTU`*>c@x~E~ZxTt|)C&0%RwV)rSD3$dVslG41VS zvB_3+i8uWPT3G%iw^)%mT7SCv1<6u;k6?z?U3dCZaPu1*tXK=8`q&=N#^8w(UV~7b zwT}w6>MPi>O7RO-Dn;_1oaFz-4`~_4`}}YC+fxMRjT=VPQijs(ZtO)OtxnoY4IS}f3L>VB*vYrFC;0q#{v@%m`~g0_g*B8*4wl1X(f%iRIY z8RuAEldeP;Ok}rwNF!sOB1jX7M$)l1<_p^n8ZIoUU?!+FgzyW94cKV#cKvlTU*; zY_FyundjRxlKiF3O)@K!kTfaeYS|{Y#Aql^u{{k{hwDv{x9@EIii^zcRm5RUMu1w6${~Y}bm$_P4MEubM_@=V%pKR5$yWx@ zHnB;LzDy9+CwQ1(thx?-FYS0RZkOuSdor>{pY$Ia8{<<^!7jhkm zwAc5~$MVZ=>t^7+To=q87`njPDa;j-ofXggixZ>1)l-D-@i3qR9`+o$Rl5U6GmqeJ? zd$A@aG6~^gu)xzQo)Q&?4r{Jl;PeDRC_u(K@#0Bs`XWr}bB5tx8(}#UWRkrd&HJCZ z@he+I&={w^O#YHO9!$ave=Dcg#UEH$i-2o7>m(y+>kpx4z<*q68@%$Ck!NVJN@F4N0S+&jpO8*Mhwm zJ4VpZ(q$5|Nc|b>g9TrYd0dLJvyh%no%Ih)3fo=%ZbtKQg(1WZz=R`z2i8W;XaRzj zUN5SG65{}h$vu9f!a+Zm6&~O|WaxcSfJ)^i)B%tD7XN2kZ^911<`D zj45+D7Sun?Lsxm&WIT1SxZF0Lu_-{KEVnC0*}qlB6u)n^RY1c@}E>ylCrDz%~Rp5utw4|`LgO=+EAez z7juSXRGQ3(O#=H|uh;P2T-Gq2_AnGl7YkIuAdANL3hfu;MVhK=?DSfdv%-_`0EHRr z@j23PcK+BHT5e9#z1CBA2<)-2^~ut>cyPr;v!d2eg~wv(b~10}q^e^yzat{%r06<{y3fT#Yy_*di7Fe1c>Hm2Sh-E4{-w~qbC7I2<=X8Qy!!MAT-))+kE9w%$W3z0>yCwH|R1?SfwA}!8`7B zQh^!8-l(p{F&IwFh8o-GH!}bLAOJ~3K~&Mfa(lPh8NEv7I0|zc3zn6q)wZak(lrHR z(q?rcAD<1{iS>ai-DcZ0WRRd1A<9S{ANH2OAH2u0BS>f_IGc~{yecW48*=4nQ=I|3 z6WgO90T^Iu79BW8G13vl?;&(WGA+{#gi(~H*$?sxqj~2oNHbs!W34Hq z7kMzr{kd;LKSew$EA^cs)nDCGZoRUyGdG)2ocW^po`MT0ZfHtNXK1_$DD@dDF5}1T za4inRvpmQ=z(}>1lexvCoPnm}mfOJrBROAFr)0-n^;#=h%19Jl3(AaUi#?H|M=1OA zpg41OTKP2KKpq_Eh+*8sqaf-WNj)#Ig)DeNb8J*?t2})CMyaem=0-QuXA3U=s2&G8kLN^2YJl&q>O%k%yfp6p*eZ^-0jR7^-GGjKfzE$OntJ#~!cIeJZo?#5HZ zw*vd3g($SQh2zYbq<7I%n!FJ_zr$|1 z5S7o5^_jgoI!1$McArNXxY}0E@2{mCF&@;wAe8rYT-P$3^F*+1z742x)yo-trE_Y%uj!Ii-+7SdjHN#J`r;)0a=m(qN0ZQj0_21qLE4xw z8enALs4VUM{6F(^H8-lHyQ3A?fp1J6k&HBSeYiy(*2d;eFku7@`{jF*x=4J6n>i?; z-Gm=N)YPoS;DJ%OGDwFKfkoy~X-%=sekL}Fn~%_0bSCkT9436wKbIKM4iv8e@$Vr#LhLwx@AK8};kJ;a&knM0P4 z(R8S7zXW*xfw+*@uv4sq<@67!vU=%0fcSd(+ zY89)@^o|s{F1|?D0KG&BF|G>8wwXZ_xk9NMoAq6qfr)mB(AOre{E;+HnPxJTLDiyw zHs)3rs`G)bjF&18+q2wh!7YXmiEXshtxE%_=rKkxaz2Gj>5QUv3YPghM1;w-I9j5* zX8AMAAnHx(NdIwSaOJ3@8u@&r>YkPST+RE{?<JIdnu{cAFKWdN__a^BaF zcO4x~o23B~&)vvF4?`X~O)%1ZZo_bo)d*t2Gf7{Z)}_4Kc9Th|<5&Gz^>wXF*M{yq z4*A^|Kz?M@kBwEz6-JMTF)#UC)$c=_T~;W7CR^Z_K{tt*5M*i$xj0aA3V~=_6&Ck#Jd`=t2dliq)&(z?V(K%9J6 zP}$jJuax>b7_j4oT$KfLe|i7f+<)zvS-!8zur|#O_r9e6%!k))vVDDf8jg12jMwM( zU(;WsKFM7o0Njq>=c}D*w4zI$U-RN#^hM1X>TufCbB=QiH&K=AZ$|5mm<3^1C~N`z z;`dsln8T~|o;o%>KkMYx_WLRiW?9Jm$+2koBd#w_(l6Jmmu=}Ke}!4K1D@ld0LGTN zs^f1FB)Zj^@23-1BqKji4wA?TmJ^p#(095g4(Ck)xUgZbN*H>K5^3ePyowM|>l=+U zxZxOvdfU7`mIA0;0kYB=(bXe`90)V=j`l=2q9cXQBz&!oP+IKra4K-6`5y3^ zu`WRK)m1HqsVm>4w=3WvI0>t{JrQ(7vhAsXMG}@VYD%MjW=s!`8SI+MTaLK<~sOJFK{Z-QxC3i-2O(l8vi1eZNq!QWgZ(F;4)b z0T0xJk#c;sylcEi$4~%iVZ;@3YrL@UD73K;!U9WguNi(jBP$BH@=W>tsu2%A}#kZP0XT03%qf5i#cE_3f_F_YurT-9FA>enT&R6#+GWufXLsBYbck zio^Uxc|*5ld?r8FXZFVbnm@0M`DEDq;LGPY4*{I}6J=|mi->P4;ytIg(CEzQniwNN zYzyzuA<`29PwT;j1DD4%RAc@|QKz;HtscG2}?jCqc$0KPjWc~7G;aLX$ zd+oPthW*OWT^YnHBRk7=$42*s+sHR8fHr91$L#(%?^ZH**0sz5E<@WjQY2k-CIoJC z-U2dee|8=(>t4u+RlDbBQpY)Me~ey{qL*OKMLYkX4RcQfVVmsQr(9BRL*C(CUju-s z3tWF!eY_$H(4TRPY#EQH#d;P;EKS|PN>yAi_T532q}?^X*o~FXf0s@%9|!IcL<*02 z4rKs{B6lmjju+-RP#rk0;i6$&N`L15=Df>8eZ=)ozMHsTT~ES!q^3twE$^@B7k#gK zqxM^~7R`m9*2aUPNO5a=i+hySfML-2fIYS$>6CSc4r*C`z5`^+H5El;S8bAA*_B^% zk#R-8Iep8u`d8SW;|s5|L5AH%)vsehz;KOlC#@1M5|?TCPqMGXRSKplq+I@-Yo$|H za%86eoSvXwhFgAwKJn{|ll05=`X#=7jaz`aI}K$YUYr4MWIRTq$6>dKG?B?UGx9X*BjO9u;RmT)e%gjv5H09fs5c z>OfxyK3A!Q!OA1*2DfU@$gtkgwhdhD z&Xw&k_fq8z12-k=M_Y`!xR;zjD8USQ!ScPb>^#_mTW%#!j8-ZwSI~4C74S4W=4M4T z@{puLCryi@o|c zjUAL+UeIy1l84vW_BhQsM7kgWR#5i}C|d!cfyU+Uo`+rsWYqxzFvnmz+-p5GPwH-* z#~VvP`9rTr|4=+DtNxnd3m3J`j81nnkhhzp!NV~O8`ZlyY-)E|t&Ey+eF3ouirzU7 zGlz1qfeK#&9UfH##U@Np$;$cMIDT~wRGQB#=P_@L5TReSci;9Nk`bn#E@K;q=DIP{ z4E%}+q?-X3yf_fh+8y*~8vrPp@jZoOylelM&zLfW+uXUBXSy|ae#AjTD;0$f~9 zY47L-cz0=go^@HEZ37*d9D?q;oAaD{F|dT>*pMErHRz?}z-Gh+Hc0c`1{6xt(lMwW zY2=QDuAbgS-I=RJf7B6-{l+e1lyV{IL?=&Opv!h!>zo@r4N77L1ya9ziiN>g4LQx> zCNs4`Mk2^v=oMJaXh3I6@cdxBH-`|0gMw+L$TQ-EGH+JK@i=D`t8JI_yQ_PwqyApY z`P6%39&y>xHJ+BS9Lk5@#nTHhHG-*?Sw2*`Kc+>3%OL=AaVJoY*;z{(i%E17KQ(D_ zs2nglM_1#p!UrpZc8;K1^~FmMUGRf0fy)mUU!jXrlr+jK)ZbH=IhR9t5aWd1?QeHJ z2c&uQ8jo~V_CviJ%@*&RkCoz*eGYnhI~4_=_IO6b^Ib!Sljm3Z|22MQzSCSnDwoe` z)5$B`Qm|CZ-woeRLlHFf@@Og)2VR9NW1A^&rsk1G1GXX-Q~(=l3NouoefLR&)cpHNb3?iux+u9xkzxLj- z1@5_c?$S!9k?y^xovNzXw(SZ=AMtBK@Z1HHx>vnkQ?Sz2gPc+>ad>T;e16ZUP|CX& zS3hS-u9{QuI!(Ap3HM`u5XXkM>}OMcNl|(%%#3uVR7nl zOBd9P54D?ogG3+^Vtym?UseL-O^db`7%95vbP55?tGb*&6R5&kCh#= zvXxeLX6WGF(Jy@^QaeSYzEq{$O$m*v~P*B^RG{6cgV3-(gkSUl%!8`AVCop!p%(-@Kc5F)u2#c4W>e0 zDfgt0msw~?KqWMkV2Xr_Mx;h~+Rg3_*j%_b0&fM{w#AsmsjYw;YgUISg3fG1MwS|I z&=Q@cK~JX}qd1}H9%(xA!)$!y*d(n+T2??n19n_}pUNZnndC85PeS8dL9f^-w$7H} zm${&*udX7~aMmc1dDaYQ^wQ^15nodZMvt=11&9dRS&;_7Cq0_@Dj*HBy>UYW45eMX zKP#IY!?8X9k>id=-8BPq1s*C0Krw0%;8%fexj*fos4{o_dF{q`QlgPb>o6u-?IX+A z9AoDlW65;d&HS6-zVt=;;~L=1hT;m8?PyW{Uc2V^uY<`Iuv?GG>YX*H%V$2-&h?A= zu82S{>`#xAc9(i3`sFe!=H3W0$FYWk$XO2fhc2-E$o01(zXX|+l)#-Wko+E!uohHT zS~UI_*WAz599ijBEgjS@G_8cxT zd97OKjTwOg37Ku%^?kk}nZcs^CG;!XSaawq^={}J)??#9S=S^ZMN#Hs>Pg>@>La4T zW8^1z9kPq02y9U%L@un3PPb}o+o51atkBz(yFOmpHPRMv3Z$VeHkdT1(W8F0mCx;r zK>*k0LpAIH#pTkM&(txfdUMXpxjH~Zs}QO5FJ;*&ZUn9k0FN?(58Zz=WNRX=*W zJ>^LQ#GF!9W~fheMu{``UR<@$T9MNzuTAdS-i1i%7yvO8z=Wvol^N_% z7wxqy@GuBz)RojR0Ak@~Yc-gG`pfRaaaFaw>-ec6(wo&WHa%wbkHHcwv&b$%#O$c+mGq~ zsK@GWvwb)B+ZIpypcD4}P5z(fjH;T;R8q%qvnVlwNI+$9QfbWZ+AqgWuKO!a_?+vS z4q0L0nO^nz*?wSpfgf{yagu(yUcGp_V<>D+umV12r^-qY%pi3zcHsOQd~6fb)q^=d zxWy6%)CJ;TRN{U@Y*y@0MYH{>KMhEwafm2^Mn}QJ-Y1Hg0_+?NMZ1JsD^SWctq=}M zVr_vZ6?R}65hWB@zO@5fsbtQovA5hB2nWW^|2j+wFEAPl5^u0F@6SDqs(iuR1r_`Vg?T`ZX(?6>sr=j8UxvsVVhzS`yQf z7FEd4b&k?^be7il!vGtR+|bUky+bqI_$kJbj=7t{un9U!Mz>B%)(k!aS*wWA*)Uz5 zpgtQuE9EvTu+32yRI;FfNSjU)90wase){15$2%hfMmxWwUyy9Z!iz$U*O;ze`z4jv95A^Cb;u z*I}OmW|gipy;qAU^&0OL0}bMw@BMH&0ZCe!9x;i??cj7K+9$Pz%CCJm z(`%%i_rjm`cU{l3j;gclyQd)Wypc9`iA9Xwj>*(HgU^(F>;gBmRiGYyZH8La3)V4-(vGO_A9zE{gx8Prvlbj=7d03N9+PJ{0JRg5~8i_~4UE;?|8bA&TE z<_mm$UN_FG)5x5625v0MJr_1%k}?&o}*?Wn*_WoLoWW&;o4$|7?t=W(7Fhk#;JI&C6-LD3bVQ_Sp(TQDwc5qzO#R6C+QIvj` zxB)5iqSEbChc~Y5p_-O}`uS5>{Mz-!N&4k_^`armt(w4Ic~k+$cjhweFF*xG01g+L zvNhip!2=L{3kQ{42muL!5DGNv5JVL~I6M@Hr7k)^?In$=8ZbmDPlR^0_mzskCO-85 z06Qt%BPZ0AAO%tM6DeSX8o|L_uJUOS9(3>|&EUe!=#g6z)K?!PfBs>Y<2%w|RmKW9y>_p@GxPKc(AW28SzW;gpK($LPppiY{}~s{ZBf2E zRoubAlpJ)y>`5qbzshGTdtsPk?@%a3nRN4ZFrvgny}J06c*f3YaCur!zNiHvY56&{ z;Pt7Ke?L)@mj{F%Yjhl@9#oGG=}jW{cRB|EY31-IxPJEcM+Xml_eI{Nq3P9+a*F?4 z$Gfd+?e^!#ZSZ_c()g-#M#5$4>P`J#rGu4~PLjkN0Cl`Z`$k>F`hXh6$3-WOU4ZhU zH_YfRI@Tj>tGrLw*evU9TU?}(8Faz|<=MEeIP2Oq8@?-N z-8|>=xs(r3k47#z))*tS z@_F?XQUY$zPQhoq5Qn)EI(moI_+Ja7db-Ro1;7N@fP z>K)V4hCNQMeTo4}S;$;)lkGC&wki+n#qq6Ukl)qow|eTFYLU(?^;uDS1vkz3k$lbm zG*4?}3ob?%vk7z1O1nB2FA-y#>7B|hJ7N`~L%BF;7c{wMM~wWjzgG8GWzIAvf3C1u z`4)3v#TzS|s+Pa{tk5{HvChM}9hBSG%89Xz9YM|bo$?OwokIfKq1u8?NBX*K2<$}2 zrG>{aj2GeEm>W3zH#o#yU%j@2VAaQYt}Gp?9Md16Q-Ci{(l6I1E<35)J@L%|Kfy5I z5Tq{{vs`<@VG~zXEzCX~up=N~N;4K0<@&_J8`22^Gp$MlYqp`%AeuP=v*ayn%*v4A zd;ES)kj~{_Gn_u>8q1*4Xby^ue$5Yv3S(knIL&RS_j~U#2M6#vE1L4|s!u!T;=)+C z_HNL&7+*jdUFO%yxmgwWwQcxOX51%Pj9+FjG#h6Hbvi30ug$QAOv@ zHDLHZ>k{>C%gq3r#K|@R&k%Ajjx%fa{5J}lP>x<~)&}X17>Ojo6wS(Nc znZLgOTva1#zsmDy8vrhlh1c&hM9Eda=M{X8v1{d|F_h)eQQ&;k1eOO|ftCl>Q873h zA}HeX3aS>>1{f@#7ZB8RqiqwH*lHJLM?HB6gh@r_BZkdL-@7VuG2bGirkJ;zSO5yq zRt|VEqb+oGJh*qt1TDNze7a8Qq+!RlZMKEp4>Fu(xH6)2A-`*(CO`cdzhCEJ)G31A zBqHj~LEmy~eM>nfurckf$5S0sk6++JZR5}-a9qf4&ZE-zrEG}rO54YEnj1KzB-v^8 zKIOJ{k9uX@zI-h#TVu=lEaR4RF72-0=ijg4hWdHdvvUMf6A2wq+=(<-jRX<7c?FB4 z>OvZpIRUNw9<<(%!TPc``N5Y`+E(N!(cloFBYXN)-ds5kVm#>RU}`Mt$D$Xn(Vg_A ze(L2=)E{~!7INXMimFe-q4Wygq_I$Q>sI>YvnH!Lqq8{nu1`!ycuPbgk3GPss;ajr z7M!;J_vwr*reG?kS&h2mJxP^&PFTJ z+82UgdCIvJy0)*l9{mI`Hv-@0)X6#y?_0;=wF3;4#1TZE2jLQ)^ z$U-^|JUL>?+BW-~GX`*bqViGU5%R<=`{&OyA3$?ahj;^%469?vzw=4;D?P~f>hIC# zGG=Sy#j5}SAOJ~3K~y7u>=z)f=^^WJDEOW19Lg^J#WW|Pjjl(#dp3zB2Kk^|@UgM& zUN>Md0iB4D&+pQd7+xVSUDOeoK@H46xQ>7HQw2Tp`S0nux>mAoN6+AatHr!}eQ}b0 zxn8}7Qzl(;5g5b1=Fba3HVgV|${X&Kgn#z5il)mjF~5|G#Z_PNcdDxS*$~l$bb00M~00kE$2|Uu~5(g4pQ`w~)aJt6e zJ7`I$5jF>KgE};n+tD)NN1!h{}62 zztnewuG3tYLB$+Z`r2Ih*IrEiJ{a^a!$VG089c}VdsYe3{cqkkxypGM@43-CM9If^ zIp|lEEvWE?C(eUXj?hs8vL8E!Tm>pZZ$$%5XWnkkD$Eh4>Zgli=u6UKC6lJ_;@f6p zoRjxe5jvv5K(qz=rDGsYQy%h9!a;Wr-8UP7M%NgyYz*jJ!npOGEvLL>uHk;M;~ePN zCDC0r!HrXbZsVYWGhAU_lcza${Sc%*~AS#CQ6Sg31GBOxu4V1To4<8`X=pm zEF#kS&UIA{aRv1zv5MVoW2_V~r%wcwgj?wZ>^AA!dH)qYsK3`STF2^&2db@%-$NI$ zZ&D`L1_bAllQb?$bpd6;6XZ`Q^UEr{7 z#Z5a*QNPzy*JCv~b21j)+XDu@{p9_{f&Rr3boA5`>K)=ia9q&P=>|BT4djXT5TH!B zaf>v7l{XZg=eY)1`My;z6jDQ~@Dy=`YAm>5`@!=PWF7y|x1pP|bnLtf;MCvi_SD_) zudoYObjJNk8nVN#hh6W(59YbFpUXQZkU6jlErU-5Jx4ECzrc3(k;bb2DRw>bgu0y% zd`sI!ioRL7Kj!s}^w@;-lau_d*g{hh2Y(XFn} zJK$CRw2{-)|CGs9hg1yBdVA0gNWD?%vC{fl#Pwh2+4`>SGY#|hXFGPzYn0!;E$QRO zYgfLxwy8g#KceW2#ABuj|oA}`qP zB#EGo*IVgAy*T8hoYePs`~Awt`g_VdNct`>3xz2dSp;0M5{}A?vI{^h$^zo2zKWj~ zZo*_UcSR@zydabUfxTB&X8AmK=5XB2nX$+@22ffBfQsiI^VMYbLO#d-7Jyr3AfamS zDXUn!vaJ2CTf`RS48Y?uiq&O2iHavB<-~kOO)QC>~BzSMbpi4dB!bN~P;A zuvo7T84I0B>uPA~SoD*TJFf=KblvK(14;pgd@CzN!r_RZLv4$!+sAvkGYtH`D?M=5 z6PQ=fWBDG-YQaK(e)q~inVQAQ2~Ubu3H~F*jBOpofHQDh!FU7!*%syMa`IMjhGiWm zyUu_~>qL8U&g#~ewJ-(H_JYo8;lE z5ox2;MQ~J1Jrl>)iNPtl;DQ~^tL^Id2Hp)jd39c^-MQpMzri+N6?^01INuMZR38)S zPnF4TuLk=KKfv^94oKI-$v{i^-V5ubL_?mKZT0UR;!jlw2`_L#QP<@8+^eT8PnL%Wrh zl!+QB{SuQF)e*YHKkqPYz5eR7^y&jHve@j&u5Vp#I!>$4bsH7@LVHl?zP#@RX%h9& zPc|Nz(1JybM?zoIzi@w+q>T1^m0X3bpzQ&GnK2RK9g*~JO1o2U+TxP^A(Q*(x?i-z z#D8yj2T9-MWm#r)r7G25U`9=V-Z z^}R+|t@XX~z@}8%c3O7Fp@YJ^d+TrA=+*0ejQe*0k-k9-|Hn_tY)6PK4s2rwM7w@} z70B9MyK866bZ_Xu``7Ch=&%DWO%e$FBO$()Rf%Fesk1p}OPxk2Q9qDO5Gfn7U09wq z{N!GrUlj*!kPfQsH>RABDTv&7E;GdA7U%#lVB1$?8DCNi?Jqju;j$E`uL9>CT^T&D z&ZKoKgKOQHj{|s0P~$5=AR-w|!JZ#p$;ZD%iJ)RB3^sL;A5Np@cvL;H@KS$|UlnDb z)4>?~$dFUh*UEq))w}Chf2m(jy#)_k)gVu|chMbpY=Eoni+4qU!}T_D;o|PXLy$Oyr0FumYH8o{Z~9>e!ka36CY55BoIwSuoePcKf?T73$j+-3|5} zaB7oi;Hrh`r*D(TVRfCSr39Ey2!7b_j2enSbU@}eVEhHZ5&6LDWJ;`Nvp-%31*Q}| zl~^Gryd)ic+B8b4KoE!Q09f*`xswg;yxqU2OlUZwiojY(H-^S>n97#pva^rcA#bqd0gDPy-8||+TKUcQuX?$F^ z`&vL(F~-EypMXBi&N1jLu=hXy3eoR?9*J{rbVa3O51!rmfnAT04|#oe&d07ktHUv_ zGH}|kThK(Y^1cL4?RlM(=ZI5SRpvRZE9Se;5`C+DQh0FfyIklNG-B}oI4*u%f1mLN ziu@qc&`D9I?U~CsYQb(UmphytK9JL@Pd@a;Ij?-mJ~nsyvSQ0vV6#?xwF%i{|6ODE z7N<97!FEw6)xD~(8qGS`pP;ML8MI;4n?M4WRys{1mZ1BEO`VQ+I_e)?-a*oLd0D!W z+X*pn1x5L=f8{nmsi%-4>bMws`(b$pzuyC!wY~u3zBid3uvB zi67JiP3M~J%r>njfODHz8kug`vJQftWk%lrndcMpeEKS<1IOcl$O97-=jUf6cOGNl zI3DY2M~L^?0hOjZ1Gs{tl4D+Roxte;4|H6oxyouYu(ra+XA~6>oE{>u@4yM2Jb=J~ z3;;~Qz&Ai1n6l2?)1j&3-FfQjsNB!g*4g!5SH0&|fMIJC3!nB}WtArguz7#9XCk&6 zb8Px5fPPwEKWV(SXIFaPDm`{a`4yeJ;XaNd-|uphP5}X$9csWaJq`~=slpEavVi9F z*~XL^T@F{EBkoJfOkSs8a61rzCE9pt9jm^Q)*A^~Qal)#B6tvper13O?yn#w_yW4* z)#HqEjAaQd1P?i&<@N21vpeEDo~UCMyeNp1iYuKu$oLiB`bU-C4!~D_!Df;ZxEHhr zT=+EQcXfaPxKn0!XZRr-41U%&Tyt{C;uKF`Win)M_m)#yWyEQo-KOp2Y$t6Gnd55C;Pdk*&hu%qJ`Nlo-ym`TvTi9Ak;u-H z!2~IGz;yd?=hK3lw))i4lGp^AxLuhr=M@0(oDe+$JOh{yfgk$hx)QchZsOD4Du09e zs==6{g0Ef=yX>4e^6q-tYhu;|jlI|Z90&#k&N_^Jd%E^^%Dwew8yNP^eJX}4d2xXXv!dAiGAU)2?K zn|pn^=;4JHtIh0qVb>-_j{Ds>u~dED?LH)f(p}%wI(KcT6DAI+h+YGKMcrt+DU6`Y zsz2Z5WPLG0mv(y+?R0F-$-itw-h0JhzLP*U@BFe*?*g%8DR^&$EK9(L64*x`d^&tA zCn(p%IhBV=vK3Dyx;FZaWB4-w1EeBWcb!niaQs+y(*RVx zoM!W3Q0MN@!=5)(Pv2ZLeRb#w=o3)ejUYT2ZJs=)&UnFfxTPN-z&S9E4@`W-VSN|d zu)zbBW_48}f4jeb#WDPCr|)+-Z6~AEUibTJS>LgfyN!QiD9USboZtj#Y@8{=E*!vdToddr!=W_S9PGt}Zv{~Ss&rA( zY-jC5Z*S&BTIsMTPT|2mh=8Z%1GBabQB3^=)WPF99J47NzB-Ouhy@SJ&*0ImWF7y0*q>!v}Xp@(xgRg-!6jJLNk*NiX$dMx+KC{SM~Q>j20N0zt)MfMLFi zj_WF(`hRtR5q}#fq?38)+}-i#osr%Zf~>`$xl!dKigkiOHCK*`)&LaUF>|2wTn!iT zT%5iryq82I%|{*@;tmW?p}n-deA014$ROy=Yynw~&+QEQ?)swVyzUEVDnOwFsNGmy zbT5HD>n?4tU=3IU`8#Lm)%QD|_!-LuQN8DvyY}A6p@>9k6@Tiso?X4FMdn~T4aQLDJfZW%I1Zf8X)C8? zVBiV(js(mn^f@7q1FFOHKSpdj9OJ-o98h2BGvc5Jwshh=XXI*@IdOtp=TEQCWfvOh za%g|5uE12cg$QCC!>2s;#E=P{TpezMu}BPa4})T@7pJDuZn=h5l+M%@hphUH^4b0_ zzt^$btvr9VHTKGX_l`xRGr8z9fQNWgUDH=a?dtD+Ro(NsxXk%q@wwAIcQSFO+bf>h z(FB56owuXoPS^Fi@A|y^-rLdJ!gp4k-+6Ag0%>PoI$luK*jW|R6;dZIuKGOc0AOZC zERTN~pI5w4zhAI9Nl-ZTGf4!eG3O_SFm=)s^Zdgo zsZSgOV4xEE6LTI$<53n!K=6T!)oy_d)(zg6vHsu{8eV4Dw5;u6^$i4Ut*eecR=Y3x(vfVvV zPYM2s$b!#8x%zgGbd!9wq}}8>7XhwT@yZZ^l$&y=AOX$@3wF+J+$V?x;-(aQdz-+v z{GKPq%Y=z`dEnAR$z5GvX`nmPF(x62OAw&)GlyExU#+49G$XaZ5JS|&S~X~4lW4T zD{${){>wn(e__eCx*opa!Cvk_=dNxgsCNEfsDO`EfcPu4xpO`$U}Jg{Uwnr==~ge} zTIIajKyjsEL9GlG+ScU#p(i^4y==v&b3V*^1{QG#DhFG;peog z_IM};QzD3`ofV(#q%MW)4^?w^pyB**XqbwBOqpi5Zad+6Qmb-S<()H!mF-wAPu+()6YNvapX*g0& z|9X9Qe}CW3M)$sSUg>&ku@8bv{k^_jTVBz>$tc^AnI0atvS&97oxWfr+7cprb%Tf1dLRom`cAn(a`}8!K*eJ>{4T zb)Q9T7n|=SG&yjZMj$n@f%yWb=TFqckKM1 zj#Ymv(1es7`xMXzRlTm#-`Sx4`$ca_`adC;ysp=YyF0op`WsjN?TfIs_86<3$_bRK zEvmHc{oj=?)4S*ICebP;xT~}88m#?a^hnv=yW`!+(>sbETl<7N{LKz9yf}KvC~=?dN3h*3p}Y<%T^;PLoyr8ZruxPx{I&dK1Hk!S)CJ)!dn)n^z#=A5w$ z4miR<9u5>7hD)xbJjM}q+o3EHTbB%gKLL3H`ULP{N;;54gmI!Muxsj z$s-)4rA4wZRYwMhXptqkN5X!8LK+hq$6^^-af;mi>IFV?1FZV^?!e`*eE&z6o$aXaeC25L?<}3C#~3Dpus|A=j%v~^?r-w3%gtCP zYxZ``IUq$4lweyZ_GKoGq0eq(k>A=EvsEX&ec6*=`=X~Pv zP{?@V7=l9;I^FKf3FwJ)PKH;bHc#mJbbUYv8Q=kL z);M^u)*Yb%&$-G~RFr**xe}pG9*7*KkP{-GPdM#>>RlG9$Lxn zpQjBt1FjH0GcMy9r+sg90PF8NY5L^gD`&a?-fd#%VHt9%x9gxzm#X*r_VzpHaEJM} z_Fd8mzDwm+mmMwRQ_{?EBF3IjKQyP+MY;38;reTbV=B*1%*DwCu-Lmk4meQuA^DBu5pnzClhkuU9s|sK_z<-tuRPs{&NI;6$MJ!2sHcBP8L`8M zOqZ(TH$X8@ThMUM6SgAsw18&dyPU{ke&3-0gZ?Pv%ivJtFC{lemWB!72@zsOzfPGG zUsTg3u_`UQj@SmDHT|CMv-EUcyD_i7y$TrZ>_n}D?W5>O@o((^imMY-*U8@6*Jz7s ztOmW)k6own@6oRJ@BFN3OLn@RW8KGQ_s*(^Dc7|BcX+Ma+nxOEWO-*FJ1y^4@z;L# zlqFq`m)&Hc#|p-5?M)ga9(4hO1JKn@3H-q1XoA1rcqq={aJjKh#O|m{H*v>KOFg^( zR~mI%?@Ax@-zo1P>AQScb^sW-H?TV=a#zRh`wj%|lxqJR4z2@CnwGmLuBC5i6Q0GLd;$(`(YHL3{O;qFyTF~EL>K~99%@0V z4KRV76eCMzD~*n|ee1ZbO8?b1l;9WGtfz9^foKb)jIpwRTJjdc0s`v6fnjxM0nfJL zsu&Navyc{k+A3$?!m)0Sb2rumK0BbaqgB>H0JG1t7k~icKpemC26$C^imIO&YOAz3 zdrY3Cp*v_paWzQY!Hxdfl%(-Jd4LXyR^D-^Pi?iHV3cvC0~BVJZ?%;!K2FvKUsVKO z^+$jThsbK+epbH2-VpEf)QtEfI4<^~8CeIG;~^99$jhtGDHZ3=5FTn3ypK=X24eQ;2dEkOMd~ zN1f8ygLp1cjk8p0%)vr0JZMlj^Op1s2bqVu@%@rENeJ9*hyW~1$ik%Avl9hk^nD0Kj{CB(*f3x0=&aHowXX?b;?!Nl_ zZUy_U>|~;sMULXV0-3ZU3|2WkH-`exmzo%@KE>)NOssZ}g>ulZDrtEFuoo&DRIIGU-DV;(lko10q-RuxffKZ3)HU@n3Aa+ zcD_W_$yLF#9&ta|{CR3Yq+M{lW+_gjxM(S8JRH@h-Ax||Vo|_u{C9fpWhr*y&y;tN z^j%&S3hFBbT!s0P1o_73*5CVYRT!#3^d;nUd_wqv1%#O$r6Gl{G;^Tj&K?L5xC%|g zmYJ(&j#40Va9{<@uV}`06MIZv@A5X+`}_AD z@BCTN@b{Lk+iRQd>_gw8-W`RVPEHWt7`k-~AtO(&Kw&N?l{Sm^|H+G1{`FvUs2A>#Wz|{^@@O;zaX-`Bj z9;O4&IdM+K&mVtS3V<EPcl5^z$}z3oae0>A?i9L=U~|`QOwJ0~89M%d`cH zMzQSz41rDb!3i-iA<%h3}vE=)z!?nXKzoHLza&cE*t@F;w zqcdgjXT+p5$5lK~vD;dB)gNCw$~&9b+tp?1l^%U%o3Hn&2OuqYFFJhtr~x|bs#4S` zNq|mYH3!Hs!bZH(Pb)UAIt_u>-~oOHNEPsO6h5`!c-X|0Z3!u`QDW)}zn?md_O7qI zzY7?!H2B9iaJP*H&08eGM`WAJaOPB zru@Xf;aJRl1z65#Th?hS&gPt$=TCf2vrlq7?A{^x_V|E;D@soQxhsxi=78O<)2AbL z)7-9YtZV+qP{kbLc%GA(BQUFQjA4^t^Hk{g1jYl3W8MDkbgO*7!@I9BJKUC+dmC=7 za`ctXt?!slgRXZwj~LzdI|BL&#a*8=rH?H5yua%<6%BCdQ^kB8-vN8Q+}n5OGwts0 zr9V^gd+%GvjJ2Kpxx4Q>Thi;S=S=K$Yafpt4_0606>WBYiiI#G&w>z%nT^B!H{w44 zIK4^3&w3GHNqJ-bnvmc)#C)z3uDfTx`z}4vj)wmh&+DieM`XNoHZrB zp9xz5Bvf$3WBPKd7xQNt0_nfc-1AW$9sghNE&$U0o%-+^AX>rUC$&q@ahyWhP4 z4}f&DRiPq^^Z5rpKY!rcw~5C%aU2#9`uzL>(G%Z39#9ON^UPClhhUxqpPx@Vp_obE z#_;@n)7Rt-2W)<-Fz9;uLS1mDJDQqB6uPBZM|&1+ZBuioyJHF;JtGQ`)3Dt)$#D& zW7O?+;yVzSOIgZHcx%I*e&2y#bv@(Q(I=$}|23Xi(#LH1Aaj(3lUnq{+9p3a-W^Lj z0^TNT&hv?%fBX-891|bM36TS1D4ypho}Zui_U#+K9RtrZSLz&UlQqw$;>VAt1xjJw z=r{zAK?$;sicB1sk-J%hhqy7sV%IhHLJsIWATlB1=~^5-Pm$P}YSs#N5MZnrI-nSU zd;|0YDi7E5;=0%58L$*7b9xZQED|}(6LI1WI>QVkRysQhp_;K9d*`n--+AER2| ziU~O801ao=ox$6d-(U@~Y#bqe@3NC^otJi9`S{+!dW8jd`e@fag*YZ~yW;(`?dAKx zLzfHN(wEZ?7n^X?cC*n}jK>u+oraYjcaC`2%o5~|cE~7ps7`Y2+W}bMdkn)|^&Qk^ zMkhpHIFWBRCZ^+evwg+pA+HPSJvou%X4UBj%V^=UNcNCYw|iyR*XisNns?0jwa8-7=a<$(=iOFl>aBUgHLdaU*D zvBVCW)UxB>2#nU}+cka~KbO9#;b+>K=kq6?pMT)v_{3xU1n?aq6Q7@-kfHeau)NnY zCoJeG_;^^*<>$|z`20NGJ_3S)ahM&LdRpo)XqN{P~I(WNp(|pF4VZv$nMP)$$IKzRNF_owC{~yE_N{ z&Y;%-=@v+D6dsVk=UQK`C{vkG9R^nDoPjgs8BF!)O9<1KLRY?bgU~@nS6(ZCP6s%F z>BQkH20nlOfp3SvfW@bQwDXCnC*<4Vc|a!g7!GjE8T|OLZHUiPZB^niFqpds3dl1~ zaTGQ1cMKRBo&(hHs(=o69C+%ZJ2v)d3s4PIC{zca-vJqzV!>FOogPrJ*gLmlrYw=w~Z!Zlim&#a~l;M3UlU{cR1}P!J7vTLH9c%djdK~ zhQ*kYKz+wQfgd72(r#5E?F_JP(SX0vK)wTS@^%2P+Svp@K_82RTFycXc_#Rq1Iksh zSRFz5wn5BkKx+e7wgBCJj1HN60D*W_7x~`llz6U;hs8z&GJTb+J0?8`mw`yP@N9?B zpkuk#`?2fWj_(L&?#gb3&0U?{nc3;n8ffcnhj87>;Q8uJ3Fym6#;ng zg>`x$Z6LO{3iFrV*sVKI-^b#*71uWsxg*920akaBi$at9E|=@I&-^~QDu-JLi_BVk zfIoix|B&y%A=C0ypTqN&T5js&0RRJ^PYWm>hv0bR)Q?FbPhawv ziGsPbIeAehj)Eq>YE9v3VZ?)|JWNk*lcoht2NVZ}9Dp2VcSHdBX7Awva>VeFi;?E5 z1T$h>dH})xuLpFz%7wj7j8K5|M)zPC4N+Od2d@UJ6+mKb?~};)oZ=& zJ$NdTlj^%XzTy}HOGvWH5C6|xXBSLm7yU^K2;9;1GAR{YSZJ%XC0p{{>d%h*>R2y2 z-E;D;D{8LKtm834XCNsO4ki0;H{MIf<~SAp1#Ro^uyQ!3@N z6)V+rOVYN!@B6ctwfg-lneTR$r3VdmSlZN}79EqijWCJ*_7(^bIJ4ecsGS0TR>c+O((jL!}j z)TF}~1?pj=*b3}k({MDXY6dqHLD|5M@IyLfjHNgv;_QsED$D*LoKD-{@W& zlVU%bZZWY+y&Qb&*Y^B<Y_ikHR=eb?(ftL`t>)nYj64MwoTw{0PJCsl4)sIzhHd>U zx~wr~jP@*iNcr03i0SjQ}SSA;djMf;@6 z)voUB_65_najf;#v8dN~dZ7mI*tT3PSPvzFVRd-@91`C%XaU0_3mHMt@ZDobG6EQy>7AuFnVbVaMCBb?OW(>4~{D0c?Eo1!nAmR zS3iK*iMcCX*WK~Z?l)DnbV`slXYp^8caZd5UY0J@x%FZN@+>R!az>Vcr|b84t_3{n z`@51Q079m01B0I?6ljOm5m*c0 z+x&O}ya721^2f&q1b@MN{sEC`D?x`D)HzQ)pP%@Ae&YH3^n7f#g#I`N<`j(M10Ns5 zx0VThJfF~0@bT>f%n|Ck%!{qM1y|R|z>vcXH^hO+;akB4>NM18TU4wJs4t_p;9-JY zg@H^3bJ}H4&|+Z%sbd&?#{g-W#azKV6(P-d7AS|5XoQcsscLhFg5#@0YgC zF~{C}=$|&u>OlbKKoRFc3u4k0mtiyEbb=&!>1r|-VB+mp2ZAx{?m%5F`VjpSf#=|~ zF|eh<>P}I0#{ix(?YK1m5rNE{R0v?fwv@J^@jX99hObzeK%8DG`8*G|kml6I^JVN? zpd%zx!?t5Yj!0igW604s*7o2!z$RcNZS!3VpaJ{ur?rw!3)m5eSpV$32_P!a?qvs} zJLu_vrmogX8t?h%4%q)nxzL_E^S5itl3U-e0J2`&fui1?JK)a3dX~OR@>-~>uxlx! zMM;KzxErfJzH`EI5%RDh=f4O`XYU2An4bbifbzk!1@j$FbUm2yme2Xtm(< zFmE4o3V0$7={%jznageO%#04uG9@*u)l^0Vp7*0GF~J0^MTgs7$an8l`nqplnOjl@hY+{ zogQ}%f2ZL#0I;!%D><&uy!xH=h~SvpDrfeJ1|eo^ApE0VmI7#Dt`X_ z1D~ItIM35{fI-va0LJ*hF&-F?BevQ9{CVPe3O+t;a!jX`g$Rdlf-47^jfcs>5ZglU zy9}I}?Nby}2B44d+oo_Q7+j7hceGj7@$^6TByevCqA@saxMhX~M6-50Faqs&5Ya>#xFMn$aRX%3d>BRH& zGy(jy-_mXdwn{r}%M9qZq~Ua9Yp-*|g9NG87k7P2U5kMd@x<_U-L@IJ0v9pEuXdc# z_;}#s_zRw&4?I7gI8V#ZbDk5=pFc65pO7JV90%05)Qdb^Ioiq>c|3f!@xYHy#W@uZ z9X^}$$RJ_lwmJ}7k>r4=Z%^?+;grFUpQ#+5X`Z0c^VK~8@D(=gJi_l0sBhme2T_%~ zz-buzDwL`$(SGB#y^#rn;I&vX_m$Uzuf>!%rpCb>GBS{^$XujS-m~(J_%?pcEpc4M z1g{goI7a3V6K{{l)H3k4cam#S-!>O~%3x`gRT!Y0Q0toqf2}>!gW#(J4Zyas*5^5+ zxH0g|F;h?clnqd1Uwk=78ZA0`K*^Dth7|lPed6Sxc9_Z3Lnm8-Kw@ciq* zBb`TcP|u>bziPt{NcQV@zE0mKgC;ObD*hX+(1@U;V$!b0tKuGsGyc&*p_>La%As>^JQz}3UJ z(!eH@Zzi$D>=*SZgh5cBFgR=*xp77f7^2Yo+J26mt(b8OA_5-TC?4!uXqkf%Z9^S9 zVhUoQ3NXt!RvJ(5haCo_flCh>5?FMAz~hmi{uWk@$9d<$GWg2L`olHF)QY z?4^dCBpF-;qc2xG@pXW|+PuGayM6LV1`7;ws|C>}=|iQfak$bHjY*V*m7L)8j(X~% zN)y_O;2%w=+~BkKP2jocXAt&f@Iv-Fr0V^?GAwCv4X)nF=XEDT39Qj3`GD(4tOU5< zf(K-L2j)+Fs_iiNse*HU;`y}m5kze3_v1K#Avk2nOs{?l#^-}OdZ7zs;6C}tc(bfD)V;x_~wKRC$*b)2=PO?k-omw!gBkulS(KX0Ll|n-*P}?d_=oc4OV!A9BydKrm78t)E~s#c>zU zc&UbKYyVOFE6Is95%KxK)%H=}Hj3WTwtugs>bUr>y6gn~-SQ5SzRSxZa##SQ1h43j z5I~qw%>#d04KCEYmrBYUm0q@>N)SP%Py%JPgFq#bns1dOn4usKqGqau;R4J6iU8xt z6#}fA0Fn+@#7xq7roll|dK#c(#L77jHo8G(pa<|-L=P8@W8j;7hu{-aPduLr#l-O# zI3C|H#=zqkk=xP^*`fgzFsB;^@a_9wpw9sv|H%VdAB&R-~s+?$ub zDU8T7^3>76h;bZ87=tkq@WAORbdJPN*(47Jcq5PRXE1l5S%g7%2Q=z!g$3qp|AKX# zi>@(k6|Yq?{1kVF5;abLR!`P#6A>j?EIiG*7;=%!OG??TdC!ms=7{8A2pMoV-5ZDy zY&1%>+;v*UoagGhBS&q>c?MU7JfZ$Msbh-KR|XDQcaC50Ob0Z) zua5Pr?TTN4#U8l3b5?iGYya);J^CA4SYpK7iQz$YwQoE6{HoKu1J=8Hlw-Cj8vh`5 zTeRMF20@;$st0UxfPOT6X=v{ool&+`ZRHDV*7`oS*Xo$_^uMivb=N|UYiayAFx2b? z4~-Fst@<1v5PU%K#Ch5Z9}&U#@84lgn&5E=IPr3b_~8=bI|#h4k8e2VU!li0*dZ6b zMP9^p-Wm)Qw*?yZPGFH89$q+YYd@V;I;s#$)gq~{p_P9}?g&xZA0vou=gMb%L|i^n z9?b4)@W92f9D828bDDB8<+{C=-(NY4Rql3<70Z2|VLp$7x%R=?tmleZMd2c=35*EgA>y&k&)n}X}kfDGc7_+hgpPh(&z^p48k=Tpa((Dy+ zn%RH5mHE0g_=Q+N0rZ^4c7w7zTYB@|%PGF<_7<5-owi2f6KlTb9{zJi}MRUi<1fEm&kH2LbN#i^Fwesr~v;A(V7*VFny*l<0f%t)UlX4fI zY^kT3Leeq%#^8Xk^W=dVOi08+{jNTaLk95Hqy-(U!3g6%t`MMIOl)EdJ5_rIL|}5J4|wTQE8Q9e1}C|@$gQ^?w(Jb zabIt>CHXsLcFzmlRv0}r0?#|FxZ}H>&Z>X!Y*6L7Yf7Li|K9mHyLWW@)$jc@^c}vY z-(eT`wC??=b>5{!+qJ3Ft^U?`e05pm=k9%X?d!5#>C$(w#j~LPG0aI@q10g@jvyv2 zW9M;|u*GT;y`05S+Fr*a^6y?!e-^v9x0^i=A&+1Xiv}&{EV(MPNe+GoP8>MofxrCaFSY?O zmJZm~`&CJ<4iO!MIj6E$8QazV>w4|)e?ZN zO0Ke9c_f&I{|6=P+vLj40!GA_Rw^c04u&rLc+b%#+7{4R?sW0BowidvJ2I{U(6A$E2sE9c(qP9JL+BS>`?5-USE6Koa$j{=`Y2?_Y z%ygcx*E?@Jh!)b0{NP5`R_=H(S^acITjmD=a6+I%Bjm$X*5oO3dJ%2t;DtOF-~Ap2 z<++lBGS!{YJHCj%c5#qvfR-a&Wwry|NJ1~ycYIY?Yk)jINGx^a9`yW~^6EMA%dQYW zk0B*UnmR+7IZ3GNT*ezPC5ZFh*(|&yhpO{t%u3y@tw?fEO7=k zd|iyEIT;uVjK>E=295!Id^|!Q38TCMSit{)R0m&u0`gQqzT@%uFL>e`REA}U^Odve z!82Pv&0s;*Ym$M-NdF=ckC;dsCcXkJCPrC@Z^7qk#Hb4llSH!s03ZNKL_t*6jG!?9 zjFI`-+|E^g=;>TYe+Ff{LsHAsRemEsWWzCa+;&dRT>$BVhc+_T<#}}ylP~*wcK1h} zNWG(2pJgyH9L}3MSZdqSQCqQH-0RGiK}N(FgwtNy&Swm#4agz!ybzg)jpI})0RmU? zVu!0O4wg9YG5E)Bs#uB~PCfup|KjMQ@TtO9F(R=KwP7Fcg@yuHF73n$7RsN79jQA3 z!xq!&B1MFq0<*TM;kG#wuw}5S*Z~5%P2oFGWz(-jA2$!*2VGX4`kfLw49E$m(sZs? zKP6z?+D9KBSAA^GWz6h$*Ojx%tjjnY15V#rBcy>*Cw&y;jyKtV^1G^{ul(D6lAiV2 zS1U*Bs;m0$3@9ZY5@aBqyfkD$^Z`-9x9{I@Kpgm`S>m4)ybn{s1n) z#@*KYUS5s;ozBl|#)l&NpxvddgBUjZ((mo>te?9>n|49HuY!#Iv(~lK4Ld&V-+TLa z@2PS$G#3%|a+eOP%UbUra1DIcXYORS-rH%o%WbASov)kr2&QfO`4bSg3!uq(=&%$-Vnx=pIH)?b%yIAT>u2z&|=!Ki^H@ib65FRt-G z0Z{&r1tlCTR0o0eXqjcXF@iOSG-HW6kgGHmIwcg0!kltU#Fii1cKE=M4-7m3c^ciF z*3(a}FC>6Qbl0~KyEZyi+_iTA3^7z4#Be7-_zazUiAmcz%gN7lhJ75FwnSk0FjWecjUoC@@yIK{EQBJYq+I`*O4nbGPj^_ z=UiOV+28=( zro1BLQuRXGK8|6^x)#2TJcC?u8qdpx*7Y}j?wq>R4cCBYy%zk{WWUSQ-6`NZhpg6F zf9sCJT^p(n=nmVua?IN%c?jhgJ~mTr;q-;Yq zR3o4mv?0c$Npt6Kc$%3R0dq~;1>bJ(d}yLS1IJO&$cfWaBvHSY*QGAkLQfPM`$eIi zUu=HSyJC?x$6$6JcUQ5kinL{>yJ(w6yu+>wA)V2fSe1BeW06;jwAyTQh$Sw(3Z^6< zdmI0xDX8_p?WLRdY+pjx=q!0~&$=e8zJG;&W&V!x8c zU~Q+n|{`7_4+P_!Cl$OWbZfYs<>gXiKRbxydKvF{hPD}Cbv@jA=h(t z%!k=YxSgZU@F|j1oyv*0()Re*bfr><4!3783~4IUFl8OMJKR?L894G!ly{KyU0#;1 zRMwe@Jk7Q`%UzIw3ZUIl5n$(F?+nyVi4w3%Y{SpMBao2BWJ*JD1H3v=B!&wcDkh)- zbX@W|bIfhhiWP9MgfapZBd;R`o%9jw2xm%SOQO)Hn}8meazNySt?n! z-Q_*1x?ll1#V70Fsa_+XTpdwQ7ZJ1vMD6s$TL=*{es#=;FSlOXmqE?o2a;%^S2_b6 zvksgpUr-064B)cr{X&BckX;-Um$?CC3N&}*W0Zuz!=`xC0Z6&Ig0aj4Y_({ivCBFT z`iFJxz|}g7{WZ|*ccvY1R8;`}uapk5cYyz^-?Y-JwUK(;b|T2q?r1;Cu7&mKg>U%& z-RblU^Q!~L5qdn|xAM@+H+6Rgf49#-q<&39J=mB(JUz&1X)%O4&GJ?YShqdI&BW97 z@l;@*_S~sIFy(=vp1)JX4p>sA*s*J>oS<>%js`Jk>8s?#C)!AF$Hcj+o%~WdOue21 zwep&ec-U4SCmZ7{2H9QP^3cYCt@f=uAv*_e=K%HkcK7a_&7Cg1vr)Txc1~}1?3Qhl zZri6`SEqExaO>d0wXgqedW923BX<5&x>o($>mzS4)l%9pfJ<7$b=%~DeFdY^fn$y~ zP7<(9;5RYZ4Ljp~=rmq}-3BIu7kTGy3}gICziKdP!7?tlY{LSrAdwE8bcZIOMxIG04e>arWE#lM6|J9TJJjErB)MeYBeb!aK?+(K`CK?X+oTd4o!#etjv z9IBCKsE)1FXL;{J^B_pjA@nx*zC5t?F6cyB)X9VDgDtee(xJGg%XSa0)w*`_Y2S@9 zwsXxFk+_}?1f}W+wjQv9l|HSPN*)s51Ahh`L=ykvX{|rWfBFMczC*`{jmn_-NGvJ= z5H`xxh9c5w2&rHDv(hzf@YPn|>6aw{7N(y1N-ob=+OM`e1Lt?|+u4))+pbMr_tw(y z>3Vf%^Xjv^@0~Wg-+>-8SjVBZqvqki((Jx%m7jZmtMBnkHVu3F)pzy&E__jbtGuzh z_gDMYd0sDu~E75$3vmE$!zf#k@ptDBv~{0FexMciLbtwOdICfyhyQ zuyq;39dpBqhl4aX`*J{W8bEU;ReZxxAod;)t_U#aCv==PyK`7CbEnG$h99oMx;)P* zXM@BY3dG900v3vsFp6Q|w&OUACx9YnpNjIIGj_-f@vY48RZ$DrNj@}?q_DTb4>u?V zj>?~7spil{FhU8`3N70#V$f3sf&ohczvi>cFCPrUQJqab%|~jX()x!1?J< zlsf>{OE^nN&A{t-&i+!rgX74-s+^ec?f0AD#3kokX=k*R;6jJzQFBNlzQWwEsZQ{K zsi~2X3$YCa3Yj@+VRX$&4m-d`%L-cqBjRABrda^?P6UDMS3qxHv^=Y*+r=tfb^wUq z>pkIkZJI*5Qcgl%;D@-CHi_#5${JHxFZKk;ZSlvEZL*iK@jwIO9l+Xew#o)T9PF~w zCw%4#%x|dcyB=)1z&G8CIPci$@~`945qQo|PG-{PXW(B8{Q`5i-q*?elm~!y`+Ifh zdZ3}(pE@?X@4LV2wVlJ;^;UPb^BPb!SK_c$c6NFw?dQ0>XPE?QZ6^kZi5%DaI~^DI z3v&-vY$1_pNi^FKtD+po-RbjtdQ0$LjwkzSaT*?al+Rfjl{qZ9&-`kATVP<_2n_if zb3b9UnYK8e<@27C-Y1#sO0jiito6lYk>krc%^@|_sWuwLkkyIRsK;^Dax}dN6f*)) zm>T+y*pqmfIuo+mfxwTnT@jelHNXvIj%Gz1jH%cM=Mz`{xuWq>+DrG%+01q``B1}Sv;*XG)}`ZR;sT#?H0RCubTK|MtMxDSBT>$^bI%J<33cXqm;JigNlQCqdE zVGnI}H`H;4r&QvMzV+w;XZtf}wtBoI^@ibC;%@ebd|+5=>KXirX_F?#v$W9}&G3$v?C!(F+s3o{y=Yt8)3VLi}k1acEiZe>07jf4xSQs z0zl+ORj+$ZI{>Fs=?B97GpE#0t1AuH9-;=?Lf@w{SWmc2#Y1$;LxU{1BC%RM=qu7j zF2T#;fdFxUVn9=(t=8e}9Kq&>1B5!}c%o6p^9Y|ErAF-_3CP_-OWlbghmM%_f{Y z)9=>^cuS;o|{In{A9%@J5F&>W{%q2Zh7VXRFh+b5wdij00?B zl%nFiaYW$A-abqXMb0zOxpTPyMH0X~pP>tx#~FHf4}9yJcR`A*Bv84IeI481FZJ1V z>tCfu{jA@+9g1gH*7ZKA>m^Q#NdyJxteb+eUuFgMx;pXz;$S?!H)J8UhUbI}OJ7NG z0dll~VKeuWEcF@tto&YB(e0ADvJs~P<$mCB&}qNh>(ZIG7tjv)Y4;f6_%gSf(fkpi z5l9|tGsaQIPH}KGf~1~6*gFQT#oI`^NeLAf(pmW0bTZ%0iNvl&CHfGe!d0@Ue6$8A zGsu)<9ko~I3s>H)&n&vH=~{kvM~mZDw9LXQ{F`LF=+&KUv^MR&*EaO6o=XrfCJ2G! zI2I>xx81KhoKkX)aT{OUOAWZ_mizYCPs5lt$&=flod@7JY{Gu$jFZ4}k~)A3c?Thl zPd?H z3_b1C8;%Kl!en}?1I~MdsG5Eg06M4dYN38TEZvS1uF`^b#Z6b(L}-4mSQNx!f3mn* z3wxXaZTp<%JI8HW1U=i?ZFp2J@r)qHGx^y2?s}4Xc?bi1NlRkvT>xpf`tDUe$X#&Y z&hFIr)q40_m)%USW@9y-KAeOLJg>xmoItgK5Ga`5EAmo1@zqa*)rLKW3{3JXfA^oI z;k+L7>bkfFiul{zq<^RBo!;*6?)UF-lSDtRft@@2)7x|B6W{6d{#(cHl*c<8wtKE# zBaa=&aS1%v-|M70?Zhj(hOe?2-+KR@J?njpT>^g3og8(Y{E8-fSt<0zmA?JC{_LH- zzI(Q|wSVu|?(q8U`*<9oPwp7j;5e97rEar{N0a67!#p5rsp?4g(mxF?Q1tc5b@qre zT)6uw(U9w4R|txg?ibl}+xZ)*!D@L2N#EtmLY}6hvH!g%Iv)Pa_4#CCKEGE)9VBe; zf%vO5PqAeSN>X&kG3%$*UIHfdU;iSyTME%$boSTs2r#PH7Y$i_W=??KuALqx@_?e>gpY< zFe&6Sz8NxQ>|j5{QqgwEpHR*3)*3x(Cuqi>qso0|Loy>Krfci-;fg0IuS) zI*;S<@zMw`*Y;PM?Ec4Bd z9w;@7EDzT|10xO<6MTb=4@`VOK)zsKk`lK7OMX8{+Vw_`f?Va}7s@rbaOImA-_j3N z%^6nL-VCIsU8(Qrj@!bs zjsf#jhh~dJ4EG2jRSL?Q19Ei)?K2ODiT0L%!v^s?fZUUwdVZ8gvd{b>^24y#@tr$q zC~I^k<1R^DQro@$Eosl?Km?S;Lq9rMgYSX{H}Rj zc&!xXsO^&tAU#~JBp5{?!4GCX7?6$;h%{2=9^wEUk>B%fRb%}dD0B;Dx(@s=VV)w_ ztn;h)N(9%fA8{}#Iei=$q7Xfx^Wi&DX3`2dnJY#9(*BCs1D#N{)u`6KBW#IDkwC^( zhw=L^uvLAW-rt>Vt*aiZ-s(Z-et-SD(_0Hq^ylyNWDmIZ=lU4k{oe2GK{PHx`BmPz z2B562eyG^p0fl!#(!K(=(vgQWf7QoMr|OUORqI`*Y8|_A?xiotxQkKjc=F$(^nBgB zNw{BWgSy{u_StvZ3{!MN#LTjozYZMf>tSNzgq)wyIZYqd`u;Yd}3H^QUP04wAmh7lkw7HKz>)u%VCs zqysYp1t)3%fY01H40qT1?=t{c37pmYB6!5+Y7ssrAeTI7f}fEzmz}i8) zwd(+(vC)b^klPZ8EM4K`GSIlF&^UQjJ>WUi6eYu<732-E9Cq{vElA`}yd-t+#@_0n z($f+^s`TcssrW@KXuy1V1a0wNk*G#Q!a!fa%DgqE1p3N&mIFj)b6I#p^O*@i&ukZ+ zW&q}-1VBu=yBc`PTY>>Pxxrhy(zfzupM6XyjOF?Q<|tntnGrF^V0sQ;281bt!w;I^ za|`wUZL!4i8Y$m<0I&XTyouPZ7ps-)y_IjN4*cstD8bA_7GT8c7$J4(QU{ovCj@^$ z3BVS&9>+Xc#hZS`3aoVT?6Csz!IvW{hWuyfaKIuw4_$JwaIcep z7x=}A!^NiD4S1iK?|^z~2ZU#@UB-q4X0BQ4bkaJF(X}l(R$dhqm1@E*DH9{*uh__xNdOp@2YM(Nc%@EJ4~0B%*d{2YLy`yO7&SBkz+4>)YVwE< z42YhKJvaHb0D(>|q$s*eYMTLwMo@p>Zv}kI77nMi9Ob=UPt|dSMAU~>=XU+D)W924lpGHKScyAnpAh~+0nwChVFmtbUU2(NI ztbTu&ub#6FBC#TjeeHFweP^4hO$iIOtkOi-u*45l{Dj2L0*ytoHs+t0^RxrmFfpH&-sN~4IF82>?67CPK{)Z|D_y4? zHsap*v~`F)s};{3pndzjvg5s=tE7fsT;=kfx;QxOO2s-jgLhp)tn^0pKWf8@t|Omg z4J=jtr>K(!``}LBl~--bE-<*|CEe$qzx!@Ma0b|nVB|lWyE?!Sx5>QgB=T!uN-ks| zSfzrn@1*+}_N?JVTNq%6xwI9L?nlL{Mb%{-*$@7`n=Fbk-~7KT;m6zrMf*GQ`}Mxs z&bx`VT0ct<`1&2q_FV&bI~uSK`YQBWR=Y)>$#L9y|9jiI@{?gvU1TvPMq6E@_4{|q z?%lh4`uDr{Eizd6?A1b(t^5}IP{*Sm8r9qL3j3`#z2c+aqaSr2aWydAH#a*Okq=IC zIxdnafc|0jL{0z`V|qQ9aSn{kpP6b;fy0~?3^_24N9uCCvI|8xVE%mM^I=tfA0Y>;XHX@! z*fBo^w{-h`0XEzS(-$8CU~u+BixNo4&Mh*)1GS5Y?J)^*@;Uz;1^NeQDt8so6NboM z>dt{Hxd)(<~1o6Deu$+sYAFq0P1efZ4Li;_(hqHwlY@m}%4&wNM zPC{`wwD6ynci76n1RfULHmJ>&G)y3`ei($o#LU;m)ff<4Js<*KNm~r<5Ikf6hn*PA zZT6g4h&Dvf0t+2TPaDS>rx63`kP+mFB&bgC>QyN@j{txxdNNp`4rs-%^Dr|%JU!S1 zQuw(D=Wr)Ti^2WvlFEWaDU4OFFZW)H`0v%mI@QX9MvcMujCx;wVW5r`+uz35(N^)g zeONVUBtd7c=(3!T0-XnBj*tx-i;1B=i6Mf=<3O(XID!{Lz6DS{jrQXK^<1zbpE&%0 z1eF6A8rxy-h^ESI>FWx!uS)3eYEy0;k-H%27VK%#ew6PBeuiynD9TvH4?sh1&Fy-H z?_FM0`6~KS9f*-^2|6CN{Vs<~7)Jq~AYUeaQn#?pRW3KdxzNvCitT~uk~7cvaoFZq zbqCbnIcM%ns9Qyy5?&vmIxwd*@POI9VY#!J_Yoq#MQgQf>zL&=uE0j&5fL-mX0A&; zejjO6X~DxJ*#@1{cO(=$R)$i-cBz{$fqH5hq1|+lPf{#_p)%M#Fu3A_$~S`EkXjGz z$>LlM*a~6COOg73iLNAZ-PsD|EIjCFD7B4|@jocH_UfV;4lc8|y? z>4qF@1@ilE@y#XHB z85qL9MQX_e24Vjs=)rcCKv$*trgR6n)|J6e$?kZYn0i5K-vVF3Y>={n3h0F50|QSR zM?DeS8(GC6`1URBkjMemb>*DpXlJ_zM4ry!pHO^2#{+pvxzo*ufp)jD-g(YTpx{@F zs_nAD=jYX~_&e?W4DRVV4rT09rlX@ahT`A7mjHJqNML*s1lC=Go*VlTa>fM>#YeDL z`B-y2y_tinx1EmDb%d4F_oPdHuUNJQ)MWEn^g#3vp^v#b&;FYj(^e9XNS7o~E+{GQ zgxfF`=EJ6s<~y{#Q*@<4*DbvFj%^#=aXPkbt7BUo+w2$}+qP{x>Dac_;mP}c=UjgO z-9N^>tWo26szzz8Ip@j|$q7yG+v^DjLxlp1-zxbsm$%}a>U*Xrdhn5%i+!IOwG8qW z7^&vCtaJiDYrj?v9AiQ9pBWT&Or)jsAhU}#3Pm;42NBs$W-sm!Z zUP8gwtE7ged6yX}LF>9n>fLYL&t)UPeyWk^4shA7D~|S~U9idd6!^wA%|44m`rS-g zlgPnm#`d4a1RG(0=@M(VIaE(uz?4JfTPF5NpsnNI!bymF+?I{k1TMp@J-lWg%G@G{ znQC9T|3{O0kp1yb@4EVP`V$U^Fsz{VrqE&Bwo5t=@T`in%-otqYzEJg$bi5C+)@37 zQS8Vm>I$)stRdusak;&_7tNqNyYhN2$Q-ZYpqhGHz{FQ821g>twwyb=F<~3lrkm7&=;7%#Vqc6Is#{E)yE6!2oyc+EL#bLb1TOx{P+eo+#WmJ#dADPCk6u&&i)J zz7Q+Ejc@baZ*U(E-S4iEH}+gpeP=hIL=?)cCjp89noA|ujX8JZ0-gh^PSGLKFu#Y` zgpJprrqO4b%opqM*i&hB%2e4OOfM>16z-f4s%$qVv58wcGYbzvwF}|?*?u3_f!*Ld zHX4{|$wi!YP@usb=dUCcdl-+*Cf2a0S+iBx&{xz7y62Y3hxHv)kU&Pwjmdb+)~i)6JCi0EjD60qi6NESE`+ws-1F9uefg7O-oW zmN*&(EV}6@Y)t#|khWXL&1>kfyV0eF9hK_vhxj@&Yr%WT;yqcaH{FA71Am}n$eVp= zMJF-bL6AR`e3|~BU;8^M(kkV(S@W^;mB60VaFY9DF zbzkoU8G$c{&Vkr$Y>v#M{@8-l-IUobPI*edo^=CPfIi^M7S)xq>tBJT#L_q^>6c%~ z+nw)w_uiEr-RHghXQc1D-RFi|@w?if6HNTjseLoPbdG7EFnHc+i_Czr-KqTaB);IM z9vIhCn?omIS6Fj6ER{xDHEpKu@_X=VMUARJ0v}3IEFnyBwImG64OD7Ko2Zl z8OU3?%h5&{;>jqJJF0i#3x8bmXKgX^Qj0as`T}+hu-u1x!zYH-FBihEVG}SPc;7W} zJAxz_b8%f&xPm>`Iy80aN#CJyTDrWuS<~Qwyf2}9lQG3J%M`c=f4nMO00SCNF&?&+ zBWwa|b&JtUN{-cU9MMxd@YhwGPNnkHyMIb6zFeaZVwZ}o%0-jXQnjvIgrOhQBjL4z zx2t?7(krV(%E&o$>jUPO4a=u()mOD!d9;WQr4+aXvUh3O1lr~6c5)a;>feo)SOiRF{iw1rp5&Ic*QeId;ns}t z{{fNHSJ90l2m1dNw@^Ao%{u;$oXJ~aC~?g?5GB+q4>sz1+EWMGKI6e*Z&-c;dOMtt zv0j_4UPfc=f?2+3r}qEpuRCz=1eLTeSsmtLs9yKqAqGlsIi&0R60mX?+Q@*)Y3-f&2GQu%$VSsHmV@6BC5rMd42@GS9MPo}xNP%wOKuo{D z-1@w9y}3c^LNaagPUGkKorXF3tHe$JeMx13q6r|6R3o zc=?wt0jLk#{8W@Y(CLX0f0p}Q3U~n1pK{4sMkPrX!gB|@E``1P%1i=Qspo%y40>@fint%Bh8OD;jW zz(jP>R$l&>maF39bls%v<5Tuo8WPWN&2+zck8h`vBJ>Fhr}z)@YkoQ4HPlkaiE@A^ z2f|oIx2n_1z7NF7kf?mLLsiN@Y}M#~Qp;eR0AVc{aDRA$rRh{RJZAr}Tx#U-R@PID z^z5oXucZh89`5!%58T0HXIc4{~7qu ze&FX_^#^W*N(sFJM!nu2K-e@2-mnG_m87Z{0W;u>t+w2qIBX#Qk4Jvx-`_1VhQ^-Vt1|xbZEa zqhWY&t-g0g2>iX&+W$6h5!H)Ql0i`(g z77MAraACDXta*a#KRp5hS;G9)UVSE_o^x5;_F5(Joy_aA=e3vN%dwkNB5Wfy2xcd> z8eL0pniSJ=cOdQMD-!rOxL}bd8vzh+53NJ!m2!|uFcXl7DL5u+3MKmWD|zTcF7^GF zQ;6Vw`QkCx+dE*^rbAFyo%0fNeO*NckgWh2t>4Y zi>)1h@)X|Avp?8j;i}H0kyY2@z`mns5%D#v;!>#}17Z0?;z76`CCjVGqI8k{DmfD{ z#-i(Cu4dS-n7C9&Rx zPPEN|YOz9_y~8yH>sxd$y zjl3vCR@8^&D8k$d)UicRVE7K=Q!YJ;VPc(glQzEy!jFp?D!nEjU%0!J842cE{F+S9 zr)O@g9_gXYa2k9U zHjWn^Gz+GILyM=eBx8Fer=KR!&^x%{`8*jR{k9$I>-1f+Td?r=cDC;goc4NW52-pa z2-Y;&efO>mV2sG@r$|zgr;iE^9=W?`!xXB~OG^?;3+!2V7fM*MO5poLAeRd&{VMOSmj2G2Tj)*pKBXJuGJt0^l&I#@LF#$l{9F z7aMHx>cUl+{0Z9}8o2+>iRnW_lZ}aEzp8O5NzW|dMH376!1#mIk4fNb2TGLr;Hs5U z89fN)*4q2XyNTWui`nXL>PRK`{-$=rnDTP7Lp+b?0-s6fP>B=^lOc-VzzA8PG-|#d zp2lZ}WQqLXUIngNuWkr$GQ$o?%tbB8^hHXZAW%EG2s6Eo$z(c~CVrT}Ef3PgIYp@s ztJT=S>OadRYX2qcZ5bWIYOrBluYqTa=O5CRq*SwVE-(?TOz8}ZVw6R}0LwNHsSWGW zUJ0RteEmF2#^dn@UXrX)^;O{4=SKcHwEI)*>*$N&|G*~lKJrF4t#`Eq_V^j`F!-;$ zWR3?-^S!cmy>GTtnEt(>GK;_0wv~ke3W+Rlq+Z`1997|?&$Fb)Dh2}($-yd0MCF3= z9D54@+aU~L3M-w#z*9f;l7b+m%M=hv-@)HPDtab6JS<3gh>E|^#pL)K>C~`_pppzg zAuOpRNLE@|>6a`~B?+~@rLkgHf2==R9}6y&I0Idxw3XgMY9bhh+f`~Z+aIKxZST`R z3Guu%7$=e?r{s*(&jTwCrZ3o6jgSF;IEq5`c!W_Y)>30KHF=i=OA1Xk3aW!^jJW3S zp14l9QAn>^8D0wPF0C8bHpDHVEpfxg=oXYRw~X}K=Z;Dx36xTVqnP_YFo^J!=R_ca zu}d&T`w?&R`N2V|0ZfhV2|-e1V8~)Z?1pSVA}MF)4l6_z96SixOBcMi#GhG&DbIRV zH&M2;HvG`aU9o@KMA@T$pS->{gP2{D#da`acv*+e00rRSUw7>a;Yf1*fl;PPDGDe> zM`v@WS0gK_s(Nf$RR?s|n%&8W)GS!q=~INM;?+Ry*y~%ft&tf$X>aiH)Sx0hMg3k%WR|RF1kuOv2`-JsS<}^I3%4$BGG2Q>+ z-6CLp+}+76gX}`#27$rC;L<>c~N3>Xzp_AI5CbH;PEd6!T3+OiN{7$Yw zSEYrY6ThEQ5P2?PUNy-%G=W1|v5#13cqZ6zL5*S)EivB=z6-)wiqqj1-h_HKOHOTM z>ztZEM$M<wh^} zw>&eaC@wqU%A-l8D&QYul1|+1-wllvpOw>eczuAzzm87*Re%TvDV!fHNcdrO^Ba5~ zjPi=mpW2o6-UuwX!wX*5rmS)HQfoHu4lf^wUQjULyk#KsO$VqpcmgOR zx1`A7Id}vOK-Y79r2PXzNzhA9o+i=kwJtbe!4jY-VHi_k7!87m7>AVgE>ckfLtz|4 zpW^ec3*epMSyWxN67CU_4`}VAClu7xo`SqV58J~ok0d`S;a~rd5^p$D{(KXw*ma;~ z=(ngq?cRt~1rI^nL@x)7bV=%X2dNgED6wu(N|kt}kwe%HQEytv4tIYtJbiY2-qG%9Bs@D(re~sdDS3aNYPKk<9n!~B$$68tl+$i#O6mj}UXrYs zSr9Zp3h-m`63WZetk4)v1VO}K)s^HR+v0Z-r=WoeQt@Ok#8)stj?|z5 zXO8Gy$)E@{Dt6GW;%p>j5KZ2_lZ9Kd5Wr(UT8q*(5?>8A4CQI`#1qn|30TJrWHclf2~5;ZFN%rq3QQut*}_c&n`RY&0=`c zU)zH{3r&!vAdt~_OAs??1SSzsJ&*z}86RKqC7CEv&a^;|uOeu=Py!GmV%hJ0d+kNg zbYOxk&_6*?Vt(%LX*x>F1(XHWu0IJ*6mN194oEf7k&WvU2w97at#Y@g5ljjsMb}Ue zlZMO@t2uB7BbdveNg#;{92;+{r2_tfH)${D0cSf#CoaPuT!V8HY|g_H!xpeD5**#n zMEy09N|Z?2dYq&n8iYoB@X_K0z|b*3qO7y9P$(te`@N-2M%-sl9XG<&l08+8wb4+V zf%7EN8%Evy`o0_~KAiYBG)zd$+vGxU=l7xs>-G9khk z#DNw80KI~XC$MIV%D5QF=z_|)=zD4d6&O(_N|i}$>7V4bEm7T)AU$9Wkq*xK%Hp#5 z8};`Yc1b{q%k4~-Ow}u^abrThlF)Qmjj;h+gy<)Iiz zlT_h>fNOzN8AgmHt+kLCQX@0yMqfy^AG~vrhH=UwU2s8$qG-R*rgxoqIcp~jqru|>EYf=ZD8d?LeP3U(VN3>< zEbmF$h_liV$In(=tAb-9W8!0i8ZK0F=rtd;yGRB_%S9d5JkU$3b<(9z*&_4|jsM8w zKR}q=O6Asuke?U!P?Jaw95Cjbp0OJ1{i++z7s8U?G4vS97ja~l*Lo%CChOB}gPxxW z&YOfOxonY?*|YkdNxEuGEwmWQ<3pe}+oXa(7F>Dc@}rOQ*b3&{AFrFYB0${`!&6Ql z17gm?BIsMsz6OLG%OX8!X|0RHheuSS6SiEWc*PcbOvgZJwJHi*FG(yq`m4?LiW>uC zgF^p&8A5r<;p3YW>~Z{~*G@nwNb?(+2%g%nOwcfIbuaY;ba_x<4dO*zn}XQxceUK2 z<}hg1`-t(|fi0Q}!@Gw1D{n$ImF%tS5o0#3ykY9!+3MQVIB&^lx8UBGraL+O~_ zL1)+ujnM9Hdi_Thg9*yQmTv<|Wf1%1{KDn9<(EtYIoZuxd#><%zW;YK(SR0!sNwit zGV_9(^LwN-$z6))&op>%qN010MC8bD86M@;I{d?huI1J5W3V{_0AzR$^3H5OR7of= zU^}_{?Hl52Cy;_dk+h5ioW9J?DEvDB5qi&L)#rgSW~z1nFkorMAJT$Md@rx2d*T>6 z5FSQp-6r{|<=nPZe_INC!G#TgU`$yN(^q!#&BDdH(TszNU`cGC%qDcnsK3v@A}&(m z7ITADk`xU&JrQ1jgYr%Si-fh1JTnv@czoWL#|X6=fj-HM4=JGsrPOGX+NDZy6t+a- z#`KFUuTi-DromloKV2joSuvLJt00Xin4{dPGByA>QK@KJ^B@L5RpT@$5#|PzlX2wv zbVT!t$L$qmf?`IX?uY~7TZHN2DM-Q2;{;2ZN0SD4hqgF7dQMQH+@Z41X% zy0MZfRMr%4M#6ntfKg!Tz1{U@bG{e=?Ed&$eT`QdX0uV?S5ttGST}mBR~&1*yBy`F zwZ)-8{^_ z{)*mqBI_iz5d4lIMTopIAg5ahPWELZJq@s@*UO-7^x#Yt;CrlLG@u}@wG?mo^~a%7 zws%6lh;q*VZw-IIF{A>SC`n_h8S$`$%VTXAqoM;;UMFSwB55f|BShx06{Vv!p~Rk} zTEG$A%4=yd9^BhLNSc$Kj{7%TU1H{bGAywR@xZ-JE3R_!K7P&CYa?=?b@wYP57!L{ z-wF~_R7dUGVk0-EwU^Fk|5;X`Yt07QemmvJ91}7g4AWiEg-VaMy;)Z6hIP$`?R5hG zKeV@FasIyi2ps0=k~V=-P}{RtQ{{?G)1y&W1T`$!xYAcB!7SyFyM=#4nCy`In-9HR zHFA!|glPcwXz5_LL#QTp7&$St1_XYc&;+MU%7l-)Wm8j6N+}W^ zFE^qsk0&Y>jBKAYk&{=}&a+F3gr@oBkakLhRi-`ld$L z39Z%JQkuSHTL6OW;;XnnC(EbQq)64#@+h;`T0CN*m%@6vpQz>Q@5R`-O1WJ1A+8() z3;-$>xB60$EN+i}Y+@Cu3PvA^)((|oUzIhGs!$zsgFCurj7ktPfn=w_pId%~mjSiF zc=`F=%|)XyXaK$y?-_(p9yC7*wRU7WViWVIhn8dx-kiEn-ZaOkc2X^=W3E5EisBMj zjX+Vp6KZni1>oSw(q9-hgoD(EJZ~{XXgNPw1!1C&Tu5K%o$u@*&JUw z|1xt&fDnhwuWv+k#-negFV8X&-Ye9#ayB9i~9X$pSrz z?EV*Wx=6~yd<99=!n705MXHH0T&J{JJD<$4^_b4Qi7$NdR)%;FJedMg*p; zANzOJ_a!qAVFGI{h(eSh5jyI+8i;R#wH%DuLpd=R;j8t$zAA=X6#7g|6feo>)QM{{ zAe#ied_st%6(10^$F4`L`1?%BZH0wR-L<}-SZMpLi+pjIyGbiLR76O*D*> zU{j12y$PW}UBSU=>ZR(1TY7_{E8ggjMmUX=Q%gl$RZR_E!YvOSti9`CA+@)g#0#^u@dhG+P z-V8m0MSpYLVk(tkLY1lWecVWIjSrxKkeNbdI6AYv`{cJt+w0K-DzU?lKS+%o;nKa7#Yw=*v;39FARZ>J+7uTq?Hr1_9y>hq6>h zV3Z)g6O{`k>Dkglq_^rfuWScCbqDjm%pxiN(96@+^Dh-R1?Kr_aOe*=KFNW^3cOm| zJi;r5&lvNbwKqK!-9$`fwYGLIz2f6Rtpw|mGtpqAJrXL!2Q4e*BzS!RiyeGNVXMrk zFs?u7uaDyl{(KoX8u)Swo<)usdIbMo%ORv%h2RL1CHmK(W$bBV#oME@jj+TDKe-{X z+oXNS4XQ z4JUaSH7K~DF!yKrlrEGy(myI^uncU*xirQZcQh1Z2XIb!>VD4}6Id*?AdH(PvVI+}6%3}K8(7Pn0;KLfCqFOUxjkaXXxs*y?&hPLn?PIKx?3$O? zx2(OhW;+GSWY2V}>73dtztnFCAY^{;dKkB__=Pbf!>nCE!f$V8axaJou>U_UfZOdh zke-d1z6jw_UHy6K#gQ37L=g#Um{WPm9S`dYk0?|E%RV5zTlGLDK5P7frhu@Nj1rka z6`-Y|OUb@dp51gju<86w8xFaZKm2bq=dz=5Ysd&FLOVslZHQ-!y|*l>S-7-?6d?6A z^GID$#qwK&JN7+h+1?@3K6mNhwUZjoJ&9|zc$BRFY#`B*6?ykTt3LAdsJS(x9s0Qd zrUiyP8A`h_C$QYiequ?0SYq~}pbWwfclGub3UyqZxTOR>9hjM-VQP>Mr)VN9iWpiU zGyIIeg62v3FX4YWhdZajVI4mE^oz?bM6&29pjfvKw(Ikk9|-u!eVnN+?5oJ{u$KJ7 z36LEK{f+*r%2l=rDeeVw=daIN^!UD}l=ST60bYVr;VEW1c3dM@&C;SoR9u5cca%-t zHFzwhdRC8QFaOTVSer})cZ@ycHHUbJj)rG3lRAR%2WVb8@+1}9K35+IPcrY?D*cmu zYjNa&1Ec=@jQ$zhQ6og8`nxzX5GM7#JXqS==k`~d1Z#Y)R4rw2uo&nyN9BcHafjT_K1gJinRz&{i{{Q_5mZ#p*`#7`*U<&w;;f zpQrHyb5K`WWKX+7P)J{6CM(9Zu>Cvk6MBZm#5rcmZhs7K(}`0cFi&$yytlaceHsX@ zfOf9LM}}V6n4ZRWauhgzF9w+_8d&LP6D@qolZ~0nOv#1IIM-CjdlcOKBd>BJB$Dw& znFWFot(dR;EIll((2(M{d|}Hb$;3P++7`q#Rtl{B(Jt^(8{L`>4O5BdtFl*gqy<=9 zz!*e{-!U)%%$(~v1EIK`o6I@J0z}9IxI9N+a|n+GD|WhS?Z^}onoL5A7&OmElgrc9 z#gHh%g3%-lk?qTysJyo&YMaGXe6$HiX1hb&`usq;zOeHR`^pBGO=s;49%ToX7QRyr zo*$cVI(ZZp+J$wClAEYpX~X>762}hlgL~~5eJTP=u;;yG^{wV*H@1bWtjGYK*3~4e z(#Mb%kkTFQAc#}b*)8pi)nv=k*KptdJ(rA|z)9x-R(fk2M&?x^c(Mv(0Yte=J(YE>lHgMA7_R zs7`etdEw_59%}}uTky7Cq6HTt|7H_Uta)A;jt*-{wC-AUB%1&`Iw4lojO32bjZn!{EYc13b4)hELhPu7% zGs2=HU2XJ+fX70pp1&oUP5TCFVtl?5`TYKT^nGXdy5A9huK&E%6Sy;Mk2Qy)G_zF| zeSmhs9lpm*VwUuvZ>~lbAlJu?RRas6RN())9M7T-NK<6X!%))ki}Py~;>ha;*DUwE zq$sf!NXVXtvRo#!Qn*ORL^PuppskU0PIzKs zQMRay2tM!;c>!xK<*}C^$j;lqP`n+-1~b+O*mrszAm@%$}3VRg*6Y< zJIYs*p75sx8?%M=%MzXT90{Yw7##R7GAk6V5~PG@GZ_tw*wm`PAyhQ9Ii3k~_D**( z7lkF~#@w~J(HOqX$;cSXW+cxgKYO7Kp%Iz7S2o2RL$!k|y5C{#RaDs2{&}bbnUDm2 z1)EW2_jly8+KoA{Twt4Ld;_}}snUdmQq0@07-s)S;!N10Nk~^0X8Oy`-b^@d#`vQE zFqUS;G}qNbvy;f7u%K>K<3^$L*J#^V`-+#%zLn_}B>)=IvwfMW7X4g+T)RD?&QJH#N)~I(V2RbzWGrCNjnGM5vTAru_&MHu8a<-{yA(LO?rV(f8riAj9kk!VT zWJ>+?v&3hC=SZ9zL;|Kr?C;W?$a{(NSt2bztM45(NyNgaN#rktTr{SXl z$*p~w8>n?LzVk=5Ea#FLPp$N!wOIF>L`;U*KV9-_YokwS)nh%8F6RJPaQuq^3_vch zHh>onBw9|~x!)Y*sx7RGmi}&kX{jf@T|F`_9jNx?ci4;*9=r8pqCuCB(M2?($%8Pb z_i9l>J|~T#U6K`WT>t%C~OiP1K<@h#e#I|js=AA_Mww#cQ5vbS z^%5`$#zUy(IBpkh%)&dqEm@r2&9$swz9VzyMD+&5K(`pA_KwCIZ5yLi z4f%ORQ@v)dq80fwd?vf-H;Y!ky)~is&_N;`%JCGUB>c!jkgJy&17u5Aoz* zcy^Op{aI&{O0V$5)PQt4Ngn?c#j*352*z1VDF_U-!|-3ft_Z(w=g{#GYm zzc}!TNuT!<^mY%%znDlJec5l>{6HIud51Q}wLi-*^YfxBN$qQuDpTYqt?ONR;D6~< zkcfE&{`4-VSmemoQv4H#9r;$G-9CdTVZ`YNfWYcwu@OK_O#O|=0#XnOb1Tpj2gMm2 z@!+(hj}|PG{<A@TvIsr(0= z*R_EMBYWqqL!(8M-*}N2*GAaB*(1#aJ^WM+bXu!h6ZRsC>*WwkKl5H&0{i=m92o!V zG9Wh!XfP`1T}A|Ny(H$n9YKl9M&&ffx=@I^@;dT-eikPJ16=ZYMfMd=;<4<-DD)Hx zoEi$}@9QovGr4FdJN^s7P_PflV3L-YrH zYs7uDWpOg)AP3M%jR zLy%7%3`w0^L&o%!R=_e0t1d8Zwq%H#D?Rhb)h zsV0ypn8M6&`^O6Xn}F3A;ym}I6oyzOg!a9;TK4$b56;TKg*l%?!<2cdD}B8I`Fme7 z1OI8fhSqidj(XqJ(T9;B_pghktVYoc4XWAPOWS@2#q*E6l)LlLacAQ{?0u&Ntq_`R zm6O+rQaj|Z@yv_QZQZL}){|EUYuhyn1SSM>qZdDPZ@Z5DF8}3b?=nlJZsK$LW95Bx z(nq*xrjz?#RYz>?`H2)|xxvw*dY{V4pAPevUAY16c`qLFqOmWkBA&kYW>P6fn|Q(1 zz;NP}Zl_)9FY&{Rs&+$R57nhh=yW?@MVcGqINzu3pNmyDl2x!aH*W(uFFyWemQP0? z#ixPwATb|@RB3f*5^~*iB)B!&sgJlV$>MXNHHnS02nsA;G_`n|4F$d;T~Bde0mgyp z2u7tC%vvKa|Ce@i;Hlfy!J>ofZlFBNE`HV0Wy`MnU!vjbZ%q-rTKlKILik9h?0iUA};lLD3^E+hb0h|FRb8h-KsCp6@;VzwPp z%SjBdpr+*6JK>hUA?o@B^Mj56EtRol2Ot9j-<)>(&#`rPo$%F9z+(}49fXQm>Z(p2#Ks^3j@v?Fmzvcq7dMoat|c?UlK<{V z;EwLnr(sIqVBe8H@D2Ss`y6DZ1C^ja&5525?86HM-@5Yq4N9t{3mBr%WoDVT8798o zyra6x{(KmG3Ut+0_&Xo#Fl+XG^zfP7zPR8wCc^ zTLn5oY}<)@7Z1^m>{M1b>?1aRWqKDk{AaHGekkk5(ilLku@=MBxA92d>cRxkuvk7&=Ha>ZdPIWkEN8m#1HGwb5S1`h(z(vs24)N)Kghp^7OtwgN~ckMOLcXJ!sbVfyZD*_$R!uF;(Psd;Aw1SjHbQXQoe7gX3;lqa@$m0&O zith@rw0exq>-WAlY$f;S;b~>)PaUGdKk9GhAqG}Xu?e$Df-ndhEgny0wiKOZA7Z#D zG^p^Et1Xa~-k->EXgI@C4$s^PscW93M+s*V15K(COg17upSG{o)_Pk|XIt`(S_AN# zU3Balp7YODM{_e<1PnyVQx9hqIFtP^BoyQW2$DFXvlU>?Zz6I03<>=K>nV*~;LDXL zFjGl?#{h1gK025QC$hoEBm+&!>(tlvh`7LIg$FP-A{U z_1frkJ`2m5-X$vmnd##8HF@lVRH%&hSt8z9xKXNO!=rA#^5X6B!m6xEa?DxR{NgZU zG)eN}%ZHOEF6F7S)Mt`%5C5p5lcE;8Hvh;)1=)fB&zrmv7+jBUFj<$a2!Pf8=+%7e z4Arw*m^Ip_`A3gJsDaKY4iohZ(3J2ec$|}yL}<07<(bWU#T$HWllX=>`hF1i^5`mQ zUQTM~G{%HLC0x>hU%yYp0dWaju2gM_Ghm*@KM6J$rUH|7ipAa5V9i$2NuXf4wk=wu zGVV*mF#FMkk-cYym*vF=9A-0H?fX6J^5oghKa_owDdq=-AfimRMtiGJ27iWW>DY)4 zhh9qncY51C8rwu436Ga4C~!47{jbz!BdhN71(o{Sex9XPGw*E6WxMj@K~&orToP*) zj4X0m!O5SF{3u{_pu7hvE#$L^x)X;{1JNSehlTgUsu%$;&DzrF)(5jWS+M+x#>0)g zIECSqD5A5SO=xJoh|fJ=juGAKlE?AnYI^-*sc7pvN1*Iyp!cKaS0EAOXMi8)>N zr|3xu$DTpNSh~RgneC(W615Vh0yWz4Ij6cS!*Dfm%WNfBREVqggrx>}4<;0Yw0PWG3@m?5L}8SKw0 z`aIAfj7b`8xAwP%Wd~%W8zPaQ;TWPF56=J4*n_`Fbe2$prQ&KFt#hjkuu6XcobIB! z&EE@O%wAjF^C-Z*V7Aiv;5w`8h9Z_XFyncF|sm74KcrnvN@|Hh+am6Cw%h0 zVvTOA?lrW!)0p0ze<`~mA`2bL2Kl|_XO%YgpU&e^1i3JXS_vcXuEz;J$o@d3XWEvz-=OXwH2N$+#bIp}pb6E7g@5a|G3W z)IYDPSBuTr?BucI*W8E6PflK!nBK}44iYQg@=R>n!6dZj#xELn!kLyHsnWCZ@Cr_Z z46*b`0y3#|&Ln~&TFB&=xTm`;J+~UXbQ}*=eopT=FVLszhb&C z+p?$GfBh+shdtKX1*RZmav!B-i*+g7S4xM^?Gvnon(zHy`R%p)le?;_I`?`5X$KvH z|F}%qB`)ieE&0D;s48TX?^*WO^CglC@)#ASOMT$(*8F9#$dVBt2XsjdoXh>|g3Xca{i;!)#F@$7wRMNTw6vXt2KIjB1WT{S2@mmX6uQj}qq8 zA8l4N2k$5+^;5&fevK%z`+kGB_hM4;AdK-X_22Gx;oDXzIhWd{*FhJgDSgP~y&{80 zG5YnH#DFq~cs)9PtMYjpb}pYEaKJM7zc9T4Mj z)2l_Y`2MLNqqp{r6GC^9%Otkzy_Bw*a9K$7AT|*m@cqAnTK9b*nWHrPL?-bt!u>F2>vLtMTg9>B}ugc1|TD z&gwtvPKOF38FdkUVi&~y&RHdVUgpC(x*tM#I^Di*Q!QC7*b)b*FTsqmk&`?|^{KTR z7Ywq@DR9g3A(%b*r%D%2o(AaCMA~DJ+L!vRJ}W3JBYe{meEjxj71~`m-|)ZVe*UxY z#mPkwA`Fh62iQQ^7FSmL9KL?l2g7_k6m(Y`@xlImJy@SI;@{qs9oP zJ#wC?Zj2-t9i7FDY^;dRjD5+e%v5%{nlv_812!fR6kEGErGQy#R4y^=VXZg^sT=0> zJ@fs|Xg+PxFp8Z0&_h@by74La{( z%>D2ROfmBoxl12wc^Lb-_0)#pJpaJn{pq~#I|hd%Txkf?PprrHkEd>b(7ok zF=G}_Tj*qmAQzSPkH87YR>vbmLVh23)1j~Q(80KLht~~A#?;7A4`@IOH(_u}1v%-C z3S?_;&XAmQY;_J6pq$54#t^_nR_BkZjLT5{MrJEuS-cjJCo1X$l3$-Z$UQf890J1I z0^Ak^$=flT#ZzT__Yvnecy2eQ0VQzqi_gq)+Fo_&&HH72jRU~dY2jri5t*} z@NNo9qx$^>var()qgTVvc##pd7ml17%-D0nF{l=OyXmb=R{8BJiIrAd=&W&`qUqqt z9Bs~M!Ua;H>|+I1qmuc;94;n1N3~J_mCZ`^)1+)vmN>BVt4`Klkxwy0i)}x4!DUNU z7xkcoO+A&S94CKWYCrLk2<{hv3kJWJ{RO%w+JPu81m|2=v3R;(v#h&*B+mv8koCR}uuO3_N<=zL-~biDA`W_hk}>Ougame&Ml zan8fqN&ojVZ`C`g4q6a2AnY;pi~i(X8Mx|vmiAKrZWXu3_V`r&Dy99nU;1cE7W+Fp zuXB#ZdJCrXh=rvue~4{ls@D8=$zy!MZk`io(rbY)9gEJ);<#Px_v361@cUj5jjHqO z_=6N}tzdP~DZE+B;ZA~>z)C?3tI^VG+vS;sC5@B#8cgpuM5v2P64Ct><0S;f`INX& zHt(bMt$yy9tnJ+?ot`_jh!nJJ)lMP`20LO+Ml?J@%^xJ7#0(^Y+{LJ7rRDOY+a~ET z(U@hncYpnuIUs)Yg25CQ3Ao}k-47K9ih2YZoKJ%7uWe#O5y3L z^vU-DsWAwP{n(>1h`(9ZTwqd1Ab8_Yk7O-(?A$6&&hGCD!B)1djC1&@!2bQ|&& zh>+m<$@9;Z()6ka^90WZ!3f5Pb!qcBJx>=+#d+VrZlvmuoo6Rbm&@dhT0gl^r%RIf z&=%PK=n&bha<%wW78}$8PxPE>o;&#k=XsER3hggg?}=;<^ZgO%yuWu|a{C$Izwr$(KIp^H(C#)J{)mv3_&S#qRllL9MiSu?`e6Z#9=OCif5t+(Z zw-K=4v9*X!&S7?3;CsFI5$^2~dLjKiv!cDlaa+Y+!J7h5f{-;C#z6!_Yh+50l3scW zcjYLvKbLjn&i|hm0AupN22%<7s@DtQc(cb}T-1+uw3||C_=IJHk8n40`{N{G2gCLpKBvJ7i`E8NlQe8VabA$w@c8ohKe23k z-R;iIerDRkHkv;DDV$-q%0hK5>YVgsh>c+nXspJ!%G!;Q%zhor4W%#yqQ_nsA&AOm z*C1tTF?QJ(ph`;6KH6ntax;W4i2%q)4fPGTp1faT<@KPWscwJmeez%Bs36K^kkjeR>RZ%BYD*Uw`zM_CBRNxAR9|}nM?Gmf z*-=5k7pO1jPHccWDE0vfklH&eqN|sIgTL^EdaY0X61kY;pg{)+1=w|ep+B4`zkf&5 z(1P@#8W_`rfwczlv9i{wQX;(kH$N(z=n&1kIUwp{BC0B@?q5`hc0Sw0oHjZ#Oc zhCR`KJ5p;e6tY8>OBZ>I>vFNS(LtM2f%H{08&-SMy(o7;$u;>e9bex$vkEo}%u^?t z0j;QZw(nD<`$~2&PZxn)@~UEO^c^-85jrRZMIY8YiB!uPf(!Fb7XHpj7lI0AEuM^- zVqp#%mFm1n??V%y^;>)inA_K9FkVyYN?>Q!3o|-A3 zN(CmgP;k@VQZ9O5>=6WFKysS^#p(}%hGS5UnFOLSp9x5Ftydr&*SbG8S7FgdlcH@t z=8nBLbr5$Wmt2iAn{~fZD((A&dE)WY3tPk+L8uI*j0_Zf(+Sn!ceH<=?PAx#uclc7NkO^g1*N~ z*mQe}OclaDw6EgUG7?01+Y5R)g(Ppp#$xeYr8*1zp%FKCL>r`r7US~EOMzvSZ>x?> z7ocf3bo+x%%Qwy+Wh(tO%Ep9E$q$T5*T}9Y``dMsZM}Ht-BONT*UnFRXEY54INgg41f!iqD3UQ z-LHY{!>;u9)uXTE_~Gi$G}4^VIEX03zaD|4l7a2cTno|?o+4^ zI?O4F8UGQHOynd?m>q5$?xRJx?^>z8>i?(eLe>ZBnfD-6CHSBsGA)*C;7VCuv@afj zF~48Oo6tL*$u5yKf1-2>lE|G|zIz8wU0VU5K zpRStS{DdI4s8qD+()sFEAKIDm-Lo6w@4UdTe81%9Gu1~iBLxaCdNljrqZ1uv<> zAyo;Y(>g>U?L0-rbKAo?q(DP~#CsczO~!CLxRnlF@sp$}E=h*SV#eEIm172NUlNSh zDe$fVN*~|;v^IE!Ter}p#=bO7(}*mbw*%`m5y|?A1Tha36`j%Ar~O4H<-5Peaj(L}gXa$|=N!78>=xDtB-<`Lk3 znRopocAY^9colvp-ooe-RUgHS+ zu#9h$$E9^$+C&3z!&>2IZ8z{=zjoq3WZhgY?I@N=9PTKM%+wO1+58MB;fTe#8yz5w z=*WHtYGOD}T{iMEah6>MxKd0mzod$I2Up8lfzgiNV;(OW5P#0NOg!kU^%n>S;2~5Y z@`Q!yPo6g02^rJQ^1gGm_P!&C*2l*o`77zAwmAEtFfV@;a+F`vkGj6Mef!UOT5v@{X%|gkG`meKZMEesOG10%?u4l%A+ck ztIir@FNsABXTqc-lJR@R#u+oKj^&tVB{^FtXjnM1kUK)FD|DcXZ67?GGi-!~S$17o zX@KdWi4~+XWWLv|RwUuRBECuB*LIGr$>WzR=g3U|}e#Qv6=x^Xjri;>8 zJEsk60G9IbtJ?kpFXK0V=N&W_f%)A<@VhcHwR$Mkd)^#w7kh}jdIv-}`oigK=%DTl zW9VmKIno=!gdi?A^~?$534_C;U9h^`WE<`(zaf6*C*OnL+}6-{1@)_oa}1xh_-S=c zrELPW&Jcir+EN1oKy@!smt|LkKHdP~mZ)TZGzsCttZ=xp*!DV!65e~0HYjU`j|fM= z>k;|&`n&t@*%|NWjv2pjnyJo3jY6|F6)kISY5wbFw1kbz|0evJ`miLa3G*z(p(+`v zWS~M=RYT7*#+9lzDrE(AZ*L@`nDT3v|cM2x{fX%GK;RTkk^kU{QtpnY_IdfRYV z%>S*V^PU&}3>3xcAI}>eI~G$Wcd*A*OdfdaAuVyLa}OTbTo8}{SCaSJl3Kbb%NR)@ zO~D8s^?WG)9zemf-VpnL_S4iN zXM_e<=Zf2*JilwOl_dl+y{R=}yBPbM7 z%z34j)nL`D!I3+7uwrbLwm=eB77Y}O;KrNNy?D*nF0TZ#g=)BP$mL`te{c`a{}QAM zu7adAB6T*L@7|ipu8mkQ@8Q5z2rL3?6DD7quO(?v8m4Qzyu_{%n)UZ-UrbT#=AaO|e*T z%oy~Fnyc6YEOJcK?%%hDurjE`Hc=ng7xF`XCv*8N-$YAHpy)zo(GqU%KNGxsx0zGM z-&v;j0v;b}~f7ywf#ZQwTB40W1U< z&&MVAtEnNnGO=KCelrI9pW1F6s96`5?T`bz`1WnBGGLX~(t z&83~<2p)Q|dm)*NozH6?X~|A@7Los<5bYPXppB{_apzLsR?rMbL6|Y{Q0hI_*G51tWiWHMRgN0 zixswWY9jG9#gA{yXRtZ$_IypO*Xic};S-~8XUS>?wqywfJ%}mZ!>OK;^KsZnRvDUS zJ$Oq*2^<`84@Xz&arM@ZWtSu=*NW~`^#;bv%_Kt}Bu?$D zpPK8p_-fcn(?vScQ9GN5K=;+p#Q3%^Lr4_QEJnNzLJ%RTJuBWc1J@|0<% zx22!jDqjJ3#i{{eL*bLfTpuS-5EMT}XyPLz9K`c=%DBi2G8oNov+VU0e-zYo%)Mp- z{o}jghfDR%gyxc7_DUb_u@0K_@x7{GGbuJu$_4nh6Skt&#-IeZV;xav$Gs>E909(8 zA`30BbY|6mj!9H=JN)u>tA$G3xze~zl=A_<;UqD&sM6X(hihn;XR25|)c$Fcm#4L( zmuKq5`gC~@nh55|d>NZ0;N#N|i(c=)F)q^<;iPa;aA^!bZ?ozpc{Ohz-2Y|YH4VAj zMQf;gFp8NfaGx+nF$yuHFu>*cE=xqURAOzK5N3l{{y=J0D+R!Et{9iIQDyCGgpu;l zK|KG*6ZQFawWr?wilGPeGVlOLJ7vKU(BV;%PtOycS8*dv*SZ(AYAE*C-`5_qf$3>U z$pFDG=^lDQ2#o@@Ll7d5uQ|hpN{OQ)C~Jdk`0axyZkJcy=#r!yB1_U!aC8r@x37r1 zYPq;0kXVf&fTXi`^?77|7}>KpI9A}m3XcNX@Nfb!Ets^vqp}h-H80a1hLr=rczH<#i2t!Zefrlj(3>Zq%Gfa4n8R!S)||Q97L^c zQ}VyS0Ka;TYVmTN?dpZG=G%up)9sy$Qe7ZAyHe_V7K5J>rmA`)yhP$ZAM+n44}PNC zfLr{y1=rBir*!VgC6WwuyTP;mJ~VDNV&^s$VS>vI!+NfFbv#{X#Q+24eIKZ^c|DUw zI?4|u4hAHZY}US#;xT``Y%cfxnCiAfAVo!-=cWYwz6=Wdlc1 zIm?uLWUXr+!gGpo8C7v6oNsqZy0Npe_fa&CPp`TD?xw39J4+423tAhP=_Qn+tjwNR zSWdycSnJaB9eMeb3Ki8{#Xy^lE(CdBRsGh-QC&pj9e zN)zLQ*pP9Bu~j1_#y5{NK82(fPDt?v&J_O|p)Ad8#O_mPT^wr1=@IORdBxuc=(gpTh|DGAJgE@XP0uTDuiFtyx5r)1;_ob5>8=1Qr%oWN5{YIK zj5om^V|nA!&zVOc{p+pCaCI!>&bi<*+8a|%gcGUAjsSa$xPDdb*pfeLO@(kL|7olU z;g1k-Kb~ir>-1lKU#LEt>vR6YH+8>-Vy&7=Qkk6?d2Vn=eIt}fT=6UFSPB#i~67m2hacQ3OWJk z5Hh9eM^m)n=vouPSKvr(#O0ZS~ebkC~5m9 z)RVcP{1t*Fn=~$#YE{ArU6yn;vTEi0^DBm%jiM@wC12zZnV(&NKtV?ZlU>ji)YIP1 zlc@_Bb_Rxa7e=j^s_BL}&&EgQwY}L^ND4{VrGidh1M?}*C9Fadn|)b=I4ViSWiI); z8Yr*N?fdDaY$fbk5kB-H0wjE3>Rn|`l;RnE!5KI#G(zTs!HkVLxW_%9Ko2YxsVL`& zDzLleRb!{l1%v9Jx0(99tqz<5UZ~JVDCHn+qXP~>-pmf)WCbG@5?{~uor8|j&SWN# zS$kaoe@MlzPCLW@d|?6O(Bfa`+Ro{z--oRjf3}XPhP^ZT01L*sD~3tAT3)`uk(Lu^ zPnf=KVJwxV{K5lQ8@-*BLvj!P3(mdHGMX&pgZ7~xi2$pYH`y+xe?~hPQ4`sGWMUsk#4$_y zMm$mdD#IW5%v(>gPOvp#FilB(g?eN9A68Vw(@$8RiB48a1b@t$RvK;UqT8<{I$mc+Jz$Ab}6b`b|09ehjxcteJMla)F0+VGVLPq=yN@@TO$!ExvyKh zG>$1K;|6XK1J)3W;HPPF^~yj@kK6|z9-L!omekdkAJDSBZ@%|aH~+1VSJ&r(z^Uov zkczXR)T5tEcZc5O<}7R=43}L!@d*_5k<4=70V7LTL#JokU*0cY^|enI3gh^>uC>pw zer~(!tD4D)CjC<^zV*Ae!)y#3{0m2HjG(P;f@@=8WkisQB#X^eX{as-dqXidL%#1r ztzE42O466{^;sQynnp=^NOw5xor?dA<~lEDW!{^ac()S58i`;LZY$3XPvsNbe^`wc zO=DLege7h@Z7kP2uku!94GjG~tGt{9)T!8QTi2(>S{w_!Lde0SyZLl%jj(~0>&PhJMBpVQ{skaY1^r~6Qsc*qWx$uv0DoVxtR6_rv1vBP2Bf%^}7P$w*92TkY-C zKoTSxgu;jvN^4i7C>FzD2FB%i`oM31*Zs`j=Sf#!Abs~cC`k{CytykKy2yET`}HaB zK!>yxC+-ijuHWo<1LF6L`Pd~!9%AYCTo{s?WPE)IG z>##Ap?TIA>dwRt$1{P;?2GUbVgA|0eW7vi3KN!Br1Mv3(FADO;WLEhg!kiRyR5*=g z4Pfs$c?SJvDno~wx2sxDZGl3iL;rNaWZga{jE4NO~g*4?w`?PSOEaY2j&SJw5`XNG=Dg+?+Ys+?37d0%dmku|Emmgt}Z zJ7B#OBxL-}^rKM-RS?nig-wD5AvgAWSLmczHrpWgFPfNgX4R`v)@X14E;(_ue%TCC zfnsfgCJ zT8alj=wiyw5zIqlhD}(L!!*5yKry$vF&$J4az%OAjrCv8d`yRBKz&k7F&_te_*^+n z%0Kmhs8)aPM+RTD0{A8(CYfg2$D$Y|x*(1KZmc(vNjW>YAp%Z~EVI@1{xY#e_OUHT z-m%EKJ#Dx$PB9;DAR^fjY?p8B*!etZd%e7HxGn*7zkOJSnv5G%_YlKB>swd|nuSd=v`85!%e0#k-`A4o&!_JHW;+SLP6!z% z&^+vp8?BNUjG|Pj3Ly2cxyZ*X9lV(f$6sHYbhOsCi`Qg*r5s&iwZ?z;K2@ z)8>UUDLgN*^`<#Pg3)C|*Fwy=-&=WkB{hE*<w)zw{N(gm3?` zjY80M2U2ZI(AKMV{q^@+|B39x+x;vY6dFpA>OAyUt|-we;No)jN<6Nqpa<;5%HhvK zJXjg}ydLefZ_7RNKWv)&!!Y;`-bfE6V$)O^`w1)YvSR#iXxmw&mRVwb(9F-G)SD_( z0Io%09t^95GCRw=88zy5L1iaI=P;mXC%8Yox@Y~w379?qJ6g}z$i2G2MnW;zzfiV`_C6M7-0-!S zk?nnbw9{u)0`A7)BphP5r#O-{%YWDF=+E`1^F|PG`7cedx1zv*q*};8q1fIy45m>? zkE(R?e-lcM!}dGsc3mt8z5BrN6!go{svn^`pYEv%)_DZVApW|Cv_2g(uy~E@TNRax z8RCHcSYR=0;xH2ngb~Dh z9TB=L!Sk5+9A^X85)iIMslq?0eRh=frSpGY0Ce#cYoL0J>jcai+NFJ42I?}3gt(6J zja!A}WpxGjKFLvI%`Rht@F!B1kbL(wK~bjK0Q6?v56}qp)2la%?82H^YQc8$bsR2H zveVcYdS-)IKVZA&*mEnV09dIw%Vi0>vS02zJr2Nq!rD4PuWsylqYX+LvBqc#E7Itq zAf|ndc9(IImSC4d?}QgWN+%8zq**C}n!kn3Kh%9rnJ|Lmg=h~)hwwi1A@!uOS4MXh z^N07(7g3PS4{kFa9EvHwj;Y^-J(Z4S!qN_QTKFzOZ;FD6j?QG=R0Gb+l4rw5l2#M) zej3_ZSE(4w6U>iq_yn8FFu_W&wvQOxS&9{gn$gd5PE;$aC!P@;RD z*7#-|%URK1HBX7#RsX;hl`X}Ttr4teN1CV0v&yNUJ#@$=h~(aqIv|RSPgDORf%vEu zhQ8t`$8NG}7$|}m?E`=)4x{spSqZzGMjKQA*pK7*XD>85P~0kmFa+BouhOrKR%)P! z(@qp{5%dW^io|n-!6@<(BxoIuv3Z!Ya99%ewE3W`zFEFD&1>X{H6yMmk2^AnV31Q` zn}Uv7%C)L%4t5_2WkF3WY!G8@6H+B!3w;z?h-R%57zUWUkiH{6^gEkU8avGr zjTAqQ=9FsXdTV#pHKb(iU$p;6gF3?H@1AbId}Z&wywkgYxQc6P!Kco`PykvTvv4H+ zd&1}fe*$L7qTKDO%hiF4uC>EEte8@w?Dzt)oN`XIQF-f6(jWQw&6JjEXaFb8{(RmX z%(SVVYs9}@F6waF(jpK7qmp6#@^!%`&{RADnQBQ&^R2u-LoVt}a04%~RH2MQ&JjkC z+9N9LzD75A;Rs)HCWCCG%EH0@wW+H8y7T?=`1)32BbA1v8&Y5^I=`Gw z%z$`QKQsjuio-Znu0QxM7z#E>xl{_6b6vcIsGDn=_K&%iz&i->pqy6E*_F zj%7pfhw#&ITJlhY0TQs~vT~>iEOu^liK-+%qY|lA2Nm_}yr5vs^}lsS;MCm>D=bPs zX3%D&sVoZ3DqZO&Qfoo*$Vy#>sezITyP+mKGl*K?B2ngYtLS$jun>~5+CuI_+{-a| z4XLX3Nb+CX;^&?%W-2i@DGJv2emEKA@NAR15DHF5R*SnWZJegYYOGV+ZQ}&?>n?@P zCm{&v%`e1Qv7_>(=j^jUp{R2djXIf386ZxnF3;J$BxMu7|{zm>zY7 z5E3_ZIm?p}Th?q-st6StEu*&Z8QkUNc!g7Uw_w#S*Puiam#hMa=`&2wFVamc89vzF zGch&9sSLsV?5D^DRS0U%G&I%WZ0ALKCIa9rHE~BARnG+X-6#hbS;iGmt>pOCHEe4m z!)FfZokuHxWznyV2@}nlxWz4;$R7hIL)VK<2MYx?;weVe3^_|Iox}RL9^cf+cIbuP+UeET$!x3+^x`k*23utwUI~FOJ*F4S zi64uZ+5=g$N=rnu$G~pK&witpKl6)3OY^cIfl#q{$FM3JYwv@*A3GUj18az=bj^wg zl&(M68x^N1{S(9gA`xtlOt5D2ap<$Fqth-=z`f3bun1s!-5l6CXk`nBZy!XMnc5i! z=)0h{WmGFQ2v{p;!btRy+_hbtf#L_ijCg!6xP(EZ;eaCmA>op!G!*;L8%G%vG@@or zXYM(ybyHDFGzm60|LL@48Sl`7(7&qWz%3vd=B+}!^bf)Xcd5+fNXfC~yucME<&%AD z9Ri0Y5tpE`P!>;6;99aQZdr5f*w`SZE+?-s$ti|+!rt8)UHwbg{oDb1X^dNbY3sNs zY|Q~18+u?Ot`%j%H^g)4EXlEB&E^!npm7;u8%gychzHj!Qlx&BSg;P6bnvxmAKO_( zTI5#_zRfCXP-V!Mo_>j;$a$jQ33vjd669h7LW$}_4@Z%UkWHiZvPmjK0gv!U04Z0D#-(g?-pv2L)6(mXqbb7Dy`zh%VL#!BQL4s&QsO=LMe?T#M^~JX@pRm9Uzo$ z|KM=HfP+;vId3z1O4{T_KlK8F*m)+!`J7I{fLiO882|tkTy{|zbb_#zNk^si*&oLEu*h{R zVD`3WK?XrLWjin6%#hEWfXFqzV*ljTV|#Q#BgoL;FFbM8mrM>I5G3)j`4n&;li)Um0^uML1e|22~x9?ERPyiI*EJHohNyK3a zSM)bmW0nASo7>`4od8c-Zwq->Tj;vBfZ+r;%Km53WglNByV~=dQw(~H$%3?-9t$;< zA(vv?A;W%vyF#=*5!;10ZIg{EU0VE@Y0ehOuH+~DHvAOYY1(=dg>qZmAIXrTCz}UY z;VEO@whdY>-o1D^#Z~xUc2YR)y*1RISqKQi4c4o~6giR8xzUd97=`QY1f2`_u*5!3 zJ`Iyio|P@KAJN%A!25|nFIIR#ut#w{j7hRcuwT90P+y5qfFvkv2dJEN=?$pme~wSgne(%a_UgIY&R^w*c#8Ct@iXFg z9}C61*yPt!%|NsLwj;6q<_@K-CYAzM^qT;8#sr&=D0l;GQ|)K5o4BwvBIr$+=opRH z;Lcg}_vpoZ7ujB1#)-yk9Sda@P@5Dr*>xHTr+wmPBeS>BRcqa zyqsWE7IZLv3N$i!qOA+*r9=*;-kjZTB!=W9kffO6r`tp6Af3m?@es(h*r@86LW9Wu zw-a2<@i617KcY7 zXEDY7ma#PAV98u7d-0p6X!VC7DC}oJ&9V3|>-8vac;M~)-fkf=FjQ9Z7Qq^+L@*P} zgu_AO802So`dTFdbE*bSJZ_w?>c7eWT~~l7qFQs*K!%1|B!p`P#yJ&x=ccE9+54cK zN-3uC5w(X2Kg9kY7XUIaO(KP+>iysGRSsdT>gaeuss8*DKS!I0BkDV2;3sv~B#ETT zVV|qv{!pKl?C6FuuQ(SgYjA?nJTACc>peY9qmdS`g;VA7D1W1%j};$Ll(ua4sr4tz zz2ZhJ5xVMUk#Ik3+{VOo7KT~kP`v;#;?=_t@wv9l(D8aiD|9PrIC`4nYBFoRr;zuX zY_H_52Dk4cdd4+#Kf&X1LOb*rf$1KGmH428$7(3x{^PDRlr;%JfS8wEYh;P-)-opJ z(0P_g& zyfdA-H_|XcmAv0j7dv;cFsu>bTF66ZhP|_M505+tft}IDAalzjeJkS7kFG`+VxZtr zhP>Bic;)RCc;8{64j2nG$M>#)t&O72WSsIF&?>&0+^D>CkiHKBGrMGvL=>t1LNZ7J zSEgeZ^r5>9Y;>SvVk1wAM((e60*-LebJ3hy-W_p`hC-a>O_4q_X9W`0TyDE7@*hY&a;78}tMz%9U{)>l|3=y>Bv+ zq=v8n&grzY1Zejo(+=ln)&;af^V9=<)M1g& z&;7i9I>%7EGr-fm2RF`UD@?Y*e?wGS+O@Ql>-h3i+&NC;p>LQep7Hm+? zD--JAQvG*d{nYBFV;NmdyN~X-WhB2^#k7WFvccPxN~41dx{AS|VJ0;)+8`2s&-g>< zhkHEqN+I6DL`;3#(olqXX0&K|pFrTy-`neK=v$Mbaao6WZWSn9BSiR^@%IhO%Qnh% z{JxR^vG(87TG}{h3o-Z1nrh-Lg;=;?%!4sFr!9_jzt!s%$D=@>j0588@r_DS(n6lz zyuDnTy8nGAy!!seTwm`9%QS_Ql$1xQKTJh_WEg?0a&!#Et|9S8!+_`>qqy;1HCz36 zJ_!SvCJoEbEb&83@0RU#zKjBctWI$;!yS8K5@iWW7Q-kQ68{Q#f;sh`fPYhH1Hav= zQvfHg&ljxckE5Ku(jg~W8|!*|U6Z!raunRBNQq7&t1>Xv1-56AA(R;s7?${cTo{RF z$umFoihbD_-?&kKJKYCGfrk}GR%4{Sa+%Yd)C`QR0#q_hw;e~Th)^IvG5@bVh*xWzw zc=qf$L^^@r{(uaq@61K7aOc;i@^@x6SW6Nf29rPi1tO8%7_?tHwbs=w8$OI{zzx_B;d9&#iw|D2^<%jj1*a@m%OrkEO)zIxWGB=Lu*KZT}> z*LmCWQ~lL>lnJf#=TB{jc~03}ade0SY>oNRkRvGYusWK$#S z4(4-t-Go9=?(pr4aiS#2RBR7_vV&GzY#cun|1KnXti6*ZZ_4OI3v6>uT&Ek?)*H|t zbGW;VtkkG{R2I^FR@f4|#N@voN(S+TIgc2ZqZLtDkwB>h>;HV-XaOT~8tNJ-8a8_F zNF&N8pQRX?lEED%!wN;#8PaOkE-K}U3^y<8wtnx-6#V_qP&(WonCpb{=(};NZ$?gu z1^g5;?Tz={Hg-P2?}E|#xqO9$Tozl5Tvp+nj)3V=x|PCS8EW_s#Z%YXhm(4SC%0Td;Fs3!cU)#z;`=P9Dt$@Dm8)`kUc+ zUrU(rCvAQG)NDkc*%h6i&)lIxHf6a^OaF|Q#V=1NN&H`yj?8+CI4htw`fu_B)_(o( z5AygqZJ-CF$sPIZ>#XDA)YREDJ0($_1F`LzDr2o&R{h$AP)jPX9$a>gW#?PfV`pCy zOictgtwB^zrJNjzwn(@4d_&Fo`gC0HZ0PgxWj+V}((LB}v+=Ffk1aX_!p7eV{oYLB zH%38ktAAO1@}p{$G3Qe#*Xe+sld1!(l0>sCtx00hwhP!toZdK2g$mL;Lym$ct}4Qf ztYEs8&cl{LjQxqIhWk%VO?&%b1ATWt&y@MBgAOE2Q`6lPyI!k*9dW-O^R2xo9uSif zp4;UB&;Dc-K`qa_JE`w$RfD|cK?d@cK%Zl}(6hOJy@=0Cm(wc8+b=mlNld8wohMK)I}k+oUanbfBq>Em1M9ZC2iw^Lm?D+D;}slf<`)iJVF zLX%ZFM#l!hf0WT^w1_>q!e;BRk4`zws}VF9t(2c~loit|a4J}hi`NV4zjsbom}xH! zMy<9E|Nl!P6%P*1g7Rw`+XMu%9~3;&hH5 zyXh>^-~nsR*P6xZj?e%ouR5eI#!s~=oDjsXL7%)5$*Ml>BG+bB9=ib#ahBIs&si#T zbKD`7mM_{#S;F3>1Vzk2IP5V*5D)RG)ETB-esbYiE~;qMF2ta!p^>hUbkL%|b(Ir} zj#tV3`vHp7B!UuwkBN@$vVc;vE<*h1(`=g}6`9R)tq3!ROcKPHP#og#sPUlhtNa%Z zq0cj4H4>Cn4Sa3Q%_z&^=Pv?p?PO9dZb4OrF%0ZI`P|w)<#r~++e6U6yYIifq*Rzk z&~e|=5gpt@W+l-XcApk=wZ*IKjDmk~OFUUc0>@8SMqWo(ch7U{jiA_Kuq4MP-1i%{ zyrk^sM1AepAwaa6Yb(C^IP(F)BlB7K~}Xw`gDj9 zd5#_fSGOH%zN9^ys2sbRI*5$zuqS+A_{C$l=9{NSe4u(78Zr z1-AYBw&{FdS%j%ckMk1qD*VIuZbHqbfd5V!x9vV3zj{k@K4HIZzMi|UySm-5W`5j6 zi9HX7*`cQEzQMXHOZCHik9jGSKC)Dz-NG!HIEIilN}0l31#_$h$JS3`7xY%>LbdtX zx*Yj9e%oPqfquhd?EtOZCkQyqL@qF|Xbq;)BIiswO0Vl)Pq){5>O+gadpAKRSD%O_ zdvJL2L#lYf5V<9DqhhM;$rd$X(X#Z^?t$+*&6*#BS{tK!ez#7?iB&rLu18OqYwC56 z^z(mxzqX=OcQsG$PVou2q%Ev;TBDiHQ87I+*hV>GuShUstEc}d(-N3g$4)!CA3a+6 z&>!dzVwKE|oX&TQWrr*A3Ra-`@~qnWE6_dioA|;p{ff%-9@E~a*lk+ zgXeXyh+O&*)0(gIQg^B&5)VmnV)eaq)5xj3@Vs$NX?Mi8&ai_BhZQV?5Z%cGViPtR zwyb@}2MGJV+?n}Lxl4B4u zwJ;)1VUpz%@jOk4;lU z4QEgHMIZ_V8ig3v%+5; zw{Vs!$5T5gf?CoUXyYS2DenOU&PH|$c}n`LPkDHm*99n|p~(=wY5*3B)Fd>nP~IL5 z5H)5`20bRKUmw5^>X}WrCnA*0YQNIZ`rFYEVJaCSd`)ilATdwr@(zDo(z%Z(Y%I!| zPQsT|=wI0ZYe?kl)7%N@bp(BDf46K92qDMRqZ@EpJAFEbJYpraoBJiO#rP-P~ykoWW1ZyDS~%RmQicH;FBWmO22l+PQbqj--(`p)1O@2DN5HuZUjRJv?eK z_k9|4%cv(!YU2s+F22{jP|x3Fcn8-pY#r0eABu;$MG2KCP-P5hy99Vut`hVDD}pmb z=G5nc1Xtjb!GX6fxCCE|;Uf@ZziQgSa*vfZwwpOE91D@^Rg{%Ty&_N!GSBgq==P=0 zD5ly=PMTyRU@-8T(&1AJ4O`gdkEeW}+RV6`-)yv2P$p@Ax9sZ;%TSgTRt)KgS;Jb# zoQo#~tJI&NQ?81MJuW50qTsf|gVK+I#@F~&468dGSKLc~W;%;_<@6|D<}965#ZL4r zpV#qsqE2glnc9o3K=%|#>&^bu>~5_EdBw)MQvLEKJ1cmXqCxH9@;O7^{_H2@)nhSE@H1g%p@6I8ZkJ`8d_>dNxHBd70KwZ!sTl*+NieSUfO~>Np~8x zYzV`pZg+8e9@K!K__=R&+15yG(tZ)Z2h3GJMnS543wG3(PS&F_dr-Emx8}LrfX4^E ztHCXxvQ>Xus$o#%DD8yGqTdOL!dl8)BmEJ*`bf{#7!U4Y#!;t?)>^O!&(aQQAJo2~ zaU*Wh`U5KP<6zoqmAr|0&lZr*rLh#BclHghyGd*|)L3%TjGz^26 z30P55vi~duFeCgxzu&ayDTlBN`EJY7KY_DN;a#2GExn2Nq0jc$83<+pQTk>-pSyc? zc>ciyR8P0AiAS0kBQYPO>Hij}x6NRDf_GY#&g0shSm|gcoBkOx+8aS;A9N2dyB)GL zu% zi9vmEc_|uVkNLrD!cA^C&j3+{dQ^A6j-6D&c(N%0y;9UEUb0G|kYp?TDsT55$wa6j zGj+Co;Ux-dx(KL$xWzdr@z!FQeUBX8OaDyc}6k48(wo1a&Mh034MV5LlCfR=YL zA5dGY&hoPsOssCs9NPsk{DV-0UVw$@jt)`}+zilbvr?65M+wylBb^QDdC66-H1+=n z2toJ0YHwsRIz$$q=NcVn#<_TW)y#n=39bBNnL7y`~7yJaj=v_ch=gOHm8+ z!a4p;NQxx?2rf#o(+#cnwE1T1tbm&)z}@i#U_#T5dAG;maKP2+0Fi>b;~o0afZ`ci zdq*ubWGORw6D)OagxUghT+8q;-Sr?h$I5GT3etwo&=mn(dq<~yO+bSLS;!9xkLaRv zuOa?Xg_(M{z#tJ1{vqp!0EnBL0u*KWNlz&CNs#o>7C@XOl2Y-w=&9Pm`g)&g?hhvY z^Gn!}GeE2sr&f&MP$hvek_MVS=BC#GU7=fg_wloabTmj8&(7<*M9jOHXmv{fSS(S> z_9WvIaT4Bgnn)7rl>lsNrwV8XP=EVlCB`p-!w}Y&W$2cSUwcz!vS##GskX+82#S-S z?5|P^ijxe}G-0Y0wNzBsE7ykup1$)A9zDE4EyFvE<90fkUYO?@rBr>RuUk$6IOh4iUU?%*@E8zZ2PM{v$~f%?`vyFj zu(o%o7u>G$4GrmHN1nT{bs*NQh&yq#0u(`&2~sPT=3$gbkhksK=-mE@2fuVH~L+-t1;OuZf^b&IMbd zH9MdLq2)R#6GdM)e(IGKw?9>e?4gd?5~{2xe+G_8`h&VAS>)q=S!d;Eq_%9|v#R^% z?;Y-y9&OejjazH13}WN0^sw_YCgkQ$)+f2$y(^a9K~I6!JC4TfPcRSE{eFj!Kl~66A3VT3SM;`Eig_lEHxx*l(`Pz*^SP@+ zS_|33q#r4$z&tKlX8r#1m<(?$HFK=BDC? zEqgtHg6s`Y-2>4{Dp4HWnIXg^lQ+S3S%a)|0he55Alfl^d$*Prptu)7mlIGFsym<^ z28jhh)e6B5bG^beov@$xxYHw!iyd8C)Qp+}16Dg24jC^uN9A7 z1q?6*8Yv?SEqjAUtZB&j*TYh9OxJlvPu2#30V3Bi{CgfSUQ1A<2H1-q<6Z%H9`nw( zZ+<6mq5%`{aIl*JM34e$+nu|bMF3GFzL~(nu&|K;>T`r%nj8!J7d}<#JyAg$A0)sB zf-)L?Jlbx@Cuw+u#|_*N?euKTAc#zWwXM^@#(EqhMxCY2_Bu!yEjBH(IXH|xd!np} zh6t{(1!4)zhgXsSoo;qc8j29+jpL%xRw=9XyEXneUPZ*>kc!3sF~ZdQLKUc!eJ<92 zwM>}n1l5k+yu;&%@8I!+cTvl{irFV9nCcFTJi$p96r3Q^QS^w?7l>Gf@zMn%)i-Dg z)DzfLeTmWqsx!JAT(K46_|TFGpxms8%#wM;%oK+5`(`l>HT^-8JUvC0gq^ zE+?oH`nCkQIVF)W%`no~OrkuIB)lnR2u!k0(MWJO79x2bthcFMXvm zGzo7EKu7(x9xyu+hXIJ89rwX zLq3p0SjeKLezKfG-Yzx0YI1fUIFh7L*TpM4Bjjv) ze06Q*GwCfVlZkCQawNM*6y3wj4B&jFmUv>tX3Nk0h!45)Gg=-xfi z8??_*6x$f<1yux{NAi~i%fdvrM&|2&kL7TMu8Nm;cVVY@z``4e(Y~F^g0ePn3zBT@ zUyD_!XNG-k{jojOaJIpPK?dcrJy8|U6&-e_YRGohX0?uFv*D3tyefJb2@~lE(%Ddd zK5br2zcZm5pU3)sh(Xb25Hqe-hFf{j=x+aFMBN9hZ21g^^+Zt5Mr>dj6! zy~X98B)usv$Jl`y?=2;x=MymfL= zb_c8Z_zrh$X|xdB>V+Ld!SL#ddojFAhNmAJ*!_4Lz?fe&TVpO^#3dWA8i38tgO|9| z9zTr0s%9+HFdXEA#&~9BmJ7W|hEd@CE)rf?3PB1ni-5N75!9_|J|ELNl3^;+Q@s$1 zUpNxMUPZdEeW2~JeFr%Fw(SV_Om{GxC z1rvbg zo&n)IS{C%up?yZ{v)$)!Y<37As5_ucunmU_DHXK}T5mupzMRDMl!Q(SFZ{e-kpU5V z^G1*_vK%+P_8PPR4l^KO&We|T-9Uq2o4K0Y*f(#=n0AiiaUtBgcg%A-BeMm zVIzrb=2baBWbem`c>>9a62}|b#IaCCsg6U6d6(J-vu8Qy`tC4Y1Mx^y<~#zDWF$$w z{Ubr>*JBl6U z9Wn^i@LXkGH@c;(dOm`Yh$r{Ymh8$KT-#&rXS41##OkPSA{IqJBq6E)%!X&2YvL?j zzuRRrH%x7#l4QHfND*iq`d9NjU|m!HsUpbRz#qy@GOxdIMh)AbFf5iQzKo4I+Un6k zsUsB7!upg@BjW30BqWs8xO@{E&rY)q{mu=9&@uk66!DxDir!DKlZOiE0vumLjs;~o zV5)mxd$7~60%+4{KgVPnQed?f(wrEf3o2Syv~~h?!6ZOMM`mX$!Or;m1CcbE2Y9G;v-0;@*y#>9jEbK2B!3oB{;IWi7QBZ4?$@6<0;hE zBl~1Fo|1u>+E*lCIa>_IpEcs{{3tsOCX%GXcuoB-5=RfyFa{wR*^u+_r~YI;nS_8x zEA#WWKes!hiV>TaiJ0=3TfEkaB0!zg>sL@Fi~UpU1l5L{n``{(_dmhYr|)6jAJ8;= ziTTC{y{C%Wy2LPO#IN7Rf0ZJZY(Yjli>%w!)iP!-+R<==Dg&+#5OH7rfJFo%I~45U zvF*{j=@auxa6{kYA)4&yP-zA@zs;+-N<6T?r67cVCt#3J17;nNwpv%Jz|Dgz{NM+F zfnWaO=lJh`^95QzVX76q6gxVt3TZt&Nd3hZ$R&I3R<{h#K%1Z3M9VU6dz=x_v-O;d z$-fc5Oypcv2hj$~q2Wn-v8Zlz18mHk%7x2M>Yi=Px2S6Z6HzBY5Ss*bLl@^d=elWx zBVa>B6s-*pDFb@y*=kvH*F#F;1Q8M;_i14)Sm|iTytv@bu|>c;}sWQOh1>a@pf5LYy7o&s^>`$eUI;W5h#CBzsdBhu1dV%)SA% z7nldKhTJlFDSjF#=^~O{S>^)c9onH-(8WTDL7bQ?idtL_(gslr`mU;Y`t%8Y_*Xx` zFaG6!;vfIvOH5OBtm0m1T~V|n62GRkMY#nLk01PXSj9Zw`R<`*`+5yytxvMdxI`3& zoV;+ay1j2Qf2{+8B=mp82qX=oI!w&T{!SyFYa_Y-sXkrZF(bw~$v4^RVLAJKi`R15 z_Dhzl)+fn6E&~&kt>F*Df339$(V|$#wr;XObe$kCYzG+*1JM`WUy=yTRl*|??-!Gk zWhfummbKYNmZ+9aFsZ)_z__W!=Xh7@8`>5_Pi=7yD=Pifak95R&xz=vi>GO_dalNJ zII84-JaWIEXP^iUhXWoydW4(nE7W-o4noV&X+DKl`t8y>%X4VV59J{8pHOC(pP6B{OR^ou38!set zTrDy=j5t9G5YUL3GX!njcc|#OCIoyGLK-o*R2v>WdVrgoE4+O93_ts6HN&G#17NB` zTSsqD?o46hEWTM2)4OWasCMyd)G>klgI*bs$+2!&+j z_(@L^1nAGZzM%lw##BbV>1}M6TuwGIKxj5ls2tV%8X{@Vac($Phd^{4_cW8F1nEZD zmX+a>|B+W8qyf@8@fDSUbb^-LMK0bSXNHE@%HO)2K>KO;POKp8e0UkXuA@z!R+gM!)IH^;RWcna(sgGR-6#@wfV*6E@ zZ?k?_B`R5Y0P;OU#^=u~ov4ElWq1|-1AN0JJv)+4Dz|6{@sQs|okG&~l76mrc-0f= z=3}dr{oFX?rW56`z1!y|`%l-N|EB+H$mNiO-n|SzppYa>2Y|DBu8G-FOX!Sz5@rkf zvp(n6H~UL2>9?d)sf#4$%Q|#R9_x~H4s9p)o9UGq3cp~oL46RD4Yct`#{>y&tJoW8U7ZIjAvf98#@j1OK#5N8ax#zO9yu2{+K zTI-k#x_);2ywKmv(qQ52)@=|GRHucsR`)*B7~usbfWCoJ_cYRUjiy=}M=IM235a zV7EWua5!L|=Rq*LV%FY$Jl5m8T`ReM=WEE?yDS~GC|VsPY406B{mD=9;^h(7AN(0M zx4w1do+Q05Z(T9LTJ0YIsKxYppjHAPB~>$UI)w>-MYyVpcw%eH;d5I_CZ=L$=5o+(sSM+Zpv_yM5jYpi>PXna8k{ zf*rkdvQh1YvG9ST|d} ze<@*zTZH~j+pJ@_o7TH+hGpHG#?X=}C9i0L_cX?qNMnYGV4in49QJtk-FNZv#~-7s z;$}agP8Pm};Rr0D=ega)^+@ujdcuw`zkG%}J>kO-KEi&tgLWfar7KW;GbUv_-}cX$ z{dHg7n4-`)p<-)bYzD-JtIxYZcGH#^pToXLYxPV{xj`<|0g!{sp91I((Bcjrt`}m9 zf$LJSn2v}BeDcXBI3AC9@$w~p{hMFo|ycm}uw zl->+TB&nO$knVBf3JS(E0Dpui6a^g?Bd8bigy~9;%n|QH#5_(-ur&;C4fAa4u8$!S zu}49{op`fzg2~%0Nt**J;kn*H^dt`(C1x@;N8#D@tXu}cTZ1DTNN0-2jfVo9fjtpF zqV0XqBU}M@lMOMhJwndgvGou=BX8B?zohF{|7<%IRj7n$EUx1y4Wnv+Sf#<_gawaO z5HtgRq^4Vd2BdpeS?LqWYvh6-%cK*q0;L*BS}Wh12wToQUoI| zE9cgjfZ0=b+t1s%d1)-RB#5e_=%`U9Uc?EF20ISgFfyp}AG6e-PN!9d)zuDmDX4Wu zDS}!iOw){q4+lwV4VeDR>l0zh+Ixn$Vkm^s* zkKQ|;KYxxFFJ9nRzx)+|1%LeSuJNk%cVGTMMFbXVr9xGp@R-nk_KF_yLpHkyPWLr) zjt9TyUFy&G%|79gNAaY5?gvrLi&T9c<|G)kR@AAuD)UV^=Wt6cXp6WJzd039%sYFO zykTKp&tnY_S(vlkbM4tr>W6brw_Gj}V);9MPaIf`)mk|MTvu_+Fq&(&LQOB_TLpPXpVmgpq_|_ApH4Dc=S-RD2 zArsx3MIdOcVL34_p*?us*>S);4$)R1!irq{JI4v-tUtFQaJIz7C6e^qc6mLSy45MH zuOzU@>ss%)TTWOu;NKEv)F4TZ$0J&|qovXZ87U%|rwNDs4oho6caj$du~T|kJdWolFhlVzIui)Z=d1z?iSND12CerHK3?@*}5;(#W^gS@wzW> zP9gaT=xPqGih$0YHjf#{AGGaAq6#40LNU>}#8`JW_Y^YCP}$Lng|-Qr;%kd8VCp;7 zj#_OqW1c6Jvco(N@A9rm?g?DBF-(-KWY3zQVInxI#W_~7Hj^lh{?Z(Wb1i#UUG_Ct zW-jiO~nv;j58{VtyYwlW${>y#CjkjrY;>xB0|_yC8)0eU)O?sur1muX$)wyPRmHC(^mtk@E(tY;5m7nr7D z^OaKY;fEjM_U;Zp{mD;o`|>4PUtR@!-kNexlHQlMuqd42u#eK+_;jj5(=H(>JH)b2 z`;l3yNE5!MB6t8`RScEcvkSdk2#~uSwd8RXxaXNj>=ef{#0bjRsmnW;2`FWOmc2uG zWG@T(trv^6bzGN;m{8Dyw2LhP?1v{0f^;jPXw-Rtb0CwIOz+*Gw}aa_E~a@LvT@^H zSjCP14$mq*>V0`9?80uDJ$SWqh-7qZl?BqyK8;aUbPEPaIP;nTcCjK(Xb@7N5Aq=^ z>I{lUf0PY5$LfsCz_0S)!eD1E08Q3&%=a-zipRs^HKSk8-;<4w{QadJawB~CKtwWu z_<~&-596QoY>u6^HRjRYt8i$b(w^;b)C|oS}jxtV4q_x(cmw(IZ%oNU7*njj5yt-%9UtGUJNeBbEBeVWsywfewxVjbwIQgRB zx7l5xKi4)ysWp<}ZIfPP8-kkxWz!e=1P$fnrT)tOoqrN&S~b_C!tlJnS zt`pN$s(oc!W+LR31l)c3gBH#;mP_&mF&}AkBpXW9YzxOU@jOWx#Q842uS++)0-Iw@ zuw%N0$>p+_clKf|ZbOav4RLG`y29pfDQQz6u*!L?>il=MS21iu-Cl!X3vT7x3aj88 zt5B9wPg6a7Q>>D4N**uqu?Vcf9rVzl=S1=L8QV3wB_LPt^6zt~l=FF$o`oT60}p9x zP*CPRj}lJG@6C0(WT&n$&dM&nAXDSo@jLa3h@i^|JEef-7l?$#HeaWy4&9T-p=6N1{)_a^t z{48Jc034-!8?tjE4~a26*7lT9IV-I^x=03ZNKL_t*E4^t^P>*lwt z+>@mDNtv-IK^RD-912X_v^vl50b1d4eXJ{{@c6 z6KXAZ@!|!ZKYyO)(=-P7zPu4-=o6POP(Yhy5_ZqBAU8w4J26gx_wC-8jB<89eDWgF@E%;AK^E@`3?TZKmHgmUcQ9FNkCsWy`^}Rg4Gc*1La1r z^1JP^YLkyn;z*XEioy(qu!Kb<%|^c}#xnDM3Kcs5aY(cc;5YFZ^pbbi&?)Lb#ZD*C zLj|7U79g3&x*$es5Wiaxq<$^I=_;mO5lk|p`kK!kKLO&}$jof=fp!Q&Kk#oR=f-=X zK^Ls#b37ZFj4)6ILGrGlt{bFBWTQ@VxRioAS$GK-s;j;rm?fyp;7k=j5zqMUIxyW| zM9|`7#<{oXRv(9ElC|d&3C8U+)_TRWZ38P{DL!6J-RsVKwfBz6kGPv&830j*S`rac zZmXvsK753yPoLu5ci%-R#k@;PF>i0-Cc53w3;oHx+z+7IzWAkL|IE7}_}L6~dlGPJL6X zLQ`B*a>fi12`Phix?oEisq450vvC*QdJOk2Chy(z{& z^)vLWZ*#Nhja=(=cKqLDW`&f~0BfOBhF7Ex#WBWQkP;bLr|)*Vz{u2pqB&vkI$S|( zJz}G?Zz}r^Cc_ud`y}j?Wx)l9H#^V%*FQ>t|SHU<$t1))$+Q#gjS?64PXa&r_j2>#g*AL`J*qcW(#h zf#awzzx)z)o`K$i+|7OWHkEsl^uD}(MHEsRN_E2*0uf8xH1w4KSxJ+`!4S~){rEc# z{2@L0JB3SklF7dB+U=NzAD`0>-x(u$<afKix=yPCB&%#W?4qGXNZzQDg{!q~&95sBAKoZbR0T;r>IAJ%`K+p~v9_GOW zY=|{JOIYUu^Z`<1_$ZvA(UnYqTw;mvu9s)BHT%fGS8@`q84!jt)P~Q-W4}D z2mHyOe1dnLypMT*gR(P{wAY=13l((jm@(q!DJ)?7q=4!UDitCVfGdknsSAK31jhs@ z6yx};VmaO7#mnE~t7l)}bUdN;j<23Q!`<-?r{k^dif_Dv@5>*)h$y6XlPfOvs#KS^ z0_o~;Nr!>00GhAGLG*p|LSmj9dE;|&aBMNK&3jCTOehG$`Qd{H_~BpvB|iJ?Q+)dK z&v3juqN1SJ2}@~a^mg;gFwtxvf;gr7!j;}bXHa)B;hw4vFGOGG1OQyan&pcmHZF9E zL}pg|lY-2hg0fcvyay4O#)n=^L(ZI&3jjh-3akw(qrOHQaKq<3sX~A>?aq(LL#$Cm56p>~__?FzJC~ z37kXONbc)p@11HLC0GN7*lp1|Z`-wV@n|(f+ zecatfN%N=hI!CP3-7AuGWnkF7c3rboR3{4|;dN(r`dX_c+-M7IV|oD~nCgsD6hK2Q zz&sVqC@A|K-g*2O@4fpDuC5MPj(30*Ol5Mt-NOzto$SCJ3PFuzFOgwd3Z6cBj8Z22 z=6Aoui!WZ_+3&u@=fC_dPN$Cdo+=(+-JsxTr1LZd@sN!w>f^2&qjO*0oFb42g#rv4 zhrd&9_+C4@RxDa9i?=isG>9~F9F+-{m45N;GM*`2irZBc(r2`m>{tj?7k5n9#GIs@ z?T%Xfgxu5jKft?B-$nV`1Ag+e&#<%?khVaip-V$Y!30G|i_Kx9@ijgNwh*xp7TgRH z!io|xzA66H?NtrC)ydo-e8qKv2FB3PC$!>-3+<;R0_tI>eH*M2^_A{XrZIG*{dI*^ zwvGmV`8duG#nL;L<6@Y?n^kI!nhS=;x)_dke(VOEg z08{bPjjCwNI8{b{l#>^a_IYAJPS*5K;8=z^lVvzC2*mV@e})dLfgYZ4ClhV75dce) zH?WE&NSc%09|;?o=&`AwLB|PA;w|{Z3;TP>QSG$DY{pF-V5**O#A|QOo?FE1cy}hE zPMM|&%d%iuwpc|_%ZyqC)2?E_o3NWJ<|??kI^fCUhj{$x5vl-HfN83z%Y@P!^L0X0 zP|Mi3tlInp?Xb3dm)-g`aG=kFc#flZ5meW&#AtJ=II7^~^XIm<+7fg3Z6rv6dy@3N zyp=^gRwLOpMUlycdk3?0bGI<=3XmqDsHtG{F1(bL*l|T;LfL6j7tSt(J(isvZ!v^T zuhjwE3=dQh?Dq#edhiIR(+MwMzQpszjPzQ7(h8U;qyy;1Vw^h1<|!epzFj(`4shlS zBej0Ke}LZ(hj^o23apOss~GBX!VEGpSpwAQ1h@7($=0sw%Coo{MtVmQu*$m7z@uly zP+kPqeB%I|KDO!D8IO%)T<)C*Q))K&-Y?ycG#H2qFRKol5FS!NisicI^SFc8TWVAF zjJN(p@m*AwWm#}q62Sn=2uu$a+Zh}&R!eDvEDpm%Fx9La#TBnj2qQF8|3RZo^b}J! zNW;t&K}&IzEFNo3B&m1=7)T+=<&+9qn9*xYH=Wd9%f|d8=w=pDxWCvr~T3Xd2 zuoDSF?~@*)jYcj={1qp><{8)fYb@6%wARs13wk-CR-pLW?;%6&Sxavr$sv^bt@E&$dBwoy&WLN;L)ONe}Z*5H*YVdZKrORfjrl;4!}(qryXIl8B=Q(jZSs zNK!fczwEtvk0sZ2C-^(}M#S4Pv$7TzcZm`u+2&wuS^i_JfdK<;V?J(U+@GO619Z0m zwYp*2mb*o2Aw^2usw$WFBJMr&$64-)c$pNb!HkQAykyqfV!2zK<##rjSL+|8q~X>@ za>7&)Y(pzpVccutNPsy!Et=c0>pCfj zqui3Xvdya7W%(pov>bFNyL zhux@9k@Wf10y%-66A}s%Dms7$;UlSHngHr5XsXCnasnG~Da@G6fWyMaB!{U2RNQ1j z7j%Q1?=pMIFf>E3~+-olP+N*$q z3M%R-6O{jj^e2p>bV$=e*>!3~E%IBLCUqj_nL*0t#SCkr&xjuEnxV??rsqX(`cf*M zjh7)}0ty&Qx+rr%sFl^(WbV-#iB6ZP)laZBHRDkwaF-EzQc*hHm^@(_Wi?IB_;;hO zf(bFQk}0{)0hq30Yl}vgZS|P_N7s?K&9OxJ6;#dRS}SXmYQk>25nigPwX9fcnPe<; zT_vOI2&+D0wd$~0tpTn$*>3Rg{2aqDfXgUga_*!MEfKQm<^eo5Sum;mAozuX+uHwT z9G)+fndFm&$yUQcSoYX7VYA*~Dg_^XAcptVY909Wi`DKx(!2KJHKBA4Y&PLjEw**3 ztO~(MEX>>-A`B?CilmfUrNnkGyMDW-d0&{0z=7OJq5g&VeM7yQ-P zk1K*~N@?(nVY4=(3G&e^27!P_pskb&pojnjQMg}w{!wR<6T0bCcrb=9wNe)bSkneftsm+orUfa-cVO zgR=1ew2-^DY+9I)yvSA6T%<;SosOgNiDj5=qu1Q{glq*Mw_{@1_cTqaaH6sN#ICqT z#W`tCQomm+Kf`&{$t;c{|Q^L7y9BKF49) zV;U#ie{dhU%SfH16tL&emUAhqMnnHydw!Z3l#XTg`B80cC;e^&(F9-u*AYwwOd}-4 zm_54*NLeC%I6(|ismZW|6AUU$98_CH{RA%^H@1&G8;P7H?E*HW0L_8Do)l9mc8 zPt}A(P1a^Wj7W=dFXx~=(NNj3N?u@YyuzPpn<*89nbcW=EbLz&Ks(*iD{)eNgxfu% z7k}Wlt)B^EbThBVMvJ1XE#cqn-!(ei0CBsAMQo)+D5gBYc!AK66ljz4mRiM|+)goP z4h86c1pSk+in85dgxCa2{ic%(2RmiIr)qt*(Sn#b_i0w5S${e_s zNW#f4fEGCG(?0XTy=tDr7k z4!PI-L)omi6{CRyfQJ|hxZHAq=G0;6dkozgtF%R`d*s?97ZK=v|DlRUsTIV5RW)V* zYhKbaW)J0&O$e$RR6K-*|3dd}$_c=PQukP|FL8EyA49)U@VMnETCG+X)|;jjEClnr z_HWZJESHpnUUw<9f*Lz%D zUE%WL64%!k@_ZAcl7`lk2^v}z+45k0*}$652AoGqA0w?7WwofXWCkaH zwh1!-RnD!fM#YpgPhAn7g6c*>t`(fJhDO7Aih-a`>u&(uyzk_2f%K~i&orf#Oe+t3 zr4`+2d%|T316Jd*89ff*-^`ng!t`p$U{aKAnNwTFiKd+D{O8=E>zaWM1hl+%$7@$h zaRqi>3AxDuHOL4)R!9z8@#eH}`j(e4rIw0EfSn2CAgKWjjHKR1rB+L^sLHp5W>)pI z5`$@zQ*xIZuVe;lhnzauBa}esL>5uhId>VGjy?CCElUj^bqto^8BPJbtx~BuC!C$0 z;N|m&U}l_cH|U53Bmh9AfUEEncsc>&!?tlmo^Zb|4m?(6#j~?hyiyqBc);PXN6{1j zAjUKuQ1i+GB9|=}N`5mU+_mSaMV;ZcVyohc{cdtuKwhMenow_wVDKcisUrNqQVu{R4neJXH=%M>GSy zhZO?mkdcF~0*ln5vLTM^hg#g5Q zTpN4PVME$38@KTDxl@BXgA}x)M}Rx?0PMi0<=o6UAthj@T5`qVaDWx_5@6SydqfkM zrh;O*ngb7Pp8-!4z(zee%nyNi!pxyVw>4>GXZ1B|0$G$x>_IR(ZFCj7w}>+`4bIDR zBILf)Un_C~x-}tn0dz)NSEJD>vFj>k4DYgd@SdKW;I)??Bc+7hb_+fn(B%xuYS6AF zJgaI9&no`}{j6$qM=NF)=M%rTMX=cRLf?0IaQ{B`hY8boko>tXaJvIZ@7jyk80vaI zncs+8xU9{I2AKvEgxF=HKrH0*@gcPM_~nXYdvDet`R>u9$9VMUCFI=UXFvNH-h1!o z7$*g06o-lhHki42wvjM(BaAcV+-|7gVPoKK%?wOK$q2UE8bkqXZ4sTHQniA+- zOpInackUfj?HD86L1{L{ku*><^v!ZaMsJH~?Q3!!1tw}BDjbv);i0Hyu_{9m?-dg) zd@Kx6P*VV8boX*m@s7*OGKWR%Fe5malPLI42)BO zg>lNfs8VYJMOYsS0E*ngyn>n_m9r^xk~+c!iw5vRXSaG$3b|CgmaadUAf%-Rh-O7M zxE55B@k^dl0VCv^(x2UCi@xt#9wTNPN@-p{h+e(|R`mUV^?HrnZjF=O4x7yi>3YI? z=p_u2;pefg50Fqw)x1~=-0Fs@fal`V&Fs=G14!KKObRgdj%i_Ll)1en`t$X)yYuQ3xQZsEN0-Mso~qzi6n!JH3#8Be&WEdji* z+erIX&%(^fRQ?VX9(KV$G{+#wLP0fw=e15l@LsWzp}b zm^m$k@)SUgCETh28yK(@-VH}`enahhM1CBu=T9I8P2^yQ zgCii+lG^e!q;FOBMoNUPEDfp^=%DFa05eW1)QLV1*zLA1&QN7!A{=VPWcf%TMs$1B zNfq^>AFx{Wc;)e9eCO5IL6kHV41v|F$7BqIVw+;5j}@s&QWw~K`aV#;!i-0c9^k=C zFX8?7-ou9<{sz-D;@Pt&xV(5K=`^;z8%Pa6UjqMko}|xzyNSj(IwQir>_7EzX22t* z0F8LbkYrEF9Z%-Ea0T5;&9l%qWxb#v5T)t{~E=SK$%E5g`H z=(O=AqxDL2EKE6qcC*(gmxEzd*R9V)jphl>YT;vEu#ekFn3a0OZ~<5D80Xdoqg9ges4TQw?)o9*6TGSbqcATAjfvSct?7PCDlit zUR;6zk9bH)BH_$Sb1Eeit+KvJziTZTHP`89F^s=zTMbr%?QnlOzLuI~5HxfREc4(rt# z+ua(kzWfUQ_y^z9qEn)a9mWItoRwFYL6V*3=S&irq3bm1+{AT1a^Sk5$vCU05?Jn= zzVGq+8*iZ2ieG;Gi9|%c!0iqsy=yOCBUQlE%xFwvW~mI;kuM_{|KB%bmimb$tT`p1 z>on|)ixTY&PE)J+sOOL}X|uAH@I9b_a890F+5sMI9#&sjE2CG`3bzC%b^2tJH%R*( z?CHb?R^nwQQJSfCkDuF{%#WD4lHibfb_}08SE;RaL!C0BTaf z!t&RdwO9I30l;zqTQYN901B0pMR}c27yxAyE+EaBWi1n-S1%!|B3x%sE1Y89n-si& zbRRJjY7xO5kl(vb@-0bm1ND+EdVQ|Ql!1}~bf7F@ZAhJX&MNH?!PNkc3dVp$E6v0& z>o&o>uL+b_$eGc11zbk}<^k3tr42Hz(SX^z_S`gT^wfS6)vpb0Zpo~5xtW_b-waQ+vl1j!xJVz?NXIS^C%z^M#t0i8+n!PtE zAgx~0)FY=3wN4nvD~#iWQbq;1<=VwUdHde?g8|biEelxPwQp8yG%A6?Jb`Kfs3Jka z%o8dS6)b0?Uj`_SIv9I zx_b#h59c}XYvW>0K<;!-Rp0WI2(rHb25LdET(YX}08&?gn88V-+E~F)Hr=?%Hv)KS zBwCiRc;S2Uo29o)U9VuM7|$!S)&&t$g+#xo{67^?DVo-=$~aI#)Rau&OTxi3DmvX0 zi7N(T&8mcf4MzDIgk$b~WQ56zJZ#o0y!F;wc>44bAAa~D zraB=(6LqNo!66q96p(>3c@sKFr3z!@a_70XK}E}zX5JklP?(Y)yd_WN-#Vn zzADT}B6KCZ1Zb?@Y+}s=)el{Rw?P4(ONvY^D&z()xxf3w9G3-8}t5oGJT}r z2d86I+xyl!RL%pmYgUs-7@nJT^=SLx4~MQmqm`XOWdGnn4|>D$xi3*DQ82|GK}_Xz zx|qUZT+4f)HVN8cI9NhS85N`cVGs;2WMFLqI(|@K5=ZZ_3|lo)IT`@|h7_??!!P;h zj3O#{40?8u@>&WKmEJ<{oPajq#B>2u5;v=i2daZ%_y?w>{sv>qsLC%{!#lyfeE}I% z^jAyXzr!nnGIFix9tof=Ii-st_ZK~h7Nc^R^^*Q-1XknxdyRdu(CP2w^I~DnA%K~? znDh!3c(nu<`&*&p-ArDyJo9m5rs|ED!<2(eYH~73O999CD%Ad$?2EUWD@Qjspnp{(KMLLohT9>l&7?4;CFF{XKUAhPf8kN$(c z!m&g!2(>D8oB#f|&wJ4p&ku~-BdX|Jl(AL{G+7y!ps< zr>pI^bmbhETBP zk)A-w38QS;^wF`u%&MoXl61;q*#kKso5vBzl&0?CbAPM`B=v7A;%7m>hdMUiOLB@W`o%7-aPzaQ0{sK)dAZh-Qjl zWV)xJ9Ac_(!uI$dY)z}hd_n(2jU?axC7q%{f z*eEa<9RBnd{kP_0^%yOL<_!l+e&7_YxGN)u2XIvuu41B`#omgXj-+CY;|_o=VsR%< zPVy_2Q|}mp^E91N{eQY5dr}476Wl0**8O_85#!iF!9@uFHX( z-i$wKig)@4!=KlCU)-NhT66cVK7qa9@q(w^V`(bUUQ2?ZmU$GQC6nvFw3tRf7?%KO zL}k>nQ$aRMfTjIHB7w86`1NW#x_pol!OTAWpgxhBotF8jGcp!q;uYd$gBd!xf3lH= zo*V3sNDNyzjz79nxbz7beu)Y}De~7XXhdRt1c3WB_MCa{MXsmJokX&u^O|Zg$&uF7 zpkO?@O>?D^hN;4G#h4gA_v5mZX zMjzatW4{%{LG$9vt_1f}GD_5Zo-Ggei|v*~DqZTxhh7%%MQ0GEYXk<g|80 zrOFm7fLW+IpT=JKo?mC@Ic~^LbyK*TGgkQmmY;f%jFE{QF^ksZw_|=+p564}oaCU| zLUx;Ik-~3BSq^*68U}yu*MdES!HAg!@l6?Eph;=0eTrA{HMt5gk!{0_x_hTvakSw| ztl}r4OF>Y-F+2aAv1H(NcWZC-U79{Q?hEXgkDDd(CtW(Hu`Zwh)s!?#D(_#qSBjA-L(|A>YvXp2O$S_U?YX z-?yRLmB0`eX!%5DZ82D?L3)~V-d4_>?G=Xz{5z`|8c#a*TRE$-^$53}?BgHUJKSN7 z%#n|c{JtZ>RjwFLHqWkDfuP_-j>PdA=dQVA8iF(RqLE@V6CI5EQb>~&hKvW`FV=xB zh1bTrjC~jklFZpz51+QIJF<572TxZ5)j%tJCtqLkmn=-Cn&trIflq6Qw3lYufI%Y& zGe{}+VySbJI4{|qa7BHhr?Q&H>6hXuA*Gke;Vi`k8zJXrZQ|-w8NcCekaSdrX>=hM zW6FT<0lyV1N898B9;AJ+PCH*=_0CJ86h+bHz))|!=c;b=@_IOHdw}q3jL>Mx`@joQ zHIhQM|4b7B5?F>y%D@OkKrcMC=xYsUibjj&A})h0|Llq`b5dU6VQK4(o8 zLSROsO1x2L|Eg90{s?2Cf6~qBajuO~2$|=Psbp#`R~Pt2%c1FRO4UgA%0E=jnPof{ zn!@rbeimDdj~pm!xLt546jz~aYWgRr6l(1I^Lw{{E(_6uG&MEa1sl~Zm zDpsh*Fc>P*pU~3}>3Q4ZF%(a!GRjA>o_rZ#1?vI9K zw`_2og7SG1etmP6G!obwlDqTlQ3G}j3gxWrMBZiuzl(2PE@_h&#tCL^v@me@vdq6Q zpueLOwMSiK_!iI}OL^ZJSmI=NzJk?Zzuo#W`&sUq)E*R9L%e&!1hUp?f1A{XUYt_Y z;iKL+2Z1=%xqgV0^}TXCNtA>ObEK{b5wQ{g9fbhMi!5FJ$=!WF$G2FgZxM+nK=)9- z&RFB3qY=6#<+v)=M#SOpRQ_Cvvd7^9It$%+{I+mnuX6PBQ@~hC`IbbZe_J9(5PL!- z9QH`|a7>O}x&BvPra<_>dC|$%#G(ox46BsdK~DOJR85&t`Vo4-17f0LqKZ5h%OjJ> z0(c{5C^^}$r8&`7U0}VJbehmLX|i(v{MoI`y?(wi;q{jOZfk%_r9sMKbtFMpu(m*Z z5@*Ia(ZpI)O(E9wX+s}%cz5ZxmYJpswhA$U{D0s`)@zOC+S-tl@Vs+&S!p!C!bts@ zwGVtmtVq!#GEt>VCTZAX2T=1NMAdHu(<*}sjv-D>Zrt1d z`O$}v`ppsd<^!5=BB)Imi%E{TC|mRwMOMtJ)E3XN5|3C?krDxxH&SqkpaYxNgNB^ou>b!a=Ed+gDuuDY*;t&EpzFtJ54Og$m(d(mwKYZp*XfU&@lB=>>B*%eikt#W-CQi`0VZ+a{t+c;K< zDZVVU4$tkmQQ*zx{nEX6VEfC!KmOZ|e9;=wlp2i9>aPp~glhE`UW#_3@nK3Ah=h_O zJvCQ$2SQDfObLdH<ko7W5*xYKRf6TVdr6-SqKiPyR z3O8jGa?n9zTPX{w#rXFS5z8J>K@l`wA5{#df1Uo z2rlT$pv4CR&am?d20UOy1lGEH+mWJU3_GT_nq4+Cmg zez*=*GmVq6+(|8wb1qNU{SIo!M!tOJRRz{XVQ4T5je_JpK|Ep3-uoxOy4>SoQRC+M zFbx!w%kTJv_5+82AFUj3flCO{KtS=;+5`|1Pw@*?xu|hk4 z6RaBk!V0Pl_O8W3(ll$JPZZ*Qubw+lkx5FD6}1dpoaR)_dpRd7rEyPi9oHzFU!e`vMc;e09sdM zCPWMwHJ=9fX@9>qr!%DJ-Jb79=o#)S;TRl2d+tTA5(lbg8BL>a3QeU~ySo<6oWA!* z`K<#bBbuqgb6pD+roCd78T-4;QeTCyrUd}1c{d@|JBqEpRhm+V$E~)e zJ!&$SGzs=D?KJpc9V&rL2v!_`481TI!YywInO&~>%bMt{1Qi*mF!S^cA%tJ`e%N*0 z&&fDnd_d+|8Ic`=kR_FBYnFbCX}s9!1P?_~Ijot1gaN*!Ni{WdF*NUusX-b90>dAT ztRQ{Z20nob{2v%1mrTDxnDuC{w26reF_Z(?WVC~P=#Vy=9VAtNEut|Yd;04;NO>_) za{E6Yt3bh+Q1cUDCy(eW{7Nplj6<4ksK5BHiJ~RJWuZ*Rf?+^ZnGkR(DS6(%?M5Rg zb3d@Y{t0|o=;AZ{jZT5dhNIXjOz;@c!lOfmTmrL+9E!-M%C|gahQ@OdSMOkvBQ}GX zISB#8VGwhtDuw77hT7QFcqFzTc36!5b0baL z3#X=B&}NET{$3`~#)O|Ca&*$C<2v{syLNp%uAjVte%vDfKu>rerC6=$m1R@!GpdZA zNm#Y}7Ld_UG9XT%=rpQ4>jxg>6D{a}%dhiHU?8HFHIvAhhxpu0Y1C^YdnB&^l=NEG z?;0-HsnecV$=+p8!xlOd2$#l|W;!}af@zlesxHga-u6>t*3fU)V(yhj$IV@! zCEeP_i4Wie{I@Oxjd=99zeZ)?^ggH=oVNffB6&lKy5dMnP9-;ak|uhqH7QDUYb+Mv zm3#8R7^RTNHx|g1oZ!wQjGsCG%seVL$jC$Q?|^g!s3c+M<@jP}lu_%e8;(DZPG;h~ z8AsLoB9}=NGhM-?c7TXp;Ni*Nlu*nXJjD8rdYH2_^4Gmczv0_SvexZEgolI6uHkWHqvc#RBY)3t9BWkc+7 z`sjXRywyldSt09<1H48&?J@?j*j!r1E|AwvKJuW#( zk$mn%w(e}Z4N$=Z@l8%PU09z337Ih2OSix)juJ#Vx^jL`%L&f#@n?V*%);^`38c?F zDqD!|OT@WGyQB18zl+-y!iVC`$*j!E6});Sdk(K})XlB(tDIb7cJaO8V?`Yl6l)}> zQZ<%#jAIU#t#XdB4^hMVvyTt8LPqTTk)PAF#xC`*cW($*^4dq{O`EWSA2mi-^Vvvn ze`bKK_c9oNxOs@?PFJ7x$}t9VlJL$7cImHA$CdA;YbzR}ZXZ!Hua1dm4tT-6NDbtK zoZ`qPM#`V++SzATK-6URlae+!QZCxIi-_{;;2+@TOkylF*RbA5A6{dOt^gJXMuOFt zgEJ;4&=>^FOW@Y!M2PMRhWI6@dby5Q=L8&l`?JAsIANdw^6X1DOUG za^Rpw*Rjm&H@V=6m4UHByvayoX-(ih21!p%UIdc~vyFf23D=||cY?VEK_v)4 zo^`9kkYQwr4nbQh>=sQ!3(FrV43Dong*mo3mRty?{qAa2bO~$Nfn9MzxoO(8XqZhpNk+y-PE64w&1GIKUIQZ=ne-i)NI2svNS$B8Sjh3zZXfPbE znAaqKwH$Q@aT&81GqwH^j)x**8cBGHkoKomOI1W?|5SWAi4E5{l@gK$c)2h#0Sp*_`Ey5q6zNzkD(YkMfu{S7r9`o}Y$l&DZ8S8|1b1Bdr{b9to zL`dcs2_~#!eW*>6O$I5|StC&mInPzjRFqR(u11{#rmV&rl~PMkEYl^ln(gbbuS-+^ zPG0LK+raCQP8(3LKQ+y&Afv+2<&E*$g<-qLgfQD7mk48G7<3G%R@eJzaat)ya;6z< zQY>K7kYOZ2y`2ndOYdFd&l0{AY5Yt#OwV-W0*55J(?lH(aNCM0hw7(C`0H@`y1A!B z0_IGae`pLVFG(HlV|&N!t``oCOptdL!dIf*-k$rj;uFV( zoF7kJD}n%`A@$$6D@bK2H)F@Sy8@pd+xrikTSEq)iv~ucd{kx&!Rjg$Wpm8snC_y} zcrD@pDtt#g!@?32dxr)aa@atr$XRkd2xBRYK6R?_#N?yL&IzekA9jx5ENa1V^t^Zy zkw8kM115rKT)B>az6egvJLkxt6Ms0E=r)`)uIO#r_Vy*>nHE)ab$JJ67`ww#&^`|h zz96xC+b|MflY-sl71XHI)117Uebkz<@R16S8d>mWx=G2k*OESk&_B%?4FO$DRHCsZ8UuY61rS8lBfGAIaZhu#NVp zEF&Wtn$uReS)i^ylZ54Z>jwl&PO5c4r31i3yP-XSlFT(*&zjuv2wSK(02Kd(1a-#s zXGe{TBiqqSO#58A7O(H+Hnb#(wR4)%2&|d17@O7fm8#NNgeXtf$L7`kp#)F%pG)4} zP8={AWvtM2`dR`kU?sC?PU&DI@XfYs9Gs->G7-zj2MWgj+g;&%e4>1QsPzlY{k$)2 z`x-ub-g^3k0g%hiLlo#Qx8RaJ$JP3f{(#;bj4B%YN?n6=d=Vk!M%r#?D*e&VcLI_q z5!n?H6P+GtFcd-kvf&I+w;$fhMpHjy*Z2Q$)y>Y?RroxB=k;|CtdDsfao_$%;i?5M zv$r$Se&q8Z!@?p&>Ylt2%(F@56XjyElCkv|?@r0(umQBgdKZ9rcF`=A0BO1pS*OmL zS8D{Dy&lMfV=PG1MMy(9iCx@`}cyvFe_xf;sDZ72F}NH2$BrYvxh z2jQyozrW49pwG|j<%u|!JF*d}9sqf(Jwf1s2~8xR>5W$xnavHQB&;hy3ysCAlS?blI*^{Owz2g>$!ZzE%fvo$)C3n9 z3U485LRx#jQ>?CHN4VDSanx;4a4H}0=2dz5WU0|{Un{^@i%Ydeea|&n|1f7TZ@n3_pjAM-9yaEy7My&D6E-o|Qt_B~v zdI18Z$0~a0lXVhjy90luj;l6s@t;S}^K;t@<{^2}JRnPuQ{-~6h%2OtXoD~q;FUge z=;n*sqIN=)L`5LFa`p5LvA`1O>In%d{i6!k?O`}aZMuReK=7Pn{|-(txRtjG#3gzU z%eZ#%;9m77+f9cpC~7)wbieSlhN@^5P(#vvX)vXY<(xrvwph-be=KI=)*$%|z_JYT zv`R)Y_5}KA5^ESXt{QiCtFI*wxJd9n!dy=BQ@Vj}@G@)H?6i-ZJI55|WofMH&9xpL zKW{omr8Z%38n_(MH|iJc*~}B<&i{uM*Q(X7}26R=GuY zHh*i8K(kzAGNTQ~HE(w%wZNf31gKKrmBNbr-t(_CB5$vG`z(tWUnVEiea1iF&?y;j zrhh>kMt&Si>RrcJNFjUDtH%6~uXF5scxXNVB?A{qdWtqDsB+If%vyo5+)68%;2O0A z#{HC)04~kCU~Q3tyu;GO7Y&1_-hXOxN`f?>1Z12ng?F&y=b_!Ry2KM5vREUOJ*Hp})SPYTuo5c58{4 zJY8lDM*`w%Fa86Sd$f)d7xPpcw(cJG>J}Fut6HYbZPbSE!xTGSW1i~k^7iq}mQ7#3A-xpXzW|aTmozK)6$~X@U9ybgd$_1^S zwDt^NW?#V*ob>E+Ta#|;j=ohSOTs)og0OSnw+Qeae8?-)$=NIFY>=Iy1}D8jJD3<# z*QttXL0bnVng&yE8}f{V@DC|b;t^IfVB22BJl?e)*Mtu)R#%_2OPYN^kqA6M3=X!B z4fzFKTs9iGt1m-Li9av6RC3V1Q;(4zL^+#AGrgOA@`v^~Glb(x$24Lt4TU9y3V{@c zFg<)>n=JkBH{N&AkwfZuv-OHK(y=opm%cc3D#r}o!N9}S0TH<8jl)nZk?zrHqVx?BIeP%4Sk5)@ib*PbLr~q8>?M$&;};hq=CH4fP+XTT6)G3 zLAIQA(Z~_gR)3V0W!I42SMG%*h}tH5BB|UKDbn`%-!&?zjRkn*|FQr%gNPJ#r3Vw| z)H(|R!w7lGGW$l$TIX*%S5M@};N_F~PGZ{(@At~UjnQV6rO~fk{PjXHOPfaFC z=BC8e-_B<8igU94alYV3?JW=K);ggQJx`<1iLwGHny-uRxB48P6(l$A9VV~E^g z`9!RFB3$^N#LsSXaV8?;aY=KB_o&@>hhB2}d3PDugLxb@ehgnOTJ;&t`J7#>mX|@SrS%yqCtKiBsz@y$-`DI!VwM3TPW0bwgl{_1d$-#Ac$Tj zH<%reVTfLTaE`W5*2n?^+OR!cARMX{Sf*U?q~O$F`epR~_8uOVNZ97`mRZiLYGlKhI;pZO}o8P{b$&1Kd2zVxX zr_t0$Y5M@=daPs5m-F=-Ck3__qNzSTo?gtoCSOdB*Z-k7_L>D_9tvsb7FUws>#8zk zNf$;kv1p-hHsYuqF*I7*sBH`inK=g>0HOA1rs;ptjhgj$J01M7Cvn4_1|Chrk~6qkF7&olD2i#n&X&^|ZmQa=I4Y^Xd(Z_~d{PdG6GmrXKA zB~hofCWUlbpY2eVu=46)<-=SWi?bTMvAFu$Av8_45isOv7BmS>1hDin9|j*I1CsYV zS9w|1`B_Tv2mR=70H{VdP}$kphB#2)hD5r$x`w?1Y(@pi)8Cyq;l~N%_3i$$BCUxe zsk*12lEVVlG$WYpIIP}wq3qnvV%>mw_wdY9S&HHrge5U&V^HgeE@&MQIVT<|;Lcv0 z-!@YXha*58^CvxjIa`G3pY%G6x68F&yJQKWP??Cjjg;_beF7YrRYCQTP={$L>%4Im z%JLn>qUG02+rO)6k8<#gYzpTkbaK|3-uto3H)}S=C@Z$h9uLhLH;rF6z~>il0q8`S zYpfP_@TNXFfNDbT#Lt%XYOju10+MA9v%82h?zTDFE=ZRvpd@8l7o>D+j6Eaf@?p{H z)38Pzm%KlxFVktxE#6!2$y`#+=^HsBIVtI^i+{g?Ib@l=&a+@IDLp&6o#zM6X)nY< z$mR8U2cQUB&~A7%#Y{2PWyxb)){31!DM-J1zYYd*9l2!ag^eMA@a!tPmW}ZX$M4e6 zI0HQ4>;bRxx9H9{K!E^m!W;Abg$V=jndHz*tVA=AsG4`)-|_uFmi=RslU)u(apnjH zXW)LX@-|`>CK`txcpj$h8=5!&q2tSOWLqlhlW3o+Re_^HEwTE(%;)0a5y_zF`ucp^ znfhi?jZeH~=OePcK|NzAtbV_BKKig17knbMg@%MO!i=zVbVD<(vra6Nmz|^?pL}>U z5(q=hta+Q$fqqr&>U`fMcHQ-M1rO%$e5(-#y+V=spFzIf8{KdIS>zHOLcsraShiVa z|1|DJ91N&AQU%X*Hw zWFt(AF(at>!%``0^GlakjI=lE-hK=@RUT9LE>?n5doA0mh|#IWhu^cN6i4A7H)}&8 zSa)#9vdxKi^`a*nM#9A_!TJT#*#n&Kay}u{_x|WxXOSO+j^w>dd-OZYWjOxpcEscT zwh{#W^;e(QVj&?^itVP6MjZU|&=d{dV2 z{Foz`0yuq~OkHyvJ*DzL8XOB@xpsCGWoP;d5No`2Cs{DMB7SFZ^D^4dP+y6n+Ry|# zqN3UjEhsD0a!WJYr&PFL%t^@hET$?n7(Qi^bGIi)FAn2Yz=*kTsPj@i@!G<_d@<$Cy5@3HrF9?5ED3B>Hw$n^ zDQi#%>%5_#2@V&ef!S$M-0Z}IbQ41S)+*v8WgO({ubAjxBUs%K-ze~F&lAwiRzBpR zM1mSNlEwOWfqd2!tQ)0{>^uy2jN#%yXU&}r6OIbCrYoPkI_-J?_p=WZopo57*-5Ax zott)hNDRVb3BL#-Wv(1L_3+6C%m(hSWPzY@P=*|r5btnwjatEhK6C>Et~<)VyEQt| ztSo2)6(vJr1&I7+;}8`fJ`T_d2$X}Xp8s^5T;7700Xq`3I-r$WVVb!LvUWW0|Z8L@CRUg3|D^^gHs<|!gACu{?pZT(U($p&#(~e*7s7vdZ zFbH_`0tRQv2jpf<*uO-H$XrMSluu#FFi#85M-kwNr|N--yjIRDRfb`4#O^J<%t!^Gx_cax6(^Yaz3Ab{L^g5{m2SsQu9DA5=?8$TP! z!sNW-6OYzK)n`^XTRJK_T#xnk_PmgMv*@Uq_B<~X0}<`OyOV*Jl;G^u}4ARz}=%1eVE*=lF#*t~g%eX8W zsO;DRk7i64%H3%Qv2Hy;8>izyReST1ZF}LowRYy*i()8frSk9Cp=zGnj#OkS9ArEJ z|A4)B)Ps32u=g25;G^~{VB6=K_8^6AGOuDl{xbgvYg;*6sSlGFM3Nyw6wIbCowc*( zp%}y7=w2vN&)Q33uTKun(e#lz8@*=AvMWd(2)WQ@*NqScg50kcX4IdtZmfI z@6_+uy1MszDtxI?eUb!=IX;PNSo5D-&*e4`=*(^-u=e`Qz(3$(75%#w2fga&h+I$N z3i6iFNCvK|>yn0*u^HL5Z`tR~FlwQ9!Uqi4C%T$tqE{(j{HH#x0N2(Hz>6#WTDdYD zYaYHZO1+ayA3+TI5LSwS8>)s|xUxYQi&xXCY?=TctAOPmBT?%aWWBrY7s)=qH0svh zU*CQ~+VXuW{nl5!Q?r<1G$=}Bsj(fvP=nTBIlhEigv0k#0CIpK=S|v_Dqjp2TdHT`@4&-x`D6 z^0;Q%kD{)U*+FMv^WGDzQ5XJ%O)ynU}%91ngz4p=`R4I%I zuKgU-_vo3Zadm!PfZcb8>Xg3qIyx%``VkKp88F5|9^H+7t@KI@6ab)DdO=nafPzV9D6)@u zZ9jROtvl@Q4yHMN?(q9P{kytO_J5B5z9Zb0kcJiOUR3&#+axRr77^9DX^lhFj4=eK zXp*v!$&h_jv;bzzO#RE za{0xoF|($i%rZgH{L+F5a6o~QUvi}ec(wEfSBcqH6Js+?C?msSAdP3B--)hQ(UP+wX4BNn6d>HLzTRNJ$hV_mU({+;>Vr6?qcm!eT=DG*lIeqdJ(NT*~069b=)v zwKC)@UvlXnvet+7Hd4Qbru)*_+6uDJcDK6eq| zk>}z1_sLp^N(2-$83<9WRqxmChlG!}8mQIhA+}sL*IO18yefrrW&$uW$zVc|cPWXP zlW5RQ1!FJ;ZtN70g@IrXfzk$~mXFkpb8Y_Fd*1@2!(wAAD3#ctXarE+Q}6!v=E=^@ z$tP6rAgojk#78F4U17DXMR1RoPO00fn#n~vxrLke8#+u@P|Ep}uh09p0%%Nsp}vy> zf(1&J_}2>aC61fT z5HOIVtmq3<;Bs+aDs@xq>^=$$&Ob|t+ZaF8MDgEDRdb!oCS8HOAk}LhF|~A0uxtRX$nOX7zdfz$ND8ulYxP^AQ&b3C;sKFcu==oR_)(H{5o!;EE?@JiUakPfYNF0ibzUIaoy$2U1kU&;^y0 zX={RpkDxl|>0T=zG#*DhM3C^(3hW3(mx4eRLfG(~Ua4C4czro8d!xPA04nx8V}u*Q zD-M*LC59s^=O!qJM-@4t{dYYZ16D&~;n7x)XJpjyBlA1|IoC(sG4pXum6F(Gj1?YpoC=QjyoN0Q zcb<8Uk@vd=JLLdi>MkcCDTWwtR!(03)|vHj=z)nJ-SsEq0whds<0q=(d7G{Co3jFh zqZ}?ODzOUCvho1bjXL$;m2JoHnzyGN9xGM%+8MuW+P|r6l8?!qbqx z+l6P`OtR1pKc)kWk{R14yQkJ&X!qHcG(8hl@Egi$HJC@+mpe8Ys7hOQgW~qR2cB-y zsNep7sY*mw!PG<#t_Z!aZ;PzcqFoJ~6P>YkLoIK3!XtoB_K~}T5rno!R%!31-Zz3m z3vTmD4`=1sUq}($s4OU3nxP4`ZOLMP&A!nP_}so3{CWU_f_<)k+jf4v2z+4{$E*<6 zfJT@tR#{VPT{3?+9k*`qAS()m!2QTK(swjwFYLQR%$tUKdj3JC~;?@`sfNKNC$_j<;;ZGUr6?y z^huOoT}qt^l@6AUimxI1kY4okA@W9>Rtly660i1~SjjCbu(BWqdO;K?ET(ZD{rzwJ zCzyc8TYQ4cu)xqooF`dwEEZ!J$U-HThZjTLopqFII?Mf5?M>Lt!<8jf3AJeWZ7f{OZNdt+$ z?wVzRT<<|^K~}o&Ty=qHmIsr!5d`%Ypqs-e-4(Oi#ZF4!%Fpyeu30jmOf~EcN*s4t z(G-lCYK%`AMEgPWA%F#iDNZD=GGftXf1{I3c*Yo;#a~Z==$N2bcI6VPs#T|oLq~Bu z-CAh#DiQu$XBu_odq#h*{*xfv_FLMX!dK!9LeA_r>V*bplgCR-Wm5?xGmJU>fY{k> zhZv%i*DQ!hLnJecnA9-4(n@5{9U&SbBQgEsAgq(dBA2A%+B=fG{eg7#bp}*aj^7;P z%g)&voI#dU6_k3M_;YjdVgsd(0|Nn5H@(|#xJfIANmNWY{L8-mJ5FSSD45|eb-iZy z17&yo?mQ@q6jBx%B%y5nc(IRq?8)Qn9pPK#^M0}YN%$O1_~9`6bC*)!rS>~T;45yh zZDcp^_GgCEK(-=HKoA3^EvF3%d5qfg7+35xCEenJ?rZ|ZKTf>f_J0bau=&NLRzAhn zNS^a*w)!!piX@VCy_phY_aFeu@!!=6C-_wy0dt5Hfzy5&epVk#a*OwDi{!n!8q6Z` zr|spq&Dzg=&3t%W>HS9_Gc{Ik`DYy*E#qa$SYxD*LC*Z)ttYfj$nb=x_uX_swSNx9 z6|UQpBtyo)DLzva%Q z-$(n-tbObh6VVL>|9L;Pl_~!2?HKm=7LR%w2z2uE+jfmiX&6t0P!v9dmBR}G=1+y< zT6wy~_#r)D*j{yP>;dh>VwdaCaT2n*$%Z@ORIjtYY;tV0da<)gH~wQPLTwOCu*Nqs z7T1uIML)RE9jEX})k)iaPi&2x7CFy4_ENQN_oe&$qn8ZArL-}zG$NHh{zee8jY*AQ zs?yM`UE<;chzN^|^?%F0(R$w(-^$+LU|l(AD`Rs6Q~FP1SDprZC~9&B;nU%zmh2}O zVJBUz*cIn_C4~ctb>Jqhto||y4>*q?2c@0rBIdLfR~^5iLpsR8JRAOXNhOT{n~)nI z$Jr?gl5qT}|6F~AHEH3Q#QjvRj~$z+-ah(mwai4^U(v$~K_-{2OH|oRLRutxec^$y zM=y@3l=qhugX8o2OY9;{v*G)pfEJ1c*F=^;TU)hDBbC9dCcbR(ZKPyw*t)v2HAbzj z$G8~j8DH?b`L1H5GM><+lRz+>mI((E;i$kS6QAzUVin;>&bDG)t>|dvUz(hQmFP-~ zZ+AOn#c)jd>FJwccZyPI7AKmNbPx}+nPKaEu5oY-|Kz$cIHEWHZ}OlhN`iIm+lr$K zS5j!0Qu9%r2}ZK5n;J~q0FTY7Q27+>O&67$!@8-ZNGEo@&(s^#vXa-uc03cz1S%?1 z11eE!qCiw?dK+}GZs6Y-?rSU5y>Ix3N1*@v$XD3enN9wFMT7@2ZF+bj3{daV)Ib5f zgU-l;S(+HjE5c>(9_yfK>c~#3eldzvFuumcM{1B2w*;E&IiPk}rAUCYxAkltS@uB8 zr>6p+N$0AlGc@a_YD(sgOz57sD^Nf}@y=mnbIQ>7D21i`<6h~p582nC)96l=z5hUO6+)MEW-*pxPg9>y;=;{#MP zGTSiF+TKST5&4x0i7z&}%=Ko_IaxuqZnd26gOMLLIL(WmqKj>2Xm}m2RU4Qsco2&)mlC;0cl)Z z_h&S@Mc?)dvg4=0{!B1PVyd6E@GiN}*So}Lt zCy-;f=c-=2I@=BsnkRa8Sutm zhJ42a=<4h5%@#^<0RV}7IKS*7yJpzg@Cb4lt*`9t*QHfK|BV%J+cIc99T~?z55s3o zgi75$x!I>o#JFx(DEAQkKWajk)o_e16Tvwwjw;*P5Ja%9q)y-&f)wHQ9|wil>ysL0 z;c7<74msE&6hlk>5c5xPJr0JO4$u;oK&^3zALwY}3m_us`qrTumogZ3%DZc8I4=1o z6#ejhv+hL$fW`_>nLNC7Pfy_oPh~?ImOB`3zr|EEbJ=-&W^aFZrbMc#3}qC3suJ6D zEz7h*9)5oggLHUom;ABm!@|407Ye2<5WZdwlNb*7)bz~|lCe(e#{Q};hpHtr0S7>8 z8$*EFBh(KR;)3uMkOi3jBw-@-d>Pz|A7GfHDUdN@LQs8DaD4%gVbXv=Me-rB%FrKF z){tdB*^h!@5`U6mx{i<%c&ZIEiebV)^qV7_N@6U(s-e^iVcB#zv(lbDUkLaO5Z|qI z{wii;8(cq&x4>MN{W{5UM(sji(YC&jTtyto?2k3nUpgRunspK8 zM2Lb+ z+~kya`D1?&S5N|0Pdbn6A5j~YqLHJ~FR8AWPr}EoDyfEjZuIxKw{BG2_9Z9`7)1!l z#DX%806y#adrfzRtjPt1*S~y>%2|kn;^x*)WEo|DK{(Qc63f7>YsV)e&isyc>HOZs zP4fk%ri9(NsuD8lH~wy30gm6MIZ8lHrok%uSL#lL!%#S8Msbz9=c?)rF@&ciWaQZ1 zhVd?#I(_2bT0RKw`6GMCMe14zlr-v+hKB!&dxNT{O2(VuV#p^&5G+M)>Uf(A_;r$= zChIk9!%%R6js`4oD1HP@&yN7%hdCUn?`WL|f00(Ky6vZ0_#%KJz- zWHN}ztcB&n)GB7VgB)lSDX=8mn;y)af2HYh_-{KJ?p?&4-T|zh1Gy?NHoZ?yF;*T<}5p<4#8RCRi`%Eu(7Kio6k1~1m2o&4~`#V4F$pKuvP zO;h!1$Ni^LnuZOE%sib(&84XGF=$O7MQxRvh4QN?Yj#LNygJKE6w>JxOK3|a ze*G^CunNondXNxuYY{#nAU7YHG;*1_q5(q0F!3jUU~8$X~)cxB`)167GeQbJuuXFzbY z-@@;kzsXEAgVT$93MPC9-ST^5=y~3Q=k>gW=zab6L%iB5Mad~+7nX#@fx3Oo1z6Cf z$OiwKw~7douU36M%)3%C{y z3*~d(oDj1IVJsCp-I5{*NqK9Hi)E$$J~(VSD|MiW8H=Nzy=UHD|2aIv3U2_pvf?th>`lK+D>CI@8Z&D(Bnjgjq2W!-u(PDdlHlvEo`Y zlMJ-izXJLv18Yzsxr{yp<6-CaA>;bK{!#-^W>jpI1500k?0AS!|KGPO{{VrHd4a!o$3UmAPjFrj zN5Ze?_^%MFOeO@9#thby$VBKwRsi_|uVK9=(Q(X!*QVH2UPZ71X4As-^yY^c$+Uhe z8++PK#j;Qm9zC>4z<~#WuWDs!&)A*aZPt(LVf*faWQgSBN8H(Xvfn;#Cm8<+Jwd|0 z2Q+GIcuAeGpFFLRq4k~7(&os(mXZe{eceVpmhF#(MMl zFbp_YE-?-Zlw7bF28=@jr-JG70;fky+{7t(94s_)Kde1BCt!*!8cV;&JccMy9bkG?<8 zFdK#hdDt@k=#Tyg@4x>(?%%(U2M-?L-o0Pp-Y)Mew9U>q07AdHIzmg9g$W~92t>R`b8AN>JR$~Zh+;bb*ppn|H3gwV=!*|>4@ zCYA>WD5c=@&p($2%4*jf9UbB1&4Y<6xKq-vl z(=!Jnam~G!G5S4jKchjti$I<4D`q7jax0f%4h5<0n|6MGKfWG=36hmdLiBWjim&ti z0E}Z4+Wa$HASESmtso@H`lkvmNg^viTE5G{s(F;dSMB*N_m=8+p}a*6qXt}uf;Y8c=6|a^zV~jTmK<- zRw>ZRnuZOSPV0~1I)Y}Aj4lsFuGzg*m;K2bJs_x&tCoA0{AkZVfvAWi)_J3$9jP^m zOJS}0<8GDt2&7v4jMzOh0Ic>>1zP04%fsaQlpxgsTZ1M0o`P)$UaEhq=wg<<^hTVh z-H}pqnQd6o<|ZS9asqSFv`I@DCDD6T&N=1*LzW29oRaH-tYEtE2B$}7_?>s}f+k?d zj4^2~VO#%xq2#XEo{{jr82qz-T{chD$o5_P#)#UOj+;`# z(a{lZ-MooM4?oAx{`-&d^n8uQ!67CkZ5RbpWvM@Z#lGB+-`;2h=&NPC)#q)`KXjjd zwR7?8@2@gg&&Oue`9l!wdl9@|nas}D>9HhHoKn*_<9pxx9=`wm@8jc-KgKV9@k^{X z6Mpso{XAfX3?j)~u!z%?Gsc|M84s-2YXIoVgh^_>TDCd6b1f30qz`z~(lfPI4BG5T z()a};QIT7&;`LzRoxKyfuQ6K>5|l6x`b(4qi^ z=0aty!3vZzq1FM%$7cWrtX3!Z_6Hw;dBV?s_6z*|-~ST?AW-vWD%eg$pkctl!GWef z6jyrF)Vf0g%~KYy)&J)H9sp=`Oap0_qGupsv)M=uIbiEN4a^2WY6b-aM9DhI`?YGS zpw&Gk(pq}j$RIMS(TFj{zH<$9&8T@t0Vq)rN!tc6cO8TD%ijH0HI#W!Q)&u~0uj(1 zOZPdESQ{2O>PnBL+a~-t1Z1197GX-H-RE_lWUlr4xhh#g(hXCmOroP??P_66o7M@H z0pvW2#}Qh`CuNMwB`9bA2e24hIb)eJR*M145DwNzxvu!Kt$Ah0EubM&cd z(a4zpY#)L)XEOs;XoYA%MMI{CGW+p$8lHg*i3&7z^i{{J4BT$7IO!6B7`r@?8ge8} z0p($8#y0^}B_gBgHZ_Vhq7Y1AlBgSLc*e+i#GN~DVH}q@Jv{?3;qwPy;4lC3ukiBa zIfgunUV#wB)&Up*7K;S{Nj0nLz?{|-N-b{iM}j!cM^79xVg!uoO?k``th9iE6M1$? z<#cm;T$OI=P7rSdXV=wqTvf-Ofm0_X?F1%;e!N-3OK5TbJVvrg_P_NNAg@vB5v8wl z9tp#AXHNw>QtGv@SLCrKkxuQ&rQq1XKcm@8<5+qw;u~;Av*=4ig7P|)PoNmJ#1I`>8b3#(q0vaUH z0wf%(XdNay7DWu8SsYTvgS_uTlNSV$oYdj0cHSm;p|TxzeKVWU$Wg~j8dxJT(F9qL zO@=337aCUCcEHMVQ!DpDJqZegwC-^2-S;i4jVyAN0#@m>I;&+fXhW!mRgy$dT6r_A zha&q(?XE;x<6rFP3hBu~x{zfOlG}6)m@o`O3tkxkT+ zel2XxEaiXK5ZRO6rZT(2uH9?o>e^oCu_sCQ|BWDZWi0Y>E)0wUo{i8-eVuxiX>L%^QVA2X=EHPic|QOFATj z9YnTcXrzh)C-%d}&*(fVxbLqGp2`4j%|k446M!oO{nE^E0g@5`23%Wb$aanLo&Y+{ z_UQ?=?z$Vn+pblJ{H&=LwlBG|f+;(XMC(91*jfsT&244dR|dApua%jEq$H^)har$H z`uu>JBCgh{Q%SyRBxz->F{NNOCk*3&VH6cJq>OPGBrS3rFf0b7AxmoQI3N!RiG1mX=64`Retg4bJY8$TG#w(bh_W1ZMapq$)me|mh3w{E|UM-Lz4r$7HC zp1eHA>gX7?umf=NX*43%=B0l=ckTBWIc$q<`weE7A{?J;BL~=0u=e9?IgBBLkxpp) z@HNIRLhE%tk1g3^q)1Z2%c(oj6GRFuC>~6pKp^@Ou|^gO5S%Jw7)IPUyNO#j?%;R7 z^Sely@yW*@{a! z4a6r)9W>pL5Sv)o@Mxw8qB!VEpIhGATcX2~{;W#$>v>^dl*00`X=1-+)5{fvOaq8= ztMLZ-d;Cp)mLqe|NG?jf>Ky{GM+g=LyXPPd)M1C*uh_JX%5&rf^pV`ELuem*s#O(}L z)@JS;w!PBZIPj*SwTf*vO$DVETwa{x{{8!)JYscxrVSl~KHQHtW^~=QXQOwNnQZ`X zR;HBx>z>GMJC`@Fp z;o%XML&5s8;PPTp`Iucsf+esbr;Iu<7K??Hld9~_tE(_cyCdpIq&Zd*8526l>UXSR zP{bj61f&2&G0rQj z?v^SEATTg`yek!b_)PeR@bgQDSr}{zfcZ} zQR^DhB*%E~-FNX{{>vZZ{)5l(^Pl|>FebT%Dre0q3^N$4xU(<|C>e&1D2?@2Y`*5k zi7Q;a$H^z8g>d9k|)b#5jCk+h1WNIME6@ir` z0884Qt%auvO0%nee+b!GHN}v0Z&_NkDMlL!vhQF9hkR3 zMdwD3MLNeiQ!_BvJh+J_BwD*6AnB4-OCpeXW{H*TO$uQ9wPu#aO3>btIcMY{X{mrL zwF$M^%Pk@@PLb{VuKA{tS>Ruf?6(d{^BWq_S1jD`HN?G=NsR|^577gN+@ieQ^E*B z;;JNOGfw(iR4L5!Y`9@VPP{ZQ5xw`@U)_)Wn2#>nL;r5u(m+n15@o-0Ez(3SWs!eI z2r;CStLi1mP$=STAyPoQ0l=sVA3y!+$9Vbjd5iw9RdfoZ z!H%97r6{jC40>(b&bRm+&C~QFc&Op^ibhfi(Mv8bt2(eMHK|y*z?_hx2PCzUOefg< z29Q0^p78So(zdDSCfj3lm_)6&<;utk0Q>tkSsmvi&cmF%^*Ytz+_L6I0$T|ph`v;U zmlHWDERj8`d&u-cyAJ)T>m~W!;WIAM1_?<_EsKy0WP@ZQR-}}@9;>C!+CCFJZ4pSi zH;csdq(sQc`uS?TJzdc}WQ+@`9e1=k!OhbXEOQonh-Gani371(+M=`JMm8icRa7ck zOIDt(YEz)mOMuk&_S8}*4B(Nj+4hqzv}-}a zZ{c)Puvi}8-Y9e_#7^nf(FRvn&h&vKJ%&1q*k-GWNsijwVbzw<^YgDv=CLZS=Dc&s|fcxh7S z7)iaOfSt*s^h=4?Y4*+pOaM{FA~CXJ=cJi0(;wf|QU=sKl-q^_?NBQ75vULU`zu{B5tyx>q)KkIs6UGowR>_x zNI@M#yVFyWfI>?FR8TZzK!_sw?z`Xk27c$8@8a+N?r(AL)1P6psYujPPXsd)PzjYt zKy)JQdY*u(85xljorCr{&?P`?R;v0428u;MRx3SV${E_UK*0-j%CC7+qtVB*V6G^l z0pcVmARb}!+=lA}!ZzTUa$zAr1)#U4R6UTjTZ`9e#}&dYLFxzk87*~0zmpIN0Y9}U zNZk|FK!4bAZWgFvQMh`2pKjObbWvOjeFj?1JyJz0#>x=LjA%%ulrdxpf67_@PMILJ zQb(jL#+uaJ92&tv33*INBY~ETyaF&SYEsfv^5t;XnL)-2d#?_~MIS;o|(ML<%V&$<%-hApu!|BM9Tz^o2Ebn%9n- zM`v#t{D7w;+VfxSn0CLeFW{ioqvS(6nb)xcS{**tnq@o4$u25{LRzFA&lW)BEqQYw zzi@39nN-gjDC}(ynzhSr2A{s zVRwn%EU>IGa7C%D&S#4c_o}z~RvmR)dn|m9fYpIAx7yF7WbsEaiU2 zyab`(>EqAw@aaoDe|d?QFJGXP;=MnHVUQ@(1RNc&LU($fG?1ndN#>jAj|8Cq%nvY2i?5~1-lEt+cD!@MM#ew3exHY**kMWw#`pFrp=!p zH+&{~i?_b(ATlU>^!uP4l)HQE6^(IpGY=g?F?CA^(i%^qd;$pa!rSUSbl}y1z1{7+ zF|H9Fwr9BZM5)bt)xDGv_qcpw-r-X2p>90~V%&Xko=qTKeO}i};Gk9Xu zsbZZgHXDiB8HeoaT`7glYeg}V-?2Fme2)_O4calRtGvypr1}<2)5eW7A#gP!%A%g^ z-gMHO^qB3N`5u}N=Vh3~2DQ&=bVwvkzLF5xk2h&>SlgKx`HIJR^_Qa2+Q~vR`6JIF z+TZQl@<}cA!ofLbvdEl@mNG~X-Rd3MgItqHzyhwSQ#KQ(sb~Z}+^`m`CXP4qYtyLw zS#4_@S2-QX$TvN%>5uL+m{AHdoiu-a4nQ3k>#>`<4ODcH2i^PB9CAIduAtC3%4`!` z7p}bk=xq<%SMxh-e>TzDB8Z)o>l!;nS5vbwT10+7her5`!%Qbrg`-VYg>Be$SroUC#NqA4H|-npF1Mh~qF~)RH%O z$f#6Z7w^Z{dC(QVf62G5kfX0XDujGdR>Ynk5k;y)v<#H|PAwoJ$S{`|_QUICHk?5O zo?Kof#ShwS zN_!fZjm&x)>o-A0<&n*?ekPQ-F`eq`6hCWMKEo;qzsK}(@z3$j{VsY1@bUr>M;Td) zJhioFC~jk^sXL|-i5Tl?!lqOl3$N%!OW4Q>QeRl&QTTon zlop{Puidt;l#3?pw-vHh(twcP6mW$7B-JQKl%j4J;7DTSJt!6 z_V-o##PkAwm9pTok z+o-jml#QgS`?&y1ul7h*G@UYcG|cDLgFTe2154yRTc%Wyb%HBft>{#fI3VmkQjiln z^ve9XPAMT%aQN-e^=|*q%FVQ6rq1~k77XUj@p1_}_EEbo@>;H&&8Ay=D`U3{-$~iC zqB?r}9*D%IsGU}V6NH9?{MvLr?4x!#(*0rU5OqqlAKEeP9D+OKCCR_DzzNyQ+3Ulm zERp|1&d7N{PJ_$~GH&0vjXQU4V08%O@c@(=psXd)q=t57_Qp!_+H9@Q&Te2hIKure zp5XHG5;OHtaIT&N2&3AsZ9X_VZn%uUT#0tNDvvc8{Eed=Bjy>zwlT z{y$G7z42pDlJ3W~8${B3ZpLMZt+qhN&s*o`A z2q952EuBH^l|ZVonB*1J4R3ac(i>kCTt9EU^%id3x{Y7_;%E5$^Dj_J(QdEWd7QE; z)|Psa($%F0I)h{W9<)QG3FO)L;){{;i^dGlr$zc_6zqHD9yO9wV{d(aPUy}-a|1Lo z4^;sbE5S_RJ2XoR?SHx&>y)KM4@n(0?W7*=*No423^Dek$hy7GtlnI`&)wuYeBaNB zm-aj~uYa7YxsuAS?tbn#j_p>vLfC>HIQ3JR3p0#3>r8CWS3hcn#()YDQpHhTPl12hNQ$B1FO{v zKm6ej@#M)9{I~!1=Xn17IV4g;z>26?Q+(oB5l2uv-kdC*6P$4!93TO$&UJX6tmfM; z`DL%ob&4N1QP()oK&F)+iO+kChP2~Gr_#1;1zK~7>Ww5UqNUdD@AN>&=7z$$>%CLz zK)rlVmYqvGm(6o20&tl*ZSO53d4dwAC~#n5_uTy@{s zJ0^dDVURK}!;lr|0@L~eL>YH(o#BJ`ZiCB9P?<0$0@n$piasJF&6+8#9=gr5k<^fM zV!u~wKoUuz)astcdZBi$G6$08Z{)g85j-W?6;(gt-kFo_F)}WJuv{MC^z017ID#G| z{N&@0L64u{@uMd=SRLVPb+c=_b?wpZ*JvcIeIG}BKFpS3B`g{V8HtgvHnxe&*BH8o zrLkplJJ?AsY|G_-59^-SYmTD=Xm(=3)I3W zRt5tE<_V;I1jvuwoMdynGM7EgaWNwjZIWm9p8wOR@c166VWC}EW8PUj+UI?(P{lml z8qnIcb+uaBipX^y(W_lT7K zGDn`xL#GF9E_QFdhE-;E!F)|g*UbAPk_9Jdih62653sT{&}D`+Z4%uwXjWUn=JFgz zs{?%ZJMV+iIqGJ@Kowjj)Tv+`1}#$rSn}I^tx`(3apMf9d5Oyjc>3fqDl>+0#Npu~ zHk%Em%>)Z#iuYu*U|9=R7H=oPNlj+hvvp;uz+KP3Z+Rn=Ak=#0C!U)Is$gKmzt8Q` z-P|(3MIr6cKLqnWmQt`<9pPKw`ao0fH+cB)A=c|Pc*s(`noURw5N<>r{5pGuxSb9W zrRlCYG-VQj#=IfURiN2`ti5L-))dp6P>4iid_7sDA6pGLZpMNdcy9RB8q!9o1KMWj zG$U~a3S}`x(Gayxm)Hi3ksPkIVw%Edh`fVE|j!Qqrf!VZfL(4i84094*0>v04nsWrLK~KrKkjSPfY~dzp~a zq8YtJfII!0H{y4?kxW-L<$ z_!8g&1p^qi&$2#S{T#(-)#j;vK-b8Cgj`j(zCD=O1K2liY#IIAGDSZoMshGJze;TI z7E!muh@GE5UPn7s(`kgHDf7LY0&A&`aGg>9$d3xH1>WhLD{7tmIM$#}uGiAtq#?!K zyYJ%Q;0P%Z9zTAB^Ye261&Iq%22f4rO|UNUyY4g2`@93O6Ip)$?6szwOz-E`$)ziF zN^HL7_h#RpMXSuotF842$C0L2#mRyG`-Dc*dpn4=r?X;Q9m-A_N zV(Q*t$VvycAG}nSV=EZ)zS!0)s-zFLfM3%+UNYk%Eaz;J1(@uHa>jihUGleYNT{C*FGtEJ> zP0$*l#IjAPA`fKZ*6q^8Vu9sirCAb9&J$^5XVzoZ3Zhs?d0Tf!BD1p}xjmz7&*)5^ zy6!L=b9V1GVua^a>x^2x*&qN+)3i0?RxdQpZF9^pQrfQL-R`Ao@QY1Nbm&P3c_MR0 zwa({ePY5Yapvu~tB3!%QGeFcRr8cL!?=(ojVrFXvO4)dMx0I4*TJ^{E>(n)^J8Uoe zjMcS{>tOfl4YIOe5lF6@&IilBqbk@zZJo*!PEJm7`^HU_sp9PL0I6({X$_=;LFX$c z()4!$9UCrN>kx5a$^%xb6>i_T;uPV@*4n@Q-6xT{$7~Qa3eKKHOcuUz}QiyGW-w8Re%S@(!MM z#BG4tAHxiR?RrIK6E%YlU|1*KX6*IHiudm|Z-RnkRsvT+m~iur6mf$>=d0}w>2hDS zc5Eq;9Ap~w88sQ@$I$;vR8FtEdNQJ47ZUG= z>n}?m-?bidS#P81gh*JLv&!xj&~6tyb!+E%1CTUD-Q|znVIUywr;(tfk-PCTQkT4{ zPEmV9%Crd((`}M-)%12zIHqqooC|s$wr!~L&Iv@2*E5g$(wv%YBqXXDxlfR&Pm4xQ zK9|-w1zeHyfcM^e2j95+4p3P;Tffu>Ga8ASgz%Kwol1nKNy}q|wI|yvO2oJxX?x4; zNM=ZOf_>NSIm~~vXV4;q?Xx8J3udK40DpGF`niqh`%^C4Tag zzr*K`9^(D){UA*7Z(yYE$G^@nBE$)iCfEC(0^Bw6vGG+%&iL7{M4I@Q)Fz}RPwlu- ze)|5Nopb(svsq29$m`h~qq6UBOG_?=0Tw6xW>fIu#S2_sT=+39D%a$soKvGc<5ca! zFQ#9@+(=0naW19qvn?>i@Z}tvL}y#nEA~8#NFq?qOu zT(@;z!)gt$7>MWybtqo(_xtsf&nDMzrdLYghE-IjXusBQn1q}|{{t3BS|akuSCf@? zu6E9z(6(}9f>q2`i7DcG9{{AOtOavex;=|tRlLJ>!drK4;@^Jwp*W-pz`PMXG-PD3 zzAjp!YN;{OGHG*XYg;eE+i$;xTeoha){6W0@8j{KN0@3wnI;?^ufW1b_p5K>p+>tV zlKz(I$zfe1De;<-;|!fCM$4pWB)ZIH(`nav>`Bu7xOPL*p}8qI(q;)TL8*}#iG;a8 zg{70TM>zxl8k8kls-mCFaex8r42H8C{y<2j(0VJv zu)RlTh+=?f^ z5t-rM0yu8Qgn`oF4JGo`7oTMWx4l9$qlekjV9~9)?CmzWYA5+;>TJ&J+;U8kzP>4G zwN7fJg3W~jW?!3d90RNXTTutU5HUKkKZ}$IoFoe1z*x*<9 zAD|9PERJp>j{^!5m=Y?aaJ;z6<0RZp%e18H2VwYfaRfC>r&-CoL%{gb$8B^Gk+~f)izf{Ub zbP6SXJ`=!%aTr0AK~(V8TW=u|;fse4@$}i#X6!3;Y4?<1-PgBCQ;CR)_n4SkvqmVe z(B>Uno1-vDr@rI5&V#M(ymlQEyWX^ev~)y!j*ZydMFd1p%BnY8^pl*YkEFb6Zx|4c zQCt2V1u`Y>$8at2IF^+nq+OUFT@F*>qA%Lo*!}a4b0|BA#G0b74l4(^`W~tC%=ICW zI}ck#k>0Bt--EYK&gUw5}jgt()6qW^V*_*O+*-Im-`nT1p=s6c?L|+ z+SJ-SE2#vNFD7!Tbda7VAxQ7sxr6idB`!7+p~O^Llbo6TxgWpH!TP-Ev)|dg^3&u5 zvHj2NQmEYdiex9YWz1_|E1>0>+!ZCq3HEwQ*4T%8`QRiCLCRb-a?MI5Nzt&1qBSlp zb3tTQLLy+XIKWgUq$19cX&AAdHY&%0#w87$AbB>N1O=q0KuxHLJ=(iydOn9h3yWN| zfQBfy+HEz*NQX!Cb5Ret11-##IXO%&lQpZoa&1gU#(6avZF}RZU=^KtE$#2u<@Z4@ zXm}IeoUhX*_7)kD79XJ}Hl zt{k3+>pb=(>3&?lpnVN*;czbK zxEEGN3KFXU9~Ch>@KDN6K5xdizAnI#9afm1(xVYTBDUGcFj65%pqwx)N1O};N|~@+ zX8h;>{Kt6u^a=j!|Mg#Set9X)5~|Jtv8KA@rl5lHMzjG?5DLPywO}zMNWD^0OuV9X z)NS5hSB{F*WNw?WXlgv!t1M9&!YNl&jmWFa^1A^(U5b?8k)aWcn$a1(qBgoZU|qCT zp9E8`m(b72?VMMl(gV^5@R+eF@T3eSOB}vBJ=nkZ`aZ*2j*Q zQ+TfSd(gS>>|TnhajErpZ0+Ux>c=F__lmsz}TqRl?ZtTYt zdFvn)>xSyJ8t7#u60}L9BQS4N*l-a$5k(%EN2Xxfu8VQG#f&ig|O;V)f;FFY`R9Sq0WvgpGgGi zvzK(H8Hn3zu2XDcI|@X>DMS^*iaNOqO*&81*5CJlY#1iej@i1u2y!1$ z=G&&SIRjh|`F3KNV7CvARIxS2EPXi;JiBvTis(+B(+f~H7AwZ@MhN= zZsc}=Sxr$9(YO4Wm*JXOe2tP8ryCcT9TjN@*>+>(eDy~Nu0^Kmf zmnrO@c|PTFt6cF4v_R( z+zx1(@!|KU@3SE&)(97m?oee#tR>Pcaw>vs?O2VLieW$PebLwC zz~0{sd)M9*dQ>X#)XI%yG_sW0>v@_1OAx~{gE1%|MonN&7)D^J;f(SV+l)Frz zG$I!UPX(Ko&rn_-VJI&!mW6{-F2~ql326w>I&SBj#Vb6kquUW6+%8ngK$*eOldNWN z?#G)osuKGa^$|gbm+f%kPzf}XQ-p3$*oXjOD=HPU{S!u%L0e7q6u4NphD9^@>rvK1 zeP2!-HThauBy=H0P1)sJsnxr=+A*ujc5&oXOj?sm(zOZ93*VUu1+ib=-d&Y+mQp}b`q4&)MLXo?%Ogm-zJTg!Y;d+%4Nu5d~tf&zVE<0yrR;?_x z?tJcbzIAy-RI7ew0WJ<=m^+7DTaK@9LHY)bN=lFdto3ah5hc4RnmI(){Ios4QKv+mu}gRCj!sAS zT6}$*L=_;zRga%q#NXCu6=$?_$c;&`gjRmkY@k{zC=LCGY=0tfDIje^n<*hBNdd21+>WiPgS?EABRL}#3#0|2;6~Px zO@=#2$tQcx$vcVHW|M|_i&!N_8j8FnFB4VFP7GMm)}^m;3P=`YTdP=eymO|`O1Swx zs3NzMU5frR2NQe;+S+aF%V2H$NGZdlZY^-g8#qk;T)*E;=fd<|+*3xJ0^9qO)WMsw z>-Va!C6W>mAOh8lTt}oVY4OBBss)J%rB0w}jWG>4NEOEigRHsRQ9`Dg{*}NZmDf}~ z>&~-|>{@H6d7T)ECUBNUuqjpKRFSEoQUTXXpsb|}g05#RtN|zFd&ioACd-tleVMLg z4aEe=$(k~0po?N;wrbk5)ng%lL00=Z=pKU4CsFNe$?G`wBLvP?ZE3ngF-qcIvDs(rd{Lki(Y9*w^pkdei7+rCPryTWa6x@SSjG^; z@G%#JM#$KA08vT|5%NK)=A7})-FJ{u!sEw}l{6L5P#~fBOhpx@UW(2`<9Mi>BfE66 zYp+RPt6Dn@9(f|=4d78hDG8yQoL#fyb5jHyZU*pOCm9BJODTHBd(jd+b3H! zS0QOcRwGlUxa|koe@g7yYnmP;N|qWpW=jpUjUZcZxm;iz2M_@#iv?EWh;hiM>kTN| z^_hzGg?CHJqRcG9rc#W+nvET=+e_vk5CbatdvdwjAyNy~9~>+(Z8FL_Yo67SW6bigAp4Q8tKmc zXJceX{28NuVx;KSwM0^826O>vT5}R&7wi$=074zd2G(3ScKb4dp;j-BB7+9#eE8v2 z6m#4A!q8z;q*L+1!3sCd&M=h=TwJ_V+0mjeVtq9^cU6K~B3nt7Ol1NkmgWN7&YPh6 zjZ~*tR-=PInI91~A`g-?lYt;51le5OacQDmNIi4)Awk#|H*LjuHOsrJ#bZY zm)HxcPhj(JV7z6yuoBb6)B}2uUz^!EJz-)|jdniy*Yu$t#nzb{i1SD>K~S=uLC(4E zwePv!W(UFoEG=3nMiQID56C&;_;4k}Or3CR1db0zEXP3sFSmPCd&FyK>(DByzCQ6; zuD%Z$x>jb~3EOU6dZPK4~o8!%=hsjjFH>Q-vIMx8O2CA%DLyGT;| z?A0Wx9Z#-j{<-e+J7k$TrNl8HlEI!(Bl2>R+V(jy60+Ay7O}-@{Hi@jV&9srd47KG z7(kw%CXeO5#95Juyj+vrmx!50Qj^nz3@hzODi;LrsgpwcDv*`);)v7Oln#QT61%+` zU~ID30z#_lZFyE{>z~|DyY5!^dbeG1HC9pF5o(g|(m&9-C-nPn*Evmg>c`-vt|>Yq zRpp{#71t%qj!)cVp4mdZ9c2e2WG5$$BxI$%lj}e`UdkB+!72yK1xlH4c93!NaDmmq z617Z?fOH*c`#p&+(c}5e8X*aCLO0G0(B!gZy0F$T1xeH0S}QIuFWvc`Qu1;u1Z>wP zW;tKgY(J6x)asMQwSqeH_1dGn5L?IWBzAjN%HcITiINeu?b*GqV^5Oq$F&^I(+;V3 z6<&7(z=%R4)BJUyAwEM!+d#FQOTQ0zeW+c-NG2D0K>=9mSq%{o^RDaydc<>SC#hVu zNr>s-=AmpJB2t{%YS@T=mV+cIXevsXlb?UJTH!zbr~ioi_wVD+{_M~2;K2h?FkBj_ z)rJL-nUttQ(q6M_^g(e`H4vgof=wZ-InsFxr{DkpAOJ~3K~!RP!rVpyJTv?{gU;3# zW=b~0h{KT_tT7tcLE9I$k{#Fx3)~w4{ho0U%4l_B(4xtrhhE5u&7ovxo0;DY;UKqFTP}$ zk;yivK`u1!bw$b<$HynQytu%{`8l3Ed4g#wT7N6-OJA?PD7*ce8>`~HAXuGLv1myj z`fXrAp|Q$-yg9=_({8X5pBE=E{3Aa7^aX}7V_?EMO(MUv zZl~yGO?706G!=|VDkIo#AY320&X5Lq-+r9qG+hoHok^{D`28iumi5f`>G#N?FNj%@HMC6h0Quj}ytn7BlvIj}( zsEY5kIShA^_Y53-S8V0<5`wk8c zmKZbP+i%~%>G2A~I08Ty$uHYQuhZ)P5yAS888J(Mq{7?v&YrdCuwtL#7WK6Sf=$=h z2J!m~^Ur$t4%%_VX|d zn5GFA7Z=FGfa8;6tgyz*mzTIWuUM})B8zfD&RH@VN)a+OC)~Vw6PwKjwN|XxYYap{ z*=SADC|~v3Rd|bDNj~3javHFxZ2zL_AD7uw)sAdIHryCibP=Olb4u+qGpBg79n>ip z)^Gc#nUy`^Fg$^rc$^uNAO}AcV4O(fIwia!HrIZW0fQv*42@2O^+c>u27;;Bi+$-&8l8ju0x%WBOfPvTAFJJGmCrS6?dJZ#)0k1zM zFK>IJwurB2hyXZ2$G!%`clUV!#cZzF5PkwmWQIcK9SA}LS$6g)sJh>Ag%M)p(#+6~ zQ^BaJ_`?8bo0ms0j1B1H43|ApT8;T+Q_hASL#c0h>Kj&awO9*7EK!IQlu$ zbPl%qdN$WO|IFPz0F9LIy{WtJG2SZ?VH`&g6%;Cd4|YtSzZodD?{|9wPy)C219l{; z@BOd_UKfd4)H0x{>jTD2I5|1O(Q<(sr^h%tT7du@9xkz3E-;k|rBsPvE#{q6kEJd; z+5PBTO4NWx(KK(z&UxB7m^~FygUf`hjU^Ts$SLFW^c0ulh{rFUOIPkh$Vnmt#SuX+ zS9a}u`p zdfB{_bmSgj>x(n}(PYupUUK%9Kuc34lQG`&k2QA2IA zdHZ|*SwJ0N$@Pnn4wB+J3>o7fk)j6&OWZg-#GRX`SglsbiG)a5E!@88u50$YU5_;M zYE7$(0@<8%x6j>?-I;*o05#fkG2+MP{R%tI4i?vDH_$Y_&icD-Hvq-)r-fD-8` z;pq4Xr4+n;aenOq?bmG(G%ePeIT`_v_V~zPuLn=)pS$_*SDx!C4D&BEzKnF$za-e) zY_IU0X_~|#t~!udn&^1>3y8DLoYOfc3^V``M^4UC%YCs}=racl6Tm22dXiNaS}K;j zpTe^$GR$gtD_C&629xbo(Nb#q(BB8#Avu@vbN!vXiKpl^Tjyk@)wD#4$(lCozIq+) z_qc0M1YIp8?KUp)kGkC7jlUvEI+s7gFtoL#+5&mN-F?iD9q&P*hubajoMtB_q7Wb? zHAZ2_C(^QQQo_aT@Z~TfC&G=hQyeZv+&VkOt+Nvl7-y#^I66AgIcZU(Hs(PrUeZPP zMxnU|R}KPEPPAfAS|_W?Woc;IDrCmw0ghK0f>G zGd#IG7yG~pjjJ&?)d7_Yh_oxacN;f>O0Y&ioe~N_6Jd_#iV@geH&aIfwg6DldM;Jc z4j@1|K@S}wNh7$ibc6Zm02C$d!6}ivku(q;N3hxhiO3a{8D0jMui7I~85#MR^WX;H z#l;1fg?QK$ErSq@judMxg!ekaLyMLtBJB{(rq5^lRjU0F0Z^kA8AuT0hbu5(#3E&^ z#sMGw{_o@6ySFf{FTr&KLcy2_R5ut17>5i-1xoSMC27c!o!pQ*b`mk0f?;JOV+7r= z8f;sMfr5%j+pF1j^Jj^HdNRFaT9b&&dtO2Egp zGOzQz&LokLL=wIYHBxu)F+kIyzx2-b0FFT^x^|5)vf%&Um^`Db>$4rqn| zLmKc@X`&P#l{r|O8_M%@R*l$+=QcxonkGL^ysjqG8C(g81`NZ1QW&K$n2TJSI@pLA zV-k7Bb>sEX05QTj6SxlAeb{7}Vb$spqnJH8X5cHPjefIkSOj8}lO|)BTMA?v1US@M zz$pV(pH)xN2o9PNlcZ_e)wA;AyxZTM++~0x_@)qf8GvxyGxOJXk-siS_1>4u1#&*X z`T2#*u=O;daOpA(Y@XtAb@!dr8c0$zQ257!S|&`TfGFc|afY*_ zW4v|y2L9mpe-Ag$j*!4eBxO(rCe*3!T+^*uz4{tz!Fs*MdcDR}qyg7B4mdhK5nULb zQJXVA4iUH%lrXRHx&BS;$g9aMdnV1+v2~2=0EqrfTl=Y$f`jD}AAR%@)|<6N-|b1# zH*QGnUhTY%X2*JiAGg=Veon7G+#5eELNI3d*(gOi+P{4H66^IEhpU8~33&jfNh3tZ zL7LleQoCAY>}In;&KWmv-W1!oRPf`cczJ$-%gf6xBB&N=;zk(2D1bW7tCja6Rx+rx zbpLspvqnN%bh_!y*f0y+W0hV;Fft7o$Ba@Sb)ktc)e5e~3DO~tN*K#?ZgRS%sf(_S zI@{-ah95gQWjMv1aZOG~p?Z~mvESqCR{B7KYJ|Kt8)99=UWoEC%IIBoO{ceJy2$aH z-6LrONFq>9(j0QLk+s(K;S0uF@7}@L$qN754?n`&cW!{ogiK;v40+IA10r9e)7s`X z=iJRhvMkYvQNr~D(7L2Ttgm^4!tFi}4-fId`|o3#CX`a}`0-;r`0O*cyWW2L?X7u| zd9ecQ+lI|NU;}{TP@DHi!0wvkIUerpi3*Qiz0PA#lJ3Vf9IP}0n+wWA{7pE_y)wHz zVgHh2Zotm37ZN|`25?1n?;?x<^tve9z-n&P`|Bn+-9gkVc}qo!o#5Gmejs zky659vB2$Hw@}LlrA$~ZM?8D>3@^`L!lFdY|7W#B9%z7`vHtZraI|3}sEu0XOpK7L{FuAuZvOc;r`upwNMWg^I;4a#XB@7U7>A6kYno}qmWn>_0Z^K-j)HRlWUap zFf1_SjToVuHJ&|xhJ#0sPzg9#9V)?Kk=Efk;`Z#>@uQ(CB#sn9XF$?@cU-@Dg0HvP z@xR8fRBI`xvhBIQiX4fNWmoBHwSdB><^im#RbxRRyQ<`r_}sGr%HfrHNnF z=VYxl;No|3&YHbpdr1l{%ys(QhO{w%eNHaCdf4&PY>nr@lv@|*u%8WJA08fJ*bJD; zrfcl6AHTgp;U}{>O(l|^ttUZfTqEnMwo?=DZ~WM)pP)L&u|ms)nx+Zo=jT{oUW(0L z*hwjo`Py`5$1~Lh31}4II1U&mp*c32jg%Ler0HNSMQevQo#wVb(CUxdIo#wnJHL93 zd)6k6bDU?tM_K94bRtwOp(gj3Fbq(2T*pvMYv|C&xB zA`C(A*lY8-micO#4z{kl2<-V>>ZNYgz?Xk9VhgWJE>?~BH&!63bXjTMV>T^Ds~Zcz--Y9 z7Uh;SqP4Q8Vn?GprG)SO-gofrZ+{b(eDddi{^$6IzyAje!+?wR1uicNh?<8AnA8vy zgTxFXRPsp42)-T2$RB#2uTCTJ?=k}^X)}?6#kj!P*%>y|2A_ZNNM<`r8V@-8wXh$9 z)ksPjn6#UW6A);7tSP&c5;&6=N9*=?#!P2Sg0wGH zyMHr6=j(L6O^*MCh5-_ms5vo^dq+pyBfIKQ1K9f9>yAiBnJ(!`Bfy_UfA$(6aUEiL z>ULX^a6-_T1`xvaTAV{lNlUbx<5$1BhtKZc!}Dj)G31Oq5H2p(c=6&XzWwd*;KL6; z#DfR-@spqY1b_nPi#31&L;H)+e>QxvD&dehu;YWR}R_ zArX#GPO)4r@bJ-Nl=GKTdL$))`#N6wO&A`PpX35)7XfMDm5IHEs>sQtO^8%k2jFGt z>IRxDbv%v;m?{yd6zT4+bKnFzS?%c_SiLIZ*{^-BSM(XMeG>P^2yK>^2V^3A>l^Rj zqaXYp#!OhKuAo8IJLiN&o-m!iFat?cvo#dEf^eMcRNMDfk2U9v%T2-g`2`+6d?Y1S zNXptQ77M)f)?59)2=@^6w%3c}-A&oz@AK#R)z7v$TDR{>epkCLfY~`QBN5yM51%|k zt(#YzYd`*HjYbd3UlQ5Pu+kI)0h*iupzuIRGW2}~fPRmEIRSsgbDUIcGe1@&xzp-NU0tk5Q(AHB~H^Bi_0D7H-`-L(Z*?7qes=S-Ftz z5|!vXJ3YhE@u_DwJbd^N&tJR%B|=FFo6QCm1ku!(>J!BRWKHXAe#0F%>k*C>cFp0O zuuLfheNZu#HCBs5+`e@ir54=#^{;`#K$a-`%JBXHc1F_qlK>!#rtf6{(43>N^Krl` zMwoI#%}hPn%zpjJORxAXZ;^HtK*gp?lg9R%oIK~O`*^prxXqEw?ykMKOYgL`Ct#2! zeo`5G!qGD0){PVVr~l)B$LYy2rZVARxdahmu_W;NC9>%#PEw9#1}^4y{Vp5dfQjf( z2`sVaqkYfzP5Tcd&BiV+F0fjyaCCHp+mO5FXzl>DpN*`a zw(iR^b>#CcgTcP%`-*f!Q9oDLZR|oC|(t9ueo{QcG8N zu}O+e3DRJohZ*1k0|E2@U-b(#z+6$3MD|{5W}b7x-RwS?nY%}v$f{~dmu#le3t4B2 z#lsg{KHJp7$pa7s$YtwB7<)_MpSscd)pJmhGd-=s5qa>IvZzfC$wj)fz&U>ZS!w z(S;^p35wOcE|Etk0H6xI8Iiocx`vWq90m*nW51sunn9dg=!w3^{kf9}E#A1#XC3_u zFB?Ux>ZoeoNCH^60&vD4+WF$ohRTRJCG7S)(5W$~3T82*t7YX%Vza7}_mev>B)C8k zleHFp8Y3i|vk+W5#k&FsA}wd1_KHxc3S68TUamE~Rm22jB2aiRp=Y4xg4q}A>igT? zyYlZ_#=_iJLMXUZ3RWx7^yKOiFP=WZeqxM6!d*T>^AV>xgGh0>yE98DU||`Z*b%7+ z`gLh99f00RpRqT!PV7=?{9q&0!bu^l)N50$1)qOa6cx<#jMM3aW1jKjt5-fYqFy6Z-`{g%hVhm_m}7~)d+ zQdma=0ySt^C`ip~rz+?GU_PII{RX~NTC3+kmnl~cQbL2;w@x?@BVlOgu`|yzZg1YB zI4E3lMxJNndB!vic=qfm-oJb6N{3xba;agEQ7FooUaLCag3*`bA)=mQg&IxA5=`hp zrHDQ_15epJS(Sik8nN5$ES%5jC41l0bEcB{lb{v;iQm=$xi$n99i0nux1f`iY4!}% zzYjpIQ#^fsaw&i+hG8%sDN;d>I3~^!5u!kAz4$!~j!Tnkdpr2s$l-1LR=+di* znSqGvu#v&#G~tV9&#;>krerFvvZ2JP7Gj!Raf~rZ$v|n9rH6C8t^wZYck*$Vb3xV_ zAj0u@#PN6pk$F4Ey|7vb(bfw7e-xPdc)Q<&%6KLt3TXm9r49-O&;h_gj?4PmkL}OV zdYQk1?|@N^;1v$GAdZm+o?0HpW|XSez32T;X)cAbROwYI_qE6UtqdNN(5%9BvXo|0b7n$0Hw{7 z&b&jlk!A{qg3dsw9;MWQMJjqmFV+SUarr%Hae);vy1cru^ev%NgfS?L@?rxY0GqhZ zrXbgIo2OtH%6d@G1>%JmdLys^{_i$1wf*Fo!^a2?GBD&vc!78T;T;$v-CQC>wF64E&0;^G3L zYU#c}C{oUxYI^?L>!D}5hreH@021UZC`IagFQ3yQe_|ebpcHD;QPi1|U+9$7U4#*;aSqHJbGNu6sQoX6FKuFqEc}z9$8xc9+V8=1B2`rTd_ntUf@7af* zs*2^#Boi1wfXoCby)q|YGK(&ALR72=0VP|Wrj*!~(1c+i49G~#7!zTbMo?lD0LM9_ zC?R8qk}gro33qn~ND*A|4o6K;W+X~boXmTe#Dr`BmQ=r285%IZ&h2UA+`>RUNeA$C zA}Syu3{fD#&yW1HCc7nQB9z47X+p^}WG>i^BQVdPc?QW5Dh#4z&muO5W`$`F1uks?qo3jtq@^X~Uo=sa5SGKq#FbG-P%z^z+|(iiJ-ch5 zKR*Ow5#+9D0>L~uYYGX`ntPWkO`1VTkVvrKCtU9*+`Yd;IUT@d#wCC>jMxhYC{PkW!-yFJO0h8&Rb(Nk6bysi|E^fXLWh-BZ}dLp0lP9(`{&Hl(u!^GPjXLS zh|TBma00+6SYo71sSV4>kn8hl(EZ4aKJrj*+-a-A>{!-I`KSoT88jcW8e zR*2CtcJOnl5G8G)l0;nPAe+MqX*ZtCcK@&s7A+2Ht4CqL)5)~89C=)AoqM6Z${*Du zQ3%Y*6hT;qg8ejN92nz%2W3K0U@ioOh1;6`t%$U^!!T4@Dk?y3d!(k<2>^bTC%XSV z=ZvC?LcmOdk{Fq7+)e<}IG`l1%KzrNSOYYFLi*mMGAnYH5qr_Sfd`A!m;q!0QiO3o zwx4mc)EePs*{8dx*|)TkxBqgzWetpO@t@vjApAO`ZOJ&B9(Mpx;(G&Z#yx{@htu&j zN`3?A!9Y1NK~0KzCo&TfCr~mlO!U-6$+;X1Gtwl=U^kKz5k?%ras#MULZ@*8(M6Sy z1p^crMNbeYM2qPr1QZdBgM~rQd3ISD7=i|RST(05e^=S|Kn%m35TmH#q`>VdL!_X9 zEa$Zv&A02?(1{9)N~P1Jih+Q{CfF+4SS#S^#0c4QfLmXUFUMdJ87)>=j#pyxB0^d{ z26Y$!W+YA+s9j%*pr|5I!bqv!xf$+a4KRoka-K1yge;a~CyROQ4r4@lY0bxLAY>FA za-B_sTlw0FoSABKbZ|y74kJ=x$iNWV;V1)6IzbqK3K)a}!YOAYPM*@n)(Ue760t9| zK8x|>QrB)3IGo{$5;%>RMUg!hD-#3ay48@Z_bc8Re`cI3H9zUaeh*LsQTzS5)z*7< zotL}Gl`SP+GZ3sjWEJ6f73UgnCEN#AKeYA;l0LQv*c?cM*8Eli26?!ey7e!BC@VOC zKii%U!8QQS`@9B7&#i@U>zQ_m#p`uDg`BAitsrNB+B`_OMzMI|s1*(Ft)E2%&;sZY zkc^jKJjd~`{|W^y?bW@ha54>(TWFfLPW6yl10YL zYm8>)LDcfcSs09gsVWX-x|bfPc}K+@&!-b!zj|fUOALhP%0kdI%O2HEL|CS+q3~c* z*Z-}Oa(H(FAoqYQVVMmEE(mOr$i_G-brKPF(+<072j+y`w8JotrbG?{#&N_rO&|pl z4@jQ0eMnXS#jLmN0!{*8N@($7S)3T0EVoUb8UOzKKj7`Vw*ZXUGBf__uYQd$zx*Wt zwtExfcs#fj)jW5`al(FLNVx?$Xgo6G^76t#c0v(_Fyr$28R&3_fBWM%xV^o_^|Q}# zdHuw5KNYK9O)g~n+UphRP_EbD(7ISid%br{b^F8ilt92DR-meb2-y1o2d&d?hy7K- z=P$p&?)@I6WE^hqkkSeHaDqyP!hs1j4<}U@-!%Tb^itQq7V_jmX@J}-H79_T$M%=s z2;ouS!2H62%_WdX3tv|AX0ZZ1 zEo>ZB=`+3}V(UJ@!mz$6n%9Ct0JSRiBQp*nka-44#^p5OYCqw6zXx*0i>FWVKmM=( z+fw8ZVa~wKoKTA5{remI&wu`B+#E8B!V2j~uAmW-+bp60hv%fOATPPX2Irk>iWZn% z|MEh6f@X1#GyYi5%@ZZk(4J$CD!6FuhglU{Gj-z=W#hOx+ zoT`Tps~1s8V0b=I=GxETd%>5CZ&Kyo#l2^UVMaPFAT5}ZrE-~N=g z>5b=W%e?w*_x{TXC~J^@IGs+oxxK}kw{KBOKydbyMG8VeG$#$zT&5B2)e0LDmd2OM?4w)3nEB-h7> z6N7lboD07G_SgVUZTWW z_faWgjvIxLm~3si%e_eOnnv4ACv0gC;Ie!*P^m&N;FvSM{pK4Sjz=&NUjE`2*za~I zD-VAFc>Ve{{_uxCU>Js4OevpEnCBV4`qi)S;>C;e{HNafbPDSNl>L6}_hK)1MmN^7 zsXcT5UC-yvQzbmq_6U+bwg=b(ZKDRdMTj0Y7to(PfP93 z1+{bZJkfPe{LTqsBY?fs(~nV0)Es~-L41rAjNN{RtLrQ5$7i^CbHI>Z<8nXX`O^Uj z2b9wZMMn@4Lk(i4RT0YuBxN(8V zXhH)dJmH_utyXL8_0<)KEFa?Gc*Ho4;FQ3eEKJlT`>-rWPR9Vim2^RGq7QMrN+hh^ zpfweVdTf8mEr2C<%gow~bR8zugFp5BjWxdXm|ur(`@Q43KnvHa^bQVSYBlQE#S~E` zt@0T)o};V#oO#3s7;Haw$Mrq3CNSEXy^=9W!Tw^8tLsbb_ZI*dyZr@ryS*z-1Ri!c zX2#)gz}tPsH-9{$%*DrbKoLR$0A}Ry9vr-H3V;{{<0*|uhtjCfgho@;lx=j+YT?`t z_`1g=6y{a48_-Y=a{kl|b#P^sVAq+IjsE#>;nk{SfEO#dF{gHK(Pc_LO)y1k7)R`; z3Bx#I2qkt*7>5Cu7Z*s0vES`5jT5deE=-A4#W)Ng=P5h?JruNA1myYS4E#2*JUOUp zu?N}#=537+!(a-XIDko}a7TfXcqYk~0)W_*Q$hiXDZtEHd9AZ_SDgF3<7;rW=VI;k zIevTK6hIAQwk2bVe&U3*OI8Km*N|$H#kPRYx(`=;s^24_+-~I?{uFt0>v}b(Ap&cn zni4}*tG%Cmu+!khH>;=DWBYkDHzsKVxNWaD`V06PP%@c8yLs={(}#e`Pi_4k>5X(f zpcBcyLbVEvH;!9ZR_|Y}gW^R~J*L5bDbr74apUHtVRA9>atb?S&jGQx$hXbS(qve%1N7@$SE3Aw}k)PV< zU83#-Oct$t$oiC&!Co9y6%dezOWU&%6OcNm8jfOmgQYCnP0-PtOfDv?Tz|2@z-}Bc zqyf8e1S_x~M$=V@vD;0UCL8adSH%_p}$MBzFR zW)z$}(lLB_3Irq>D1xj4;Ldot2r@Htyo8h^vK(;Ax5%d>E_PFW-fS?%jSCD2+wI^%a8|LOPSB3(eYhive1R{&c#8R}U!&v+DP<%&p)fF~gd$5qo;`eJ921D9 zRUfS%?B2i>Nisb=(kzwiA&VYTsUc#JTY3W&@XCv-UV*v^AS7-{1VKn3k^jfFGz#FI z6oZfnOSQ;T+|7j}1y1mL5Ft?lCBoodJ&6;NMX+Gtgv17*PRW4N!M#3`KX(oJq!vnP z;euujWj#TJkceP-q=1ToG~ugXeu0!PEAl1F!x>QGg-x z_BG|g6dbima=w0>0Md^GRM%fWw!gqeM75yGnl7)uyWd;-90ctZ=e}@9cR*b}<`Eix zF^ws%jbIH}YThmZw9;xnuKCM-UJ6T|!{*gfd7OD;1W5YXXP@EMfAwqZ_d6s`?Oah5 zD2f233`iunzE1f2|MRbr=MhB7JS)LCCc@lRdlgmpJQ54>P9uUaOQ6M0A2>n`1A%bU zW27>Pv49vIB(fAHk?J6n)dIEZ)NWiOaibd|x3;2CY3qZ++ghJf@zxY;upWD%K2maxwJ4yQKc&l0`1qj?FlGV8oDK?-}nAgTfeT?>&?FO-g(9i z$7~nJeP~U`v%rlm_O8i%$KwgF-@L}*aHzQtQyOu3afu=`az5F)q@J3C-P2sp`q4cV z)?=!{7nLy%jDZPHpCqt82hrYv&H@?;nWRQNiCS3uZnp!c1Og%PCif?MZ~7^tz@zkX@klRfmLUZ+8K_DQRPBZVL)A$DDcM87Bc(>HD?5H5#*T(6 z^P0oO=*AT*NO;oXk#e4Hi@AcNDJ4h}C@DrZK65cm*o~9*L4g5;9e1+6>uT(@R8%o5 zP*lLAV9B6-!XO!3X0QXDA%6ghR0>d}$}A)nc|vOZMO2}=V1OcxjI4^nk@C%=HtufU zR#&zE59at|$k3j@T5_W8qTk09w|d+==`cB}}7!o3!}DAK1`_W!r`bwl`x*Yg~W z_g|xbRaNxi8u8mgU>C18DN;kx)&jTvNd-uADL_5}t`g;3Fz1Zywz!<|g;PUbkr_%|)``zzwcQ_yo z3G>PFP$>-179kUc5#ALZQmV5H!l~P*T7|GG1Je03h=^5iefYA+e~;$mq6bmd-fcZC zUa$WxqrrlP;~qh^|4vc8;qC)7*R;L|nbzJ0_g!P%;=Cw`2at#Iqbf}$XD|x(7Z>>A zi(k}&IW`8KPcxaPC^KQV+hbRr;OgSSBF>3Gnn09rN&|8!n06D07 zVu+_dw*jPV5W zkx#`GQnF`CRG?54IW72&$fQQ z@7Mq{`u(^DfBite(DK~=*l`$fb$R(`m2Dr}b|bLkVT_{grA}Dn!e7cRf1-Y^)^#)m zY9UXho-}<5KG?%W8CVulxw45&1= z>qoqgXNgyuO9JhFt|TjRlB- zr%qGNyVPnTpaTyBcv1)ZB5hg;9n9s!D12%%w4FP6B$+)EgS7x+PCn$tb^-t;0OLTI z(opAznN1Jy$txl_obr-}xsk2%m()C9L4+Zh_k9rRq-5T&4w_ak<0?lej>UMs0n~z` zGbUCHIzu84tQ0F4%L&4=$fvC=(9z~KmjW#XQODldIz|T<)p_^vB)Gjh;`VOFv^!y9 zg?c!B@Ju0r6sy%RB!-G5FNwU?>opXwy=)ZYI?pq{`|dl4DE{Ve{sy0a{yA=LZtze4 z^iO#8>J?tTe2Hhzo;jbieZJrCadmZ7onHuEc&n6!Aw2Sysv_o;!K%k{sO-}-ab z@@Ps4A}xn_&pSVr&po8}2$DXwhuJCs;+xuudnhZm!BNXI29UZXgno?qHyQOmPB3~; zhx~DMy^u2+?eiRJq3}*r!4b z1h!wT|IF@zXa%P-$OYrZn8cO1Sid4>iG~0cd~eoMi=Hu0C#D2Kc7cf?*%IK7N$~Xg z0>khno;`aCQN{K36)rEYa5x?J;b@dcRCfgmREiwn5C^6H5~CPMJ)r_IX0?rVVckL~B* z*6Vl;9)>|B3{N!&c6WRQPlJ|ifRO8Z-gp1*hj#td@oT{zSPH-E`+w}7Yp}I{Z3PJ; zQ<%|!C>RhST+-3BQq1$y!q}QePV@Y>bRr4niJ`@cM?ed-xc5H+G8 zz|rQ&L;SKfT22HwkPE~#8ed`ON$AH`4JA!5PkwPwF#eRhmX(L0!@=2l9ip1I%>oD` z8)g^*(Tr0V{Lgtdv5#%UPqL*R@atP4NH@H2LiTkCp-PW4!^1JD(jP)HkJxgu`)h$p zG4CKUK-sPjPq|{DhB=oCgxHvQE^dkOwLECa`)2uMt%`k&ck?`r&_8b!)q~Z+f7ErO zdJd2@d8$Pb_4|N`FisP6HUn5L7D@2==bwX_EuZ-*GNn0C8G8kk-dTgzzuZ}%yf zeftooYWriEex^PLun4n{XA95Qkb_GpIC;qCWBYlv#d@jx-9a?O_i#gvHgWS$(CV53 z7JLLweS*c|p7p!g!tUh%%wt?J3<;$OZg1}}47Q;qJHJ|a$F+1@W~JW>C0^We1qg+# z&diY_8bpjC5fT@mSiiCqOK+k^*VrMsyZ4rp^!oY<1|Dnu0w5e63@oiVs43)gGI=>- z#g(eZBdp#ktipinC;nbb&|S8i(#})GpJhsx=bNb8`_UI7unMFc{c5m+qY`1$PGH3& zPMklQ%$&@)MGVrx^dOHwP$3jH<06=)4MQ$KM;=#fe)pERzL&7+4$cYVTP*b4AnWKS`E@rvVL@_7Y z7%?G2YE4KP;)_Rj!HVw($v>&YOvq-W;=D56Nih+&*?adm|+ zUMA$6F{A4TcpUEd$B&erLCnb1 zmU4KB+H(`gD;QfozTlt+idG+@#oFuFVtZ{N&GDC*k*3M$eKC4}b#;ZSt83&upP=U!nbP(}du=l2$8gGCxm~~SpQ&GZA!DrRK~Mz|!CcBu!m=LQ zpP*^bWMEq^$66&pC+RjLFM8Si9vS~rx)XW;0Fc)osL?~Q=U_A?`am09#CrX&zIXB# z;HSy-38iG5PA8;fM))GxQ+P=Qae~1Gjfk`)_Zjc{7OGju;OcTSv4E3+kUV_e1LOtZ zG(c4`lNseoDLCHVfrv0ZP1vPy#DU|1er546{n}sOlN~)Uol3nBl=FR%=SF+{j9x_KYVH0OI+~UCxk<*ROuS-R*?SiE+F;;raD5fM!Tmlv$8x)Aw@Dm`^86 z(}dk_hXB*N6}+IeYdL=$Mtt?vZ*X@w;s5)mf5PqUErwyh)2B}>NV+t1spU2wnx}6O z!QGv$u`O^ESOS)DrT+U5y@#)V$DSARV9P5U>$G>8a)*x)W><3YLu`*A>0^7C&4vH) zK8cXEs=%>j2!lpaXn}}(M|3Q|SNQG|JmTwW1;&OTd(Zdl-?oI|wL;tXYkiF+L0jHq zOOfxdUlncl_@D|L`yZi(zZ-9~}glvH~K`1{^?y=O=AUHo|P! z!-GItl@C+o9qiEM{1Lf_XaKkYka{Bbz(oqwotX(KK(-Dbv)pe@*tBqrWPM)wG9>iB_iMF({gf5}dPvk7xkc+jhARLqJUHiEy|m+RoF)%H z={$niK;QtfjgkPpWq2X1YbY8WP}Lr^t>I0z?pgG7-a74RZQj7*=jXE#q8nD>ol zu=mTt#Jw`G7T>>N)bar*_x2$8oHQ`C_vlwY79gmHO$NW-h(_q; zB=~BoKvO3lmSW%xoLAOoS?%>USMDXPRCz>P6L5f^slL|lHP%5prqP$yugx&~{+V$P zJ%WNYwXu8P3hiH9b2?XPW&nR!dYOfMVjtZxpw~^%z^y2{hYze5ph;D_`YvdF@FXIt zjvw|rYC*b?dx3Kv66DyQTKA3CmvxlBnxrYIb&4RT#O$v`~6e6djOOenw7Ujt~W6`J*Fz%)RokX!X8CI;(7s)rJ#uEc||io7Uo_<-;+BUKwxQaq`q%@ zLztDVFHwBT^f{mqAW~2rToXW(rE(Y&*R)@RgkhL4qzqMtWa9-;hDctlot_`x%WGD0 zm5Al=1`JdmM=M@+I-O9wFq7dBR-`x#;?>hxEedm;-epUV?{%kTi~ZR8+P}IYhe&7E z@0%vOI_IU}eGD^NoAEQ!C_Uu%2$DXw2ih7z5LXr;VuV%E3R<{eBK4f*hF=qwO{VXP z25@$|ef1GxrN2ihr4qv4RlXO}H?5`4)HGb?H%DW6KU$q{QV#*{R|xf65;`=j)5^>Yo2pPwT6+zSTJ$N)LqFTSl&>0#X>^M<;MN`pen4jIS!!@#&})H zH32rP|71nYeW*FXlaNPlJUeCyut~kXTbBqhs@=DEzDtG)19eJOpqlGC70+E{ zfQy3?A|@ySkTT=?`VznW&99K>j3Ne1@1`BDF0P@X`2Fwy4W*dpDF9HK@bVYGz&H+I zWH4oDJ^*qAYc}Cdn-@)E?pg)y`}WCJRp6h}0%9^z%hsr?`PK7_JOrOqK%&qBKngDR z6XuJ(<)>3YzPkmT?l52mC;^Eus{ouJF0ru^lm$iA!kRh&!XBBbreQ{Rt7dIWOFY!} zQJMXDHQO`nLhCxm^8y$I)q*~$rVIfbaYXegQHA8}imhCuV_nGxun@$1P-x9lidQBN5RaXf5W)*Z0q0ffDJIkgrhX3K(u(y&=(pu+ zV=z?2iUAoTGLL>@tE#T{ornTto}{dR%mrX^P{@=q#B+2!pQ`L`+}#TG!RMvr&7TJcc=W zfhpAEK+UT-a#b6T5fCRI>(1-N)6PhEz6afLr6@d2xfBdy#xg1bi>$ZegMia5gpy^i zkrDxfT69HQ%qY}(Y^iFgtkC1EiJ? z$Yz9@Yfi+AaYTCl+$&fE`EWof1uvdF0bc{tH2Qjoy&oW^XQPh2hw#|KQk+z(=he`8 zU!4WiyscU$jynI=_qf+qGX*F@Bs2_%yaAr1cGUx zmQQ08Ok2Fs|`#cT_ z!#F}Ddo-8rvszg@g>R!+O@Kgaoi-Z~$PH{({~mT&5%uHjDVYj{1*Ob3yeuG@Z5#*= zY#I$4hGvM9$X@vX03ZNKL_t&pJhwP9inM&snVfG)vHugkV$bkh1ad|W>!WT%@gze%`FIutKEQkKH~QF4*&8m|AO~7H+cE- zC9bcp-8*_f&I!{rVi-n*(@Sg<1DHcMZ~VseDhKW{`pH>U0K0gi%dH~6_}=7 z-4hm_VEXWzH?Q&f^&4ne0<|e6E3~D6oQ2}(j2c>1s?ZP2;RJxBC5)6fLFCZj+(+1!g(pJ00k5f z9U+CGvNLcl6Xv;q2Um_2AW9$%NIHNC5S}e`PYM!^V4hsDv9RWp2*D^oiYz7!nqc8x znd*QOMebOw;ew>@)fd7Ep?UXFFtG@;G{v6T?7mGH38^Z)1i3Q97ETd>-qw6J0i^eo zGI@j>Ktcvhwo1PMYXlb3V$LfFTh|^Sxm4hT6xb0%Nib{7sRM6pf(ATw0J)HD>%qn% zcwWfJ&;nJ$<$l7|uYcu$i6T5zh#2qRzr(-(`yX&R9Wjn0RMo2IK7WF%i)TaQfYMlZJ%e7X>khX|NP6uGVgHi&~2uhY?R>`cx?6f63L+Y|n)V0CBF2d`ypncc9wEIaPT7GV9 zi(~s7rD2>iFFF`#NL1G}sO8-?azaoSy0v?*9w@c3($HmXsjC5YlCybU#&bm<;Yywj zJ|fSu0gnc9N>$YScx^?Oe5+L&YnMU9Dfi}g`?N2h=`WsEI_i)sZ}nc6u$z!rwL6rg+XwBT3aX-xh; zAUo%uNrAyZg}AT*AwxZ`0k7`Cgt(Uhs6p=|X4Cj@Fk8!k%E?n9`FWr=e?36hD}T*^ z>>vhdRrYEqAbQ!U6-yH-ZTw)1QK1-y0T<&40Itj)Ai3abzjp<-<-=~EWq>lx8_>K( zyFJ=@hRMe7K?@=`{#yQP&x{W=1;K!)2-78(;{Y?-Sp?7{SNYjBaxcEY(mqw7g+iuB zrK?qZ1DY<=FO1c?-)v3`*T<}7&HkDZZf^jf05J*mpv1oJW^ z`(PE<6A~w=7ip8y90dS%&(X%ahMpfXYU&ns8l@6uEu#&Qjz0RytPq_oXD7%E)Kn_% z4o^w~Fiznu4&0>e^Q z0Tzs5{K4QG^Qtt!%xJHtmFYBnWl$STw00o4yA`+M4#f#t3N7yLUZg;ayGxM*#ogWA zDK04*ic68=5Fj{T-h1yilV6$q$n5Oy*>fJVBGgG>xj3lv?u`Zs2>6FDckB0@h0I!f zF=jV3u~!vT=t%dA5KFh|`k-ZN7admXtfOM{TifGr*R08fB7~VmQfQ z8h5aY#&kO`5GH11YP@~lREDRHH56u_sgA+(J@h;^jAuq0m4dZOGUttXC~g{C(>Nkw z{U*{U64%gt?(8uH%6lcl&aD5tqySmINPLUkBG~AL=x7vX=ngF2+|1XAuu{?r8fqnJ z7As8aiY}eHxY|C`O-D?Q_09-h!md}H_GtXyBoljnfo=g|=TV8;7fa0PFqs5=_sPpb zjr?R@aGI4U99b8)oS~ydNOam@W%V^F2$6}Km3W8?ZYSpA2%^$cq@(MIaVs1(V9H0`M=@mwy*dsQTok*O#CI#5_Up8TZ*!SAk* z5u!V8c=n@UEh3W6Jy0o6Mb0sqPr8$kgp^*y9BQR*+9g3<{o`92PI|$|0lyA%b8il= z!C$_r=I=pFo;MC`;=sqpu)JXjT;!Brr$nn?E3LS!CZJst=RO=Dpk<`S(hNzUgq|duwjdE~*BN~(Po9e3SO+dx0ceAHOLRGB4)~m2b&E`g5ap9C( zN_F@rZaNm^2<&F0M|DqY%#>iqLyIqOM`$olmHT^NKJE3U zLgysok+)Pu;RriR>!4$uG-t?}OkWM*HXZjzu+ZPh+Q8#;yhnz1^p<6D zFDCAsb@8a6<}2Pvu1g@OdKZIG_C?+mMZMq3enXJS%MnL-#Fw+AMLMlV(EVxnmFSSY z5Vni&U=AEn8_G`@Wl+&auz(+>U=~4%q(NF|e8!X6%dhOpCIs;ZDjzIn( zoTcx&Fdxis(D`Et3C_s*J*6fw6sNrHU4}7zk_Q`lprWRBLkLPs1AFG@nZ@~xik&}A zw#!T-d&9_$HeqENQl`VlNY_beWpGxaEfH_W3C{asks>u^M~jHzUfM?T>OsS+Kl8SV z*%uEtj@^N;)N;AH#4%v0SIYl#v*N)rI(o;9>(I)7D&ZW~5cr)C+tnq;1IM;zKy#$r zCR+~=E7r^nD<;&O(35-jr}fQeDy12gKlB%J7&wu@kp?r$x|}*613{%!@NIYJxEV+- z-h|rPCT=(C#Qw~{fw!`|wU&08S4bar-i9^5Z_kJRnpjJ z#-TGb42gjprxjbnqDzS~=+!vg3?;fy*ZxI2`<;cSw-f@Mg4}x&8xPBPx0ui!kx^D$ zm%GNqNIsSj7`EV9usXLSBN9t<@$dT~GMGzRXRGLVg=ElLN2FoxXgn4U$H?&z#t^~g z>bX!Ycabd}cPX)AGOCwHB3xV5e$Vc`mn|czC3@%`+|+2d!(txk4(vlVc~7&Gu2#4- zVGMR^1^sMyeuF7yN(oT&vNo4#sRa%+H-|5GSdm(MwLYXX{04J?2%8?5C*_o)_uWss z^nWCaz~2?#aTVS=uIn3tCm6sHEgmqOJz7h9r^vvfj*Po&z^h|;+(iRXMV1FY7^Q-R zgtVF4_KcBX%^HkJ~-tDB*?`4b&$UCn|cx{ozz zaWcmevg+@)AuR_gmtKh)BS1SPl91l!r?zJbfnr^X)?4=;llN^tD-C;#_q>T7$1DD^ z$Jc$_2vbbyhEiFQ82?g!)Yu-zI$T3e9`$3&*n@lyjSu|)K^hx4OOf1<;v@p7aMc%( zB@7Y!PbIh|*$t%QMj)9G7i{Hulrh2cp$)@!%?MGGH{Qa#5A-H@GefJpA`rjN1AQ$B z>5deC?k;XS|0VnjZl$h2gN*p+K00>x#WxpNOK=smo;7sU&U>P}BfXffqaxm+gv#2oeS1Qfm~49PA;>x7%_FTS7$*;P2X zKsz~a-~SzWNe#EdTKluSEb4E?E!Cx+%^SXZ9;a@SxSf%Eoy*DtN~nrWupw!z(n6{C54hO4Y7>rt+x6t&s>RPB=wqof$;G!U)PC#+8_N4_Zh~ zuGhLXd@(5~?z7ZhxiD4WT#^~>#C5cJuT3T-9l>sH6cJV%ZO@RVT?Rd$ETl==R9+C@ z-QSJN#ucWropMK*h|9(-yu;=H=tU2dEjmmb>**nLBz&TCGM1JGMO~-|*ih49hL& zO?uIn6iRb6+v$ZFLJat4J&zL%X}U_DZa;F(G!Y*;wxy7~IJ^aHOE)5atz9};`f{2f z$zP;+65IPa`8$4cQWA>nm@+h$Q2D?XGdTE z%{}%?S})O@eka6fxC(K79Rbcz8pYjwHLG}t#Kdg+Mk9bh*F36gc)thBv|I7sOz1e@2p20R9M=d>WW z`>*!~B1o>i6>9;n$-ntC(dhcf0Pre*uIE8=l6YMb-xwWzY;D1jOa-?bU;!!-*q;S~ zVY7;+m&*Y!?$~LYCt+s7$caI~F2(^-O>qi=ss$NO9Qt_0^%7FP#0W zI=K5dj_rV6iLx>cT`R28>QOUp$bL0Wz1q{`tXuDMQ6<=2&$a#(xYX?Z>Bo{^VZus` z`>NpM?(Rk!*w+y|_|MHdnDAOMvQM1`ndzr`H#U(sIh-0j&P6Ua`p=m?@9cluDE~?0 zQDKNGV^ft&Vl)g~g1M0;&H?C0_V!8^-&|ZOveG5hG$E%S7Mv)nd34MK^CU+&Bdt-L zUA#Q|!q4X3Pg9HYe}*PKKJn(1JfFnMQ$#mJ3ElR0>eS(N8wWVkjWF~$X}Bm4MT z7tr+8EJ>%*uk@ZAa2vtiv{UcdjUYs={t0Roooz7JTZ$%Mx_z@85nJ zw|wMp<;llSbI0KLH%U_dr|-4~hI6!PF+JE?cRr?)P}w<^_9r|92OGud6IK6l@-*#*NfJHFh$A$FZi|tR-1{mNb#1 zFqDe6|F_^;`L|EsCh#wDjF?N_Fs0_3JhHz0HcyZ1-W`!=&sOQifTzdD>%NxX$9rq* zqnfRfbrM34l8fgg!`RPV`7KCx4NBK?R>KoIO6;yU$+dYcY!55n&xw1egNX6tisYH} zUKtkDX3pFL5>DL?AG-uegS543J7&7R!Wru+$?{l--YX%VnYp=Tb($mBTSu8LHINT| zE>cU)69AGl&P8bZIC_AYp?jXk-so+a)3!P`hxKC(_*K8d**{*;<$n1l6o&vY3QDBL zo>719-n{&nxsDLZp~|i0CQhBmU%z^KxdR0!MdmgL=cj0E*XSm9pYcvoy-VfLpwhv6#6Ji0b3uW1 zrmfLbR*9CCr2|9+_j#<2+x3GJK4Sxr6<45p0A7SG0r2uEiqR1c`Qy=VGZBdzB|jyn zaK?_s*Z(qMA_hQr=43qI8I*GAhQ;5liXKt9WJH?yxCfQSVyjM%|r*d^boEF@-*!+-}6m2WjDQ|<|i%(pJ zXVU@TYhO!tY}M+H;e#6&+p2x@mj7W_jFAK-A*Owc0aTL}7GxC&3m@xNmAAJx`k`4l zQd>BqKdGi`E%mQOf(ocXSA;V2{IM>h3lPYr&PFINw?xW`Fk;hQ?^M$DpC74N3J&O? z=x!V&jyB3!zz%{X1)WJYAk1JphfM7sQP!CH(oKA{dUG`>)V*XdEC^3%CY5!IGJQF7 z9+#E>v$#RK-|K2xa;u~bHcR!RTkg*j%0xHep*nk3JUh=^=c(7S*4{v7yfPIY6AW!b zx?wpj%)Dv|Cd9)-DHnuPTP$x`^;f;v7PH-6qKlmkf2o<#0`zqG?m0f*2$ucr@x6tr zv-Ec%024Yf>L!?6l*EM^XB}<>D{IP6r704!mKN~&B>!DQD@tH%fXlE|+QC{|t*_7T z`8%{aTf4nCsT(8D+KzhGeYOyfQeC;{TITeh7P<6ioRyVh9kfZ8gn0Uk9yA9^xJzB^mWS&?h2(HLI5Sh=-fa~iL&9UFXn~RMU=R3K|YB#c5+``;Z6XOi`1nBpg!x-*AL+B-U7q4jltagz4ytvJ|}&G=DMBt8G`4_u7tB_Dw0

NUutz5Mneu7{DjRq^8tjp7r%=MSmm1D`;yZ8(RC$ z&yl>4Z_Bpqce}e7f~eVwL)+dNt55dRc@(U_A1H^-T6VRky_mM;SFh9}+yXunHD8sJ z{S+i?EvdS*TRgt*#DLznw>31+7o&dEZB7=K5+q{3H(is3SMu_MUp@pPMaGUDp<{DL z(J}G%o@vpx4&A>FJNFcDf8*D)goxXg{|&EQ2KysFf|uIs2pi}%x0eaPzor&1(ds+m zz`Mdrhx|6|A4RZa4IMXB%I2A0P0tY?dk~6`Z~CZ5U!M4ZUA~F6dE|OCyZ@&I37QT@ z%irhWA34dZ2+l_+Wa(~>WzQA#6*$x70%#$BXJcqtbz#TM`wjh`!Rg#I;E@(K1yVO4 zZ1_&@%zEWGfDjZMfZqPb;x5G!I-ed_z5Ywnt)LLHM$M8SvF61xD!OQW`y`Yw~#Ny|3r*PC9` zyj3aL9wE-u9wlx|RjtogNn#$xit4t;gMU){5fTnv-YG;ADlJ^G@fZWXDhET*H`frcand`k2#k z=M-26D7*PzG2Rs>li~~DwH~a`mc7)O_QiVe+dk#rSUNtD?h-s@ui5R3i%~~L!Rw8~ zvj5DVDuS#|BDx>XH*Ml=kf&qI&zwd6)ftBsHVcrK$-NtgfR|Siwo_AQLm*YZki=cW zAu&zoW@N2@>$%ZU_2RTxWOBlK)z9s1))`SE%(8hbmAKev>Pl6fkOocoTa6eid&j}- zA>G7%vx)0_xL7jTOmyv+GDtno21vN<@|FV`lxMk88~E*8q<3!ofvb##f*X&s8BlGA zQ0-X~9w%lez9f}=6B1^G@{Z~)^?bHLp;(o)MDhZD}mcDS;Vlbj^Ocg3DvU${bToKmt8aJ zu3hItajx-s8Zz939lt5g5IS+eGB?0NuW8*YSsy1A`@>+GEe>G&=m-Pe4Gi&Y-QJRP zt>Z)v{bwXR45#1x7xW9*XUY+MmX&jL_YF<1c^TN-+oL~ff_*WD&M>p%MNz1&oF~=v zG%UT7VuUPs7T}sDcq4tFSp_;#9THzlZlK(06C?LyDebERo}(}1Sr8ZcX$QQm7gf*h zC1f;SC8Jn=Go636Cdr|#*8wd7em{uKTW2RNy5(1beqa)%AdMk^Yy0K}-KW~u&reBg z$yY=`Q=Cvtp=J4RwI2K1`>Q)`6qfq3g))C`rz zNcxFF&;fpz!=%f`M%$6+eFHGKA;7EcL*OO6{sZac)jZ!jDArMOyI)T#=7= z;;nsQ3bf^igJOX-9>d3@paoUqu4jqXIFV;wL$lS)nVZe`Qa&ynH=PNVh_0ABZ7noy zAklp9j!KfhelkgLlamy`!R9wS*s1^#bF%kDeYp3`vxvV?==EOs%HPnN7MgR!TALHAP9!`8BxJ!02c^Q{-7x!?=?9e^9K~wKFbRhUSH4T8#5}f@^oYs!EHMU zQzxcyt=YI!Ad6%10tNlXN6E#zf7;Q17_>7~GLzcxDR6)O2s`cY!It^-mR9nmHP-`w zI~ zb$(vAP3LagV0c??+mpoKpLk{~B8J{P5LoGV6g)TJHR1N{Gbbadk+I3n!J+Fn3yAt6=pa(y0*l^g6a}4LF@&45VM**0RN**Oer0__Wb!xl zxhG^%;`goyT5g~r`}0@7hKX7h4NvLv{3su(?tMVZTF&i3vk?*PNDu-N%8wEZgtsSU z=ovxxUOb`|F~uXH`Zab0RbmL9$My{Y8A)?N_DC$)WLiA9==?J8rT`o(_~Lp#1gwhV zSEDFBx_bDPa(0`a$G$pt)IB@HCcntAl0zU68(J>pckkZe;rqeXzujGq(zwCHSmAO@ zh+pO34)tiXwzjsrv(|rpK(@ zdEaeKBL6}Jp#$tMd;d%M?Js2pRN=b>BM_Y&h7Edh2U_#Fh^SYgz5HnHDdf|tnc5Sd zI(mBpPe2-d6ohM131y;a0`s=!Vcb!s+LdT(RCr6j(!gOghu_hH2sI{z_sHEztmr74 zLhKaCF(UBEyqhW0D%uG@ge03S0SOdNZl;T8|34Q%gbqK{iw8MfgJ~v|nHE!tEs?LC z&n8GW7^L2PC?_+e&C>FBLZ<0U9jGOhzOvEEPj0(_Xq$@U!7PTd=+nQIsyJiC0vt3! z=_1>+f@aj;NAvsI@5R(8Rveh6?RQIh%Y`L_EV8-n)hREzE`7jI%cTGpzQbL2AMxGc>3E}G znG6h(6i5DS96d7bC@8&BQG#;mZ9~S;v$3$K=Atep)X|hKh(7EO&&@vO>g3JZLYzn~ z;TU&jZAa$}ib+6@{zw>1k9!T+5$; zaJf*@dt9;aWA*v+$UTv3ncV(kiW)FV08ZNcxC7FafSL4ttG9>Oj|0DJ%whwq1V!30 z77WIWehb#DJLT-u_X~pX|?w*i2|q7%9bPn-f{5KNekrAZ%LzpDgll@^o?Q zG?Ak8194PrMi8M{lpEkcNcSU7a7@UrxRiY~wP_c?hfg1nuqhlG70J?mFdLa&NuueI zi!}YcHxQD z8jbG%>6FjT*zgQ`6tw#R1Z|X!jyaa-&2?UZaqZx5T1D@`i*ao(n}tMBoOoZ9-{b&0 zKiJ=K!KiYQpA#awiH&tCG$P8OQk?NLSXJu{HBhJ1*^3Yp-?n%lVj7QzwTKOBu9NhS65P>d!UD%Y*DxR$c=t`*W-MNXrJyw~H3NCA6HYTwC=w}Vmc&$E7 z6=d)8qUI6pQN_Khy`hupTVd!aGhH8T2@tc+EM>sK{Z@%Jh1%`+H5zPU5?T-1$#0fk zGc;Ww3>l^u_j4f`*3MHWmkg_(%bxZ3y2PNuA_>;Yjq&m4u~Q|s3?X>|PIx(tWiG>N zZERk1j94Y-g~ayVgZ#p+@RZ}daDL?~2oqVFu)rK-u7h{{SLW6w{fuMvTaLro6J`5c zVm*G5@nGSz^6rZScX**5Q?Qt@?}>!d_?R9&9#fA{g0$MU@iuT@ z^^&p9S_#7;EOcH_z2K9(VJ4US*gt7GaRaQc+=rf8vkn+~8Zw#89NlIgfFomMk^FI% zQ-1G|CcrwfIeYSHjnshjAr#^)oCz<~`S%OIiST6Pd7fXYT`K*=J1W}7Tu$H4hZ@ucJ3H(|be1h9bBsiigdXbfZ; zs4o;!>U6)y9T;s+_McMje{_d%7a92Ky2E8ayE{9D`hC4pVdUVvzJBNdME@0oZVUdU z_~w$_^g9E|zq!ATGZnx;mRuuREaRQcXbf|S#`M89Eqk+cFgvRvzT|8Sl z^|Mfks|qI0D8m`d_v0u!W1O`KkKEwd4kCQ+HjR!a9d{H-7REzMPYSbme4OkyW2IM&qe^m$Hh~LD_Q{WYB%spIb)C8|+R!hEy8q7{l3g47z!HhMDCNb$S z^{V6rItBj({yaBUi_9y&NK(^bMCMwS?8SZ92PNx_#?fjh9}9dEre+pDfu)m}k+qSv z8Ujn4UJW*Cy1z?Qj*lX~a#_VC6ecAmSH`4WKf0Z|zqYkK==Hqy*%Am9O*<{!m-hW|5>g_=29b8CRV%?+BFXZFb0!Ab(WoIKlEEg@Brt>yjUM3 z8_q4u_;bIOp73|&7i0yCTSrM3B5GpgY*hU${rf)GbzbR@%sw;#L)mc*|4bY>4mi#i zPpu()|KX1XWWhVjIIaFEa7CD1ioRZp-(+gnBfx!l^$CyvOSG1(Hm{2B6&%;fdiT!z z6RcmD-!ijQA^1jykQ`*AZ85G!tP--@Ov{Nm;uZ;olG9gQ8hw>-G1V=3OgQI;HTvs1 zTG4|K9CtP9w((?idVA_ezIILLDhskK9C-O}ZWulGw7LW+P1@=npLn2AY6YTt-7LH~ zeUb!W91hgsA}<}gAA3I4K3!KW4c zS@LV^SNcBrAVMO7T)2*1vqV|0If2> z{r;^#>zQ1xJO4b`{$>7FjIt+7^7_$}*bwyZJ$IH((kX+pD(yebN3^U6!uAW*@B~AK z111~&`NTER>U!sM%P08?&79bZyDmSw;+%f|BxnxH- z`{)gShUD@|hU|0QvcE6W+zM0U>g|&w#7#EwXPb%-)sr{yFsuj{hX?l)@7g4;lj1S9 zX1m&$d(vio1dP*W`7*==vDutr4XCE-iMuY1aPaqVT+m|D^-Ag~d2O#qP=r@yaBIbW zVtZ|xzh|OPL?~|A*?X=^ZG6alqHf8LlHxfm#bhfJp*{X7^=#~0GUHbMY=oK^pz-eL zQoDj6L3BFX1C3m+6zi+j^HErLK7C>QN6S<-9buD!FkF8z+-4ENSPj#=b*8v{q%n*VN4JC5Mn-@rgk@GBSJj!!mORNqO6VLzjR z11rhn>df){3ty=Oji4y9eLRTGWtGY9Uy<+MuJ4K1-Z)Ajc)LM(&39ByX4}ZnZ5&+b z9?WlDoG5iNEXg-ikO4p}4K0=Bmtj8Aw7EPd!a|3$;;U}h)tNU3rEIFx-CNx-1a}Vg z$TYwBJqacnRMsnh>`ZSql7??6W}TGem^#c;C;dE@ANX1D;OB@JD>F+J2S03f4kgSf z|E4zrlrgc??M#MZh7e({w&g*IKY{>l+`9d?`OheQEm_gs#g}UdUXZ~2w~sv&LX&YR zHcsyh;YZy`DC;RiN$7S1$ec?-0g@B` zNJ#DM0#C-+&PNIJInU0^+dY3dJFoxaqyy8xjWR(HJNDOm&5`;x`Ur(SzvNHsgWDv6 zi&akmQt58-4-m>k+_MUj>PlM5fL6b z8h;RN)m#l!qkqAvg~e629^NMaOKU$mY~H**kT6yc2|Q;GV&9>s{^B9}-SPZY()=~F zQysJJyH5aM;&7cK#$!AfLJF!tem3dXOGD0bE4mL%lZPQ<+DtMDd}k2$UR)B*MrXOh z^d5{XyCq#fGgux8zmY8N5NR`bmw;YzBMIAg?3O%pyfO~=SxPxHG1txw`f+{)&2()z zYGPNs5nGJNdU%>YKm?(mLST5byvfikGW>qMC;VlGt4eD@~DQT zEL2V8`3tl3Nl}taDI?Me=6>*&686Xatg`-9{1~2({tQSYDx~coDp}p+4>J~ui-s#H zsf@~rS03(r_Vp5A6mTW)ZyHn(R;g&OTVdL z;`}{sM~~TmK5?Pm_C76_@nV&aB~;-|*gNZ+5pr9M_0t%+)38;u zs=W8juayl7RXo=GWd0=%FC?jm>__de0efjI{DT8qvUhJV5wz;^>_prI?!DA0^#F-% z6Ar2Fc{De-+g7OzAE3|WsEHUTxslq$)fUr}O{SQhIsL7r%?nDZ<@Lf+8*PHYLUjq% zNLAme_O(-uSRAkgDh>*DzB?w$$TgbP7bE3<;yooZ5Y{g{H>nsT+e4#`^{N5o>{L0aj@^q2A99CfzsWCPa33{Da%+l z^SWuJYd8d;_mb9SaR-`kyF5a#&3R~n_~=f zRx1&N#U3CBw4Oft^L;YV(??>amz0PWB{$3~VkVn4r+z4s>1Hii$|Et)&k36FpCT^h z8>3)Wlo-CVC4Q*M>_o>@+%NQeH0vxRTxFs>_Sml%l?OB2j*0C!ZD$e(zCN|I*^z>U zZkNTU0^w&I_iCuqW$ouanskU2bls#3GkPPI=zq{ z?llHB3$p#{Y)oOM!ytxBAqg}|`<6IAwjF`xjx(e^yBm!GnFa0#5 z`ic$Nmyd#fdks~*NEI>6Jo^F^e>?@I8C<#G12uB*Ccw3VtU{fhSLyg8knPAr@&s~= zrSCW3bJ6N%yh4E#asnBKGQ?rW`ZP9TBlRu3U@a~SGaA94l@-dtd&F08u;Jf znzv#Bu*p4qW0KnUkCh=c>@Q#PSMkn~1YZ>@%|2G|uJk=|(?&%7O0mx@eb4%2G|;j% zra|hvIB_MdnH&6NGlj;U3Y#D}Y*5MqE&jb3TEmqJCw01y6z{WABZX@tj(3pl(02>ams5>%ODzIgbIX#D}N28ET^nDejMsv=&w@uAUtTT>q(tQjU; zw{ZrN_(|O_8cMW^D1q=Ue{IR-_wO&Y535JH)O6b-p8nM&!2R{DGzhVJn(h%=Y;Tkn zxb8V4{xWDd#;9Uy_TaX*4k|IQ0aLlHww_%>eD2zM`#(=omMj87Yqp7NL?7g#3lU7i za^x}1?E;kFD&e~0+TYOUjC6bT9ZLdBHj|@!*;MM?v&ZZ7{5kz-*}H352=;ufhLPnF zxWLs?ReZaf>_GO31g3pi0u;i~0bxqq^jlOcr0l$$?Y+0${cc4hGEfqFgt4BeDU*^9 zZKoSA0f>4PuEmV-{u<5v7Z2i4Jwkqv9SBh|Jj}q}T|rwH0qH~{TVKarpWT*I%^|Lv zfa4)M*gwjz%O-|rcTR;C(cJaWzPpoE>~{VVXLDCbzbkbKB0h1Jhmm` zPmn2H)$<2a4DzpzDsv+>ah>w&taC3e6LQPxvQZyd0#8bY?A$&u#2N&cuwBb*yIWYxS?lOAqhje_#FZE51Kz z?z&BXk8+Z21EY1oY;16;c>U*458CLW^XS>IdAgr3vlh{)Lrq5_+8&Itbp*&k}zK zBo^=W`BlNh&G4q70vV6w(HDEnk2L*$x$|P_9IoeRe_A;&d3k6h7FmIHzvevt?Ns6< ze4vrbY*Hr+rVk4q+75!$nZi|uIFCaJ-@d`pON;hXz%^eKvM{nH6X^hsjJF*GT|PQThWjGliV}}WlKxb#uoHh^HE(5+ zHTU!|r?Fx610S#)E49!f&$I^4zl~v}tAM9_J;>c|0_WKYdfnM>lHOa1yXlH^Z!1OKdX#q|64@T2LCQ{K;Z8pD+g*& zImzfCxw6@6G{;f)?4T(=#G7ko-;4 zx3=>E_KLlRjCAM(h!%f25<8NMfb#n^)iOwLcBet5kv7Tr9&FIRgW8%~XgZgC39t%! z9rl+8tcegkhB);gi~JQxHgstQtfZ5xty_wjf2hPE*Qjx9!fCG$s()%DT2RI~(q3aX z40Eb<*0m%-Lucyy9%y@zUM<^NJ61h&-^Ic4Zb%12eA(yuJ%fV4}HMZj|OV*Wr#D>3po^Vx$X7vFvlOQicA_j}?ffyso?V~Rb$`rKtQQ|P} zkb+^I(KCLiIdbm!n@n>G{a*%JWjjRwmT?bvFtqa zqtSTT2*e01N0>tF{`*qHHirX57mq3IeSeBQ#}@396Y>M;3pcJCbv~^2KKVT$#n+2w zVw1cWGb|-uX0InUI0*9+-%fJZS=DOz*I@{|HMtS+BVBU`;VyZ#pOBjj(VI6#s-7EG zm#b)eE?2zA!4VHGbzf*w1hrx1UXw{NicA(z2-LL@5k>}t$|C8{d^8uTpX#@z$NrHpW~q-wYt`H)hbD>(rz0<& zpWc5cp!({Qw})e$Z=hC`{0C|oxAAtC$ZihRQv=U$qPa4KJirE^+6xF;vGC%C;;1 zmv~8XfO0cr>mexX)@ck${933 z>WN{@QwfuUYR@V)@9>M!SjQ%;YFHMQ)Pq>)|Efi5;r~ORFiFomjxCGgt+yYHAe8iP z9cnstKk0i$aUmTPW+_^uWjowQj2^C4M#ICB_r;r04F(^@b87#^a6-yvOg$c zCx1O22u@jXc%!JD&4U$`B6n;K&*$KnN7AEVITWs-S27TsdyrE@9+%E?_@}???2^Jj z-p-&kxe-hX!xJnYTnZfWmfw4aY>o&5!rfDM_V+)}oR4rUpS3PKqr_zeL80z%(v-{v zgVoFK-vXjgs)d(NdSEX;ENRLZf8I>M`q)c@ynp_K2hUK~aQEFIa?{;yFS0+~-Qvh# zMqI)L*a%KZ^^@lO`t5JAVev!)q=n~!hcB+)LU>&ck7wWf90KQ<@sKj`tu=6wbskDh z{$gN-gB()mg5-KaNeD{JGhRBsl*OPXVHU7pbVNZ-{y!H0q~p}H^Nq*9JPhe}d$@&f z%@1tASl~rYBwupk4b&cMlhbcflFA3wlPhGu+`D@OzU|73gxH$eu45kAV2bm>8i9Dfhb~G=vN|^X{NOmiyxL z+ona}tI}ic!jBBi{;7~?Pq%i|l1Q&cMppt#+QcLPx-c~003*En^b=LZ202n}G!BJ=)C$-T%(6;GUgkfpHF&Re+HrYyXv-1h<$E&$#T06xE6M(X|`J>{<;E&O^$%DI7T6?(;m zbTSq*eF6(Io(N8(bKnBrPG_P@uvIUuG9sa4V1B!8F+k`=HCTY49`zQ4#{Amo{eTm? zKVvj!H0L*+y@xli(88X5@~kCfFl(?(eR;#8Nnqq>!^-TtxG z%<#-<^RCq(?~%88lA}LO{V-5M6I}zdU12C8=E}GcP9EX!) z(;thLYh}>2se7gUn>Dkvn~FX$B0JH5QCfDJ(<%h}2@^#aam+j=KDI``uR6%AL8uay zZTTr5EB@;qX|ah44u&Sr?|HC$Ft){Z=6!2fpL%-kj{kn}ZV-#-XwG;$O8hPLO*(;k zD@Pt$UMgU}AV~DHeE+13vr#E~g){rXjZ0VG z$1!p-Y;J3^7_O5L2I3R8W_ydEtj*8Es3x(uJISB@V0XajCQ&8cjaTRj z*N@i|;-IgdB@OB=qWKau7pVIv>FXm4CpF+^oagx&A%zj7oyAP?saB5N`?Ftsz#@z2 z<7ah^$tLYWv?~$MyK1ky5T*gL`F8(C{On9ih_}^WF-xl(_Kd;pnvQ^w_5SL`YuKW2 zq$ox%h$&dT#8p2Tp|o-=VV5~_$mgY<^3&jO)+nTibO&((Ej12xIf_o(-6#F6xH#IJ zTY|SqW{V+v5m)F!h4UInEi@XG^#aHsZS-LX53)9K4SWSekf>)Ikgu+L1F7$yAD?Pk zC{udYuDo`wq*@=9gRyRyC9vI3VXoLDb-~uwo2iyo)Vo}5(RPgAeIM_==f;cRE4x{a zC=^7(cmv+>$sd6z=kQfZLJYBgK_IuIvC{d-st%wrlBQX>IS_=DF6qvp1OWk&mK5nu=?>}c76j?;y2tO{`#e1S0cYOxp1s#zd;MM~S@Z2W z#;A*xlZh1w{~T~jwf=mh33;YSClJG%;UHwhdBeSRhcU;TL5MInrnJ0pT>TXe*Tq9- z8U{q`4KnZvWqIkg9h4y~xjIHH$+x-R%FXUf3-YT$vYIL()K zMBPJ_@U0lZpkRbR5DgO^88j9oj~=#x4_I(VcLaaqQE%Ph(y*2^SZSXx(ixPHU=Q14 zDVl*;U$QaiLhNy?ULG;(#utv*@dZeDB$(nt~Hk- zCNuPkSpU+`!e)$)jjwtc8E)ZgT42tXWA#cSLx6r;4l@K_XFh|KbXa6GSq<`8Hw3Kw zhNdf4%SQ}Tn3~I>xg?tuW${LW4XN~Pd2DjnszRsDi)U?$e~hboOPX;XE*|w=q{jPv zqkUotRFqf`71X0t*t}>o-m)aqPn4B|zU?1qUoo{cZ+X2pKU!9Z|H#-_nZ0Sq`rz?v z3XDNoF-71DI47&Cc>oN;((3B=1LyOYIeSddQcMo6d!SH2YLzBSNd;xN5_y^sbc{Jh zBC&P&GAI4dS<{?|@6&NDhA+RdzB zBuNPwvxKpSP=^e&vb%+e@?Yegr)i z^>+;l2I?d73o5fNt%rsT0WdsIPIbpY0sTJ*_~vhM>=u%%s;j%o_u?Z3AM!NwF@QCi zDWc|INBS|;L|W&R(_U}6VR43=&#T}}*9qp}8r!ZLuD4$4Y#>ih?CA7t!pXzD9^=W4ZTncsTs+%OeOp zGA$%FQY_JBmoIChfi-gLYqd=mfb|9<2i-YJf^}QB29DG~HKJmpnioxvt!NH~;0Qac zo zDN@r%s2j5WU!aNIFeN~X2MABBli*gdG}OPX7rsmWFSxyJcq`*Zbqu!N_uXC9tyB#f zx^dM-Ib=j>^PQ%!lhT^K_f-;(_WGK*P*mJs5Fxs_e(XMSRQ-xalEH-kxW!8zn>i?5dYIMbraCc&&EbTmcdl;0tv0 zxg&wM^K#USDG5-LF0DLwN+YH7WCpEydbVSOfnb4hr?ZEv`j&Q^@pC8U+KaNVS$&9`o z2j0|0p3!t5sf!}3@l)@Ft`zEPp+SR(p)*&Y64hwwI?H#Z9Buy=F2YbHlz;e69AlYg z({GR5`a?RKgbXrJaZ`9_hi1@(kXmWffqt0;#i2U@5jJmYC}O|&rhudgI71Ln_-hVm zfATOV1E=;ONdD!_< zPvueRf6WXb3^~^q$&Y5B&#YuE^7Q^|YT$FUGwCh%$4qo-wH8&S3a)LqzlJw}D`}^{ zcUQrAd56~A&;b682n$22CFmPiEEJEAy;H&52^GCLIUUNsJhNftNxm}rWW+E?&i7YD z*M@W11(g8|lAT1GMN!Uz)D>wwW5ZzFg3sUjTY+iG7y}f(dJEN{t_gj>gtK#RA(Ef; zubM_JmslPj(|z8UnU4_J(Kw?i9{5C49l-uTlQfinv>Zx+ptgEZ z8y<2>Tx!+!VT-d(mi>Bdb)IKPaX>QtLq=a5bz20uVAFMd~x30GKf*H{`9xC`1P-UDpYA8DTpfl?rW{Z-mSh%lT5j{_iSbp!-hGB=UFok zg9}ET9G5dxDTWX%kvbU{!qp81=-qPFCn(&pg+w1t!|CvxmDDcQ>~ty2vy~Jj zK&M6RBVaT$iMVY+(q5mn*XHA`YGTO$n`biT+%?OI^_i>o-J4i*?V58SvQ8}Ff_7wt zS7H2!FPe5_bhH>Eg-(riyg+u*bQ5!?8GwqQ92QXI0d+n)b}x5P-EBl|sBpdnONTaX zr8o&t;iG%HoT2V`cHdX@i44aYSEOa%j_{QpU3D(#6kOEZig>us11gF816Jp=W-q_U zF6zRcOeokfFBM~mej`4RRkv>4kGti0Wt?5{y|A72I@*+4KB+4m4>s^;@#WSMYD8QK z&fMqzd>MOQ=$BTCgjgtAwo?e9+WXZ0LTBznQ!Rx33nbT0?9p#ohrWQ;|F?nYE&u!3 zpBRZ`!8YhwtG3#STV5Bdk6n3FRw~S3>_awU1X(2~wbL{IG2olx)c+6yw~LP7L&cNC z%&WJ}pradq>?Mo9K~s&P#z(|iJGY~CD3Kcp)Q+i9ZC~h?p?^OjaQ6AA?t?Et==x`} zd^jk_(~}5cb8syji!Q<%*L7%Nk$)cYZTt8_Jxs&6G7)9tI4Onv%j{Tzb`LuwvMzMUK}>r^L$cOZ;|TJYjCpWG>#_ZgZURRGacf?5Xmna-|>@_5`NxVB7LUU)`nCfHA1)$9xC+0ULnMq8DunUYP*u8mN94PR;A@^ z%nJV#W=w`>F+=m&sRG)CLIZ~))qQ&o{3Sjh2jxY6weh{Jc^PvuwLmWO2MyQKVK(*< zZGy;k*cYEs3eQ@-Am+_;L9IcXkv<7V7iS8I7ZD3|hf(1=D z#HU1rD)JoVt_!mqn--{^{(jZ$N)69RX5tNNU$!Ad4E*$5GxBjbwH*FBC zG=##GuJdVkw03MY*v3wPmhtGr5hW3pgNx0EnaJJ|w-_D-P28wvpk|P%_l`$wR($$S-Pnx}p)!af z`l92MVpgWQF~AHY@=X;T*5)!8;Mk~fUr(AbaBgtw%k<^4gK4eTh}bi~{|~X5`gpr{@6SXJ_{#nvb9$2}X|8>zd}|EQ$mh_-!K8y+uN4U|?_PsGTLEs-f0Iho zv&Rp8YQo8J6rmnX&w;rm)sr^>(ec+T7SFGJ(8|2hT4#9DdqLvc1tfl1n)pBLA zEB`XzK4$!^wzk&2EMF(q5#z@t+%n(;NB-rgU^a&i7>uU@%%h_P|86|EAo~CQINDAf zEjVEclIX6soV_kKyeIa*H|`dBUQu~$x{NkL9T^>aL92T7s2pf%`#}*0&8T7Lo%qD9 z$AiZk*+?)%=FWynp&}^Kg3}o%Ku+pWy_klTej{^>EzF4fm;AX z&xeU`OeqWagv_-aMW~L4`P+Jc$C*40W^hG(A0&OFKxR@i^)jlX;X?`fmF&kE z;-YhXRZ1AlD4f=y^&UA>Pqb_OH}m#ptJu=|;UURJy?7Kpu#NE2wxh3Lrf?wHj0aBD zM@9>PXHaQ6@o2PUd~bJN%I#ouqIX$&n_K&_uI($^<-rG}{ONUvC9X8%x)=VPqXelzU5GFyAzTc-lowmt>;2jEqsBNF|UD zby$(;9DEzMOoS#61@V9NUK5g-IOtoP7;|7DPd80xWne12BGi_1@~c9l7BSP6oO~G$ z3&y#%BUV7E7}&2H!M0J(o@q0@k}1gaiVLvGO=o;$X_s$ZK^2#3i6PMq2J2Lw07G4i zw&m#KrO4W`z>;uHmouMNr0dON{b>5S!6+o$K2HA8q#R-$ol!ud-2L^Ite#;&=u`ac zGxIUo$dvc|`^+J;S>1pEsV*L2jwD$lpDg&eGl zd#I8QW`?_D)xowGT8mNK0ufakP;;<$lhbX}`v_)S!mPqpJtWHmoe#66n6ro2V9+PR zyqj>RDCoB3oZYK%E*Jp_L$1GFvS>wIPkaQ|A!7q!;&oNVq15*y5lN_ACw^cQr}qNx zfXdz?<~$H#oBKT@2bEGTs3(%ce1AzYFTqCYnNOjob2j$jux`A{)p3x1jEDzYn};`L z6hrZqqD_l_F4^|3*U(;%XA^uIi>_jyJs~bnKisK8S>v_rYqR&47(Z6jkOrz>P*EK} zT&-H-ss7k>5*D7kQ0<)#@NF&T`iX;Q?Pd&)t$=ZvX8hx^_l_S5TEx&5B}Eb)vEcLd z&KM_M7SuJ?u4!w(?m?QllAtPdJ2@$QNLfrRxgaYwu*HG3V%n7k zvb3!(2<-({-0EfhGGTYI_@q&^-La$Q7FFzL`XK))5E@Gd?8aKo&L-pF)(Z=F+5eQJ zq^Y^peUOaiy|tMYl}F(g%&yxSA!*gDJ(^glP0YQkWKl4wz2ecVa$>{k7}X?iJ66o^ zzoqoSHBQTPI3Bc2s&8rPnSJsOcEYOneg!e{lC=)1@G4H-=!hfvHF09Qc*l2Cm`-LA zZnMO_CX^|wGsPDNb3Zqj4HM$}TZr>&Pp%f$yz_jT!WB<_(hgg+F(pxG_2OK&ZzJS| zzh|gsxj!<#qnjJB`ocLHDb1;n$il1m2E^lh(q_%=ht=+n3j;A}jl;(w;om-Q@00v< z3jvGqq?VSjnIQkW)dL{>EM{2d%wK7;rs^j`D4@2SZQFeC_YHhd;K;q{cO~1iwDb?K zD#T<|Xv~^xh!ppVf>#M{m?Wya*v%#(r;Cyruv%NSUU6Re_l~OPN8glUw^OXa;n~r` zm7UjT{}RfvqF*U7wf~JJH|!FQcis-WxOSj;6eh&P63=>|(*;B^m?cyPehf^~EbQzr zs44&mX~^&1M&j4M{1V(2S_v+#nhVZ-^uSClbi?SzlQ%Npd?(8|srKSEhW)_>|6j>T zl8jRsIs+RbQrj5J+#^*44g8Bwcx!7AZF7(Mpc#Ksjr?hoBUk8W22nMXr# zrQQ@$EUtzXTIPNo*anud()10e!JZdevc7j+9$susW1F0X?u%HcKMc^`F6{%7WbutG zyT?7sEAUGgJ(xp=@HYf89T`bit`7pC$I&^e9w9r&cOEg&-w$o4T9t+qq-5RM$JXo= zhL1njf2ZUTS>b!DoB3||^^&LNQ3qegf)~bnpRNROK&Evn=ku4WgWnB&7l9j_EBJ#F z+7ib~S7-O-Ta8m;op|x3C8trrLyF>+cYAC<8wzcMzn(Rb(MI=~qQ1dw;WQ=jS^)1h zIZvdaR)ppkvmc4**|q)5ppZh2s65SZ@+QS-D&1!+hvuQknfNk6&D@VPaw1p-MtD|Q zTl%iVd}GYDkEb;ajWaCwanUMr1qCQ^1h>&_>Mo=W-`X85QtZae&#YEqoG;K zaqILCXkYy4aMpC2CcIiC`Tn6g|7(Gl+o&PcMs5#F^M{L!!*ZV&az)PB{a+Y;evDC` zqMSHXa*5W8sTPB~y@!d9KPk<~zAFY6bP~(g6pWK!GQ7$QeeL#5HT0C0%$CuMI zb^ZYxrV0{3!~cY!r-u#yYhHm+^tN96@ax^;a^P*ut?6Z+YwF9HNTaa3xZ4S?3Tq`@ zW{?O;D!FL=BxI!J4f)*ky~M@bU$q7HNq9=&AZXli^Yp|W#OlM~Q7lQPrlDV8WF*fsQcKhV#B9XTms}AjepcLN?s0b1 z-v!~O66HO!yd1tgiBq0|M%F3}sX!x=ZHJ=ZXwzFMb{^XY|2)PLBleRoSE62dmseq^+2|;z4nBXwG$GwmdY%Uv>-X1=!yXvqu=3aoMc zv8|u7TK*&H#KcNsov!=I)b2lL<#p=$Kn_72jULjk0Vy!f!=0F0&MrUrGv@{yi;KSK zxRAOkxw#@;U}_=wFa>#Pn(_^_E~BS8Ed(o~045&CnTOIHCBTtoEiQ*n+W=vP%OT<` z)X~V?(h^d1TEb-TWl4@vjQTOyTvU1y(k-W2k~ncgK#VDoDG3Q{9jk4(?GEP3ydFP& z?N(*jq2*rr-G{%Hmq+5q@z@XvysD+Qj5ptQqtaCT z(V$TqqlAL-8Ral(pjgHq!6-)oPko?n9mFBI31Q-5`u3^b2)#M*Qv3Volo*~UnP+GbJR}?Pzm;%>bc1u}9_ocaT5_C=i7ZGf{B;vA(bP+cP`3cx4#hN$4bdy z74LdV7akZ)z~Qx@`u!V&+VyHTI&vo&q;3NW;rs~7uzb6Y0LnQ~JD}?MFpXlM;C&({ zVe*rg$M$o}F7w8&Z=Tt<7=;gFFiw}#KP{IRUs4XhnosA)N^b6P0#o^}r~G9;FW}AI zyGj4NzcNL5eG99m+?&;DOH3=f5HUaSr=R|sHHB=GxqW4vw9TWdCi!WSn>sfK2?^G@ zen=&Df2eyu3|K&4X0~?ETYzF?JMn{}JYOBr;aqxkNa3Hg@~1C&$cb;2wZt9t@@0hm;8@A}SprjrWxI1J$3KdOH-YY!Fa5Aks%l?hR zjG7!#Ap4hBvA(gfQvl~5p>(Cy5BodfotRJH;Gkulm<&IygqHYN+rwfT3cfkgA>iC< zd)#X?$*^n&BJ=1xN@k6mTAI#V_Ook=6hPdHj^qXTin|@f9@x|w1Ew#ueIW9g3$pXO zpLNgUO{`hEOYw*;Mn7MJhf!i5&msUM?oJ2^(Z{0X#BJi~E#zXwIKQIf@6>T0@R5DE zn{}K^9cPg#E@TD@-FN`8&4plJ!9L~puk+BfU=B9A8V1?Oi9A`sd5O; zKt^%Z5K`|Gb^J~f1BMRgI2+_(7VTEjNW941CX#Erou-KqZ?UO${d|&urt+zAm zn@6>!N}rld%&@Z}m*Xc+1$txRvV3cs_Fi*sP$2kihjTQ#mCA7pcf)r`xc3X=n)3N) z36=y|8TWdf^De0;Yp@roCqj9%FiokTNf!}hdTPjI#O zQG6{ugBWLc(syNHnGY@F$HQPER?0Ziy>Bp7BOb=8)ZUPaPtXkz1!~AJLaM!nl`M#c zt3}h{OMso>%pNF#l^F89v~W#@P4Om!GVx<^6kipJy&)R^KcY&Ti@?>`u&x zUWq+;7g>9;Ax(!ygIN6Od?68_4XQD9Kau zCSCZ?RFs`4kvHMgWK1$SZc$|C7w92y3Q2M0243O9kW(C?s}4i*6%HC5%4iE?YcG+Uo>r16{y*(=zD$R;ymr5}T$ZB4!S*VwqdQUm#AH}z>G zK8KpEXal<6fk=sh#s38I?8`(6>HpjgvVW*@;ZpQhZ9UJsJRab1`!swnO*gisb3)iLhD zZ1YS=>@S^a`)>Tq*_M9lZ{rY6eQtDHVhQ$Fd{LHAp7R_3z|kd2hw0i=g zzbD#V5#jzFGp3MvkQzOfBOoAuPc3F>=oJ8-F4bS3r4j0(R^?cZ{{TF=> zkPbjoIUe|dLp)mrumeDvfPyy!ERKe$&I?_by>COvXkkGBW_x{*qb(%dsCs_w{+{xm zO5k9R7e-C`Q717sr3p|Efu|bJ%R1vS*y49b64r&!VIZRUm@o@fdYth|IG#jpALx4r zF7ftHTdn(uJy85nqDQmQfAa-!IqSNV7&6n&-JLF7!mQZZO2N-wo>CRL8Dmx_F8gAa zO>lDEETmI6ZM^>bdp6%(Wd)sYAy&``r(1w38d#*Cv;TR0e>N&kBWE0xDoDe7^~1a|M+jYgmB*jS;(6pP%N|IHTwp-++Z`i&1ph-vsBsvn3 zSz#i1g(gC20i>~6&oH*aL7@mBGHe~-#P#X@)lN z;8`m7@q34|(YzvVU*)d9XWOG4L)Qlm0gFV>CM3MKq0~U;%fC=J?3Oo7frO^1FNe;S zew|9Ak#J%so8>fGCu|cLm3EH=4RZaiPU3I`EE8wd*oY7>Q4?(jC^D%g={1m9l5(bO zXlS_Iy!)`?N}+ceqfwIxH4yk3?&$9yec&FcS#Ge-|8$BS-G>hRRzpz$+4$>)9UIs} zYQ`0*?QZ!9Mg#Q3DWl%0WHJ6sGA`;qm5?Lh6#LH>=h0fWys#$$?3-T=1B7z7Q=+Xh z0@Tn2y6xLt@m>gpe=@1&3C@`;(eLal;bEr*O#YkdD=+Dj4=8Dg@_bn_ObH#(8l5!- zMxBwD6NDmP-s-(0z5uEn>JT;bQp!HWumu9T0Ym}}TLjlw&FrTd>0a6S#`aNyBwVEx zKY7D0WU`h2q*h*)cG1rk)v9UCyz4vc($Oa6`}=nT5`Ukj&I#+E0zNceS~K_`8C&K zf`4>z!g51^A{@}|4(ua=#{=x^G<)BXYzSt)0#H?WEbIm4i)8Os_#MJcH5?J^{%ryC5w zP`)K=dCBbR{^98YW2eyBn;Dd3nh#fe*!T78g%9#Xa+Zym8|Rj%rfsao zI|zz^e@L$xO4p6=Nd!|qX{%cB4#sWO)}$^NE`{Y=KqQC4N^V`JJf!E=3PEZlJ>fdh z%N@;lEexiYMrK7<4g3LY0XMw+gwmWD%lZ>w!|T{}8-z)>}2t z%%d8$Mg2*y8QrS*^wM-Jn1@RyWSF5Xj1;pOD2=bg?h)l}H_u1vECKGuhCo?fW_?>* zpMM(~{`&qt*5U!lzpTB-yB8JnQ9vneGo!kSo7wfM@7Q`y71!~i&$}Wr95fS7h@H(x zUL=^0=na68+)h0r6kR5o_zlgkJ*A*pNa8+T`yuS=wi7ODuZ+T$`#w`WJiNgmL0kXQ zHImR*|8}u8?5f||hVUZK-X~nn6EOY&K8m^x)XacKK^)wxdN0plc<`SAEG-hSF;|6( zwVA(R>}P6_@y4{0CT7dL7YG1>&$9Z{d4)R@zzPVpK zpPYL8+EBF=>oaj+YY*k}4ypCwa&bua=OP<0bNQH**(?P`Dl5+f1X==+aW(n65iS0y zkZZ8Ua{?+;{cm&uY{{7VVU4Vx*`Kt88CmRmLG<6R1j~!Ep%H`vUMp&Yd@ln^u zQ;$4kA=u3wQmz*Pb4Om(sZUJsv&nwQURn9k=1rX*u}%F;P~0JpVFj4EYnb zz}FvzByLZ8D<4f9KW+^f zBxi5-nd#)yYJkMkNIN_9jMl@u-v=^5zWXRrsQ;29mm+$Tcwk*A#Y?Q=*qsbzRhZ@c zi>;;%Q!5I|Gh4sHLJb8wEg3h8{qEzx(wYbw+~%m%M^GcP@~*`~C6{1P7-lSAvG6b( z+S=MW7WsYB0D1JJA1JXx4&1w|_ul9M@&cZW)k4sB!w^b}@|<;*FQR2MRv?Gm;nIBn z!5jhz_I$f``3n$P7#P4&2?7hGCl|AZ8|&-;9A4jsWoE?{@Nfj!aUiH~Cks8Q%jwZb z(j6Qpyi!%yU(a>T5pKf_B( zAa`kHb=?tQ_Au!zirQ`29FeAy?T)@ht2`nDn&`gUwW*>!?53#X#EtJ4-S#)3|W zZ$*Z{Tdc_D!@kU~i>N#wYO_o%OHSmnI(wSl&Yyy$i84rMDaz51@1qRdr$LI>rTQn; zlz!kaDqhKc5z#!G)v4(kVBKfllK#2$#aWbTip5U z7EHq7m^*mY{1t}Ax_I;9JX=%b91Fsx*H*g%o620b@U_`)1FIy7|A@>f?QG2q^iJJt zd*j;Kw=;~n3}T~z^=5rR(pMm+))bn0_CA4E%}!Y7XP%#5z}>7Z$OfCjGju5t?WVcN zb=2|=`>%NM9|^8ZrGbk4(7KC;_|_l%+7}`nnHvGK8F7zTEde>7Y_;1lufl%?{cM~l zjOx$yBagj!Y>MNLrgc{7LO}Aci2mgI32X{P69cbvI1_V)(VaILDu_hEA^U1*Sol|F zUx@d^G?AEATDn6Av#vq7&6$Ey>hL*UGaQgP`k^37Vc zjoz;SXZMnPqbn??)~I)SdOAq9lz6PQR?vNZcL}K?z4lQj;9$Fa^=@la15@TZ&p^$d zb`~5vV_|zni%idTIDq-oPH}eTZa?mAeZ1j1 z660s^_QkVFMBmW$!(t3sUkIt;6V|BAg~?{DBXdYBsu={CoC^zT49bSX1Tx6(?#M?S z4A-UylLRuN=MKt_cc)pfx(dA1f+1fv8xv#+laazmQtiA|&j_YgQPW6&=N6;O$HFLDhsO-b$_uiE;;a9=oy zi2n8z`tIm*osx(CLe#e%fN(mx`JsSmwK`gWrst^j4(INHD%$j4dgJgnemN%c(LX#d z2|mMx@?W}@HS(-reyF+~zP)AeDJj3^Ui{bHv^HDRtj4?=Tv*tM$bFb&x6$CSq%75^ zL9!eur@M9+6C55ebm8)#SK>amKK$*h^7&zp~HoMo{`{mFI%< zDOBgSoU&Eb!E2o+m%~o1&zj~^-Sx6Z{KTH78ySJR($d6fE7wZ~iER>@HNgl?Nxz;K z-gCIEHpb$&P&){6#Z|v5T@5&(s5;L1Q=4=-|BmS@(lV0i0}1;d!zSXn*FH)wFXY%s zq8pa&N$+CT!nB8Ux7s@6|JY@4FjYMqy>=#M05j1(vfPP%n z1=jf?ce7KqHkDgxuzTnIcq_OUaK*&gX(;@zlEsy+kT}|T?5APUyTGcycP-zAYjnP? zyvc3L>@sTL45J~GMK+Am&U5``|Go-hfeT=$VODd!oV}1S>J4M*oT}oY)+se z>iTaWi3{tbgo^Z8?#Njb9t5CJi?fmyZ*PaFVwgk`D<90(X70U9$Goz~5yupKy?^y9 zcMX6kd0y_5t13Xbieyz23JWNfW>No{ae(y~;Fy^h3*WG)R2L@DvIL z>Gb*pYQ)*Yi!v0xT1RC~Nqi~Z_B21qzx1lTxGArhdOVtVqHkQ*X*)vXF3qYqa4Y6d z5DUL3Yh^8S7tIYIZE*FOukdj^NMd!1w~+cffyV@vr0a|%9X)yQST!X>1zt4c3?7rW zMo@eEI$*RwFCjdRr{?-DcaAXoM3 zeb_eKh0p@CUjsfrOVwPGsgE4fIsTx8qC)|<*CR#1oksvJM!UODX#7+^5;csplb0~A zf1DMC`dWw6-ad0<&jI>v8Ak%2>jU0zgdTEGkeNZn<24=$9b`A=w-6_9exvJ&0~mFa zA9n*DGWLg(rBFkJW$23}76O0tK>rlQa{`*$`Q82$3m} z$(3F?@sM!1d1wFk@&^o-;vj8=%FX&@zmXz7_&aEBQ{e2>)iNP0%xC`v6=z5=7 zYm?Zq!d(Y~@SU_Edko$)?()rgx=MH3hBa9x=$!9+Fff$RJytws=9$^&TV~{Qd`$KY zen{xNS3%#8QcdMn!w78fO0JilKg#Wt(Pq>F6@{uuIRY13h1i;>y5rtn`A^TA-^9`R zvUaZ)6Q!PiZof2s_5tyjSd_KJGsY77uyo;fs>>EHl}YLhw2fI{5ABM4z}N@n8m#^q+!-u5pC+()8se~ySlmt{#|-uUYHNkicgFu;QY`E z9w(LSQ@eBFx8^{G5U?<3o9~MgP!p8SNr8T}hfbizvcKlJJLX$U%V*TK%XoTRe0P$B zsu7Bs0gb0JTzmaA?*oUK^}K2)PIVHhrrE4@$R#pElGBgP+|~oD;r172Z)`ag%yDbu zH<6%=KNrK9`I;IqzuoP>O`K{P{!1F$-+)e{xP{{^p={e<@ms&=r+hT!c7$#8Yg}2h zg_I-l#(@BKk-jH=ReL>CCln&^7Tf#wd6%>FX8~!^mwv}b6vxySzf>~TjcUppyqEu` z-K1WG{`DQccYE^1|KmX|1(Skeny4SCX1>8+eFD=&%U|BP+o-}uEO>B0>sOCXE)R6=e(D0>&rwIeoSSu$6}MMz(@g_cnXk{5n>>K* z`0K-_Bb&oU|BP>a^`mV^q5i9El0u6PB5hVV&x__Xk@GVmy|3?!t6TE(Ni(WX3jH)n z$8`&R`k2T*AUpiO7XYMTdHt5DkZfvUC&#bc8BNH5CSC6Uk@%RAxLDkZul5~Fn3pyi z{F0Osnt0{t)$2;Yxc?%2NLlIna*@BDoKUp+;kEx&)9U)AcbHR?BooR{{?X&pXsP`S zmSksaZ**d)43A$%6h|;Lm-A4J3Qw(j^@Yd|oGP6M6XQfw` zUkC3QLO>)i3{ynGaIFlnO!&@wRWc$pSnO^;r-Aho7v`3>d7{%)AqU-S0f!~xB- z4blWdS|WJpnlSv`SdPWQ4wM1$C)*IS#=czP@eLQ zcJK$#X~?;>z*Siv(P$u{hzW-d`=Ns)FS5~pSCcp$OI)vf&u>mdEQ~sc2_6*aflA{Z zYEq1|v!j3i_R`0(0qr~m5gg!NPW9u|u+-{%Yn>nSZh!elp4>%hEAgKezFOc5tB5R{ zh;;nH$!rzCCm&RaB!NJ5Y_8dR^lI_yNc^}AE)>sXl~J4TKJL}BWj77-fxfTpc9Pl{ zQ@Zn|ihsNfKrU^yWng(8#h80}T_ONGDByd-3d>b>BxehW6a#i@=uub z6_RUfM$u=j((I1gx>96u%y#so@gOq`I7U#s&U|VXD|c+**pSYzVj|>k%9_YLJRiNe zyDyjHo-RwDd>{M*-qBBi)%v|P8WpBUKGyustZULcAwfx~WlTBU_8M{j?CMg)omifP zMEv=c=ZaBT8`|yJ@+9twc7dhbzVCN{6F?8iC96Q3L;(GcM*SNgCkemvPKhewa|(~bfA2b;FJ!76fnH*OjcyKtSotnA}Va4#Hz$jbuXN-7PgY?v~Ry{)RUC^Ewr=QB_T#ZlD7QsW9 zgpM0OprAyHcs_&dDlXb2LOfK2R@W1~Fcy?LSB3rClpwcPphO6fVsX~lGu~WGWL55h z$j$LoBIeK1T2Abh5>@I&2H($~e;YCtsuM;>K_gOh$NkaB{)Je=Ogy}jydb#{$fKk&H^52M=qXIqF(nys27@6}Gh)KM3 z;w41~E*@NgSTqg&)$u?*2Vc+kI-E7v!C?wH$P64xvf30I_$btt|2pR(kLv}QipQF2 z1SAIrCYIbFph{1y8RW zn023Y2T|A?VF?d`1nZcYqsLLh zsKU$hZ8v_R%HMdtwPVn+5+@Fk!pvkMGbV6DalgHB;oKfD3;Ona)ftx$uNJO9ejI=grbS5j zh-%{HscAiA?nn=)=^67Z(6K$y%Wniq6~+GH%mJpr8|dj}u)maL0E0 zXz>F(V5F?f=j`R2{5QnDY$$KF1;d~Sa+q4# zvH*P#5#4(`9YpIH+#Z3KsgHa%pS!U*Q^?m1E;0SJ`co4}6m8X2|E<5)1q#nC%O5sq6M98nS$h*{ z69np>)<+D#2WArLftieffn}7@*=K0mwUuX44Z7*{Xran%cJ6cu$`SD4vbt}`6tvJ9 z5>x58x3({VL3SB=VMB2es-o(Da6l<7xoNwwO$<0fE-`0%QbOns{iFmARQ9G+KIV%s zZSoDKx&==W3YdnX5KPa-#uyGvndVb=bp%P?lSg0ss5+jEVpNprc(^*}0MZ5PMFgt%;O#wNUAm?&iqMSwtT8A#tX zT8u=+mZGX zDxt`*hr6MaLTd7xo58zaBDg9?Oqk&DiO?3%(WmvJdRNe0{Iy&+0IH9@qBrL}F%XkHIYH$=KLLFAy#10Gs(<>6#EEmH<`QqSU_?6!qr?g#$sLMbbGr#8+ zdXtVl-N6w5j&vh@`#u5oW!=Dg#I+H=%K0B%{rK9}@EGA%r8hWczj$LbJoHGZ7{U=n z-F+Ui^zB;QlRQ`J06=m7LnrZK3r@EP4K7~Gx*Q65Yar)D?JnEW2{6Pf*^tWbp@}5M zPP%xYuQ~*tdeJa3F$@H0D(#tv(G>>fK51ogs!wPN?K2hgjfYnTS?_Pw4qa02o7;AN z@6O+Klz~d)G_Q|DmG|g1C=8#Dg3Yy@ZB^Dv;E_|mC1a$X^sOcHPNuocUK~XNH*P(C zS@Y|}tgXGD##1AxLhx}++rKFCC75zGu*;?y6gX(5xzKV&a|^240Jt5GyK{UA50&g*(PSljmWw%3jd|naS^F@P zR!I_+Dyu#(r7V!XSuJ-TS(|jwYcXwgbD@lw+tm}lFjX{rd;8PJy9+e(zt0zbOpII) zYgPl}6EUP$E6Q5}qc@a3@3^{#zjTEDgs@GN8;6?Z7}LjPE?LeurG#a=ax`a}qcM~| z+y`WDy!#PlXf47T8Rr?rUUJedna zpfqR>Ju>tyF z{pr{pKp%RWW_{M3x)RWH=^TF`a~D<*ad`+aI8D_?U;jKw8$IRN-aCHx%(Z=lEqt(of$9%P5u%-HyPuwo_YsMT ztfgpFjbDpiB!5pa`=0S8nOK5?GNpE)nR4O}^}K_IsT#IMyOO^CMS%^||I+t!5}a@; z7`{jZYP^Mkn5D-10P$4GnmBh{2Kh5;YE_tKj`#{`CH=eTyZ4fR;^Q{_=QUgpZ&odt zR}2`ar`DOX_T`6quQcMErS@LZYM6J0u&KRR5}3=okcsAm@;KaDqsQ2}`#2S`Q~IY;)61yK`YhsVgFoOX z4u|qh3`!Ea)^6Oa(SAaRwWP2%BCbI>EUB{gZUKk35EAQWRU>=Ml~*jI$%{00wuJ!G zdl&x`5ua0T_v|ZNro|*u!WLCgU^(|i2uZr(^K9mRHs)g6bq{Yi8wNtd^6PVf?bX&B zV~drQm5shgLW1%9D&;J%jmPGWFG@!j)`3J{!q3ox;a%WVWIQJm&5(20R$wTjNSI0qqAuJ`WpjG{UWObHqlPZsEn>vNl}m`gK!+4R%F|2!&vU@$3lgc@o_1$Gh z*e_$lho#ghhfchL4R7uJt@+*`3KWl*-iyicS<=uTh;r>^8Wnv*yw?gqY&aQRu4wHf z^f*_RF)}kwebdUiHItQULUg+IM^0ImXc}HKY*ZpyWXwTS(z6gd_Ta*c2TaHlRI66) z8UC(a@bBe)ZrAm%^AAp1>x-uJBY5)d6q;kjUUp>~C7(a>hwBb906E$W8C}rO%BRQR zQMw)YccQ^f^i?^ONKVu|ovnoFKYTokMg-ov`?piZJEVVKK^LdLNxA>a6e&jnrH|+; zD1Jn`k<-LpN_b@&m7@4gUQsSg*_M?fQyvs}Z`#WtZ(WLh&*VslM5HAH zv#dc{jba1gd#3n<&U{XS>ZvR-k*}?3_aWh3uiG&xDWB#rm+XI5c`DmElfA6q7yv z>~EL7h8wvQu(G3D^p&eX9)T}o4w?c%LsI5yud>9#D!yMLo;6{R zVzpEJxgj^N@xM8gB#%kupba?5=$(?2N>v@yl?q zl2O;HOA>tYtq5iZ2W^Un_8ZUKa=-KrFLb0YcVt?cE!{WYwL${!4Ottke>)};;i^X9 z%SX|hX4Vo+R_#>mCX{ZlftQNU|%C^|j_!crQ%GGq?yAkPszBP$l=m<9vrYyHr&TH)Di8GQl zA+gSlSCWQyGYz&a%>R=O%<4m5%4AGxh%&I#iWl zN{U4I3?o&0j_pq$L$6hjK+*=~#Kn&LyR_$<^?htzllR$2^Gd(h-CWEON=-jLXM_h9 z+L|xn7dsLC7lr)lvTsDF^=faO7Ysyb!fLy3N}DpAsL$SIZbjs1pW!ZezULx*ienEe1CVoYv~rVW{)BdK^_$eFhjS1 zlMb`&BPah**WqjVHezm|vPjx}u1qkE{=1FKTVzIjRNN6kld$~vShtRfT8g}(r_G4Y zQqfzh5X`Gg4S#%B73`ehza2>}q2$l@6lvg5Q?9JQz+y!B*Dgv?I?yLc9C}R@Y*ta7 z^w{cR!~Elc5(hRdRs|Doo&qQJ$y8`i6wwxlZJURdf(}!wm(hd_S^h4Z2!Ur?yBS}y z;35Dj4uZ&DajhC0iBQN-qtat8*hzsrMI8*t9k=Isu|zV0;CO1Q2yD-zc6_B5Wg+R# z{l-409{kxmxMGugLPA0SRI{UhKx~4u<0&Ny-?3{E4;4AB&3b{b8n$=;7x)yt+!!&v zg>3KMp=11D9JLT(cB$ACy;*?I8~Gx@*~U19Rs`WaU`nfRk~xSGx;~D>NU9bzui_+W z@Yc2bz6b`wiXUe7m|LpX^Rk+V4MYy?`whx5+7Cu%bpQ8|LE;G*L`)(^i?4YyVi3pN z<@+0epJoT+9$ooe}4+xM{=C;+w01&R6t^9 z>K}a2mhI*O+8%xq=%|XyfJWVn)X{%}nm>(X<`nltn2}fyVC*`!3+H?5K5jFxOr-n;}yxAjO-m{ksV7-v{fx zo637HXJ^&pS)@C2=b=HE-I$@JXDtCEcYV2DlSX9r94EDB~!D{nfhpj);(;+=LR-pRfUp{;(d31A_j!* z4*h^MjNMWoU6H_oi~-cLXvg%(kuuepkRwZvOo2@_0H{|GKy$2nVVE2GC$*VIEPJCa z&G)Dm?d#5y*S6+%OZjh?S@HF)1&-DBc78s2l6FTXrGD&qEC1zA>!w7VRdyFr^~deY zsUgW{$7ou)3eb;{VbR?fqI&HLR|fSqXn@p2;JDltAF5aHMU#^=qA@B4&}p&Cf%v=qy$6 zs;cbkqEH6LrsWFsQ~h7CY2^a-%(>|?G<$R%Hq`geugl>1;6;8eR@GA5;x1#vaAmse zg-jAvh*&TwQzVS$UkQ63RTa*V2RD1DXxE@I0UmuE8|XLuNFPsM@%0O!_Kj4p6^jpy zq6lW|5fJ_nB|H=r6+CuK(EG*q+>6memK_d(?4*yoJdu%FkWfz8^C^}9!8D~b@2Tz@;5|Oq)fH+$TRov z?S<($$0rmL3sKajvJ0OZ4Pvw*iPVrphM*+fxJ3_H3}cYXP|7=`&}KGmB1#P8@e&la zWgKV&mhKE=z+L*hpY{JdjYh_}Fmu@0y)F|9i8c2Z%CSW=6?oD#XYqOct4{`lvuL5H zs@-blE0L2u9Vo96j6j0UnaRUQ@cJ;Nmxt%ttEaTCEy$QE@3FXG-G)*(htmFC?Gv$O zM64D{#il^}(Zan9yVnegF_Id+$N zPNFf!6&ab=*%lIj#FVOLs+O1(3B4-`FN%CRy}6gaIn_ml#YeYZ|uwY-&WsbfJ z$IVdA_WYWd{w0%BzI;s*6MN>V$XK&9rIqJWomCFRJfjJ6ip5zKl-LWgCdkb9qs^Yc z$ar6Bgpi%*9t=Y);PqukTCq;?KC2_0@h-ocgU}(AKO9eq;S{O zF&z1!wW}V#_1oXpxkiFZGmbk2Xx-ejxK3OzW&H+)Ub(eXvD9#_{3>=iJ*^t3^t)n| zpH@dV28bS3s`r503xbx@e9lt-XGvt?!qKS4(C>6EC>aDOl&aTHL?xO!I{LZXHiPkW z1N!){dDgf)ude=ei*m=jg;O1$ym55D32$u`1bkEgd3bd6`RVh-cLP-Bw|RJ1$1>eE zvfmM2eQqnCc)AS$IHJc1fUh4&cjDl3Awt$L1%Q~NG0X-nv>DZgEv=_a+SoK4;NA(u zBD|-|B3L}E6)uL0q&$!9d)QZlS;j+df^};yPb_n+R^#gCieUL9;Y6U;D1{8jZv2uI zKq7MQQo3bC6~Djc9ytetW(8uN<_vUd(ryQV0go2+3EQ@B)Mr!INgZ zB)?;Db5fSxuWvJWniQ)p8k#6JzDVzbtrgym1P$9~yI@bLT7MN9$$+BG`0ccW77fOs zgG%lGQ8@C*t6{ift;-EjlH=JJ96)S z1Nlo>OsB>>1WUnBB2C$alc#&!s{`{z7xtJoQRgCbv|PU5(%7YpWaQ|nO(!H6@6}yQ z-3=>F@@q+vFCWZ`qzZl5EL=d=oH>s5aoGZpN?RCK#mg!(EW!SGZH{=li};wtVom zMbHmR;(=)#$MT6>baC~GrNvu~2vmySTYkN8%A+dbbheBbXf`Xi&80BxF5zNFXh9bHE<^Z( zw>=CQ^sD%RNkilkdpb>;e@7Y9;V4pQ61v3gvg63g=1YU@ zU^EbNf^LOW7b(QD^J)`Rp$c$eq47`W;eTr=as}lMhu)VHZpc_>6^zG2Qd*=fxF8kE{(SjWs4Wnmbo>^zKO?4|ffEUh8Nl83tdQl;S$;ot9dxbGSE>X?umvx7 zmcm7Eeq4D1yK(pTBt_Gx4^L|q(==!3C%U*EEW|Wz+>$lEm1}v37Bx>Z5j;;$c@oY!H{Sm5YuFi zAluvQF6I|GHbb}IFEN+3F4;drhAY6FT82+_(>>nVf&t;;E}F<-bxJ*Mt5Rhn`E_LhhP`k9L;PIz~1?(TrZA#Lf)Gj{sHmE9LaxVl4^J-bGnmZK_)O{3~}!6fHBu zi-XKB4QDL-Tq=68v7&JX>JhDklO4MF zVWH$9&wUMtu`VA+oziMdi*{NDl5?v`;ooB1g^IJwhgQAPlrxo2Ln`u0;Jf%1JRoRD zgx_4nl-mm#Mnwf7{v5O+ts7jX99%R*{5^DIkDj_eiucnm6>#VFHgyDBgA*cVOQN=g zNF56zN?LFT?p;JmI3=!m!^fk#F55Yq=iW1lq-YHYqIXF}iyN53~7iwQ{acUT0 z2Bs>x#mM2F7HTYTeUG3BiW9Zkv@#uKY1-(frqEoG zg7$#%7Ubp@A95(`&RRDa&xfU6-R$otMuUdIq8PZwXv7j%dcChmBHI)QvsX32i%%lw!rzq+Bc<)GR)M~hIE6W~5+~7Gq z+$GLzvqLGNVRb=;OyABfY8tsWr^aj zl)%X!H!IxZ#{B!aZK;$Y@54iKmrrLyY}@HdXv650+sXc+ZD|H2TwwhZr$w>iSmJT^ zGRl8bb3|2S-nlwKkKq z>9hEljr#E)ekqt$_V-p@dH@8*8Hl&e%gxH6f~Y--hGMH6eS&iK7e5Z4!@Sm%A3jd! zsfj(r{!@{)s%Ip( znv5EUm%iH-q?#3w1@TZwAgS;hSE4wufJ1F_{-{MPE!}&g-ZDz|ZrLoV{o`US`jgC3urKh0`EC_ zSgd=K{{#87Ku|317nzGP#lG?RDVcvieUGD|CT+;kkS$^wq+eqc5)zh{f!}__Z;wrU zrH}pHCYFvrwwP#i5%>)e2XoAbvDAxJ4(ShwBG>||W*pP?DbZE9oAa_INlz;p55)8q zzL#b=ef}(z^8w{KHA@Ff862MV^v^Q;l-u5+a?>!yG1GWB*hX8En_Q6fGX2NZQPzxl zv-9NU^J~%+?7X<|#3=^j5IhfZf2bhPDBpZVmc5q8;co6ef@!^?4mYC!1?+vHAkt@krx_~HnirL(eQh!Ml<>e7P_ zgWY~#n=Cn8Xo?bSG@2(5y}TaJI0`a!@C%losjH?#7DWiFHT|Y|VH-1i?8l38G>`Kk zQmDd}@a0K2=?ER`8cJ~hsPAo3l2Ayzd%Jr^7QK3?)~s5+*}Ga*6YtN zxW$##RWO438Un#QozbQ!NgQ46O=K1>Mv(L?pB{&bUH;sUicG{lj|wZx8KiAbV_F88 zqKHzq*c2ont%g(bd_-(AnN|(%nq$B;CXl}yaiktt4z4es)g`Q+rK~6QDX(T#*2~#gYII zxeiIAqNdqqNyZ_tRR_j{C`oryXG8DZD`w5Y zIwe}27Z;wHP6C-Ch=B2VWzC*Vfs>qkEdco3g(O#^31fd%Y!Jbq(dkdt<8a{U???oS za8r_zPllDH6qAUo)KNX{tYn|44yDiF{+lA(DVjbdQZp z-N=^pXX(;plkkU?6m0;-hI4f`Z9=`1!GYzAUKV3{$#R6srSYfsLR>U6`EYv5zHkgJ zFRlRh()^A~EFI8NArqffhkoS+d-=nfGg5_1O(Fx`jG)Qk08>mghywk49DgjIt@Ly{ zdSSD1qYk8fvv^aRy{&TRdTD``4I~)eb8J93UUB8bzhHo7mS%BjQs`dnlEg7z&1|R!Ep(efoMEA(!})$wAeR++S{Grg zCvcoeluRuNq7gd*96~K2Q;Cm<2^Q?OUH0xFCKwu?XAjHTW2lok|vI+0KC6K_a>xJWqAM{||16Js>Xo`PD-uTJEDMx_gZ z>=8GU{Sf$QgLp;)QB(@_eup-1`bAw(xH_B--2zWdNmayDf~ax^dUcxJhc$qM)K!fq zfhJw%MToS0!Ic-g;_bua!8;271k+7)D_F**!HF-vib$pO6p4>AeIl6(Pk;4GR2601 z88H-bD_=4zy9Pvv+>c|;Ddw!=FbLWq;ws`J89TefjED6YgE}N>Lc^W;Z9a!g2Ujf{ z*Dg~jp$UW*AAUa)5{H=1kY)6FiVi^o;`V@lgzgZSnoXO!k1*lYuW`7v$~HHlv{l^_ zwOlH9JZvaZ@8=pf1}b}uG`(@Afn|>7>kde&!5D0MXgiy{|3V-@9Q5|P!Kj@6bW>^> zEgU^yt6nvK-ZqLV?n74B-10wKu~iQcMT*bg^X$2txafiy*|dhxR7_r!6ia9*f09jp zkchTA>zX~I|6}F8Mwb8oHp~d;g9YsL+xOGNzNX22EFMv^zVph55UJxcyn@RpyWFdv zpA6d~bU${`2*MY|n42LQU8>fJeJ5=ORJ^vQl`+JB`OmS; z-$19;H3(uN9Jc!NTBAIk_V>$P@C*XvG81d6-ZB#*!dB!)wcro=qaM0PWOH$3{=5J= zmWKdYoD0C#0=9V0k=H0y??ws>Zen%PP(LkAU zfjr~2MoobTg4=+G-s55y69{?i8>a(l=uH+@jGayPM!vu6SdfAt4uQrTuVkfXRj~`U zRh8voTA!VyHi#obDk!qf@vbiQ88Z~K?kAGDnofx27hT>~2Dn5U`bUJm%sgDD-Vka| zmfuLvo`^a2>3bI-$78Ud(Q>*dkmefZ+fmdQRvM>;BrN%(8wO=|ba!RV?e*!pbzYog zaNEe5S~sur^M4t-om$V!xajxqe7e?a^SOf*O$QGQd`wq-2YmCYvGF~LkkL@0H;iY= zm6y!swh1AB`3PA{t2eNp$%AXMoPBd@O?$d)WWxbrYCbqT9C%?fWMo=iZ3vLZ4)V>f z*h-kFtgc1(;6b{gwoRrkvPtN6r=uEAgf=!e!_&FRU^^-TU4ESd4t^J;0{+irm7Vu! zcnA^2ul~_nFm##n$uw$iRKB?>c$)0|@+>KFdwb3N-0A;>?>y(Xn_j(Ye|F>lasz0p zPW2tz{{bMBDU@4lrMFj{d*S%Y2f&7;>6cSu^5NYRzkwoNf|aUhiDD$MOCY zJ$i5X1Mu`Or7yU^dyN%Z$nbvo>xnCtoP)V*U$=k=(`QMx-n94A%mkjcIeQg>x1aqr zVn5~{FjXlI)Fssty!=}WF2UkGtLUPT2ABKa7rmgoTrc|%fchi%8k@)==Vu^#VtT8; z?Fq!}*2j`8NCW#gHjY#I#|P$wjIZrxCZ#$L-2IOwxS05qzngI9cd}*{Iltp)wWnkp z)ErnZna7pPubbi2)s4og)1<SWof*tol&oQ1s+rYJaZ@_xVw!4EF;l9{7PN2{^9yWHogiy zj@bo-x|r(Ju6-x5fnR!i zj5D^cF>=@*3r&pF<7w*$xG5E*EBHLuL1mep&B{>-foh^fY%7=Ln?@k4u4dh>Li6AC z71f4@j|U&NRp8x9UJ3I~*B;ca+}CBk)W2#y#?4Md^>!dJ3i9&>qp;1|6x-%$j;pSG zABvO%>0VkNgWz(*f0n-2sfqa>4Jk(a4P*JlubgIzn7ga0QOPJqpN!;)k~-j|UxuH9 zu!FhN)a1**Sr^?KO;+r3UZl}@v&qt3ftJZKr`(sE@ajwJ>o%ehU~D+dyJ0gEG1T*^ z;x#bW&zXfdBL{w%nDjlF^+4y!KuxWc6CFa^6;TdoM#h3^6;^@%?-8FfFjB)^*Kq zS{S`p5v1OQZq>GKPK;8LwPd+)|HL3WzfsppVh&14{MaJ)k^C(P5-7REYn+GV+OlN{ zml6wCUzPUvri2XdbB;%|KIz>4oLiA89*#IRqZ@5%eF(>PSf|3F{svlxrYhd2!Q(A= zIH(iDxg_vdq|ldjRD(Lz7acJJ4I@Hr)mWf3&>f^KFOn@R@Lt_z5e6~b`+H+J255E= zfh$8k)m+pO28T|IGV`{f2vRtwf#_>OOe7al#FH+hfs$G<( zY46xD)6Oe)3tSx27*24L!$8VVl394cCy9!grpI4M5Mw8ToAzk>SmkHVJh?k3mPrgsNIhqvnd# z&nr(x?7|s6j&q7lT>a*0%OJLWN#$$BN(KAkz)jehuZb{am= z3kFUI3rAeoG2YxIlhbX3WHXKwzdZ^0SzqnFl@qz2#wdKV4vdN_Dk@3>cMs{N+H4*< z4c1jfmx*5SG7QQFz|=q-)O*cdg%HHu-SX{-%CN5o{D(w`KJ$(+71kPiUsc(9UEe62 z38VI&`AWmot)Dr$_R%XR*tfT5y+~DBCl~(~IrH&0=lp(B%sQWx-RRh=Pmt;5fF`&f z2kOx5^@LR42i`V2vPHDyYG=NmSQdWX7Ty9BEVm9XPyQkeT5wX;OuYHda9TuW7C2~E z$0Z|i5tN^siC3Twi%Jz0*mQgWKRkiqK*$b2Kg}6qkQ_J@jv9;f|5ne@CC88~zKt9G zl^1nE2x~vYGo}8J#fv*KF(2WO7g@-rQ=xXn##_`aXiQB79OQsgpJSE(D-^(m7-fb# znn?b`604LwYINfjw6q6L0rkr1CgO=?17YqrqAUkdasSlS$-Kx}(ce1n%upEMI}+Y_ zdbk0>0Ts*97jzKMTy>zA-^BJ=IQEHuEbs+LyLZw{Db0zbe4ehf60h%@NUPq#P_+r_ z`1i~sAD32j=U``3=ShjGr@&JD%IfORqUeGT#2?3U{&A&+JMw3oZuX*h_v>N0Gbvd7 zy^90!Ru_8i2ZW^~v8R2+M4CNJ={ES*k?;zb!+}|dvLl{>(gFZX!1S4L^YuQhGU~k& zdcpH3>yHGgS{iTrSUU!Qb}2y8?co2Qm!EJt4`}eXSK&rCzz+vPIsjh=j%q9V!s1cl zNSeS15I~vPF%VW9F}}$jvl8>L4sm}zX?SKmulNvGc*1{&d-c-ZcHLl6Pj7}TSo_iBupgLBwb6^>S-HKs|XG-(yRN12!wi=UP6 z`Lw9}_hV$UTSj3(@E6@9Pv+H`w?Q*$$Tu$aJma_CT2L1gY0dWSJ%=@lU*UTb+-4ZV zKq&|XNJc_bz2?x7cjKn>1);&|*ZWGqXF^IUd|?^%Uwg*(b>Dkv!0G8J2#0${T>T>@ z)yOy0i?ol?q0FahGvobC$RiwqJ1J$6JDzvo|kbG%#zYUvyUI zou`71GIb~Pl*)xqsj1Vy*vxnoiVBs1ArT=24gVyNm`Ptl`zvRWpd2?QvV<^oFhmUN z4M+HiQbKqzwQeJe_olJ})rMSeep+k>k8zsIgg^82)G;>J-Q5`H@o^03b-X|>vM%wa zMgF6L#}tu^YDiM!(4v9hN=zp8xGB801(5qtN@Jq`n4u_OV;75H{{4KCoYr(l^RYTR zdfxSqF)P0Myo&cYJj=|yv{1>hZQHd5IQ|EktACh&G~>>Dff%O*0kE9W zT9WlkIiLUkh{HwkV0ytS>(P6=u-3-Go$6M|ptiT>`$?jwRFzeP*oNvL_dNf)@cAf_ z+kf3(GeE=I^$X-6KZ{8t7TH;)vqR~rO$WrDh>d7R9un)H+4-1V^C?(8u4T-%3pM|p2Gs1L<2g?>E z!C08f6w=BQS=0M<+PIY>2IULL5Dmtndc(iC&~ODX6Yo?~mxmjI)H z5+P%1$kGEnVpyHeR}Nfct)I}%E^q_;nw~uUWnVIvUP1~HwQ!dRuSQw;7?o{u{!DYd z7sr8$a(D=Bo;g-#AAAX0EzX%4MREaS)fzKIF`^$u)6YI?-mkpn^}vef&$#Mj6q+tj zxWkifS+HAm0lzbgc0fagFh>e-BatTde;rHoPbQYt%Fv8J_~@4@(S9VOPK@;lts&zx z0t%6-B=dOUZ=PV6kd7Y=W!Urg_s_MN4p;q>MSV8_12H)^_i4OdLJAnU~bT##46UE>m+xBlbDa{bX$uct8Tt zT}9o?!9fYZg^R9%Y&URH1lCw~bq4mj3WM_9#>GGbzti=~7+8KqU>^WlKW*5~1<5xBQ`ygUm& zAFV%src}H1d2rGE9J zK40RXtYKUJB)rG7s(`NGqP2I;xA(H(eRNe)Vx;j@f-G}_ny6()?Hp36b_9P#SG?Dr zX>dUOb9bdXqB^Dv?T3R)|G|B&*fyWST*V0Chm3}a#CtnWb_)82Ij&kn!C#c7ZeD@g z%M)fxh)u4-Eh5r~;NB`^Q*32Wt5nbqVle{Kj}Z<+fe4~)7fXYu>G58lr1*vR=@Gc? z0v~_l|9LQf&_|5#m{bDgZG_$no|A(SLhE@)zT8}c@CIa{;E!Qp+8;NDyTK_$PJh9& zs!`#nQQ>z!*qrMoIe1#M?y1B=9(9V-_2$Xuo6m2nLD;ZTM{3Yp@CZ^f6*mii;Om_o|(0#)(Vdg{%abRbH!o zl{b$7^-U2XQAM_0|Mf&bKOWpOYe?l4ZuIF_eYt98mWvM9{xHBRB-FpTi4zkW(*=sL z7Yw`F;xa-&tC_ow!snrir@&rhZSj+#GNb0c-NH5M=6s(823xgaefZ!a|4z;IJ63C} zcaztZEDMxCEJ*Ql4u&H?$_d$4A?^}tw8+g`H#Jo#0YdOnt~JTnxLml+_YWr`)yfkv z&y06Pj~67Tc{2(iypO-R%L3Dtue%#!?sTngM5erf+bFce1EztprESca9L|Q14+0n~ zUP+c}BCFlR_<4MNIS{qXF4H%71fPw9hs#dpTr2alTzIyNqSy}ZJ0v%i*`^(g9cK>K z$)xOx%vC(R-3!@q9ueN_K#S#ipCU2m2xVqN0pexdR5M;$cIU9u% z3mYV&sb9TNO=_)e|0ZDz>5e+QcfV8I)ZO2X!{<9>e4 z1IEM?9lN`UG>?=zx2HGI%viWL49Y)eRwYr_iZ-!sLo%G7=c$;k4v^l%Q(`5kFkn0R z?$wjwVzorj?cIctnPR$C!sqn2#XjF-{-&m#(FKhHM;gD?>u6uTMDUMi-S~Ir zN5Z(1{yu3L^bz%bNu3c352%#}<3EBNb2Ob$f%CL51LeIxnW7IiHu)R+QR&omsmN@f z@fIQ}2t}3CU>2uU0dhF6*?D>8KVbi=Kezi@Ynn*LPbje%jid0^y_nzog#6adHkH*U zHAGzxEc2oCD(YRNZf*%%h+h&^S~Z+nAsi($H$YW{Qm+7kiGt9;m2 zYMRGmFI_m9%KiyBLqT%_@T}tQs;lc{%#l?7<=FZBBfhvaLUhdrt=y4OZ7z(?Zp}`X ziVAE8Q&ZJ_R^uBNC?i7b$_tmHLYX^gUs@cc{`fcYn+_jgq&}i*0+pdEg-Wi=&STjh zGN}=vH=ABM5OZ09h98b!i|g+`FY|nyMYCe2xaAR4db+DPtO1W2v&*+nw3xMDXLEFC zrVh@rpL@|#9Z|;(kxlFy4jvAX!LID-YW1U4G7rmB>^&e5DeMWnB@wX8GM1TmF-!=IUX8s#7-Xtx?!zaF}-Ws`sYnKJrC>Gy~k zlVycI`aQQhT?{x#+= z#h>WYg$Wz+xZa~v^~9c!HX4hWtCvB#MGbDMb8O$Dq^@~_X^ng;5Ek6$nXsT2vJO)dV3fiw?%`?6vV1*8crR_&O_SWuXz*_VKd?( zZtl-lZj?J+b}7~He`vbOm^Qe!-6F-^bx_=4$Z#9Zkl{WYh75NrGTfb^0|sokySo*4 zD>h)b!x-@Od6O^UM?=!2sodv2m#Q-MTFikQRzU$v5TN^JuO@O+%ukGS^aBT10M7x~ z@XE(><&=N7#wBbKZ-k)4I7WX7?2YgPRXWu;C;3lcsLVWTnx-of2||t&WPV&Nz2OBZ zfzP2v74PF|m83~Dn{I)}hmVeUSgGV;=Zh_BS(K6Qn>GM(u?wBVS+{==c;c2c+EJ2U z-Zb6%#+ByzqQetc`G{kX)5jUY%_NsRGN%q&0-uGythXe+KR$2Nt;!k$N=i`zg=M2N z2+JyRtb3x(X5I}dyl1IO@*qYu*uQDC&CH25L^I+A0Je`Sg4+;OH9+PvPBhlUH_#v0M_;z)l{lr@X9o4_cQ!5z^?xndA&T-7(}?%-s7SP?uOdfi7i?~;bd)1O2aU7llVGw*H@L6;gKvGhYk=kTR*7k zo4nqv-hz5~ic*$vK|i-`F^;pZZ}hDlGKr`(F2eP6*cgW6M8;G^JFF#0+G)DMoGnwOWxyW8C*O$Tj8w}xVC#wIUYod9{|EK$Q33K_M zaqPXV<4H;C#RTsZy!2x4<~kKWJ|UsjpwijdIg#$QStujBq<6u7Nz1_{t0=WNQsyEn z98xCu%YkTBElYxDfIV)OGDa9Tnl?4nK%^e&flzYJFM&UZWPmT?fdz`Mc2$5Nj6Hi(`3IA_kk9B9rr8N^hX05!rDJkU0 zJ^r2O4JfW8`O$qPEsufRP9S&N1E-T( z#kOXVS;x8$5l1v}PRo7;2jJ)Dci4u_Bjl93Reyl^@*ja0hCZf=mszae#H%t-7fgqn@0b!u0q#H3K$||u5@I;HB8<< z?BL!QcR(F``*WGLkxKVCX)V6*H1+1|gAyVh3D&t-#W-qWTo&|K zCYO@JL>}e7c9swv8Ww++CmDp;ScJGTz;Y_x39Scs0$V|2nl%j>01m;Su2+nJ-SHd? z8+A3{SP!`iBfChSM9la|WctI*xw7jUN^2|6M!pXt%vB9O-+z+7ppKJ^qJBfQy|_(V z#aU%Kiz-Pb)XNeenGTRaH4s#$jM7#QpWV+XiR8{I{G3f$-23yyI7SXRkxok}t1GQ1 zs^=%(aOFBtFACXpX3v0asawas3Xa9B3a98h6O2=Bn8{6RXrv|RT%a{i^1LP(8^04cDHOlm9-s`OUHL&B<(Wzf# z>ru7iNX5x_5o5!R#c;M&rI%4m* z9yax@5i$%0s_;W}#&Jvs_l965PzxRam3n|GQw$XgEQKwi^uyOhi7XTBd7b^WJeU+O}U9Tg| z6(xyw@WC9UV?R{m(&Fw+wTJ3RF^z*41_XqP!eC}c$ctw~v^JGzHevMfib20@(KHF` z6?+Y$QYLPuekv;npdd#!@lhd8+QB{y6%DVfQ2qQj^7aiV^{vyjzyk4+9xlS5VYU<| zryQ;+`ZuG99@4L!%V6cNUMTD!8)L1)yeXIB#PK|LryC5ZU@;}<%_5hbPBlgEP0}8_ z`rgX5=50#2l=pk~2kvZDywq5+Fwn%v*No^8W43z9Eu73LueT6!ZaT*B7<@%mc$NEV zIIOmwZmHAl014uJ!L6C5prdo+LCG*L=MQgXQRQl1vju0wqh6Q5*f{O7us8G`WV zkd;1}&u?Fge#AhL2MiAJfe@ZWD!3q0LjhOLo63J!{1Ww$3-$(R-KGixwE02(gZ%ym zh=Q`kSm6zzdgqi9QYq()J=}kQVg{XOGNUE)u6M!r(#sNMMQq8=pBf2h>HuWo%*|XF zk(M(uVc$v793VNI2YRJb82&dz_R#}4Ao5MypeR8g%ZV=neJn}wH#X6Q*s zj}zTYX5-&wy?3RNi-iYBqO*K)m#FzCgY;3|LiIlFHcjD8e~wJm>alCy5+CD09~C={ zpcl+_l1em|bFxTI_R>gD0cvY%t;!-}Vqy{$79RT2b(~ZLn4>(VBCT35;>l7~ebv#IbX-;%&Bw!5OQB`V z1u`?$FOM=nZ?2Nt)}=0jNnE$SL;T|>voRAMJ_@qPj$en!^vWN#){TN}I>ju(w%I)qd%5TipM6V8JUp@mcdZy`ci(U@`@K@+gsUUQsV^RA=dEJSYF_Z0D_G>VaveM9^qSWH#0}#xiOy zAa4}fCWgn#$_l7_9|RTpzzBr;6q6>BM<@XNP`3CC+y&4t&^Y=ga67{rXi}~hyyK_D zeF#xn@Ea0m3x21y<~V#=P@stzK|-fi;g!ntSe|R7*Y${0EUV9{qAJbuV6dfUxlJD% zGIGa6(29VJu3NO#7bShe?gy|hiRJm+5wDi?*AScNxELwhi5-k+NV@}hc%Z6kGrC{9 z!hVm_U6NntqP3MEqF$KLm8aay`H+d!&na7%jRdJ8IgcCwlPv$OxVb9X+PGmV)n6Mp zRLd&ifNy4imb-0e-cU4<+#5US80PkN-Btr=C)Y z=g)j9q4|G*=J!2q-ix2Gd>Sk7;(_7fwV((B&`2Y%U2HcA@hR}ZtSEvqc$p{2^s*?@ zh&yPgi1?M-hdQR|!3-0U(KM<>3e9eK7TWb%XPBg}p26{04MzWHf`tmJCUP6D*ymb8 zo@M1KZf!(1Ds-@wv^x>l)25{^d$YVFU&Nq5A6qk6j zv}H#ucln2ndtTo5(|&eIVsE%oadg;MJ0~OlY5!47re|}L6OO|)J5lZILE*9AS-f){ zQ363aurbU*N2oR;`wyKYR(IA&`WW@r{S$saxzjI&m!yr3F-@lfMT)8Ari=HyW?8+) z$>vmRA8UJgDM8*$KWl^>wSXzKat~%b(>Sob`A01XLVNX(q*8Q(^C#-@ef;b=cn}gb z9%x;D!uon*%VsHC)y5kZOkuzwm|m8n#Is;TP!KK1tEyl1yGceZgUEacQkhgyGd7`P zf9zl1Xz)ucI%qxi7GZ@cv)L%mOOjFmArO;-l4>I)TmIzar1xvoroPZ93@L2CHaW1m z6P=tV64Ww}*nrU5sKvM+xy)5_^zLyT4E84B$pZBd5I^JdDafos%Jy+75qt#kzsR4H zD;h(A_!?K)8iczFz&U(=9dbijY0h#nieUC3I}XigBL!C-M$QFSVARCa!SW!a%owF8 zFqL;iBNJFAmDD3jQ(^-7I0aF5W`Fuh8Cvj^n>@0ddb;8tkMK2tZ%C^}@#kg{XMT~s zj(xWzzNW@_r!dylzZJ1~^oGb-`=zRF7!2^~_3x64H}fFL?`t7!Z0wrm=7>?tx4*{h zC6vkc0AR&SRn|FsA$cRPp>mo5PZum#Zs1o|b%B#UnLtun{h%x1f~!|=x$zXLj6(1X z4&HHG1zhrhXw>CTmNH6MzjBka36R_gWls)NPG_=q&_Hr`s4Ppd#C51yxp7|a`9TA+ zv@~jUMUHcFyA%P-Eg>7VH84p^A1BUoCvR6d?mK9=rtkm4MwUg$`jkaKxg=Ej?=%dR zMmXY7tmShrr#bHpskt-(X-bLIICUO|Kip)9IkX=-o~h==ouwKU2vMLMFqy^A^-}nl zlPEswJ*vUr9d?3gO3#5gjEq#h=q?wfw@vdFUMEffMkFgao02y&#*kNe-4Fl^2nKFX!b*%U$&N_Y+xV_8K) zh|p=Y!x;t=ccLll|7HfFvh@BiDa86Yd!Bq3@f|NTXG%VzFlecF0R+j?>;tIJPz)RO zyghsCRC515RJV@K`gmR9O_n{GIX1k$$@}-?`v&8Pa@}fcv5l^J6RzHYOivDJTUJ&= zWE7y$s)%F|hnZ7X#G@tXfHFOXAwJ#4HXyX>6n9tdbXZ9|lSB5dV@THkB{@>O#z?kh z8V37gHR0t21oT@YUIE|b`w^SUEvZb0Lk41ja%96RJPY|U6-yMw%*a`cDMIj#7SvYN z@7pOeNAG@32BQy2j*?OtX~V>a5Sr?FgG;s7tj-0Q?|-qqjk>9~`l4A&_R&r{@&uR4 zOabwWSP(|@myJI7#NhnY#eR%|_A}ukQ97>fErC`!^PRfJM(>N}Md|<-LSbYu$^`&` z9T8F5;?~hKbBP8ewy)4(V^>uR3sF3BrX*D)@wAlt&|^2Zn|1I7?VV@xfh)bfT738D&2c*f#hxaO;~Ff^+OC06)P8DWiCI5QgJn< zFMvF7q+-!deQdMl&zMZ{=eP}KbRot|#wF1ox8L3tO{C%?8glF}3ZXmzu1u(S*o@j4 z3qo!;yw$5sI-?itz8>TUbpd`rSg%<`7##9~FU9L!_z|UFIH|AOPf=oiz2)N8?g<0* zw7sN-LUCDQ);Wekm@A=a3h{8gSD<9~k&EjA62ZIPvns)y5h4C~Osu!ZdpiLx)d4o& zPWyvVijn9eXBFXD20L~mWC*<|?p?i>s|vxTDl%^(jI`GuA=BP`lrW*ak#`xWc_GZ} z@WQ=_pVwBW@k^zhI)c8FF7LCBu}RO@YF&zLx`7dbT$)`gK8|E~fGZ#Kk1!rt@2%bl z&?d^V@VkO3u=wQLccBO%Oy1Pc7A+sn02WEf4V&F|V0v3Sp~2m=B^{F3_e z9g9IrQ?m4Uf9o39@w+B0l+Z*(M7%G0QOwfLii9n$>l4Sd15VrcmrTq-C^&Br@R=%f zk1@GRGpBLHaLK4OJl^q9C(G9BtRj#8p>fTe^xQLwN9aN&rBAAH-0e|(tR&c<*C0~{ zrD&ZH6@5z_3C@u*ZB3sB(9k2v$S9c(lTs#X;4CpAnX9i^b;|WnN8xX@^PzALGa@8$ zq%H*;#h?x)<{0@b1I|JU1p({?;r#YrGry(}yOYQwvcKiGS#X{hMzm1(q4ljeJ?-FG z);`~|ua38N8+UdOk?aiNuJBbIh0MI}Gkaqy7n|h*p#zFB$EXUc50H}F^fu6F3m-!a zb8uoyNYj|b`?~B;0D3sVn zk5hN`ysmox-;Su9Oi7BqHQoT;4l3ub3TJv8w8;?OR>eUVH0S-13_t15(5s4RK~1!t z#jQpo?kCi=NlVFfAN`%2WlU(Aw4hAbiVR@j|Fr=1^}PPOKb=g2UI7`L#$!@ELzkjA zh|)CPTyObBLfLck;b2xssIuSkN>YfQIMPi(wT-}yftYy(f~s6;@TfqF+8_{=+fGOa zMnri+v0c+C{2Czz4xNGm7Qx;ribu*yv0+LL%DwLj2ofN~51r~9#RChzzK%`jLW%RMb7~TC34u374~Oy+f9r&# zULW&c$?_itn69k540$(8qo}Eehld4)gnW9>pNE6~p#)yP3nJ*gr05PF&*18=c!^RzsCaSU&c{|`d>mwN`q5Ky*>#fG?Ec_)(RwQU25CIF<7s&h?5d+H7tlG25! z)+iZa1oXOG5v=%sv=s?uTUoeIjN``5osUM9Dp>TrfZ}8%CQfS*HtpY2q4Eb`Uza66 z2$_3OxRX;D5Tk*UM6rif=vYEhdu_R0fAqvuT~AWvz6QvEEqgR>g%FV)^oRiEKtsga zVpE;mWagioj%z?u85O^kjg3Kf;YrE7i=(LTX@b$*dkEO`A9b7J(G$I08VZ4kJ{y8S zS1in0Kf^{ZUe)F!f@m;HwGT&I(!8?LiQKVNM?4;U1@OVVyT7kB;;hwUuUWCZwE|bh z3!3DEeAjMI^gHf-)+NIxae0c1XMP+j&9DW;^ZdS9$j#057w06#xXH%)tr-O!W46t^ zI_*rmt#gC)-)%xz(H_z1$L4I0_aA?8<^-i)3YL=A7w4)n62K2b4?rwez~gwPv3URH z59Px)GV=yM1f80%Z+TU+FgoQ$hwfjb)ML*=;ooG z?L&Ih%k~V$$?^vuTJIkVzXWXUUR>b9@e9)M$bz99%CE>N$k0E-6!v;B?UTV{NM|fFflS2|hg! z+c<-uXEql6n229C+P-$3<4O0p3xB<*HeT9y^YrUD^=ftMdvt@Bhw!WP2;ffm3M}ll zHaBPFS{W~Gw;tq;Pnl1B!HcKnMC?RHA|(;tfl1Luy6|HP1 zApJ%);i&m7C54+dJQ2x06Nq4hETe+K2;f8-9cjB|ha=$)9xZ`ZC3QLVtA*w2SdTiq zgqBnLFZ+$c5ay6yOU$pSWp4{ck436=l_!}H%|GoDpL!Y6$@Q>+|K?!nxZ6UNzp6}G z$)Qpt9yca8|` ztA$nwM?M_f)~uSLD15@fNq~dJh5$TIFR!ooO1Jv$#Oik)tf#-2K*9ZyZuIs_IZvPC z$Jj+i>VN>qkU(>u1&DaR{z6v8D5-vNc$LgEX+!rKDSN`)dZL7Pz2%Z7lT1zQRttox zLj8d$V_Lx63-f)g_MVdTkGESZQcII?eSOzuoRek5JQRw(+9cJz61%9*p;?g+mKe{B z+e5(<9wwdFU%wYix502&w69oH&f(CdL6vms#i2#&6?OmejS)y$Q;#@d&D+>$aB_Zr z{CEm`PK@DOtn+@luN(SfN;vZd7en4A>vasRgTs)8OOqSXD;<&e7%0PWhf`%PAOR?n zibngMWj5=P*`Vk@D+8gJY6bM*5r_4sIXX~;!Uloz)DRS#Z^VjepE%*ASgkho{jTEq zMUIB_gBX7ULv5TSB5r*V<$L^Da|$Y+;O%5I>^w(|woMKi_Kj357Q1z)#N^*8DgVBO z-e$gY3>`vgNXZhkH|alZN1%UR9u~h#7MH+8g!6d+eRH{j9>={;YKNWO-QCaJ{#&z$ zC0<!xR~LcAL#RX~#k(&#nzmVFpPp8iE>@-j ziC^!WUOmmez5It?z#)zH2e=~UG-DFOcXtS@+jrI9UzrdRYnA>l6d`C2v{ywFi( z0qXGDv2+&iH>;rRA#FF`RoSf4(ff{Xg}a;U>k+Moj*eJ#${E5p*(wp_>^bglLtYR^ zmVkJ~*;#>eM6l@Z?Ocy?vA8lh8qc|JeB!Q?cGKB z3zYNMJfIlc8=sG^1>rV|D;sASEbVhggz$Bu55B*=baMre)z|Y=2kzkk`gkzzF1nb* zWsrP@*7i)Ey6t6XOaMoiq7Jwg2`y31-YN zBse)c`z@_T{M8`g*?S$sYklK4QqKsU)lj0b?(DzT==J2oW%zO5@0S2K(@;`Vo5PPl z%Tz?xt(=G$E9mh(QEuWP7n&IX^jPTy5GEIVIe;k>GtksXI>QHqT<9vhSIKYTkbu?wR@|eTZb?C$A3Y`%uq2Hk*WVs%_j6K&I8=2JBNk(h{sR8zi(BD(nUBAw1-~xK{@ZQ&dZSMpLx6ZaHDre4;P^wzG^%xZR0l*+Y=2 z0aC+UPBm9x_%BOx=rD;MbdACuiPg7iawejZ@Pq^6rjQ@ z2c}T%)hN`ML9+Px1ZN+m%=3w_F`D8$pfjrlD5g>>s!ueoB%9FcZk@B^I>f3B*_?hvNDy!^wMZWjXJv14;(r57%( zhUF~R9?VO7yugvM0yL_;z`rb_PbY4+-#|}KPc5$d=s9kOPt=>dBSMwJpPrmC(mi}}EM+Ryt4Pc0blC{@@x|qh1@8NgN{pcPMTJAeewU9^LDWHa zHbLQVm4@9->wj8}Ab9j`JWjyjd#<)1k9N3BBM|0$A^5*|mABI{0N-Z2g?)LgIN$z?-EyRBG~&vAdXWvEZQ3zks(7-1ZFurpm2{<3 z&GKNA{xzAM;EhlWbE%eOLClm1PDu^TAeZ{vciMrkB^L3ll4g^M@xZplJIGlGQk<-3 zEV!XrH)lOOzE@EwB}}_kKxdjqUutD-eoF?{>Rg&HaCvP`WA#yu%Tpxc!i)wQA-Z2Z z*_QqYSutvfEqcU_!ylup7s$ungshXTb>Ev9?v>x_xK>CQ#Z`( zgN`X|N2?@e_3ogFsNytm@wuk9HL?^}OH$+MCDM@8BD8lX3V<9zswiach(pHAC93I< zLm!aFkI+9yo|mpLjjCaJ?10&@qGs;xRA7oD$(mViz-elz4oRf?yxV@4@LX3^ zC4BYkekg#hFh|%JDz3Au0Fzmx#||3EI!~;%+A{gah9g?*%kXSj~iWM8B_WNZlRRhsNU7L9PaP`9~i%EuMXwcDrArPC0+8HCtgVr!{ZI zdzlx!UkJ5-=6{20h*^}wUa*V*w)VYc0sf0VGPot&qHgL!N;s6@q zcPg@0jC+h9hMee&%hWO-yqrOUZ9RyjSoY%|AZm!q7rn3|e*jQRoNT#B=qndps4Psp zIR%Iq0Kx<`lZe!{eTP&LF||ktYd-W26eByZo#D?Zru?yMx{Ia$Y-kPG_a`?Wz>VSU zbJr_vN^()d@KDmob~srE1B&&v;H^lyh*Edd>cAgR@9kmi29j?=d)L*1V<)0rr~?Er z-d~y}e>?JYed1|*aTo7N3I3WvoGAGI`iiAb#5SR!D%ofrpQn=@}jro?cUPZxrlafF{t=+^1)ADKBQE&Q(Dk5C1)*tmRDFYy= z35YWQd9+iob}{>642?^&mayDIfzvD!FZ)*b7f92^`2Erx^wi8nP9Ff5Foagw4gA#Pi%k@SBI=43E={xy_64cd-69FWfKiNDVPnsa=r#$IM#MgL5!K9tTHg50 z8dS}}G{>JdbjLSsI3sj(1)3cr*H3LY_{MH|{suVkt!;Z=HV#3`(M#yjJG76LS*$FY zl$fVc826NrxQaHgEUV(6ZHM83Y$QTF`-6GUqPCualvaF}ahW6y$HnUSyf*s`Q$OU$ zfzcZxTm&&U1xlRP5~BlSziuqH2&klN@ygoOClSi934$d{ zNcBxxtL@Bun;ToP%)iaH>#@VhfMS+^+5R9Wiu0klWe6_z_| z)RnT}{=1ENyg+p$Mtg_W>vhr9%Z++ScZYq@i9md&p-+Il*Ky%0oB%USVqx`xAAfk# zRHBKt8jNWlxC$b>5{m$&)yJpqenO>V2JfH^z6nbJ-P}K&Sn7-U{53V7$uUET$!1W~ z1{lmyt!uJQ)Bz(BXH!t!0gVcXj$FNQrCHzXcYXgz*nEuXC4dvmtfrcogxuIaBsazkK zFtbB9Su5+Il5_b64hZR)lD)-Kp-dIp1r%p)lIql0s#Wh62pS!RQ4ahLa|oOY4}-uy5?J zE3L#G*SPtJY4!$qYU_iJ_}|=KZ!DrB;V|9MLHY!-i(!RCcW<9prGC{S=JLIL2?h zWVcsBh+)Yz1&{3Nef-C}0uIpXvLXTK?k(AM4(*&^es`>egVBPRneHhcgsi7*3tAy3 zjwML&?GBE1tTx(berSkf$z3Yt8Y@ejDn3c9TFNZ1V{CH7ugdGpJNLypKb?ZWWS|4g zH1PQQBh*S9+kb>9UkX(vMVggiqay-kj@bClt#En9A{!>f_L?0Nfl-?~MRxd^|`-`(9^HFo0IQY4^MeHwOk0m-?jqwZ%X&HBJ7gjh?R5F>dg{JbfI zBQM7zxOg9iDBAaqqo#Av#NyNsfxhuBy}1Kf;@(XnLM`wrrD#dw^>Jz!zP-x+NPIoY ze_{FC^``T8=WzA&YW4Oh+|AZJ-(7WlQQrNx{GoE|FNgn;@+b1n`~UoH48qs$& zOZ_}u%3`wu$@W62ciV7@Vx&7aK7pey6bD+PO|^=^L#PLu+tmD_849U6?L>vX!8#ZN zF@(7>n_LzJ)mi-d0|)6>)??Fx8zvIy-2G3GFSBOi`DRW|Bs@xg0%8%(Ed@(qktOYU z1Unx_kbN4qoJRu6rG{gMOe6h9a9Bzb2G^hHd!Z z-W7V%qV{2b0A{w?SJ&MgT-zN@+OVm8E_mG)g9(frp7>wQFAvstYTF!I-d1Gex z$9?_{yK1>NZ=$r6gx*W-HObzw`lm9R7RcR_#moZ*j$pJ*|$pw-x*6V7x>C0!anTXaDdzCBeP5)XhZt$Bg zGi-M^xd%ig&hy4H6!Og&KpCFv-Xlr%vJ05b(`cl+2eh-MF;5jLFVz)6{>k!Z)I;BK ztXB0q{H}TDw4XyMl&QkRr5YPc|K~j9v&%~?p{Sew?|8`1UvYnb-6z?{SuH(?kQi5| z|7iL&l`z;8yT17NV~sivBQwP1am)(xT~%&|proEfdfoPWPI9AG{-v7uBYoFZ+QCKq z>j9qs>wS=fPPulM+?G7|{Z3A-tSYf&#R&7G;gC^Iw$>h8{e&xiYDQY4$LZqk9#+0o zZSLiT({DZEipUJ@G$Vy|zK@k$0F8D;NHNp~x{2|=O z=hl+!0GvB6faSLix^v$b@JO1V3<@y`>xoHtxHAYPcnS~pE(E0Y!pVLNN~$-(S$GK3 z-Vyq2Fbk!f-*?dbIf^DLXC+09XZ*f~LFWlQ4mHWWX+EHz-;?(tmQxRo|0@L#TG;2B zM2-SSL(FGDIN-20zhIj}kAp-|Olb6KS}0-~$@@)BETX69Z}Nwo>89O~4uK_)HZf-8-X2$v1eiEvPaQnK z{jM(lzj^b?I$s6|)H>{>G!(6ozyzo>{{H(Ln3TlZjCmx?5Z3T&&G$;qRrF~z9J7O6 zlYcHJkU58FPl^JygO(x)vvu{pYC5ie@v~{BAQ}bDGycDAC{q?G-Bw7y- zZ6$x1Vo$2qeiLDq2&P0Y;m9b}t0sZXD_bIGB^YWGYxHNb_<=qtQ2<8_cRgnWXAfyP z3fZ)W=nnEzhg$&A0>4`|oRsRU8~!|4Q`PE4rqF~D(*kl7iWD?B0oK$_6%)S_w*C$o zxXjp1EK+yI3`x36rl)G*!@iag3e-N{2Gfg$5qyZd#Wr=)mXf8lTLa0crlo6SdDkDg z__hI<?Iwi+g(_kW}&3s5fFHPaI*ZkVlp7p_LW=-%7uVrtQzme{359OX1%< zgG%@(opEp2Ho2p)*5I8k*{rLQwLMhw>8rFR6aKP?3=jacxUJ69!1kVTysAOjH<#0wvZOadZ#Z%Nv!QG)f`ZVHG3>sfx?W0G6! zr~0XZ6FZ1;3t?{XOvotW`P7dgc_itK-+;`V$ay_rG4_y{Nft0dDC_&aA&FKHJS`Of zxBaoSse*$BAj$Rh>Bl=^6&j@V9o2SSSZr{W_bne`9NKXI*_us^u-v zk<_?SZNdIPoczAoPZ9kgc-m71^qFD{fb@ZhV8X_Yih89g_SjtORaK{iPT z=9ALc{ceF<7R;1SNBbVP6tSFLAqUnuo@1ANYY?-5`i!1L$o_eaQ64pdX1zdh4j@JV z3zf?X|0jk3u%6RhNzRr1*3?Y7XDz=Im;(shi}%bD<4#@zuSg8~t6MB07$= zx{aL1nj$(+Qr;)evwgboIQ+f`8RfQGUYmU8nbq^Kmb0WqjIahdWyDqPndd*a7AzNh zO@8>4SvnNGgyUpbKGqu4I%3%T?c>mMo~fTQKE&ChE-u6iS9qj|@+9x(u2piDU%Fr^ z?k_nF$6V*7LVgdd=OlqXZ$qO=bH4HN70;kWu#Y*PzORBiD!`qlr9(Oci#{B}nQ zcVl%!**#Siw0;MOHP)sMp_VTcNmcSf@c7-~l0Dp+VALA;#uEpddu;;|2QddlRaJGG z536ME^I16{4I3LTn6$kfP4LS!Kei2%yx@pD2uhA>)4Sw%Jp=s{gMA$dOkAKHLuI8y;^2{-Gm_Q_co>ANfwg~cj_W!wOg z)CsH0Z;o4TG)FHl;{W*vM4xZwik9;I&RU)RZk(cO0lc5qw&L@jSMmb}|Dph@{Wgv- z2qZ2E9x{R+GyakD?tXf`{q%{r`;cuW|J3sUn(O2zVd6jsK=i{zbzWziGhmZ6L3WLH zlxf?a6ucY+@NbVKh6*xRZeb@~{bV5>!Ap84v=_K$?>)1%0-JrGcjMeo+@c|wNgwe| z5j7U5eQn3X6sJ=GF?&)(!~2Nsw2#dIrdKj(L6@Wqg=d`YJ{mUDtN0$eczVXpSNDjb zb}|ZaiwLSvg-6KjG2%0v$|7j`y!<+-B0{kDdNoXAVN_%bM*U4r&ktAwXz2O??5Ty~ zKVpi0snK(ozV|Brv~K!#Wkw+x&0SasrNev$<= zl6<`~-d1ar_A;kT(O4YG%8pdx34`&hp|GE+P;O zXAe5vq!Y3n%CAH2nfhN+ZUgAtti@w2f$X@DyvpJSUK^Eap9{s0h<^)H7Kx>TBTx1$;rG5JzM=m%@E z)hk9!+!IBT6J!eE8nR(cvTKbO-zOzcl+}mN8ee0q*K*yTYe;Is$lgaAsH?cknQOqN zfaEYq^?+notRI*qyz&Ff2h7$VN3^G8rKNj7C%cf_(C*i>Qs!{F96rr6f?3#*T)I>XDN?sL6ZnJ8xDGihC z4*hCz9R)jnT0Q3%z%NR~RJQEU@fQ*ibIf^T!bDmL`?JT(1H0iM(6{E3?*4wde@n0a zWN-=*ZfDa7`-$hvbxw}7gkS;~aXb)-)Te^RGGT?PwGRBBYx z>9)vDpP0q-9>0XODe;Ybmh}dI~Nm+glK0r+4Qt}+$@%t4wy<4VtPIC5onS{=VH%h02u z{yH~*m*E9*`w_Wk-xx3zTny2QUHjr8{3v@0&-V+0E24q|ZpiVrpU;C{*;e1#pZiSt z$ddS_1(m*K40DNGTXSm=YN+)HvDoVhd_JB8`llWGJ_0uiGzwbpzT zZT|a=*^|U_vJl*f9KPuIxZAVw5=NZcMQ=*5?BjQNlYC8g0OOTF_;nMs&T9 z+dtgtMvfg^9!Dn9MT&_w#?UOsHS@x+uWePKgtTM;g>OsT4vEP*WUC*!mG`P-?vat# zD-P8Wt7&M<2KWVwx}}7cdXSCAT;o5=I;V{3{z5-mCZCpO=I&__ey4a>Nr=LEy%Q;E zcY+7p>zFXc4^`E(rv-dHD@w+;70%PxGBDlP7UdY ztEbW{d)wUEX{Q!WN$Nyf2vKWY8Iv{eOr=RO-{nL-<<{ak<+_v5057qp*Cz;=QT9R8 zy)Z#2#qchGOLc8Esri&0S6j|33w@mi9L2n`Y9SO7N2w7)o_M>gRLx!(=QzcBh=6SM zcA-$?oYdKk@SJhEbo3l;gU+8CYomEnJg>vu2(;)aaP<{@RF)uvWXxt zxy&CbCHLU^RTzlxDMgC(DdSqzSQlMlE&{Tz3x9xu|2IAH>wEJjeWALs)g7x zVMTO`=U={oUao+`PBS$EOJD*=+R5L%M(v(Na9(wxKE>jS*uaJ zLz3;^jz#CPgLI+qx(DAT>uwNz&d{CNJcFX~vRiuX7A!jBmk0QDT#&&LFj?$+&v=Z)oz#&vI; z7Ba7)P@91tdN*N8km;03Q4E}_};F1 zUvSKE&$x0GwSx9?IU20lrTa#2|KP!Gjpi3oP_hk~{OyWFDfwHT{lgiDbVs!4nU+OK zO#v+Tav-cb6hXi@Up1XmKm<6lm#p zo_FT^lgXdVWRi3Cx%b{{U5iX$!|6+N?Bk9%o!vTDR2y7*k{R|sJSP!c-Tl^m?g0%) z3bFMfvGZ0(+#AZGoT;mAPZSZ)j(V+M0dWB~y&EKOnKR{4Zt+W(RP=D75#s8}&mT+X z)3Hn=fBqCcJLf%K=lAyZZt-^@fa_VipZ7^8YZgGRs8%uTx#cL_ldF}hk@PHMh6}2nKws} zNZagG@*)VI*yI&O3ZwtK{t%4MN6V+&%K*O%CcvCyWW4O3`FvcDsjXg-u0ht9ANE;_ zP#`8d1fJ+QaK@?ZYfdh!J6nP52_H2tzx_y}%*%1EO_mt4maWdIhsIGG83MXZW&ZY( z?<7};hzs|H8<7q8*ZsFZESOAP+O2|Tn8c+j6@*yQCW08jm5aj|gFo($kj7CkLFO_^ ztJB9%2#$&;P6|&j5??V%Zm$!ekRSuCXZ`JnXhw-cTkMU~+nhHF-7aCH1}{a@a_Eft zZ>94v&?F`i`m#L8{fy$pOW^B{X0>h&W_w!}B$uU}KGD> z0n0q;QHnbUu{4spRl2w~4LoJ)-}SNWYBm|Xqe+QA@z^7W7``o_6oXr3;7d60sJ?bn`Ul?EnDn0?6%6m3Z|E`|1#VI@+C-1{1U{Vl zzn2aF6>5zz9%*TE5ar*Lz}}FyUqF%LZLDqM&n9?@?Cktu_vc;Da|=|CZJ^u%Kz_Bg`(!btbxPUQUGb?SIO#nq^ojtlTb~ zrPZnL7>-k&%(NNd{*Oz&0cocIy#9XKHf4Qk?W?`>f6eaB4z=@Um*2%bAoSY07o3U( zQZs<9v*=Tb=u`BAQ)f^o#=D=jfBz#ax37K#R>;5qD_&a=Ekq_s8j3vWl;W-oITq9! zG40FJ((1ylk+cw|o%CV|74`B(;L`v!BL>e_RXaCRHQPN|>}+93fOA ze1wV10me1^xNst2>gPWL8f0`77>azCPo8SiSXsubo`iCb20_!E2#z-n6X>X&a|6t}qgyJqET2sh>_?(a``D0IBi9lssGHJBD^xA!laU*|o z;m5Ha0gXVq%{467sq~&ijnYytA^f2vA<#s;w8+HxQ3~Of7~vLTO}X zY~+y#jQ2LbU$)ACy7*bh`ukao(0B%r6f$;~x9@G&(IgfpUOAz;v z>9lWs9^0Y3(A4npYAblV{_*3RvB8w9fhe=^FjF%F^L}(oQ#cGlIY)3Ky>^4Rgc5vk z7~+{O$!8=kM^<6F$xu%B4dKkzs=C%1hmOZrNo$$hHohY%sl$I;-aZzK2kz3pRzwfL z#Dl~=++Y2rGu_yUb5TF*5Q}Cdt8Sz`7_$rBXO5q?X$m;z`TK@hj=7Hu*8O;YV-sz~ zs}lPLH9d!&!9@}wJJyWOMW162u~LU-s34jD*o%ad)^C7#j+l?gp31$_esZ;{Fc|8+ zX6(7=_E}rYu#1tVxJ(qUm7wKeRO;GW-%kI~@$4PrurK~Q%N#|<7%REg`Y%Ik`s(Ii z@bb1YjB^Cw0&KHF+fH*YIrSw7=3vZiY|;d#IK%5K8=UEXuB+*163n{(fW!BsdZBIKhxHt5C1G7M%F?8H$v{Wk|vmYI^z$YaogvC z1KxX?7AWgebQjU~hu_H`j-uj0F*ImuiCv{I`PH3| zQJ`JiRKMbBcyr#!S;}jI>d@$>WlG5r^J++Rqu5FI%qW+hG@v}uZ!dhQbhW-$TKIWpI?QKL}by~F0?E!52-kP|Z5R8L$=6&tCf)Sw^PtoV^eU3}RZ)qemU-1Vta zcQQTl4OFDhR*iow{glEXQ=ps`hu(j?mcpO}X}cSbdme)_Gg1-6P9Ax&Bb0@m;aKsD zNupNoE2x1l)ikRKbqDj?@p+O>vmbOmIwSacWU8QuA+a9GXsOE^X$0_AjxS;rh{*y9;VTb$ZI}7whC`6AfRDaMzr-Tad&L6s+-$S< zFhiSo7i^EVO>;dED+Qskh(i30Ubhl73M-)+MhFa-qd5IIcYX#!xQMzF2IHs~^^J)S z)_MUhiNar=%3XwV0$R@#tDb@IH;7d404r1J*{!--TW|9FGy;tZiW(FY6e_U3d*!LX zH7-nb^^NXCK!pviKp{+nEL5Le1;m__F*FjlvVR0&5^tDg$M`+0jdx`b%>N`axND(3 zk=ddu_wYccXtIrpkm8?38y7jhwv>Qq9-nr3*JksV*hpT8O;=NKYTKT87}rYJN{r5g zc3pSBf^61+E{;mobarOZLLydO?q{*B>cXf{f}QXQi{4ldo`nk}LQ`Ag#*C=2`tWlM zlt{DLO~F__@sHzF?n=5*jZhtryYk@0a9=-D?pMRv5xkmIcIw$hzUMx9|B6bOFxMw0 zxMaKROdiUwclbZjuqS!b$|i&Xv$@*gFHoQUpNR*OTiU`qal1wpy0=WZ+umdZWJ~vE zePPR_j7Nqm0la0b@hzeyr5(Em07a>rBEcyulX_{XG_TF-^@@sCz_eiG& zeJWA-DOGj_(66PG2MrKLMay__r@NIr2Wy+#s*{_)KYL(2v*%ZZy+-}o?cBjYc7i3F zrmTH^Z4xs89bK`f-hxrHY+pJ#ZLLklBFj&LJ>@whw(zwg@Q|OLNKGITwp=~wZJQDJpa&c5RpNk*BD`2(TEZUGt*0!V6 zb;jZ=`yJ4E45>|iqF*e-Nh(V zZCSOQi%txOY9_W8oi@o-L@M#nxFMU%rnJGwOt8|F1kQEemD@VYe(4(yiBCvXZ#vGJ zgTA5WEwAoq2P?i^CdX@{CeI1+1Mx4FQzBP+qp3uvz|5^L31Hu=8t9*5%;E3}u~kLp zq|xDC15}fkA{a1<$8=hP{XqFySF_&R$>(pYq4l-ToRN6t#yvf!#Yv#Z%j7F+PK zp1z*f|H&1oe>8KwvA&-n+Kzy0We*R`MsdN_|BN`bOjf2&uYnsxD#uJ=fGhIDi{{u- zV<(nGc>@5=T!ALZSyzppvb$E%6+3-ZCwyIi6!T6Wj@p>-j_Hde_~^`j38A6%T|WQK z3D?W}@jeJ8G25(neeWKDU;KDwYfsG)hs%4|De(cPl21*2f$v+_M|G?UbIR;KUjX^` z&;N;GW<@w%_O0(mXa2~}wLH8#eq4XaL*YAxPf{dU7cjHR?XJ0YGgK;u-__in@~8P)}AnM19HP#SZZT(vcIIo<$c~Jp^#K8y+uRH)PPPi?itUpd>zM~ z1&5rJ->1Z;k9a5L{eoNf?3~;rU?JMbhQS3(TPTRDUZlO^QU9wj0T0caSk*F}BiaBB z_+b37R;VWZ=14Bpc4#mX7yG6Rc|K^CS7&j)^$8`}vQJHj`8&QFQ#N?*f>yR7sJ40D z0bn8ca*P(h_W8ffHYI)UvSA7}E>9#-@P~JB3IZ=BR{0!Zj-~r8EYUoS zOUzz76i1^X?v`5(W}0NkgxK<9A~Rw({5g0qEN8UtQ9`EzjL@ujk->w2q?o;;yWxrB zSF0BKDt!nTBJLL=9mm;p=t-*n&9*9$l+gwlCN#q@tENG|H z+_f(}vsP6sBq+BHTX*(bcgw6gh3h2yhO+1&nQnjN7_Kl+JUMGZ&c~!8`0(8P-jn;S zaHw9t^=Ak;pWf)Z{2Qcem9hcumHbZy;Te#-b@ zLDr5gt-ZO_hC*Is&*k-Q42L-cdFseR(P^qs!@+Hu zgF206Zj(n+odpv~;R`!*gfzBx)8Aef-|& z{kvh=&%6Oxe&<((KIu20^*yo@{W6%BawP`@4z7>{ z&@}EHS*QZc_cimEzdA4?@f&Z@io8xWicngMfAx{O>%;d*%0tGH=Zf=RJw(7dMrBWq; z0-LvWq;pEityswn@uGhUQu>WfZQ5;2I|6H+9-q|{_9-2x@Z|>1tPoo5BbKnD4^Ov_ z;6;C^cs)oQmnt=kN=2emFG6uPglWv)g8{y!j*-A}v6OIfcEIiNK%+7IB3E+jUe|@! z_OLrb;!q^z&?In)BG=mUr!5(G{}Z7xhRQccKN)xrWF1*;zx@YurbWH`eLBS_5@sdL zLl7U60$h3s0BSBdlY67`+`g@`^0x5Dr&ecfP&xrE-X^!M)e(tr=&t`$C=)Kbk*FV8 z-!UY(o2djI_9k1UIB#}4iZfL5xD=8TJ|Ed9Ki+br7@++t|RczQ&@M*g;+BlN25DBHOIVQ?=XI=?Icl?gqT1e+pUnE8@QB0B-H*iQ?J;yIT@1(FZr zLaOKs zii^P$U@YMk7nC~@rS|4LrnMwx0U~{>4Cbm_coPOyS)@?(x zKZ`Hr|D0Gn(*NO_c%~kI9oJlW#240rl@6h&65bf1C8uMdX7zNKZ)Gv+lCU&gsL2?O z`C!dh&3Z9#V6n`U)Uhmig|-sRIq??MI6C_8+uoP10+AQX4ay^V)QrcK9dQsRg}#-2 zi;}dg73=TD;%+57cmfm=uxam5KP?O1oc?93n3cEsLS70?lFc?vdhSYqB3V*2*1nF8 z0u{e8g8vHNKbil1X?R9LiY!}K)O`qYX@ck0HJ6G5C^6NcmT+m^xh-1-O@8zpxaSA$ z&6<8#oUc2!N{~g#X}Ab)&a_$!#S*v=M|s2it8O2EMVGXYUlz-bSx}^zsbiaPhf@NW zE=>|O42-NBEnHPKA1p;bg{S|;$Mg$!TDz0%uX)dVw_g*_iLH@Xba86c9Y1?NQPy|e zpyvl%@CQCL6%5CbzJH+j_cbBtOb|Z*#XVDGZ0FGGWdP_NjjsPVZV>j~u=Iu`0Ft?_ zaN{5sQn;%LPcj6|w*#JI@bvs3>oRl@-+(v)u@tyi+ZBH}jA`KIESQ#nsVuu7>>7^@ zMcRI-BwP}O!R!7l$W~l40t-K#Q(UHBe3@rO^&>B~2EF#YdqH+%(K7w_FIIb=@M^>% zJZe*lS7RikV@Sz!codQ8^s|VT!J7k4Vc!(oXcRDm-#rB?6_c2nawRXQ;U3)u`TZfy z^IKtYZFT2A0;=@Y0LH8ZL;^Q8eNxh}_anL1GF2EBZ1%|@N^O-O9pkHQG`yU=X%sZX z@Yk>)GG}tKCaQ|M7xY)|nw9$4(Mc|t-xZP92wRpS<_WI#Cn1#UL?PItb%1)nQ5m&W zNPdW-knDuo!9}e0^N-ot_k5yTz<$}mD-NI@?f&^gCdmzyIyHl&YA(+lTS(M$bKPC;={ zFylrk*kWedTCC9jH=b{*y8eS+kt?X=81=A=QhlhX*5ELgW#+gwIGXl=4Iyz{14qr5 zk$N5=7C~VP$5{s=bRaFb2Kx2mAq!!9H41l;fKZ0Pc%gt&#`%2}Sf#F^V6gDiFDS}% zmP~jN1|$9^WO#B8whTc8Ss<_yhrwlG5IoM=97h@p`wxw|Uv3JI6C8#e@ig&gd&loD z+w_Gq69X>a-?R0-VPHvQZatyjL^1pnpZ=ibl93PSkdRdHD7hC*H2EUoI*H^>2oyuC zLG!TmAJ_-jreQP{<-xcEt@IU#aiko32N@UK(A5h<`n)^)-FY>T(iTY` z(`)b*B+m&o@iAyK&{g4}#9(~pq&Yo}wYbnk;uT)ziet#B4-sqr7DL-a%e}W7O^OqOIAEWLI*NxCaf~0=!4+?ObXYg zM^LmZ*r!hMD!Ta?HuqOfLXqBn2BsU+rxqD6pQ_8H0HwvHZiIVI?Ot_hncqwa z^x1@N#W~fba-q6Vb|%vr9&vZSoT&o(A)_nJc)#7xqkz>2(K@*4eK(xdZc>jfD<~=- zxDC5b)J?CcW@fm!E;xFwyt-~C+5pz96~HJ=p@LTd4CWTA6q2i6s9#w|P!i>^xJ9z^ z&Akvnm$jE*fzr*%d?9P6xCqq9NZD_Jjs4?kHQzj+m;=cgY;z-i=b!|we4e@<6r$~Z zB)xvc}l^5i%F1Co#!h^}Q)N447OyN)8+jcA+}ci1gLN6)B#%ka|^iO*%eImD8q zUWfEf*rG*06bi$U5jf%;Ytl-a^(=$L;Bw}jK&`(ZnKjo@t~><60hGUiPSKmBgzY`b zf4_Z%F8=%pJn9@A9K4jypcs3|f9yi}k2{l8ttNUL*IzkStVrU_> zR)i*@|qd+NI4l&Z)iGShbbT{pdFnOP^ zlVn%VL4G->D*B|A9JQ!5oOz*f_7to}XiUfsvb`B*^?fy%7E)XYG^VNcrc$x4R7>ks z`J>S|OmiLaI6N^WkxZlE3<_y(mxbk-g5P_12x|N42!~opSN% z&b4ihwc9ipo5Q)ijS{lkAlhu^%Vnv2^4DB4@W|E3nzIYSkl5hqJzd+h;0#AGeI99z zo6U%|!LAf33fJAxnpuI|pE7*Ck%_6wrU&pVvK~u45l1la4D@)-?`XSAhkxLibx&5w zPQ_Af|C&=E&izlyof%beNGTM!qAS(EY$y6}71n`+l15-otLrFwkV7YVDOb8}!73%r z%G@TP5c7-bB$yOR_L;VylNWgz%r(gM(K~)m9DIId`S$5$!~BP!DA8pecsl}>2QJV% zw*Mv70~cvFx7AVVZRPL8k)?~8;$j>oa&8$a_01WD9LP=~v7eTxy^9$)i3&wtXFQvB z6dBmBPt2ju4oL?4B$V*M5j#4kv z(VW?ABEdln_g7BEk`N}sZ#tGCuLDJpv0N$k-Oa?2zl#J9U#V(QY{C)fX`9nslOG53 z_2KmkzDu=5EC`(>%_Zinz@tszBo>h6U(;%emHFH%6+eD0HP&+FhH%WvJXv?iq+7DCp1NxpXM2ZUGY7<% z5ZXF&-8g(*JmQW#wCNsg&}>xnZ(Lc7eb0xIrblLR5ewJ7+WNl>Yd^(VpB|Byfmi8r56O>urUx$35 zD3PSX6vzAJn-?kuBjvOxbQUr~F~D9>kEW^sIZcKmOR2SVwHzA2uHijc$uoLg&YcpX~q zsWOw)4d^$N33N79bPQ&7QYeqZJJN;BOZik`vcnj95^SDyNhD(p>@{0)#J5Ouh`Gx) z%aPPanmf}9y7|4=r>8D>(`zHSWqcd=ryt-=0j_1>i$VQv?rM}$Wwi{F@VHGms=#yI zptYdsSHnWP?D=nKbEI0CoHdRV2HN4wezG`3ga)K9$xtZkl1X{>RD~2X87?Z8S=6^r z|1hD*OD&^mEN|uQ@bl!t5~s^YfznI_cYT-E;(5Aal$%$p{!xp2h^b0d~snGY=kG&iHK=@bgUR|uF5an;pd=jE-` zC+8Qv3^cXkQc@HX!yYi+q3WVGFeZg)VPw)YHv6^8uTDL4+;XdwV%-|kl%b^F?$Y$RF1Bi(!?A-Rk`Q#z64uKp(yIB>A@~_FBw`=FL-DF4OrV(T zbkeVc%$u7tJFapGq~V+HQJ;(twO7VrMk6{52z8dBWA)_<@x0+Y1vUx(dA3u)&ttS| zdm{5dgQCg0`7Ii3)8)9OEoW*iQp$jGUqKfBIr}=o0(+zo8K)iDYTD3loTn7Jcszz9 z?1JMb=b;u5VltyXV_U>zz0cJ_-Id2@&hK)aPwB6d|2AipG1_yHr_vDr(lYP8y7X4n zLije=HfJSwE;IKuS5j(==yc4MELQY0jeO~?^sX0UeyaP-^5ke{8~1$=0sRJlWK+N+ zXU?>1gJGdNg9&H|&JA3)X7|VL0TY>zGXkt$L_}LWV{5gWgXS#nz^3(`0gafopSW^h z#SfdNw7SQe?Nrk5i(gK5Dqfa)X>1r>#6CYWh<1C?5Pstx{p;$Iuz)og5==L5Yw+op z5x~MS?DU7fWYL`2vF#B%5Y9$7rQoSWpf7;64_M? zP|Wdr<%U~=8Hq`y=7ylcFide1=H(Do@^?W^c(A3M-eAew6!-uFpE%%Onzad|j_ zg*2O@IV4E3B>_C26l{9AQR|9;B1WzTz-}V1HY*DHb$TDPx~>LdDo;t?zn&szxBk~vhF5HQlTQH& zYpRDCh^)Ar?-#Yuu?-)RjiV63UEcT1>9UcHSb2P#S70~qj}dx;l8Zch*B%sJi-oHl zfVQxoKhmf71j<;^mBd4m5L0y=@jZv|L~J2gFSEi=0K6k9q2CBoKbS~uzg>j>dpOlfhv$O&r@2J zE_HFuP9!g(AJDEHJcW=L!+>POjiV|3WtCj}G)`t^8JJJwj}jd$s;zRhliVT|+1UU` zeTD2E0vJL~zX8`E z>_5lKhtFk{Lo%#X8L(X8J~-32#;J^uG%h4{`sq&U&{F(12oMpMaf8?3C(*R_yvPl7IfGm+pj)vF(UDng7-Me2>@6SiTH_U0PwPFB z>GW6qU;4S69O*)XL0hz({aRk?)%0g}V*EkSi2^_8bOO1u-~I^@eyt*&U~bVIL&neq zRSu1sjx(MkV?u^EjORRbNsK16!f%@*E)owDYH_K|CPeACBNG=`Ip5B4qe+B)$xP># zOoh`lnuz@+q;C9SjOyEYdsUe)QRdhx$pGxYF=C>nG8!NG;RAlQEY+{jCCg9#oTNnK zMb0v73YYTkrB%{X0kfE1$kv21tlx51*TY_~4|TlWGi-mVPNgSEN*uf+$fUKFDtE-s zg3POnnk&KVn7h&ko=0}V)zBjR{*_JTlF6RtlU2bb?SMHk4Z_Yz2E8$&5rj}U;h>mN zLJud+u6;k-w>_O+zKeHJPwqK=++U_1p(vz2SWo%YxYe|48Pwp%aY?#1aDGoQQ>3nM zb;mk;8rG9?nC5(vq&A(U6Z_Ld5x!6X}@lv@5u!Lrts(qcDg>I+g1`W^unN&-|i3!;nfbs0vL zUpd21Mn)Dzb^vS5E4ncj3d4tuHJlDlAI5!UVd-AsZ?Fjmi7|v;AR$q-v=tr@Nb~gZ z-+w7VjaG3dwqGYu6oz9+v(v0s-D~i5aqzZ|KN;3zs{hQ~z$c|VZAtxXJ=CU6f**x= z=1GR3U-^>SXh`qLO$v=ALc1Kl5y|}e(_6Qm*ET*~%pC-qa2lS2V281p-9o0~*)+0~ zO0p4`m@wSZLD-3swYNT5390V7RWWIMmNKY)zPk`t#l2*a%aGD`1obnQZgW;bg6wC= zDS=scvZlt2;1FM5yYh)>;jb@pAWh_wIugxg)`MCelC^vC){VF&+--CvA$fA%LydH< zzUSOST68J~wTRuZxutj2-!XsAm0%-eSIc}5<~>!eKA;Mkz6H39=846l-Gn1KvjBG& z8;Jk(CI!r35zGF-zf-CmQcgx2a>bzoi?^G$`rDYxv3OLz<&j;%MIu{_k&Ib3Er@+o zcIBw$*UVTb_D^GCSnPhE^@}KQtm&&n22;|rsWiSUr?gPXX_$V|lnVX{ zuk!HG{x7ts5Fd25wyOc}(&Wl%^#h&jmz{-}Hl$3WJSCNoyp&GtE8)1NKsG9rOL_Wa zxh|U%H*r%=Bj#-ri9a46mCpTU4G3ppjgLb@MpRB(|A;tBJe+oX8t>hFAX=Cn--PW& zv<_)!V_L!EbXgFE9=R4Lt2hQ8MJ#ppyN0{K)O#^`)7YSb)C1hL>7Ya$j+#t{eiaSA zR59338%MWP;&ivMqEvM?wMQ#>(?%T{6;PuvM45@S;Y2d_ zMDj3L_IW?1yZ_zrD_?UZDTz7sFHlt~4bN$o;K}`9hcy<4Co}Q$rBWEe#v*Xit)wUa zRcPvSdCgTO^IS4hyxc^Y;iB=A;6x5#D^jP*iB8d&*s7VlZCZMULnmTVx##GLBQvMg z1CB+ozVBP2)+(bO0!b-EPE2z1E$Rq3SZRgZ&_D@o=w2auR|q`4ixkay$-HZJD}q}0 zr_{|1i?jl6n4Y*gSJ{tz$$MXZGxZqW&`Qu?MXnDQ7JY*?fBxiAeKm7!fqK8J`09Be zO~@nGrf zQ&P8lijUUZc1nDe^r(nS*T?gqnKc2`NaXSJDR=EPdS(L@1X&{}lcIYz@Wo>i6Vc_) z@@%$QF&%v4y~>DK2w&d?aWUKc&7?=yL z=1mkcpH9u07znQ`MU%bMUmF#!2baPI$+F)7Gt{uLj=n61K)zW-Gfj3siW<|dtC2!? z;amv8%J?i5Db`b1TE-Jc^7!kyz*3zAWWd&Vf^JlnI}eTx=qs zb{JP#g%NJdJ#Jke;+sevuXZ1tdFV2VNMk!48RWio zck5Z3zQ=Cy6l&)AU;FwAU{rftK29Z@Tt1v{{Qhwy5=mt2Yjzia3b$HkG&uWuHv8Ik zV>fejn|C=gGqZVj|N3^rB0)H!;HAAFVDJda{a@g~?tks=)t}qhgpZwWd&vI-XaO|V z-WOA6T$&~2PzVAUve|tB%q-rduP79@X z!mppgDF>gS(V^4y^H&jme?*Ar0W!q+djM=A0{VXM^9fs)4#Ep-jW9PnPXe|TJDvhEN9v)W5ESnQ+%W?aUG_=xVq&MRpTI9EB_F?~!UBM0AGPShnG_DoS4) z!j1ymnYO;?3Hr==<(+9VN)n_ieW4j4PF;wwK z4p6*%>?CU;B;dH|kqXy!5_CB)#Po(dbZ+{S z#gjPqX3navs!vTQ+v3?(mK-drnAS6uvTE(>S%ppe1IPX655VL$=bpst=XTzu|643< zti`5{Wa0==Va8X6NI{>Ay^FjioVE8kE$E1Xd_EE767bi!RkE*+dxmwhRqpAsZ9ixi zP;M2{HHvSpu{e5udpWjkz@NFEsA=p07!aV{$UQ?r@|6*5>CRR^Q&$ny+e>>GJaRSd zCTcqPGU>rQB4^qz)Ti;G`;B%L37vy`_vV1uuj=Yj5>M(JBPmMV{y*he^b~e`I&~Fi z1h$}WjOSD7Zxgp`^ywpH&)Hn;zT-)NKk$s>>{H`l9G36k3DeQA*{%}JfcZ)K{q!<| z(Ynh$z=blrba;x4qN(vCZf1mNmk+iZ48(Z~9F6LaYj0nab7&=+HRYuKqp*>DxEi`b zWVOB(7Q!o;efiisR%zaQz86jeC$859%}z^biK2g*SsyE`-zKrku2>Lsi<}Pme=R^; zAlsrsn$}h~k-&RQ;pd)=kgCw*JZi)#YmY9V0`$$#qgglkU3V3?i2zJh-}`03tDfLT zwvKZ`E&9fwMIIo$3-DD6^fn%!y*@bleQbvyAbcoN5xt4Ub)!#8;Q+KUzOSVJKJTUA zv0`N;bNhk!)&V)*6#!O=9Z6yJaX0`d3y3sKQ7=F-*#nlRMq4E}Y@1JYlmp8(8GVoj zLtZ~t`Pc=Ggx~7r(1wo!uk;1^`8m%hbS^4KfgLlzbO@NZg+hpLpD>%g;|_wafA1w& z_;C&bOPUjX%zmR@;K|Bj)O?{p%WOCE1fls4%e_sy<%=den&IjjNDPCGoKBN?Y3%{q zIC3AqbDDZHXtT`|4HiPr{e*HZkgmABO;x7w<nl9)v3~;3e_2eP(1G}tS0n&dDEgQ1{%Ti-frb?X+j_F(^Mocw2ZlmzSPL5Uwxr01Se9rG6&&Ws~Msp;8uH*oh(k8HIH@)JSIGzMCow_Z3Rmb1lJDY71KN z5q2&pD9*2i-i7+R4arWNA*^KT2@`ey-Us)iQxlIPFih>uJ-BKuS{z^~EEV+sdCFQ~I$r>X%=X z5+o97G=cO0rGFazyf{i!(pQZrRr7Bz$t9wW<iK0#s0#a7hNh)Xj$WByJML&@b(%u-Lr(cVx%>ju{M7=I-l#l9UH1WhI# zC2F8!IlPlIa8eTNW8FB8?_JjeTn`9mc+ZqP;>ih@69_k%PKBIAjm z;aoj5j(W(pop02SsN!)0mFA%L!;D|1F!!F7T^8`^f*fyfP%GI@D z$h}=vfCzAJ2M!;<0G{8_PM_I35(!#N#GGmUDeI=<{E+$R+>jxAxHXqW?YcM1<*AW) zGqba1 z)A<^JG#}~Kul~*|c*=So_%n!KtoLc!rKd{doMPm?ATe;ZisV1WflhrSv+L~7ySthA?a6%~2o8c`KRv%l zf0BoGT|HjElNlW#m|#a&1tKA7t(D{UO8C>8NRsGhRkhyfOTDH3B4^K(#=0BuQ&Z4l zTv~@}}7>c(}Xlq~=Wp#o;ia@gslypGf`t9X})SqiBXY$KbOl?S(Q$+YMf(QFy9Uhiol7BDK->g+ZU*QH>BK84oy1 zF`n5xIQW^YqdDiEy6fBoBzL@M`!_mq&|++6KIU&U%auX=NeSx+bBI@94lW~Q=EV3% zNvsxH+hR4CPxx_oMpr_tM|A#IkfKR1)W0!gz5o2}SsHi|aP#I~c{|Iv&v3Ax=4rRnI2lc-)k%#pDck zErFs&DKj`H>m_#fz-Xn_>1xd)!R)IpLxZPC!KtntzT%D+(_UpCH8HsCQis)r_RfVTCiNRP#V1jXGIG<~B~Td;?OSmxZa(VgPA-SPk${ zhTAe_(0Dg0Nb-0YHKo4l0UoMe^~E+xzK^0o%5NAr%gjVzoh~z7Y<9>P-!#+J3^Yu}c5dAt&wM1_FDAH~{2M z#_{)v<(t%1!(2xCDuvCF2Nc^sX0S5}Ws`jX@)}*w zPY8It*rYS5?va2JS!N6$?MLM%bn-$$MtkwIGXwpbu>gPn`1RL`S2n_1{)msN3nzW) zH9v?G)-D6hJ)p}q3Y+}PMlv^o2z z9B{<}ixh~{M!6>sOnUC3zNQJ=SLIR}nY1=3vQt=-iV4J;q4)<#6yX(l8vn365=UCH z^?K;?itMz}Q%9C(6>ucD)qeZaV^%n0V4UJXM(TIC$#0~-+m1pH9iHvPOKuNV14`z?<@Sr_OK>CO=2{E#nXqaZU zhwu1VQ^(xw6r;Cc$_pg52(O&R>6U?aepcJ=n;K-U1( zV%ja8`XO5y)3 zV;RMixbaiB(m)f^k1dy@pZ_ZE4YI3}=-E1>il^@0as$R4BBRy4n}f+pfRgLa8KNz- z;;<$Xm-w~0IAADofKK9Hvbqv6qB~Lr*ZuTD#q}8Xm~B|Zm?UOq@rCqHo8cNmrr9^C zcqg|pk;a?1)?qAL!1V}NE(dQ$)0S7V!a1N#W7PI!RW%BER(gIA?`XoT?pw25Y$an33e%57~~F}uoKbj zSC+OJTWKH@)TZ#5`9GS@Dk`of%EFC1Gz52dg1fuB2G;-q0>Pa|65O2-+ylXaySoPu z?(Qy`%Re(~^&1b+m%3GT_Sxs#{N#dYXQxQm>gc4(GjE4pXlQ77abF3XWXQuwX12E+ zB^Ol9 zybt45vyS~>@=7-t+eqDymOZ_|1WW_;GLOYCfO=L62V&7Lkm#! zaSRV)H@eB;RwfE&eC+t_eZPx-q#mK=$|9;?tz(51>Xl9!<;G3VUYIjR_e)`M|JJWy zv)A3{v2)EJtNt-ol{T@i7jekJSGZFHObr%2nOX8_z+^zx3PK#FF8!GTHM~x3KhI3_ zG3;g7f7m_I&C&qHXlAwjdp#f;-Q#4&<-E}Q`&sX8UIPkx;r$J=Av|sG-a}j5-u8R@} z>RaYiNMch;o*Hn<>$qA|2@1&e3-X1j@Sp;AgnnSBGMWc|7rAbv*)Y-x4J=!7Q&ArZ zS;l~$f?zR6vY)k3xzK0E4%uWT^Dt9Vj!GBwtEPf)Hp?<3vb*QW11~czo>p$}{2ID_ z*?TsoG_KtC{M2H0u%+<$$w$6iJrDz*ja{b3FINWojS8Oq&P_@O)~z0b6A8PCb+<^6 z9rM88;Na`yB7+ly)R`~o!#|zfG?u8cYvNBg956`akP+1$4LWWN?tiR3kSHT&F2Ci1 zZoXxKa!v?cHCNt^a!wS$w#_}Z52SWHTlt;`lRf{sc@qEpMvVfLu&|k#nW;Ngps@^t zkN_=_iKG$j9!69OFKFZDjqC9x+z7_kQcBY^dC;?L{X4Ewf)5pJtcXrR%qZsLFIm$Z z2fWQ$;IIFLuET_t3G)Ph+{+ZzMsJm8_|sHFUsYbh#{6$3;t1!-KOw7TO?X|#@h8UF zMW11P433gs281EKp(4YQZZ8r?KkPKPjE!=_J)$h30~8Bgx#oK=0#)eXOaK#FZ@f8d z6PK`N7f! zl}kc~IntIIHJQ={OI5;m&eHQyCBASb+IkhI>!&MEkSp>%Cr@X}RT+oiPrGVkgkvyr zB~kIE=J=Y3$x&yf)YES@z(%;Ma>9BfOmJd=uj9Te92$*Ij3ziTRzeFh4y zj~VvjXkWP_(fNL2Gqx*KK&rf)b9u8b;9db(Rseagw$?|lLat37rBaDi;iqscVv;ocReoY-+%#6}k{3`nJo}>r z*y|5zn2gvNzJd7-BbTW|2J_mgHH~gNk;!LdXXu682k2c{J@2(rGxJA%Xhu-s73(Gi z&7>FRMEa_=Np|va4jHt{+1h}&-?t3POboqyD3?P_21+ZhYIAA`L^fu9eSM)dMQd^1 zZ$$l}V45wqx`yFeU!0#0Vw5KcpObKtoWGrB*@CijXD?PJ+*tFza8JU5CKNxejh)$H z(4MCUSi28%{R)jS>@ess^tXsB`q+JC60T9;wgS=%FXiaSnQ-$#Y!GYq;^n$muB1^z z-@_umL|hnfgO0`zeCzTnYiG)k=o42vGEgfhDs% zeyr;qYwr;Qx7FD1ye8sn9*r({B8PoYa>+Jl#4)Nd>~>7d7%6FWEcED3jDq8S(R?P< zBB+QRE5GItdmt1G?IWwcw5LfdSKpo2tc+7)i2~|fMjp)OYQDu6hl+f1)aGn~jtrza zd>X{W{N%YAx0e+cC8u#6146Z3Nn=L>v-%E@e*8y6ISKBfApZtJhv_6igzEYDeL4{K ztP|Fr$G~*IFJBbu8%`Ptqe;&b;W0>S@m_F;03G&}xA9>NZ^}XE9M*pPEHD&Z$X@KY zOa0o``Ke8`7=l(cVm-6>`-knGz|M_jx$`jdqR$o=HVrGY?PR;~C$IckLR~_u_ooBb zi=#7b+Qm#CFXm#|O-1a)e+5-~vtiW4CIhDXu4AW%OQgdxnQe4nD=6QNO6uwZMdw5Y-Q>zg0?t}Rco1q#Lu+cyJ25d>X zn{1unR_I?o;8USv#GV6PR224zu9{zk3)4U}96PEoFnR%aP$ICIZ;7M)@vDq0!3h0b z&f!J2lWsTD$PsAgEcVhM5FB<0c-n$OcVq3T4KDiVLTGvgCbJ0oQle5Cj+8nywSUssUR#S#KuSeg-A)}Z794)r;8nEXz`1afCNr zNK46)zrCd_b8Yi-U4hKZxTx(^^NI9MO;NO7m3$|R)~TeX^mMk-@aHOV{wSSj3Hs2Z zr9e@VdBu>AY6jxRP>Xgbo{bJRR!naL^|eGec#UZ(6Hq#*Stohve2B+80~UW5ze38g zhLavM?tgY7)h=QXss`MWZV4l_dc_vLh9`&1_*e!UxHN`god+s@cB>xM8qQfg1XX3o zM^FYj4G)|h`a2Apla{arrJ+TSal62Rtt0hKLHCsl zeGk)wmp0>U3paOU(zy~On@I~9QX|QW`sIPzstMZp=vP5ol85Lcfy!eK>WvULD37q$-WArQRHi1ka|C2Z@7)~DCpzmfX5#v>F_uFY1nFCe9Q~2SVih!C(r{=R z@NVn=SSuce+CZ@GTj82H$>s8A7FAie$Jq-J*&t45XxxvRkRqO32-e<0>ez?jeh~Vz zrN6WK&STIgr6hklO^o)oOA_*LKVaA9RQ1O-HCj*tCEH$&{xBu*lj3n}a~ z9y@I~XiMF8&>v}=e@~1(Zx3+-rV~b@K_-e~s6k4sVG-JoPTkYnQFjcam4j@<7_0Vf zp}I=K(otw%SR6BVZS(cV@#Q$PHAqn zim5R`)@4|W$JzRFgR%VHogc>fmrO(b?s!O##N62T?8H}%!*3t(5KB|H&5`9XzI1k7 zfAnL7a+NgUFhadV%#GV$sn3SK+ry;!uRDxsL}NPxgSHAtBF$Co)^Oy z;=-Ki>z!4-w9O<^=n#C4bVS3D2GyP11O1Gk*=`Hh_j;b9f*|UzlwC02z*UR4RfKdX zHz8wv@8xe}dOV|XYdWPlvI(xyG3=PpQ$UdB&(yI0j!^;RLniL^Cjj>=Wn>`o0p^83 ztn;Hw%);KL4dwR=Op9K79z_m?18$>VPr`~?Gw*O7g^)-usv1HCiq5FW9uWPX2LgQe zo`7$^`39<4o2>J{qziD~Yncdmz4AOLOkH*T*S@BIAa8dfUPm3Lp+*s;5+U2jsGXI1 z-a?$fl#!y@{eyr7&)7@C0)^KV8?_#Eo3=IhmGpoQ!I{z(%m~&dhtq&M8aefX&$IgK zc8qS4MHSF8M=q%Hs|kgJwy?Y3Vp=IpRpDT~R(&}CqcLwD{RtEYUBsgtMW|tmRglp}8+z=e%2)7~7gh36WWU-y ziY7T$sGT)JxXLkWn7faeRIA7}Rl2GOnWO1hWI|rWXrm3ZN&zZQHVX}8M=f&w^o68C zVzhjN|I=~RaBl&{Ne$jCRb0dtOQmj^|WNg6G1i`C!_lr6Umw zN8q-)4;$f;VKO|Vb#CApYIJeGdr{167-*(k*6lC#1vIX|9PzKt75ZiW<9Hz>(mAdx zc!FdBsFL!D!&cd?+2Xli!QmUyO^E=r$W^PB!wH|Wd9uo3C#;f~DlzOrXpCs#`S1wxMe zK*P0@C_Aqg4lBjK8=-)Xb>;`1!Ynl9+2Dn4FvVg(*W#SvS@A7_>?k9RQ0@{xD%$2PU$Dl;&ebs!?BLu=jUEa zWrThRBzt=IiMFFOhjKsyc@8T%K2+C^>|A~Bs5XH_JAK)7*X&yIC>vOg5!-in6V{^sLme>i% z><(BuS3t#9CgScr9qJ_x;*B?PUD9&mlW|zbygYl9nVii?E60d)Xe?_9?Bu(hB#LP6 z9;#fo>d`&f++AlqcyOW$%(~!9#tH2tpcl(TAun`O?3EW6Y=w`ioy22oqGPVFY=KMEiZno%(PfOcp9+P{~z ztyx_YWEJqzMZJ%ToM0he!YfXt5q90{^$! z4FwQg?(g~TX814YCWUl^d`jJ@Bz zZ90c?9*;GUdJ`5{rPB-d4PK1Tvix&m_Dg!{jhZX#NEx~Y5Wrdd(@c&+bsVrNYRwzxZ`YS*79NeIGiFq&lIHx42?CAHYt8as==e~!@r5umfodg!=0_QvL&DF z0l%er_lA|T(}M4?5|@#$Qh78<^w1Y+5K}Bn`1mjo6xO@mD1IzCHYquAsh}_@aRSi0 zf;gy8;h_@Pi1bKcbGpwhEA?kLewi+}tJ+7RdUo2gt9y+zXv*fqx+8uQfSzj}jQ zRk6B1iZgr=wwwIWH~hd(Gi*Z(L(bjXwCO|@L6PF+l8&Eli6;J)3B`&9y5Cpo2BG;u707-3CKOAHI7TEJ35Qoz=(Bx z^6iq{AVK*N;e^OPp_E8Y!?s(r@@CM0*RMiEYP(^A?%$MLDmy~SBq<{_zy&a2PsL~+ zF#BIU_<~bh6gy_{Aq|LaslG*{?{Ov)g+Jz3 zankjl1MGIs}NS}GQ?Fsev+NCPqbpRXd9n@j}-q*qLmAEr#{K4y6kt>$Oli_Y< z$p_Dw55)V@0uM@5Bt@Rzp8SkO<~KGl+aJchgR5pJ@vM%4g1)pktJ_k8t{A!JqBmUC zCQKR$gykhIH56Cd(NTOi?1rLnUJiRd{IO#stATPv21~&61<>7_eK3qHe>)(^h8Q#$ z16B_QAUtiodSE=in)sD*K_TNOaYL$fWP(Q}jN2oKgO)c_R;31_fRoQpwyR54f1z(b zZ1AZPm<H2bgS0gbagZCB)L#(9lVtI^B_`h6NyNWIA-yf}B2>)&NLTT}7;R|?uhRCK& z7@wM%6Yk5{#%wuF2t}RbBFOJu@%wM!`9lG+Tu0sQ%74XU+nFEhc(&+2mZvY{8^!*I z#pmIwzUJo-x*d<&zCb^=`;A7^;4q3|{`8i8snu6!56n9J@i66DYi1uPXr)nwpNqqx z9XgQCY{eb3Q#QwB3?VH`lJoqb2#F4^WK`m&&Z92qfBwNcfiwbVB`Q^s)Su(b=?fE@32r~cbt$}NKr0_ z<6UyyB6AoYT7HxvHW?uU3eDuFGpKR~;`luM4p^n%=1ASJ1RiIreFqF?jsX~Mn)zjA z+rqXl?XQnVjW3TRhE2|J+S(YGP1}D9w&|RGY7vH$QW}Pk^O7n<`K#brRFQZ z-Uz#d>k41}s@sXu#E|fL%mjc~j$@@K61F=Y9>||4OvbtJ8xauPy8daGv%`!ri_mbN zCX-c+g|K9mZ9Qfs*h6PiJxWYWURyWTXRDQ5mWzti>e*?kfsOcc> zBkyaL%wDCI69-#!)3hHkHrnsCT>O9yia^vd%y3;Yu7=M$eHMkkgz9MxN?Ipl!9iO0 z?u$gd-n#aNS^pS&@TeN@h7&dOu|#JKb+CNeqIq^S)+801oSE5A%H2}lxuS?`-sC$`- zzE$#26Gy35`OI4m@JOU}XKI?=eM;+cjFpkk%eH?oIj=Jj*@ojzmWpebB_?{qG=A}e zEfAQ(KKfFAoplMhA{msvSFrI7OIb_m`a=~`_^dLcGo(|o5jJ&mnbE^0owlOr(*>Nq zD?KfZ9-bk?Fu8W>P5S#(P1Jjp%41>gqr8qh{}~WnwLjf3__7ljZ*!8%`j!(J4Eu*R zPlJ_+V&}&#K46y-N4k*So&H#7GI=Egb=&Jua9Gq~(*?Wid3<@epkvF{jU%pGbYk6_ z7pfc2w`Ei+p4lX*r7Jy0NGQ8vj3mUE=os-S$^2PB2CZ+FCAPXXchqq1X!4+He|Bod zu`Hv>%_k(>yST`Z<$H-t>T~>@(fXs04C-p&4r=cy8cG^`@G>thM8Idt;Qg)K1kH>H ztxdAoK%{ak{34{R%*oj~s`3@EsC9oGS$xsk57}`a~c* zp!nN?NoMZ=JDCvfhYKRqfs!LMgf0=OC>lXl1+Kq>?Gzx!oST^ZV+9ISO#rB%x7=dk zq-VT9HXYQUh3tgk=Cd!Z0lEj;&;D<-uHAbgcTHV;k$uo_@w#De162WAhSewd{hn>!AT^!@QMDqS&M z*bD5*DeR0wt7zss3Jhe#_}x+Y7!N?Y;kNMCacd=J6~|5qbKB*{ew=4* zMg}d>5#oYIn^=mAZzhF)*px2*`n;6n#vjU|3lBjHRE24{bUco7B}cZ~8B=O^t#6 z!Vd(i&vFB8Jy6)d?Cq_4Mn`@=mA#{*9k=(z5(dLSA&4qvHODX%R)6FiY@sAHac{7! zaG~IgsrySPrfo%-U>*c=(tkD!pLbkSab1lHt6e09i%8GOp=FeHin-7F11txIPTJ9VZO$@;_W!Q0xlV9kR28<4 z@ue6hIB;^GX!JN!DEheu`LjWXvL{`iMl%w^xrH^tg0;{`>k&d6E%Q^6@sYE<#Wdsa zJ*TbGzm9=%r|w7~pgsL-hsa+Bxeh+peh5D!C*7HP{gDPRwa1)b2ji_82loY&S1h0| z->t7>seYjr8@s*b5n`vmZJhs68bhA*9!JRGZ@*8gZwC@=-IrEOaIyi9EBe^y%XZj} z>0+wKq;Ur9--)dAS%qAGllE$bYGbIerubtIv^<9_Qg_1}l&qJ}S1Di-_Lx5ff^PPc zAIx`TlW%vN_Qpy6Hs25eNWR!eJPdNoZ+iJeJJ#Ppwb#UPnXkN#EBzM-(6HTGv7#~B zcvXh)r&`bj4O$wVHiX81EGHgbTe_4>D-IoUv5BFxOTB^IDPS{214!FHITZ;-rYGWw zfaKXRXH_$p14Ye#WV56oEbvjz2YZi z`E4au7F~C?9N44W6w1q;NaEq{ehxH8*Y|D0f3-vp-+?HX>UFblDZDIo_n&f{Q6o40 zd`OBpe{Y^Gp`&*rN7)VJp{+iQdzd>qIy#sv6WedEeexX7;U*0%z|ef!mlgdlhZ69X z6Z^hCOazd=@wbfqA9frU5imFK0xs|_zIQx)mj~6}zEJ{z(Q`tP+v->}3G=m2EiQZL zZ$`W=$2V`vvR~`U$xQYu*XtWe;N%L!|2!C@VBN}06;%8;y?aplJT7SN6L$!Mcpe0- zcppiHVB+HxUs>fYfzswY#1R52lOmofh={8$a>(1CX3d)n z^Ns|7JXfLH1seM^C2=PJn&z+!HE8;qt)LLPz?x4aB~#SRh$@79RILm`ZFfoA=@dOR z`RJR5XM_9%wRL@s3QW1}hfm%9fKI|nX#$d=f2^!*!;Og{v==FR4;233D(o*E-RA>6RRLE^dz_5g2l9jdpaIU zDl5g^v-%N3Aos~a@?P8!|$}TKb_~@!kFRSSvvG4{yg#tc@Oc)Nmt$gSKAvH zcDyoXlw#vpq=fr|h7LX4I0cd=j<0V(y^}ZJeza|e^RHSQ^~X=Gz+1aMd%r9BWP$IK zwX|TCMMUpJvBPw$?}mhv1cxuPDf?)UhG&Q|lD+dotBBW>(UqmFtlv@~5ZH`^F}twk zcAqDj>mEiqlU9=t?H@>q)>4J{+mQ3KM_En*BO+RX1WauRVFvs7eb?L^ZuvsLtAMgA zBE7Igp87kOkiU^WBiYJ3N&2X08R@Z%3INyDB zyarq&Chvql))MYbDAN1QyV)TdF4yx33&Xke9t_Dp{yGu>reaJTJq)6IB~3*ty8URq zMtepk`de%5)g`}$Q}?}#kGgog(ftDC0~TC=c04mR@tV2!msAt0cXy4$R>~k9Jhgk~ zk-8{r_kG~_W!Mx1_?))3EC4M9Pc}4E?>+897B}C*n(`JkCBPyDK4Yx!8IYIi`z|in zi)N7O8$7`I+ky=@M6v8%c+OwYBlsE7`nEbOs=kHKkB{Zw{%|a~roOH*mZ945B|^-Y zA;N^RR6)Y7>m&h#mdV4aCBse-siTqmZ#7oh6XKp`KZU!`<{b&%@L?04<`wK$Z8C>| z;t=ACXqYGyP49SiyFujfaDvN%PKY4cOp;Z2FqoT*FEEN;&NU-#H1U|H`&SZAl2Grx z$wf!d?2=Tm4{D~`wRfQ$Jqq^H{dCjD1_6f!a_L{;qOUXoq%*npzlW?p+z+4v?hxHy zhFz8%UtQ2^7jau1Z|qYAq{WHwt6T+f4*={|RHgsT+Qqm>`@2|Ce})Sjm@ei*omEFk zqrz<@Br&RPy9VQd8(l|JyMG|yQTJ3VdpJ3JVyt={pB!&IKfu^KD9?T&FFu7zmn}P( zL=S}dyw)DwXCAm{AK~52$IsvATn*w64GxCkQl`4vp+^3R(sZA-Kbt(fBrnIheZ$V3T1y5g)}XJ!+fq$#d_Po>FN9ThOLNf zbbfY;Up}8Np*~rb$bZHVGpSA+D94u42-S``d&nu^v3?XkKFsl9blM71A^8Aq5&>!$BG{L z(2~KyRlw3OOXiB2~(*<7O96#kZIeBujP5%a&eehrQwjiGUnGHpl-lY_tyGoA|e^goA- zjoqIXduGwf%H+vwJ#DrX%4p=RXaUU(%H5;5c`|4I=63C0hg^{AAC{{Ir5bEv_XP&laR>lag^T zM<8PRd8Y=Cq3VU&+_A{m`g2`3h|WGCh}{u)o%>q2S*5#X*TBFotAOS)ZeF20^SBkX zrrwz_0}KwODzd?@|6N>+mtgf{T`iy}*rTDm_Uqjl$d-vpp*Py~_3<(2@q}W6RYMlD z0QuPvkm|g?CkhUPP0+u8-}xK1B$NP4Z*Rz_lnssTQ3I-qo9&ArG%=!IlwKdC{!CqU z53u&j&yas3Re@RpZdkTMS7}$GBl_9nq&Z$2ASQ_J^z_AQlAkSCzP%N4EX93wY4Y&c zLNH~2Np8|%d=I9TzeDbaOf-ha->3z|o|u^IF>u!E!xD&Lez4LK%fGXAGAdz1AnOZCcquMqWWr9AOmUKlhi zKTUrN*GZpPpj-khZg1P7w)RH4byi?y?~y-8I%@0RT62css=I`NW8mIu`!56xP+ZpA z43?K2f8(9;u6>Vc*r}`EGiSC+drprMEt?wMIzGk*pwY0LbU9u^A_uy*K1(6A7D*76 zts%PX?o~!|ss5veGf3yc+FI&nwu--|-Dlm8q>xo3y4(tf<*n7W{G@k&b)PPP+K*dL z{|6wHLb0;!#4(eh?G-5Poy$O6HT)OR?yms8Iaj>HBYF7ASf>HGcQ|~;-47Sc7$j5# zK6qKIGnFtG@h~XA(bW>uS!_xsKXg6j3GgG1#6B#a@ z5z){H=M;4AgdgI0asfWHUfzXXKe-oHTfu5oWJLc?6ZOmn4~VaG-TUK~vAa#&F9vjt z=Ke!7`P_QnKmwr=&H-w4v|v}#gS)1G>>%DEJNSg*HOR_}U+eYsU0J*}%Bt@9YVJ{i zn9lwO=UqCI!RsGNte^ij1_EL!pkoy$8Ls-Y-fu<%X>VNz2S}NKXHa2vP-aV^hRxM; z(2nw1=63IE@RbeiyZa%Y#thSDKuW?RMM$gWT$3=GM~>4WKaATy>_pAzGQ7&nQUM|i z8-VeL<_Z?JS^?61;zJjovS}aipK5t8j-0F_+WfSwDYbb+-op>-RLP;o4X~L%N_!Oc z>*6X0?At?E+KimQ!o&M_&P{ScWA1YN4R@U8AN~YQ*_|;eWe@S}4LTxoBDb}}kYfc%*2<8BQ0rZ+(zksKB0Ajn0ywIN9KkC#P zv`0f+0WO6}16O!+*#+Vi7Erh%RznMxzTa;}C=t&=>V%#PR|n!OzXc?;n#LqGvMb^f z#Cu;NZGGLzlb5fxLe-HLqOAnuki(Nw96=@)maJLW@2L?i+1_*7l+@To=;)mDhjAxq z(GR^SSlt!bvaMxUi2TS&|Jv$yC#9d z4*%QE7j2q(uk149cXB;QH5`&DWnzgVitP=*VW?9Rva#R63f(;4?Pn15pp~?#u9C_{ z>Gq#rbJnyI69l^4n3;uXwCNB>qZKgEi90I14?VVOw_U?%8?pEA6w}r%DN_(Or+O3t zm0iar?r~SuP9G*a+aa7e#16K`Cq5{TvPHT}f-osf<@BOeDbe~6k)yCTqy>NmG>6s# zGi_kG>dMtIao&lM%y8jWCe3AWZz~IG(PWl3s4^~LLYA6lM(AC+sA6~^tj3OV9Q(VU zy$ld1+yX5!dPuS>yg10s6dC$&6=b7)U1{#Ky$K}}n=uZwxx^YA5c6Ix5i0_FY{&;2 zym90Zq88{oy-HSxP!N8>Os*zX5VjvN7#vhjw*{hJv#?~xrxEYS*$aoqn}S(fhOmuN zG^58vNxGfzO6IWsLfWPQbMcf^+=;^kL!xub%94s7kFT+-Pri8jM!DC8co42Gdh9pp z4%pqKS?grP2a4d@3i`BQCP-K@6M;0iEy2#Od@Z!uf^2par9x+q;DArbeHf+dGbbBo+%^wNOOU>iM^E?Jbpy<{#c%U_G3%qc5rz{gy4L?NcyuspKyZ>t*z#B;<ENI82z<4F*<18Qr*0Sz}ZE(W@Jk;x=3QEd97LcbDx&0!k?Utj71}O4z7= zkoKe;RT!!@<_Gxh>Pu6TOgtW_Eb3%PoH-1^hoQ?jlhlp5ojt49J$$O$TMws=%`I|D zB|6S)zffJr)`(vxX(f#2$yKAR$geI7@(}XvAAJr z{2TA8*6b8IOV5#!pd8ER|8B-Xvga_~SGQh~MpmfJqb>|x#ww6Jdy?sETI1vu2#cB4$D~AQ z0uraz{uMoXJ?sGAxEt>I^z8LL(50Mfk7eI{OO$E9E@XX)9e9=$y_URh0#FjXI|l-v z=POMHibZZp|6Sk@-*#d6gWrOx9_w!(>Ukp0U4tS{yQYu>y|2kb_TPbIv;gBPv4Jal z9tsWwew7ze*;O*xr-1m`HEbVqis9W{Ro_0CL4n2L+ct>>Zi7c&psupK5+bZDsS|%l zE;gi3aXionSEL_T&aUvgP;E%;1FXLlSP84}XCE)LX;AQX)JD!Qf9l*!ZbK;&hQmBX zXKpcaWY(8Cc&+&Lx;(x-ZAG4bHcLbaCnhCZWZG)VTB=U3PNCCGNaQX>TBpcO2)5NE z4LJr4)tnu)_WoZfC|-3g7=BMaOty6PaB-Izo-n1un^G?$C3dI;xWAoUCBuyKAu%;r z4j|TAEsYqbus?`lc`otHj`9&RDV?%#b9sq_pRJVY@e&Go>1WD_gK%LPfraZEE)|3i zbLwoMLOOLIj5?}y)MW7|Y8#0s#7#PDKeMQsUJMN+z2CvwNj*N1ul)|~oTd^_*Xt}$ zuEz-HTCMP}*O;ResuujU#%-L{`&*YRM@{^6OJe?K^c>wp@Ql#P}=`Nf}e3#pWj6nQI$IKc{X_yW6e>8&G~ zta6zS99K(oNFKi?4%e|IVC z4F?Wr}w(Rw4f|MvM zVRG@ige1sA$fr=C$23=Y^an%< zq&ymNKg$P;kJY<1xJ^#{T7BY`cOrp8-Fi`aj%C;)u*iX^T7(qu(@Q^ae5Jr1s^AqS zt)34$+$EY9%p9*%CPiO9`S5}{}gFb(lW|g{emxQ-9(x9g#WHmm4?bIdp zS$5&uV=K+X=I=z@_x{tq6)i8MPalz^lu{!#ugylvQqq;cq=GAY_MJU;@L}Q@+sdq| z;QNCkyxQ=qLjHi>AWPt@a>w%Z4#4fNnEEv?s6pUP1?=B;7a}@qx)MfH4_@89I-hjR$};MCM$Ro@w%0Z)W&X2= z$FFr8odt)o@VP)sFZ67P!pIBDRa%?e6#>It^$`EVG5%UP(U2nAU{hS{IGibkF6zC( z2iX2c*1hIuAq8lkXkQ96OkD22PYVAY>#Q9z;0+86f`zRtJjTrwXJ+-#m$^U0ee-D) zy1HHF7+6{0OF&&Nlo)^bEBpyV#vxL_*#3##2NWFv8NP-b$FtsR8H8=y?Z`Yzx2z6Q7TL+~NVK=HY;9u9d7>YDyh&tkg%OGEST% zcH*1;g`$R{QN`vE-p8kDo$_O0`Uu0MY!%iehIFDCn0^klkBK@U=8P08A}ZuVd>3Lk^09dzjj$S8WI5JsYTfd!M% zqjHs*rHsUAp6iTL=D`PXNUFJkO0t4aJ834UPEL6^RjS}Y^5zbvQ|AohCWKo1k}5pz zV~*?Nd#EH#&C_)xF)lM+7%Hqoi;0q}&q`U*r3$a5&yX@#$e zdsHbyhQFZLG8!^ZFuj3R|Mbq1drJvv0M%ltaF)B15`Ca&0Lr zhI9Q^ydT+Gx43LB(OXif>5R1J&k>!zAd&)ap_pa{bA$~zj!OWRwo{gywq%bOkzpm= z`zR`qfAQTV(HtjY5_$OQ@AG}Syln?Q-2H)03|Y=z%PMDIWuzta&Fa7lDrR3Xp-tGLMZObnyBUYE_-Y0eQPIu$%S>A_ULNC{eWj1)pWheaP zLbJ~58FUKhtVw6-G{o)GYR)i}SSNKi%=a-f#9xW=fu14&)nWun;oG~rssE4!-@wqc znxVi1B4+KPl15VwqO^6ty~qGy)17o90U7}Upl=gEH+$tr#j|1X1LK_s{ClOqx&zjF z&FcBk%7G)wC!wnkdx%$ysJVMuX@^>Y>A)_m$2@swkPy_lJMO?iUlJtDhw;dd*;-lE z)`n)9l^sH$tO-*x-+!37U0iXbKVc95*&+()xdH7Sd2;!DxaOduGzK(=t@?x3CE>M6 zaChbcn2eUV3;uhL5X(79e#LSw$y%s2lxad>Th*=%!4W z%5vnUrARt@%ui(-egGF|a?-k~O-rtF{RLKAJGd!GO2HH2E5KyYzVXAeFFP}nJnKiH z(8>n$$tEuIR8D6--p%?$Q=aqJoRR{avjoKj9~-;hPdI$%t_TQ2kkK2Wc9&8 z_e$$*KU_cp6f*WX;r`q1M+7J(fE^Q1pnLz19!4z!M8W;$|D89pxCvP}JwtdO*{(TW;CfYqPf9KewLX*=7oSKYX0Vj4QJwGek;T2!{ zM$M_+Nd*O$JvYPYdd(1Z>^Zks*9hpN2DS_GFjp1be*1Nax&)0+OSEQd`wTjQo zJAan~sQZDcmfGkcSH?T$dvQd}_VhOzOxnc9G?ijI8SYI~NQQmQ(D&cZ))r{`oZY$` zxeYCTx$B`POr}o4X$SmKee^L9=JvT+OA=v z6BOVq#WwanplQ8pJCmN_T8n3Y@mSKEOo2JYl1l_h;DY}6#AYx`!F2H%EEdRxVhQPD zHHI9B3w=2D?|Ir?D}T3{3m2Y{lhyU}$v|gqzmfs`af6bQL4*wHqxu+Qk)f`>3U6R@ ziciHQ>G=1}pA+%@V@P88l$JD5Svp}zs7SHl!B38vWSXPg1vDSX8BBN$eSUC44@$&f zM=QTZpenQEm~k8y4q?Y{hj7KBCuoXx$9snK5BBMYhke5eV+({(@xk|kUAkBo2*t$C zZIa=jU@G!Co|3NmY-5NS=MpooRgs@%OJ8l4Rjah1y;h$3_w7v%V>rnJv7_X>X{}I% z(xzk|6y+P~Lqvc0z^uQ+Qu9aO7dmYJg3cbsKEz}Z!%pcGvh#h%lCO$0@((X2RmnhI z(I-_@W6A-!yR_l;p&ap^YVpT{1@S%)dQxFa+((TwM|*tQ8n0mtRMpC@rw->oN}bk_R)O zGOb&Vm_Xlu7aCD0jGGaz{bFB2kGkflgUWzYPd@y+8TN}gA`qJ(sT}g_#57dVCVIL# z(1SF200Y<9;U%LxG5e=)c7P~&yKt+^B^i`tmu)^OzNrn)Z?NMt9vC&e!n?8W8+Y8YyXDl6TOk1k&+KXwXp?&5+G{UE|&g08%eCkuwx^ z+7I*|Qro<1n;W4t3)^A^ywyb8$(L{6zO`u4r5=Ix_6kR1)0^_-nRDdOidcY5_59^W zDxNUJ{~YAgFN&$S*+M`G_ZnLVzurr2vvtVzyG% z4v_}50f)iIl7G>|({x-g@|ey7p5vIhNaPH}cm)e72MTn_;G z$LIGh=0~Epf3KnjrhH%jtOA6_Kscc2)wM14fuq61z_W|Pf5ayjRU)4^Vrq0h{BqXgB-CsLu)IqW)z0K?5ml^0tqK(eBtp2y(gz@17~fN{rx2jr(li5@8(hv|tWY#n{jKQt=qSgdo%; zoo87?^XV*?WcH}8`QPAk>Z`-I6hgQiV&-$)4LG7D78SJm*HQ5jz72EyJXkIp%{U%` z$HyY07V=jc!4sVNld3BwaDiPG;S#kJB9sNy$nch>;!?tUJ04P6X{%~heLDo^XZ2kg z#JPlH0l${RY&2nW*ZR^{g{Xt@MlMymzIZ7;h8ov?^u>8T%91dz&1{Wm_Ig_^_%Be( zd8SJD(NxT4tS7}{s(0|VcXW_^%f#7<_Px?XClWjcMar&5deAJ>L1;g?3pJ2aTw`@- zt;FRE8V0@CgnN+wpet^oJH8(lRsh(NWwj|H^pKrSL)y|gALa8?K|;|DDMBIVrtI@5 ztxM#E!aDLe5muW`qmYc^${`W8_BkrmgrRI=KkD*U;h9>N$`uXlcEGk34MUOQEH-(w zyxLB!Xib4nr1X1;?j6mDbj$QhN%;x&840Xt_Lzuhb4Vv$pK2tzc2wWi6q$d)3au~W zeyp0ZxiXrXS-y(CDmCqs1KlU(MTF%0s}dE{n$m`fLin3bZYvpI+nF|oePU+jJinin z_i(D7pk!yn0$4rT+Rb)%Gjn$E!TGjIoi*Pr^qIBmB=>&7?SRL@6MFfPjGP*@_+8?fdMSRW#Gx ztMwcGev6Vx{`ySB7e`!%#e1;Hzo%7zdJ5#R*^A<$W`QgyP;LGv5dIG>K$Ks!(B=^k zKnkE1LKDZU9$AY%qM19YYmWxp2E*({WWGoF+X(Kc3HKv4yCIL?i2mBb`x;NyZf%!I zy)L=1 zUd|}FAD4vIL&jchSzzONP-(+2-snwz{&1JU_g{VkX-i7!d7Ii=d7+UN;7G1y9^@>q zPP>g`_~g!!^V18v9wBM+&xwGX+d`xMZDyTjf@sD)u=lT8g83_?E>ZR_5AaV{c$Z^`*P9+Or0JICYxGwaeluO@q&Ozja$aZB{4#>@!lc^-A{C~#G8*jaDHRuiV-ySC2dxuaStB#UT)dGKv`&;N~uNhmI)%oO?Ur+2E&FQh1W zDA}>y-kt;<@B>+UG^z+EIlcznX!^x2ypPN?Q~$;MI{GT=Ae{Y)NVl=b>SRgql$%ng ztIrhvS($c5`IB5d@E0(aC4J@-R<+$t)C~p6FeATLELyEVog^i7F;q$ZPzEg zcc$&0%4En?e7Uhd=#309OY9643A*xZ%s>t?oQdRLdVc=t zH=6mH6Ib`@Bb)`aH%*>@|9t0Iy(8-HervQgw8+^h@Y2)ct@suV4 zH+%!^ApLy8=)GL%h3&A3f~0L%<4Iq{jM@d#`aXW;BJthbow}6Rsuyt4+Y=`b;L>2ku$t;T zi16ELBjerqJtc?R#))qsMhdB2mUr*NEEQ{2=9_ED@J>GoL=I<*Z7CNP{P0!ao2S5l zr+~pe_x`>6yO8opEW7TmsEzA8WZIx5iazN_c7rYa<_NsHCQ?SqTF1itC>gq924u9F zEm^r3OV(gZMPg9=0~6XeNilci4kBn`ZM3C$KPm!>cinfp`O(hV=dUK1q?{Fg)mX=; z3G?xzLKHq1s>c~^dv;AX(=h>ATe75qBWLPtE-fp`MPC6=5X2KTE;pe zX1-c1+2sjXuAr>)cQWeKx?>K3U)XZOmSY2YEex6T|J_cI)$smxQ~2}Yl$aOCV!4>i zP#Re`VjM8_9|pPuX=^BHn2N^K2kyNw#+F`^Uax%p^FmE5X*I`E(5vH{@+2=DJuv2T zysU8cw%esE_~TdxYowrAA`@JXiCc!6(ou2)U*{L7L8%!g42GnSw9sZa1p;B z0C1@l&fUADwEWI4&jIYN!}be-hmbv{qDJ>I7F|y81fdcmV`YV#9ChO%&9b*>^C!)oYnN8= zBpw7em={ca_@_c$)&Dr%b2lNqH}K=*WUlj2Bd5Q`he)7V3>$|paTo}CqmpyUcL`=C zGe1$6?{CNtgRW^5)|rQs76l-~6Ar%a{7xN)495+;M&1gBrPemqWW|01I##Z~_dXc* zJ^?GVUP$tlyFn5E0ZO)hQ?Z!@{|Eg@4{yg8N-gsh*#gj(K$}L1W_PWUMO&-aEupK} ziv6&BC+FG%8t(l|>k&@$>K|2j_KgV-df?#>Sy^pt&$zWI_e7o&Kh?qsI@os!9RqIl#IIs)))jsG4B%h}#Lg zaP>8=?kxoULW1b=q0;zT)u#d#EbN8&p?fU)`S#6VriVdJXi}n!ECUQ>0LG$Ov&&k9NnHF+C`k%yo5C)Q^f+@%Ss`P-j>&6#xSr zx-Q#5iOf%e=%BF1v|lGP{Jy~RK4YBv+MW^E44*o2iOb3g%NywVu9y5~!N%H<_pf!} zv}F&D?hng+qK`aBN--;4X1i5NLF++DiON?A4(g^rLp*?z+OXSG?&J^rtk5g1wLy2} z4wrWSLM?b>L$K4gWfX8PxB|#gEVYTnz{hJVA;9zcYbsQ8TR;6A|yyisi5u%Mgav&TozmLrGLG4UHa4ENmWs% zO@Sii?j3)7lAl{{{uCT}9^$}@$>jfM0X#}Xikp)I;5427HkdBH`YLxBV@O8jfTL0V z`|Ovm_phS2BpLfXqbK7ieb*UHpdsJO=RV9YU%ntiX-9LWJp&nRvTY(NDC(FgZ-p}_ z@y)jtxZJl(8ihKIOkHe9Z;p#r4bP!|Y%*RCR|!O|Nr{QB-rhWGgmsG+^)rcX|2?vO zf&3MBT_#*I-ilOwmpfk9QI)AtO~Melx9w3)#E0>ZPB@rKZfsbOXMH-tFR zy_&`E+B1_QB8ftHw(2q^)dxfwvmo)+Z{&7uEMGTtONyOVj-wstK1t{E>XlDiHta)N z+P2kO2i0)SaQjiBZSsujB%*!x+D|C&^ikY=^as`@B$Tq5&gAt&$V0FtijLx0ZzaT! z^3xP{wY3=H8LCcEOJwoVuAf;z9JoRVQWqerPDVVDLs)Dy8?`Gao9;(fE!UZ0c!YDi z)P|QUR}_6}sS2epj#+EmUQH=c%~YCSe(Vt={{=n^Jm=FKfd2EFDc%)Jp%G%{lk5H% z=2U6<4ESBg%WkwsZ@4}(fm@S2szstv&QBHF6_lLNfzl!kl4|sBXI1~;%93WHE z64CPc^doBW5Hh)p8U%O%e-EBKBYJ7jL?%nhrqS^iab9Z9QS-lpx?_Bx&Lhma!#j(o zmy5^wnTN@#D6avdI@WCuk}+<$Nk%O+Ej|qx!rEa@>du^-91h)Kj_S_A7*qoyeZ@Iy z5;whWOuktPP9Tz4co-kVzmY61)d1+XufO3SZES^|l9_(MpMZo^m^tDWcdo>4XRT)S z>?fePTsxl1hx!fsT|#T5c*KTEf709H~ush?BZH?<*VWjJe2H z?WJ>(iyezO|EpYltX1yTTTcF>Pd{P{$`^_g=kHn7m+#W)*>Ak+T!k8)ohjJ&z2r0Y)4A8N1IR+zT*R_2p(B9O$60yb&*!{QD+o*)_= z8y)zwWE_GJ7CPy!$~)Yr+A| zd#BpQ_)s@3OJ3iA#O-MgZWDFLnjJHFk$_5@3o>Xe;%O45GauPi!}&@)<@EhI{rVM^ znVqI9MP1>2^6X}=aeK}7ybawBck${Ni>+@1XaOMRdbSL?w+#LsCl1uwJ@BO3y$G4V z1AA!ZT(r&Ghs=B0ohOeQ~@>MRzh%aCqkw-$&c20%08y-n$ zSYfJ}4dII$C7{+3KH0uCha8*4?A&3vp9(?j2bR?BrJP? z3N%yVV(_VsU~(8zMNdDDoLfF;ZagB5stocT&!ccQI>eTJsum7RnAWdBOAU$5P_;el z3FpSjhV+Al{or#$u<`i3C~NT!J|*MAfsG(Khc~E4N^;uKgYXMOn#B_Gds7^$ZMXU# z$0y`qBHvz-{l}BfpNS$Nk|#5l`EWu@5{~lx>TeTii}vN;knm&iA$FQFB9$WRDAUFh z!I@h=fTl}uar5A8-b-OXK)_tr=wKVtI>_pBPMk1n)$~=!`p<%5#tEZQo-t=xl!8=| z7%*=}Np^aNPO=Sx_PdviWJ|`FTYe%p>x!=KVF)vNtLlfjFeeMsprBwMNP`Mr%#X_TK%pX!1h!Ov3uMN}*M+MkBAA;6eF*mquB9H(KZdZ@%Jk(I+>sFlJE{ zoQ?8FN=U83-@;GXNZryAeS)96IG-Pc%+IwgSDov-H0}{uT?wzEUd<#wraUXm$0zj% z0|2HLkAON6_u!?t#jvsC4*vA(^G^40oN*2@M65O&TXEA5%<|)&TjvnuCaWM67$PZ! zps{C)+4@cE)@;ISzhkF=RUY7dXb*VTbVjth^rb_+Vp|Kpl!iqT2~tM=-cB;s&1ui( zkdK!UKTpU`K|J^;cOAv{oq-V{?ICJd@We4G!xz=rMu~CmofZImai%DKfX8LQy`|XP z&b_!Dw;PANgEfC=#B^u66|=&UYAQs?xazfX_6K_1IXqV}j5J;XY|_0gf+3H`h09V4 z=D(?~CG*$2_yFw&PY;#Uf=p^kmJI&RC*yfBlIX_Q=#Kt=dDktVF0d_68urU;ADW|W zdeLmJ;?_YK-U(^bDkA)=J!A2m#vXa<#9$(zd4^uh)iyVV=^BEOzGJP$4^prGMlpVX zHCaX&8omtl`$4H`&8Gq=TFbqrJ;C{ee}f}KpxK-vl71H+;-mk0J(p$CYqmCW#@yM^ zrZgzG(O5*hU1`leUuk#>mz=`Huv0*L6jP(!m_mFwPs(TyTg%i<{7JGR6?Ytd*s!q^ z!x$ZAMx&Zy03%+LKOrQ<^%o(die4$q*B|rT9vqJ0{0qw{X~%zPj&Y8T|0zMN>4xG* zROW#|1;0<#ROKHHk{eCUMF$UEj;UxPqUn*yNGOrOk=8diCy_7<3hSnXNNIQEnJ{Kd zF7zE?|1u3Nghq$t`!Fu;up9K^#;R-pA;A5UKU^xp@l+#5E1Sr@QxI zmg$J&rn0&Q%pp!Awy0m@*wh+3E<$zN9C-Gaf5;w0s=`#RbCnJKI{uu_omwn&Sdlqy z-!5UqTkSA@tWU7PsxgyruZSWmNY580BPEqIMs7F^ES-4T%ELwSYJlN-Al|WMduBz07DSHPUI?Z(EPx+QP39`bm}dr}>|| zsa|S8>~!TUEhPLK2o}ciJ>Qs2Nvx9_@Qk9i{1y7+6h18kKl<?gL|S`v-KB{c)$tvHeDTP~sL1#CP8HB@B1pM>Hvpm(xnV4NhzBS&u9_9qfu zQ+WNxc2^~%NeO)E)*pJUZgRn|z-k`3)0aU2c5pK*nqs3E6M_6(C zkIe-fB8(wjw1(S}Hx%t0S`I-!alRp7N0%L$PwX_l8n6)fzTP3R>j*5W$oX zLA860zY3yatO0gv|5Kgw@qzs4jWz4Rlqqe+rL#Ym*1&0TaW`Zkc$vAvNo_Vz?15+b zUWw^uHQ3nH4nrt0>b)jM^Wloq{t_zwc_dS^lu}m!@B;&@KVT4VES)OKB>f68a7#&~V0UxxNhSPD%B%>Sy&TwO9Di8S0cWPH5DQkUv|B76h{^ z0DK0qPAkeKc%QWM?=LT+=1ao};C}>wgvWtH){c*D)O6y-wf<$2|rn z0x>S&BGtwTm+Iz>c9xA@F0uLtNNN!P@Zc}ouNPAP(1kX)wv-tiN96zHEdrC8?C%yNC$?;<44vh^zfuZXt~ z#?`;J`%0x$GMUUB4NlR$sWN5F5K38))a;DAzGdHS*5BWPqNP@!2c&U_lr*)q5An0U z8R|A`w)cYDPB;_ z+ml{N4Q@cw^bHF;6rQze)`2Aa)7Pwlwd=?9(|P{E>1l2tL-MtJHunN>B-!du=Ci)8 z|8BX~XB+T;oSM7enXrp&7+oJ{1jLs`76H6Fz*^&*-|geO*XQ^cMp4^APf#M-aSA*Q z)e3hddE=+kq>sZs+d)wPfyduJ7I>uol#SY&2#uO|$xc^Iywf@q828}%yD3;j)_i&C z3zB;~^301@7o#XvU%r<}M`uJu)qLYxkM6cM@Ti~53vR}7+TAZnQODoK(tu|!NNuD3 z^fLu)q@1BDM^XrCqdoj%gTk`z;(yj65tL;SzbE*vXL{^y&|3>DmqXKqKU$k|sc7+= z-t<56Xmi}Quu0w<%9>%7`2Uom>Y~g~fyM6slyDvY}vgz#R;Q>dPMXq}km1Nc5K zQJG5ejV`%=;y13u+{GzI5ZVq%)per6!IX&#g9`j&J}KDjq3sv}8sBqkhcWhDUuhxu zMo}TImu-cSQ$+?kD8lN5m>^_23lC!s`~gNGJ*r~9$0H$#&5)NTJq`+OIDU)V_mL0| ztqK@&P7ZS-3_@y`upUg?)lWn`ggq4uzll^GvWwi;cykjSPE_v6HppQBPQ3iQ`@6_# z%$p3$BC1~^XFyG0EsZlwpOY-xt0L|UH_8XKaLsKLbf~*J_PiG`&J^D=#n+1&Z`mb^ z9=kak%Q$QD*SXc3_G6r4o*9w4&MFb4yHS$Q695x;;QxBFzxN?^Js;2dq+XFzbW*L) z1Y%f$kuNZJ=-}>s9vGkQ=KeyQlw>9<14=|-VE;wT`1P*Zq05F^VuR=BGY^7bU{GX{ z*S=RnM7BhT&=d(X3*;GdUkA#d=38A4yAIU{X>%?PQ?%6*BEh%M%fd>SRw(xw6VQtB z|3xslQugEK*Qx5T?%3a^iKWEa6WenVQ)X-_I80Z(&w0;@_=mVnFV2i-w6b>ID*$CM zy|{u^Y1H*h-34axcN(v}H7zNO# z%;8)bTaC8#m=5c$jfEGO#Ht_yEy2*LUvFK%7rR_^^ zuCsFWkrJ0st`Xp(lul)D+djWKnkKDZtD9guLie_JJxY~(>6M4OBnI~*)PB*tsyD_NHvZs%9S*)|C zH`G2qo&2uk+4f9u)91bZ)jK+FpRnc14p)i+(8#I4Yn0g++sD3>GbWS+gC-$vxC3MbGAVDlYD4S;8o6cRV7|NVH+KO{IkSx4> zxUv~uxmj}zO1Juh6`Wv@euZq#0Q=#a4G-6T|F){OVFX(Bcg8Lf+K zl3l`D%_I-2KEjQSO>>)05jvb4_Lo-&^QcPa8V7dB^>P93hE?PntlNorw_Ma$L=Eub zXvAOoeiY<`;qf%m(|Oe{oY@Y3TcahE8C?U3xDP3E>5gAE_x@9r0ITgHueTaNqcXs% zb}FB22{@1e1|3$6JMaF$gKZ^cjbT(MX{OwSY=vi&@oTwh!jEf(#r!#laK-Oq*Y9}9K}wRo;kwYyLFgu+VojlMp9xIGvi zO=bda@)2)t;Z0GkkM7j*&pK4e?Kh@l*m>vLd_i{se8(C*X>QBXGeYeh-W%TUW)t;7 zV)Pl&4oH60N>n7|MqbYQ#qsMLUvBf2Ls@}p6d<(> z4-X?4_jbcVMnTQ%jyw6^_D7R`AB?A^aEj(l|NcGt7A}6NdVED<`~G1!>Me+pdmWTK zNwb*7*y!~nNIEnK6uJ+9Z=+=!7|HW)+qyc>nHuCBh+x}w6*R)JR(xW+SbS$-Ds7}w z9moxFzPyb3&6$^IaX0y%xPFU^v(5vl$M-ixrAQ>=UQ57ugQx6z;5maA@nvqvnDmmc zh18w@==_`&BT7=h*r+LSO9nCIkPm=~0?f0{-riwgStjLf`_CV4f;c*YI0R*7u?9BiKe=?RNVu@P2(Q zk#0;PGaRCP|Kf3NTK~q}jeMU{VI@p2OP+_7c7Gm_7^^9vv-jC8W@tQW8HY_tR?ZQJ zwR8DzTTZ2$tXZb|V1!6AN%A)C7X?3|KoJ4_Y~b~C((o)Yx#Gq6u6y&}S(8^{pdg|V z`S;@S0{A67O0WOZAza@3dORY=S%v-aN06>L_Qa;%4kO!eB;+=+bQ=^=mO>WC5&2Ky z`?C7)X`5YYr0;YNlN>a%!RrFe3t-9e;H$8SjuQDp)vP#QX$N>ERadzI-NGZP6EnU& zFYjt+clRLh4B&3cWv=cQV@fjYbbkXgtnA_875sWkX{>toj(zm#xHXUG6BYet-!7kF zlj%xRlyucT?O->Vu&T;G#oHc>ph*!z9JD>4Ly<%wJjm|Lr4-jkx)YcHh$reu^3D-m zv2SuLKji)8wdWVR-G6-aYpnxx2l+Nj?Fy$DViRllqHzoQITv6DEPRQ6qTrx^BmehK z69@6`@WFLLsLZdzti4c0HMshUkf|7wKq>Cv%2dMmbQC&eZpKSw@h@`ro(?3!xv0B1 zWWDtHyPwoBsv7-eF6&)YFG+Dqxh{yutflxEY$~TxJZOcovh! z(IZYbNFB`bfoKi?x~&-v*TcG@=gO52i1k$*CtJ6=8lHA5AFOogMSZ9ltsu3o=YUHj zYF}MIxxhbuO5!9irha}Mos^tJTrr28OwA{ z*$e5IoZY6<;S!!NYtkbd#^M4oA4cl;b*rx*(8FnG{Op7r;-R zktihcPEIs)47hKN%N4sq4Je1)?vgj-P8d9<&c2|O(`Ib=8ZQy{Y$=R~zLTswB#Q#oyUxsWS`5vc3#$K8!&R2=?~8y&VA+HKWCITzh* z+%immydMoq)!$@H_nc+B%MmaXfOqgZH=IA8Pyl7%qOX(s9_|C{=ezrpIMB-<250Pg4tB$2B$cTOgVBE-h=otEFDfD@7W& zDQ)uX!;L~tfuE0D^>pb2&HV3bGp$E`V-2}`vlxQK#N)foYD0%>ayZ4&ew{7C%#w#2 zG402{x}&-{-yS&W#O#aSKk_w5eMz4NuJm+p(cgcM2iu5oa_T8G-uMk-xvsqhj&dL~ z!Tz5%P1$M*ach_X{FYB{juJr%T+W1#o1`Ji>7jZIGt*j@>(Iuqt&V6ClK6@5%Y24U z?WCT|eBa#&$5~e6fUsksud@=dd29DL70$uj6n6WgB4Hkxh}9`V{cDb6N8<%gqE%KZ z6d2XdR0GK7QKx-C?eqk9^Vy?PVny_DPpQ55nro|cWqg!@M;2CsBmP9g{ zY_BRtY<)E!mmk+*EIfhc%@xLI$?>^=Un8Q~WEAI(HW`h-7tXo`(*_Y;Zes0BeM`Z* z=TtCpuY}1Oi=ld}Yh4!Shwx{ZJRB(g#-0)cThH!y1m*epKc(7E0WcZ6#G*P1&igSE0o@=F7 zy-Wjz%-qg`7xK8bzt_o_u2%70){|KYmOzs5xvzH6!+ze;E&C7H=h8k z<)ZXX^u+Ig+;^G5qK~NS}7LN6>%6;{2<)K z6x3M1o+Xt%oB2yhW{ADqJ@NVrhmHH)Pa)m581T-~FVyXSS8(y~y}xe6-JA;v@#ojC zGNw%=(!+WhVK`hZBX~kH$?vS281#gw3Mcn!SdIWOCroEikjJ_IH-Z?UcCLrXUt*IgR4h?8QFPsm}7pNNX3#v6uQ7-MFlFAJpjW zsMv&Erud@|wF4qu;dH0vRWN6@y9wD>OuhcDPw#oXLfGWqWTx=2d>YmzS$uw_;9Xtq z^ncbq(2hpMkh~POA88FAM@cqIuQ~> zWytVn8i|%kq5%9lRkN9^TOH?oaJW3Y>gKNi$Mys1Bc&Fdkl!`@O&3?-_e&p|QPexz zWCaclWjs4>uo~)1IF@TrPy!Ln--l6A>TsCL*H?m#b3`SL0i5)zyEm`^^or~6nd`R{ zCxI4NUk#Ooo@#WhuZ>$2KRQqM1tbfMFCOPORbUN{t$%jh_S_m%zplH_@@mZF;wWo$ z$S*3YvQK^g^#w;1D5eFR7d353!0Cm;0g=bEMM<1OX8!cE%1u9h9QynH`GwDuhfX0H z9FKcQ+w)e8@zSF^s}v30|NpZ9BZqfortzkzn3N|?PVCY-W$JQ!t-Z>F5lZ$u>(7Ij zxy(c9GkEn&+B1TD*Aj=4;K5!-tLFvZ(QgygDR&<`VrUgw9Nojsolwr-a81u~%<<-- zH#Ro926=?#<&kz?z<_4qaOto)G)zS-8R5QU*~b6(;is$D?MX42N?v9Wsg5u1Fq2#N z8M4EJqJw>9QHziWMq7bp(L)D*(QC5Nz)HF?Jd2^tP4fSqYb-?gC7=viz7tw!kntoEL$Jf`xNDmM9ZwI4~-3W zB!O3ZaFp_c6VsbK-0mEr=V>Y;;~YQ01Y~K7mbN#FL5L(%WY3(f?j`V{8ZBpabnimygc|HPxT`8K6u6T4fJe%zt)NK0yDr*7RbEo7CDka3KDm3Sv#GoK}EZ?>SIpd!53 zj3{-R-{{`r?Mr8{zsdiVP+zDZGTn=~TG3?v&Pm8r>`79T5Aepw40~qEuqTh4B%A!w z637gQSfg)UJeW{d|L?T)cv#M)PN{pM6?^5LyUZl;Nn)PA4do) z3=R^Z##6yOj^-0+Oq1Xtq?9f|ht5Dsl3C!#C%gYn<3H@-R>19R@$5X=m5-ovMX2yy zAFLciO@jqgmYc5q)8_<6ynxQIJ7m|q9}ALC?+J&s8(!9$1QDrh4;$j9pI8i86aTR* zH;!|9jQ6t{p@5AwNOJD_M|L*I{p6X05c_}@E_;VgBjdnBQ381eo_#sF-=0m5%AH_U z)3p^s`Y4F}%(l0;*Ko!OheM4OE#4?DXi(z(eV$CmOQ6%NG@19snU{CAP$sa8$Zwvwv z8E5HbD31p;cSBNdS9xpYEwe2ko(VB8?~;EdRp)G@F@C1slu_=Ili>*UsFaI`aw9-I z-1Dt4?V`5K-@@IKe`fg-Ymd0dh?w0x7SIaQD!H7ZNR-}j@<;SDfqNv|*i?q7n5vTX zv%oYDQ6vx28|bY0!hN^>i-r3n=S_=GX&^ulPBryhxI zNHUM3GHqL@OA>+W_^^8j2YXJR#><&(?nFfY)vxg0pl1T$O)3?RrAsz~X$*v@`}w0T zTtRw|MsB=^y?HE(AIr|fqOelGb?M8=JtT?#W$@7BbG2fu=8w+A*6S$Aw$!ze3Dj?W`Wz{QAsye??3R3%5ioO{vaMHR&X55u>nwWFTi=F) z38&)O(SZIhiqwTb=sg5}O(+SJT57otnFo-yu6%fxZ|GEwbZA`Ldj7(%sND0}7;zyY z#fq_gy=**tW|swHWfj(3yldZA^iH`De-%6})DbL_mA_@K#Xgmv9A{<^ki`{2AkolN zltv+|9X5Jt)Zt70Tq;9tBUW=7aCRR+){UVQ4P0l?=()^0tmR%2+P7PsNo}rG!r&}S z7w_t)5tc-_O{fM#W8a;&<}X6b3TDS3J2`*3oq9)aE^Sn|ps?7^MwjjAyQ3Z0I#W?;6m)Ms`Oefgzr4k`sYPF_vnMbCNL&HPL+|G_ z`Xtrm9Emd`RbC9~++gUJ(wDsYkm10@N5_Ps;O_p@$v6F4MA^H-yDu+zN=6}MSY>o- z>}$udgplj}GBgG|kEs#ZcUVONPsZe;7`xqJ%7ZnCzs(@^Fr?B+ELr_| zagpwON92fLKg*Bm%xDg@-iO#<-&{T$0EU9b%jWHKFgy$b_{2336c@Rkg0fZ;eLgVx zwft4OKQjIK%ufM?<$rIXLrHr0nraz{Gps{$=5C(?G)*NJCW)cUq1c2q0_x+Y71&yg zISHYTvWgM=LEm_o$*IfT?Wmb1Jlo(Lu=${hl<4NB#0uXF)yUOPJY^!l5~eg>pIZao z$sS86Z>Z@7tE&r-t-; zL~a;SJ^U^9H>^3YLEhsAu1&^a*p`*5u_mO)rCLhi7jVveye@Tm; zb{?VnH`?J-NQSRHf&X{+LupnR#fp~;5k{MUV8{I}Gm0$HGb_+O;YwAjo|O?J)}zU( z(q4J*`BeZRG}c~}UmNU9SH;esQn6!U#N6T3&}EFWmkpOaIh#tRq5mT#G*)($a33%_ z;Pp~Jg)M_w$qg5s7NR9*cyGhztX#3SK2OkKywhRvRkQQ%MR@uWg!;6TvpTwdj7U7Rk1hvsf8D zlJcDk-CYBlvAv!vn;yd*kufbyMWVrcRdq|U@@8(9KdQs7-}Kf9DOojLHq(|r3gM^z z8tc@NCNpwv&R<0JHUEraTj)pj=FnleIP9~fK5&0x1U+d-(!15GH!!t(4H$n6VX#(tO19ohbw;EJ2-&h%KolqDAS{<@V{ zKy`yt&$8mYaunlP6c5S^{9#v9-9X-|9$~`Mi@E=A&U8=~Kt8x%#=d?~<+=y4_I~U(4QO(39Kd_kW)B8BBW9j1yPi`6CC**HtQE$J#l0Z3tvOk>gy~!ZQ5H;WL$Xs=|L|OxW zY1Ys0xH4pJ_TU_S3>=-Ev7#vI{-DPBy`kQ*1VXHu`cHf6^s2`dWUs)c*UcjY@MY-z z{zYv@5)(>=F^-){gK1OBe@2%M=+F;PKC96o3r@38Lg&SGyq-$K2btU1CXd6 z+Zxy*QxlIi{;VbK|52AD(;0n!glO`2<7;Vc`O?pC zS#L}2NZFBJ&H6WZv(_##LFITjQUJDOOOVm6ffNf|Xt-rFL&B){$T1)w)w=a%I@OfN zFDsx8*s;hxsc-5gJ<>PBy39E)ySh4<`SVyUy0orGcc5+ ziw$kMkvF3-@|g%g2K(;skI?ktU<*0Fx-pvGzvtFaTk%ESqtue*xk5qwwI(vAOr%zr zfW$ z^lxw9rQ1&dA-@;A_r^jxR~{e+Pz@DLNEoog_HfoFN;!fip`8IZK~z>vd(z*^SXQoUmv)aW-i-e27QM-X)Z`x^M?5+w6q!VdY{`6iHA4j zHOPKnU)TS6hKcD*H#YJ?C6=aG7cO?R;P+ryNKzPAfl(9N zG@4EbuIR~8WvEgV?ZERzZ$L*Uq&kz#CAcurjLRnn`UbaD{SjX+U~tnr?(5$}W?(T$ z6&;BS-L=(tfM5OZD+w8w1`lZFft(&jmVAE=%`q*m=a-WEo2UFq1slBb1ApP;K#j}( zGQ46C<l=i>P5-Wu>UF#zNQeCE6j_fo$LLH;x*Fjw-0Pw6 zx`s_FuI-Y1vf6>j=5PU*T#Vv;PUwmm(gysecv6h*vKY+8J3!ALm{XzybCIk6TszTQ zyZ!MOuKg$eC^}lj>>y}qYN%+nhgo5{wpbk zEG+TUmG3O0EdPTje6e8kEc9^D`lx)vsUWW*g-N&glffCb7LqUZ567*&JkgI-LK|LT z{v8rP@DS`|u%9+7GHA~)vx-^GME~&(+8_*QUYK^}h7fo5b`2~q8#sPOBEtyqG#bjA zBpo6Gl*6F*CpnO>n3(EE-o+2Pi_qh8)QcbrpmFid_YyG$rYX)DB=t|{*GBBz?G~B? z{Xa_7MeG=jI>erI#@GQ-T9*YZ1^MBiOfwnw0edwZ;XSn!7LP_EN5A6(#W`#^$Cm*t>GA z-UU2;u}@5^QgQ>?`%3czjF>b#S~=^zmNFlLGi}mCG=SFtao-q8>b~70ze6Eo4ERv4 zHJV8!8VrK)q3y84_y%!Rm+{Th85+U5agS(jx@K(~dr!X*rNS4}=)UVe6x8D-t&81; zeoO?pIuk(Hts6joZF*tDr6c149s{40&}B-=99Xwq0jLoZni2i{L-$}HkAj1I`l+gA z60vDAO|EEB0Vkr*Xb~?ZbtnxLI~H6&^rvyk>Z@~}xLR)6H3nQ82|bjwUkGN76_rm+ zA4fnRS5^Is1n?<;ae*82izyrhXJrw(&RDeT?}Z)DifM*fND&GA*xWR4Q)}*UQd`FF z*Y4Y&<67|Qf;XeJP*zCj1i7j6fQM8UT5X1OE#+IJu{e@b&8%^e@+S=CDUnfVm(R>v zTZ_<2C)&l^#C17`-i|ccvBQNBhtTlBOAWzar>~2dARpMD)xO{ePwXEKFyf3yBnpY1e9*1J0wK9 zySu*UJ?A@r`8N-D?0fHPtyQI_^B^}%V9Ya|hj$8F(H-OE1F39hqf;g0ou>uaK@@0n zPzv&fJr%XXkx!*n4ug+@du?H3`&v4S4gBx~UTW{R@(Ub7lcgqpW%^MKLAe{e*DvjYrVLd33}9wN%8&t@gM12VjtgKGOM0^g(2n(HcrE3piBc zP>=mAuwj`OYFAp2rfLfjIO={*0i@K`uD; z;^~771i?8dn%j9M)(pn$yAl&?pW!auWa<{KWGz&$flZRWo?~h(;s@Lu2G0=pB{sJw zA}%Bk18Si)pXiZ9ah3s4e*TAPUXS}rOSkw8T;VR3d@_j%8yBKkH`~x{Ekq_dG2{!a z{+J!)-iKa`R|Lb=R;a5x{mI07)SLkVotcBuGU4Pnp;&~jRQrZSn!z^S0wH^W$0iI2 zo^eAT7T(rOP-?Ujk>xr|w?198|M(DY=ux=Pi-7DEUrtxPgzSOxyQ*jO0OK-@;x!f( zRIB=<>a6irNFoHMnYt$6*x9P2iTQGI*CNcu8nzS)xgA)n`URq3jNoVv!AD`NL*fKu z>Z3KMUi+Q%%U$4jlWp_(j%`!uxdy6!$Tj3K zza6FvN5-_+!qJHcfwUehIqPuL?xQ6(fJzJb`0j!HmESEjmZ6Ijs$^W`CAlPsAoxln zq;tbunmQOM(e4cyITm7OvEsOY-GU(rBs(uBssd`>vdQZCk#xpIei5Oi+OaeGG9c4F z6VV!avUM>cVb({*X^}&d-HwNvYW{KP>0r~jX95`93RG`&IxNQo=6H@ax=*1jxZ>dt zc*+SQe09STCUD}oLWGq5Nv zga{Ty_Vl1m(v9Zm)bgQ>`58Y7wb2-sXSh`R1z?KX(UQ>cncja;Fsh+EI{dHe;?u%a z`jVs$o>fMP@_Q7Cd%FyytY~f)%#eT{7)an#A5IDj5AO6Zn)E-eF&dxy&(2lZ!+qMQ z;H)DefNk)&TQ4$Ic!OzYXQwjvE57_~3C?06L1@AU9!x{HX{)IBHT2*rBDrmsZ)Cep z#bTJ?%CrxsaC38i|Fz>+HlnEHtyZm>BtEy7U;ijPhf1}QXy-q^RmKp1SLbm3Nu%g9 zIU+j;hq#nh_3UYiITXJrwry`7R~8f>NB|=+Rt{(8vTxE`?}-z|t37L%iH^SW2`#oX zeKwZbViESehsIH27VKItI7p@uu-5fKw+D<*0Wl(++Y+&84o`>S^SrrVO7-?*s`vD^ zOXg9Z+b8z9w`li?Z?L6z{7C#?jLy>tkw%s*>MqP-w%Xg4%)({=TrGR)fnlIE(6ZSFfsdLbZTAFHrEh++w5k(@(~@+RkxIBgOPm+VE0-$r&fB*6a)ys@!m#{E zW(3ld*1s_ju)b#v^wK`r_I0l?j2f!+IE;v{;u+>%)KuMBBOi2jRxMV7GT%tIr&&^2 z3YAE=;ePAJRtb#L_`C)rn)#jp1Mh|Iko6wOI7Lc zL3x7aKjbvif>FH^a4|~dIWaZRFj1FVI`Sot-C67SbNwbuoxNKN z+w}vMrlvjMvAKP5SK1=X14LVpmy|FTKo96TyC&Xq3DwW5tJ2f5XxY&1pnl91?y{*5 zrVT4UU?E?}`YcRkhP=Nf$08xyrBP>am_fJH8{I{HHcnb<-DODMCg+9+t(a^})@a=- zr#K7t1!a>a@GH-4N++q6X95bM!>QQjcRrO%3|zhJ{YI5jN&H8 zCG%}0$klE$V02eWicvI4Q1M@Lozc#XknYEiUrNRu*@b;w?0TDj9en2lr0}H5mk$am z|75i^`V%L`%&9iCQ46zz#1q__GS-vJo{)Xph!3K>4$NsZ$%x4yVIeBbVPsdQX}zJ`v9R{|17603|09SG2gch#E@j~OyBG3=&*!l0 zn_GY{0&r4Vu>#dxu&i|fw6^G$H$T~BVY${hqs`W@^{D$_>0skp&N@Q9`4A{`;10+) z4aPYIz@Nf#Ihg3z47vUXVh;T;sbyrNzLo~b8baH{7!(S9824ZMecC%;0TDkSo_n0r zIsS&-2YBzdE}!LmyUfk73$0{%X0EC4&$lszj|i$z31RW?>GSE`h4BI)rc< zl>U5eqOrkhx$f4-XJ5k)Db>t@5)liIGGm{kL4i(j-_IFJH$Lk}F*$QuZ{yMX&2ncU zxQ%)-3-*N7)#N+sIQwi`)5m93tF@Pmz2>Guq2hC%nvOkw`)=BX^$uZ^E;~?d^=f*N)oQ-J>KpvKn{>RbgEv!=36vsSS+e)TF#|NF#Y?t#uk@we5LB)Y@;6) z-3QB;gUXVYs_YCx?+{cJ{D)NJH_7B1#i2Je#v?n7y@IH>up++C77&l&d>-LZ#^$g83B zDVt=ffTzyhTs%%4=+(~-%D!qVP60F9w1b}63K(Mw1hd$`dk99v3-qU_dFrLHf-5-TtuE_1yLP3tU!$@yy zMeqY%AxLZ!XB`e0*)w`}EZK@v4bJMZI|8d&a1@+ZZFZkMT^DG|1lVyv5t}8$s?s)& zZ%}^Y{Lsgc^>BA*9J}!e?KS=yL#j7qm^~!%uq0TrP+fUG;Hgfi3a@z7OEf|rNSwuw zpAC4td-i%N8aFt$2pTmH>ag1Wv#%AbS(Iz#h1AyhYFJ~0~( z`+%S35^T}wpS>FOb#TD#%X4${9lr^cHLq4K1;o`S$ zqiDw9K&?2wl($ZPq<41Op}W4^abGMGV_7;`AM`y(RDKi+)bHUn@r&Tcn59wlbiSFa zysv2d@zs_+=^c|06_L~8c3OT+{de>fbH7g-Ie1)B9i;|ahg~tQF9!aPxGyKf2FAa1 z)(YZ8pl1hRAT zjC^ZT4J{UnH(-i7O;w4k%C7>92rZJAF?!(jwr2|#dEMS|N5^n>znG&nc*)1HN!}Fr zp5YY+m-a;_>wAe57kBS4;#WTKIKPL0@AL`eMyRz|tY)x`gP+;ec2nTs2DfHNQ7Kute|7d!r38Z`0uav2hIbA{hZJ;))JTOp&eV8^|Cj#hiYf` zkcJv#4lfUZlPOK9EE@R{^Mk0iJ1mucX~=v^&P*$K@*6nJMd%AlAX*LC)A7s~EM zX|m?0FWB9?e?Ocqr~2RN4JjO&cuR_MSl0<(bM3Tl{z}5yzQMGA>*uMcmT}51X>27s zTsKJXZ0PI{oI93Mk-eD-zTjvu_3+_q%@lZ2)opf4+o1c%U@}*#H*-4Qlwgt1098_D zIrplHIdk$H&y(+8qkrudpzqEmlru)V8s_D!SmK%B;QWmG{faOscacrw3ud`@bC|qm za^9$~Y`qQdDSMdUE18Z0?KfERZ}EC|AI!EpOcDR=2@%jhBE3u2Ne{IJj=orLd77n0 z_*S#Z@MqYLmmV}Dfdb_Pi>R_3_1>1maGyK#=a^8D22B&BHggYq*v^Y-yT|6D38XA8 zK1>_wEfwj#(8s2YnHq6KJbe;s*?JNf9kclhF{EQ8(#wtOB#=3vY5Oa9Nf~1@ldJgS zHt@3n7qPiBTyR0HXv20q2uu~KlCSMCh>;ZtBar;In?9zViv9PtK*{9>vVY8Zo6Bqe?lesoOXn9G91|n5}TEuy@Jw|nV)NfyhasW z%ZAVIE$s2Q+IVr%`OjAIGYyDT$q!^#hWaKuTi>UI^FG|Sw|cDnFSRj@YZNH`rqwkM zu~5(S`@h=tL3x+WFLXG+zX8(RbJ zTTGcm#iEnC*RN!-*!yNWfm_;!pUkGJdh+Nde;%VzI+=nKvF*@3SBOp8QJGYb9riTB z1rBw4N4pcuNTv4m#|QDxq+ItwqBW1&S>@dL=1n@rvtztNjFSr3961?$PHujFvBj3a zeV+-9ZBC8-{RxjTbd_XNXw5s|3h-t^n8u6J}4h&b#%n5)KD?6mszp8%8-THp*G z`crBhLsx#4#3N)nhDgCAfm|4XOH!qfiqCTvo0aO-{l zJAP#G{%lXk&@*1YpU}`RJQ-_55SqcMrz37M*$U5+;zZ1 zd5|ako0)9Q6?ru`Kby{A2@8td6?ZhSmSY-^N_zLfZx-8;9G2e zJk5_e>|GJiEQ^jBsZXFMPQLobDy38kwN}4=kqszB(gjg=)h`tT7F9!`J@K1%)4X4P z{)LC*gu<7MIP}b^K^1yU$ja%nA%C&l{G+xI#`E5x1ON{Akrf4``JC%%EFYNS_LBBm zUz_@1KRz{e+2rGN9s<6h%GL$#OLk!Z7HHG32(=OjYd@L#%W_1wP_mCR^`xOKamYFV z4JXg6N4UbxYSFc+f6F>%o^D;d&j|$p{E!>Ui#y@P5ajvK`#7L^yEpS#2wt8Xt^aHn zhsGv%)-RiBhwp1xnRW5jS7Wp6%s6$A!UZChg`*ADm>xm3RMp7!zy3zR!hI3=Ol@@^ z2q4NqrKue~h^G$ip;Xxj<^ds$8R%kLIp^_;kt_yAj+K$SAgR(UQo#7n+Zgb3C`~Np z8KZRo!L;_dQRP;hsz~CJ4&-b|4MvuBf0|MKS&4p4NryHlVCHzD z9a&L6(`P8V?UEWnG{f7m-g46318fG-=UWp1@++r2#Fc;;iKt^o6`)u<{nBF>m%3d# z@k2r61eaAc`FKYx`GpywGLsn1U`$ZBXWFv?BMPmMvXMX zY*=}NR(KpBr(y}8Cx|k8WxlLANW<4Mq`epJhV{`5)28!?#D$gc+C{(E?0N)>McOrM z0z5+GM{&)MpumiBPlOhGoc`A7AAoGG?M;{L%@c)KFS^a-oX#7n>VUuTZfv<`fs+J< zd2lpe`+=XlY#QEH%vm3?AF49SbH(?OhtzM&Z&ZyCWC_)%Q5ETFMs!3Vm9}}f1{}Gu z(AT@h09NJs->uYBl0PlT9xTm1K>8Wo{sHpG zuAv9$=z6tLraU1k;{+xlX4pSG>$B{b2o1RkAY8m4n%Mkc`I0Yv^I-4wxI@N}BwwYk z{ra3-a)9cyb_$h$8XwaGZ?P+rHbPN>s%e;x30bOMwv$FQB5Y%>psQfeqWB$|hl!Hb zHm2)MyGd=KB`Gk@m8yqgjVKL=JOg%)E|nm>2^M$M@=w zW<&|WfK%(tgW7^!hD@r6sWump7&`mv1ci(Frq^o&!hDf}?|M^~)WK356L0X+X;D#W zTv)KioUNR`IMZiT+)&J!&<4Cc_JALMmYfX`);K|n>Ls^*3y4d)*Bm<24E!Rpva%i( zA`<=bKEVc9ifXUDcMv2co8If!l25-41D5*1f%Q*oFrOq&ym#F~A-9S7Z0y1vl&i1s zCIiOb&@k`fecRk;TqDptrZ^jK5}i4$oPjLuFy>)s%dSzKUf~6_ZH~LXp$t4Gn;NiC z$-qkh85y-q;fTFCrnGa2EMX@Ww1nb_g)MF_8UPa&6|Q${I$`<44Ag-z1*9$3j^^)< zZf>EvQhNIB-Op4`lY)R;!HHX3;VaMTd=ta-xbK3&Eg6l&lrMRmZOM(B!g6?YN+hMK zsO)ylBgHHJpn~&#PFsl-vyQ;;12^(iMHEIrJmTZAdr4z!>+igmM+<v%u?v=G0J0^7z*9Tvcl3(Q?{SUrdo$3{BI$--Ss}+#DlQuT5`M3t5y9d6eSDP0cSU39 ze>6lb)bfi%1C1VO=-}US%$p}>s~^Rt(xC)QVgee=ds$E_i1Mn`gsnu=h#m})c4MWa zD4`#UJSL8&&&u^ujcJqiw*#8+i zyrn9{{1#=0f?RvhpJ7rI5uTv^MFy=_o+%aCXlZ&IEg}IBnRb&xo?D&cpNd1jXhJ8NfP1 z#o-}97qa~=BoZ1tB(~SmIcCy{51-^ZsUEc48~2?yx^KXH1VQuLZ+?ZHvA}Q>k1WOc zJ53V;KABBG@4c(~MIfXZ&cz*s-ngK`vmidZ*BvI-Zp~x9Fb_c&I_G{e@^TeOu25a{5&bEsMk>p94o~MGE=;Cl-ft@?_on0R{IpBTa~XTDVDwe2mQbENwy@D_|3oK69hCY zg}pAB#`6M&;i;1!jR*Rga%-0wK}z4V`P`g+V*=iCBJ%U|19b&3dSeD?$l)jy!pgc{2A}e2nMbO${h?R35W*Qkq$*G(KwRcp_PT z``_`AGsR0tZn;OT9xuTsYKC zVeX*vfYg4ay({nek}()mvx0_3_kMQ`*P*%e>~PRTeN$}(O}dzZv&FAt#iU{JtD2!B z3B=0wTUpaNwd!(Ynh?vh%%Y-2b1lB~LXry;s#JE9W)z3A)axz}d3jUNtux zDBzhNmn*fr#tG*I4Oug1YfsC`qxr$_{5Z$fNNEF1`_${Lv) zzmR0hAEXyW34#vYyn&qzhiRxWij6_-GMMPX;(q<>hwVmyeuSAh3nf;CI7OqLFK8!^ ze?T#JtVOlaOO>hcYT^L=?&8$^(?#D96Fz17*%!G2YvkMvUA+xD@JVDmKbc|}W=vF(*teH*DRdw(J9S5Rg zvfKr~*KZd;mZ;Iv1a;K90YZoi>|DkWPjBz?$rWo}+bC=UzwlmTzv>D!IOz;giUp^J zm3nx<0ZC(Xdlw-61@DjpbP8Aoi^rBzb?#S{??E$qutTStcNE~H3AFIq4}e>1IyuG! zrtSH#>HFZ^d3q_Rl=EoP_c$~0Zrg<%QB{T;l<2#yN<1BQW=)D)PYh3ZNUDWziSV$3 zy|?u$+RE5#T(wCbo0maSv4f>!))AFXj}|NhLsxv;W>Ki(Z$fzAjLwCsL%zIx%N-8N z=EV^spHS|+^9s$t(E5Yhe!`W-=a7rj1y?IUmF51-eZeHi-eKB0>^b&u*l1$l$ALI# z1^ZoQ>+s@jB2xLeyA4oZTTp2-gHpubig7=~YW?58Ff+;P=L)_Bv!Rw+GdFN}PNl;D zx%8mfIdybZq+qAURM+hU zZm4)|V*A7KTVQ^2duCEuTnbpZ=I{ZAM5k4=*4*gic`l8}sR4KsjL4LP$}zBt41^^$ zDm_u!H&WX?BSKFLbr!TJ!hPY@&yR%dFKgb9&o>?Y(~KWEwL+AayN&b6dH7{#MQ56B zlo~rtkR%RkR#uE2yn^=Y1Du1i4y^S)8}zh5UOjEQdv#@aXUTO&U3uly+G`&0Z9lLr z>wgBGKdV6OcVkOS&<&;kZOa{m@UT?F7ewA4f=ebx%st9zWA%^oPjrl_>vI3LMr*S{@!YhxD&+@`TU9y|bS(G}Y1A%c#!L;k>kp|W+J1;CMfHiHB&|u@r z%2~bY1-|X^uQ!df@$O=30qG$HsU#hqXHbq@U(n8Lk@~?iu3KA0hm0td z2L?*L#+Ej5(CQ+jByNm8%WYTXA^rF*O2-90!P1l8|DAfBLY>}R?2RDefHK2cX(f7r z!jqA>t@RweC3>5v#z;aW7W;R4({0R#jaDu_(H9a~^0A_}a%v*CrTlT}TB} zZwl6WHaNW>P6orDjN;l4YILf8Xt6U4v5~n=I}PHcA3k8YyOU|mbR(OH?Q-S+X`CHF z{ZXN2EDKPc?%V$L^fT)zg z_iq5&A8fP>e}@0)=sDg;zyj|?p^qf0kTl6`S*aJ(YUye^C`S_UBaA)I3P2KLgUDoS zPqgH`?%8n#f+Z~4y{nZF$?D&kM1!tCDBuh}-G1_{?{0}HU1pw{K|x{8`d3*&CFs5# z{r}l1wVzDRU}o0K36S-o5`4?j6~ZH{c1J(-+mn^AXXv_ z&*BQP4D*R414I~V3ioHFF0~C#KaiY%jtSig3028sPUIslK8^?~VLB}YG%1*17Td}G zT|rIzL-RXUg0EB}0rVI!Xk_N#UObtk%Giu>u_o##OafPXP&bMYoSaja*W>&U_nIe6 z^IhAN-F5G>=0g6b=G~uCY(bMvhrfR2o$Lkhx=+`hJzQtEWk&yc$fjHoNL4Hrax#fk zsRacO^n6deNCRDP<>-zTIb-?Gm7q5i+baL*rjYlGUGj^n_P<918U4~*->b9OX9Ud( z4swS~`}TpcbYf<13YgIA9N5#Gb<7 z@1(s=?u9C~vuIQN5m2#9tiT|TTg1lew>Fq;MJ5l!z*P!OB=oIEfJ z!wa!D+Q^D7m?TumI}R(h&o`k?o5y~$+00~^$`eya&Se7$AUboRz^BPy(S%!EVQ*e+ z3^!&Xi0WwY;%ha3Z`9IuHM4I`J^SRKxyW_va7T>5(l#tF5E2!VpZrj^!>_zTQh(~U z2;CaavZqyGxk0|LsrI9X)(So<31Mz?HzBMlQi&PO;|3h_2{7+S4IjJI7sVC&%q6HH zD$4)Pl9sKkuByW0^ompa=}={B!=E*iKXCg7`$5ub1USFA8#S1^%V-Tm4~$40+#9;K zw#Zujo`jyBfGSyWfqr_!ra|}dv|CqAwzZd=udND@fKzEhuo0QH89!Ekz+eQ-%QLFLB*)m!Y^VS6N)V(udyvGzOSmOEjm{A`H( zZZqY}^T|t68~;J#hQJi^JLjA5fl8u$bTTlWUP}?IOt-=QoznQ@OPcpKxng-)DpMqt zSb&!GFdNN3Tgs8qC0gz%ga=VniL?uNMha|iZ7qr|&(^=&Yw4RMYo~t3tG_6`sGAKH-ZsxT!MuF$Eg8=yFbgbTVyodm%2^t!JyS(R1O}lhwg5(gNvR8!F8RnA3Zi?pX+!gY`d9e>CGROGe69g`ltt% zs9-hwzlZ`6!f|hK>e~vTrDSrtR0rGdwUO`io z>dg|p?K8b3hihchi{1;6)w~EXX6{`@y5(;Q>e=`U4GC75*FS!08AZTUQ}m%83h>GB zs$1QO-0rg8c}O2ROa+`gU}4Hp>;Nm1;82Xi((v zfVx_W)e~Jf9sNK)?U5q*fr=B0>mBj%0!5HsOD&%a1=nyY{mTT;QQODP1)vF#`_3Qh zM5MS5R(t`=Z0;+}FmACtYgzFHe7NjZM7t)>Y{|(L602YcjA2N~ZXx4XQFpPHCFjvj zxvtCdO$-6i>gNes4pL9_Cv5{vagj`Bv-DG6a^JwyH*ynGQTb%&l?b*q#sPj_!yea?tRR9B-j za6QNhF4c)OG9qyU|LNXir7JOd+@69Z9OiB6Js!5n17M@30edc)9$Nxd_OB?Fa|u(| zF$=6~p8>Z?(Ywpk0j-2QVGoD5%Q6_z^?M_DXJVlf55R^eCnuL({-6bC{XZ7Kkp}oH za4wJneImC562sBnNV@*to!z|rubPXU5EGYwVplQaCi%mO7A82aJ0N%}>fg9=KTU9V zU?Gv=K{U|$HvDdU>mS@V@!WM3T=Hq?yoI{7OU`KWhwYQT z1i!p{`P4RQfm-)IX@s?pznmzCT>tWmE}010@1ja=l3y3C6zwn>w-ZRQOUhm;4E{So zA1~sh6FVbW{kr}%QOf0)doWHf{RGYHAb;_|>VHZBh5Efw>ZcAIjgfe0|5fPBpv>zh zI*%{O0rBOS8@!^%af@TZTv1b(zIsU@VyPZPxKN&8Ck*lRXR(hrfqBZJsUGdAwY>QOMif7O{>)*?Vqdu4Oau5I=1s0wo}h&h4!r&2Hu$Ns zyZ%KFgmwl!c&0Fi?gpPsVH*AhW97>Rv<2ZzlWIHU z*>yjP1D!Fydqoy6bT>h$f8ulwOUr;$$|YZO@>0HN^{p^gAAbBcc+ASG=mOeYDV zHnccpqpK}PsSAGo@Y5U{`P?P%Q+=Sb<1c{^2pfERLW2i3wy95*u0Lj>supFGoZF6D zJp0b6vCyLZf*KN6JDeyyicGh|+T$nykJ zE~{m8ZuV?K7o`SG`gDR8Y#`RQudy7LC`mD_9D7Z$sPd9azZyTWza+hK z1N2DOJ*Rk41GsW#X)1`i$5&(Lm==X*eedoFJgBCIIz=P~sB`Y$(xBnfCHfTY-w8s9 zC7H#DHl}Kra7J0F%AOIG)#HHd)NxhxT;CIu<6@#k+q7+2{PieeOZ}ii7iCCqf1rur ztB38&&%yV;67lVtU_0o{7vrbX74iGqx7Oy^N6RH1&^sl$Y4uM3hKD^fbVIYuT8#OF z6_bxc=Z|qWHiIyUGhvhJ5ggNrG1AM=ac;Ew%f55Hb#g(%=|9%7-hUsFL5@P8jrTY` zDv5ho)QVVfr|fsJX?Vd?Pu2c&7VGILH}~PWbSU(O^5ClZG|=(xk-MPmKx^Pj+N%Ll zG!Y>Iz+~Y}r{xi(y%VVguk8C@I{oSW z%*6_^lT?yPh|l{vEa?e5e8cofgLKTx?kCH=E<%cXmNNw(?qx;L4XDLLe)g{_ind7F zH`Jv|64VEjjBxOY#BFvXTJ7LSpz!5iwh@reoZT!J(1IX8`WVFE;Xo#Ka6g34uJp{v zgWZJ^{&h|7#B+LiT6*9P9ZbiYh?411`wc2ie0f#*r7pf&04F0M^I5q277}7E5lYUklxYP$6J%9~^Lt@|$$gpA zg6nG5a}|3z-AJoQp~b{ct_Xj_0e7EM5JGJ1_U-PZ$jCPSWerL4l#0o>GhWgkbjB(Y z)3(qwj{eG4o?tjIK>K!pP&}&R8scsIb6K8N5_NKb6c~{K zQ!{iLlpQNAU86QZnMHOrw#YL*o)5hq82JY}K(R%Ggm?nGIaxx%bvU?2n6?Z8(%CBB zVYR(Fc$Q>O&t+e72N=jd2zQd)%m)6GwM6xSXM^UkuHjRWwv5cL zvYjn`3r`D4$lvFp{g`x43)(%?5s0UnqpL^Xyub8 z{c6X9*-CYV@0WBGEQkMv$+8mt=V1s`ZN<~f$N!q}#r3g&`&c{>4ArD1y+O7ndGA-!QV;RS+47vz$s%b>4T_%| zEl(85(6(!dxhcpow&)G-4Q$CD)RZ@?|68hDme`WJW`f)2q-+d;Nrz1cunIebeIwmG zW3Q}Yj($>l1nqiavoXBUSm>^UwV0EpMz9K?6YQ9rCaKqCPY6MqPvSQ}efEVV8RUUd70 z>dXmx{h#^v?e(I4*NA|SQ1?>H4QJLU5U$AyBB=N^_@js{YW+#Y!>p(}$$hAW4D-@+ z3N!N4SX*urKw*46K*}~XXa2%{T^hTV6)JoFwz!UV?UAPZFt?=Y;Pj}$zq`)j-Rf-4 zgFvfmCLCu+kG*~Xx(@UPIk+JJ`m^GDLm?LI*3x^xZ~p_6@*?QH`~hNk!0B2~7?9(~ z+1D4itR4P(PV2gw6okIv%=M9isIf4vx>F3{ewkQ25-7jmPqRaU9S0hOuuwu-gMt;o)G!2`&@`%T-R3O ztd0pr2{v?F=Ox0Tgj5{&N?L;bP@vU9Lj%zyb7)iwRM71;`el(%zf}Mcl%4Gp+|z?K zy+<%Y*gPBbwdqG#Un@>w=knbh^6_$8*oMiZ2|+TOt9TAJau?6-YbQt8IYpxjxnb}R z2+!Ka$K#Eper&2HjcV>{y3p|21nJ%%J_r#q3>us>P`HoSW%$-PddJg|eT|N-!^5>@ zA|pZRBk%+QUJ-fu2X9XGdrrg7=h?@{y~X6E@o=JiB5afzy>BRwvxWY(dB3XL10x`= zynBKG0d)8yJ5drG1*po10hr-V)W3j^F>4wiheCYZ*L-2zjzZ34UiA$FPBx<^Js_>R z@LR;zyewwKz}mIbC;27q+#R5w^K#(-)G=?z&si`11B26Iwdp{Y6GcFCfe-f{->GIs6Obn#PqN0U|4=R#-GMtAe2L z42hzDzF=>t{FDRhyN^Ed-PmYqZ&W3CMCQ!vB9O~|s})4$Dw}~z@Q~E(zZRFRWpg%6 z4Rig%{ee>gAz|J?q!J3OAYIOvuK^|Z=%pX+8_C?gHCew4{fR!&vdi^VJ?1gvtZccpaOn<59LxJdS^TTVAE!l_n zlBiuKEw(jFHWU4U@XQXDmAr4nkz$EJzN*nXVjlK9InP=y*+-jK@X`+2*A>pDVnpk% z!3o4Fq!tjBtK5A{_BlCCvoEcr!yr2PLZo-+B(zi%KhGaoz1(LlM;0qLTbFlwx!*K~ zCvq23e;e8Ijs;JDcLKORTb7M$BQnoh&Xj;|Ccu&C^b}P}Y+7NW9uIG?t>1LYP}HDs zM=A6x((Ug-V~N%Hn6%8yaDP$R%)EDGwURi?l!2SI$Hs>y)2Odd#o@NdKk>)as!1Zn z(1zMzW(E0Frlex`PcA||XJ>3A)@lj3SM2O_q5_C&TY@S$DH)Se?M-IbaYl{pTnvP^ z!e5FV(ECheHBIeh1A397`|A2_rYv4Hb3eHMxeVtrF1mF`l)JhrX=foLv`9#iE(ZVJ zC>x_n_U9=sfhhoi5-|aMVsmy5fF7WdxKNnq4c(vp3-iK>v}0d=m>{}e!&Kw7cp>-gRHGtiK2Lw z*vwfHoSW;tBtm^!|D6O;B!8h91pJXGx&a*bHxLTr;zD-O1P=5PAO8E(mTZUp02k@^ zj0|_*o(sBIXYaDN%MnqoNGoxZ*tI^j30G~jcz7>eSg4M+36DS$5HwO!QnKEpNThoL z(rT2ybX|$+uX5I4?bHJG6#B4A@kOfn@0Y6OI)dVPg=w&lJ_sV>WuAYve*M2s7*Y&e zwRm;Hq{IN`0))`z&qK=Kq8;yUf~XD@L%QB?#1W|GU~h7BPP+$!)+O)PlCzxOzn-HS zQb7+9jhy_g63Dkl=(urx>QKABekcDv)J+Nb$*>P; zgT6B!=Gy)y7H=*9ZQ}+}Jh-lweKp@>8n^{7(oKail$OK9NfeArLI2q$TwFN&Jf8If z2P}I!jF^}hfVdQvd5hLF!-~cQklr$Le=^UvZ3&QQ&|;n7RfO^|vw1`}*srVu6V}0@ z60yn~5x{;PxD`?&-HkP)gH73HUahOPhB+;!=E220-}42$n)}A*CG4Wev7d?D322*dJ%a_>WsgFqw3}RnJw{tUhsv{om1)sb=3a0ex_rQ#exMSqGAp{Z# ze9-b4+IAb#Dl926UNGD-U5+YccqYlF?e8kbyGP_h-Jb^-t)5Sic{@k19V{$!Oa?Bt zloLq^^@pZh7^_ZpvcOmxXPt%~#O#J>Asa}#` z_C1T^65d>kOkO2>m3{i5JoVyF)pI4|`s;hs9i2BK!YJyqYp1(7QV`pNNq5S0`DW%e zVnQtJJ`z?U=dV3o8$fX(6%6R&fT~1+L2bmGC!r`V4#O{JM*`i~?Biu?9Nj%_kw5nW z&PFye3~?ny{c?=%H16yB)Tw8qz}Yi;8s>eeU|@<;W$XCz?297^bT^9yv&MG}x6|LS zK!JLzv1;p}y;y|{iv10}?dHD%_iVkNhnxZ+92~=O;0rFHNsA3CfA|0@Kim0BCd1Jn z&^X)0UH=eO1yW5_Cob*_^}cl|anfql-=f5y7sbw|Jwf#Y}a5|Bt4# zjEeGoqxB43!jKN#-QC?Kt#nEW3ew#r-7O8$jdXWNO1Csf$56s~fB$pNT6|(Li^Z_s zXP*1sdtY1Wu^1Fz+;V=kK|D>fk7caY`hUl?2%JqBO@d@FkrG_MPjDbDjhSXf1kR3c zHzCIiL$(4Y->n#mqAhW-@ZM8mtKDnAKSRWPwY!F3i3nCZM%VNAJLKJt60{tkA+pjq z6(NkS=+2aYU4yn&SSC?$pEU7<7Q+$Kz0HU-f!x(n1DF5zV?gk}^7VRGO6!55{*DgU z#mFSY7D<=6HR;CT``ZlMOFpBj_x~Mt#@UI|Y{BK8?1xKuE*}}vtL#uXvKva7E@jFq zn7|%Ji+xa~2M?Dr9nhiQM$|G0A-BY;qhc-rjU;x6NpE7>s&J?fDR3fv8 z!JY|QIwuc-&3#=E;v@0C2ps-Rbbh+XcXb^k*HcK)FjtU>?;<6KMT7D7pFeOUz|f6W za#61;5yE?@e<=}z7`iPTaPA$F?nDiSX_$SW)s<;ipU~OpKMIX(sE{%h)a%)}PFaMr zHDQe9Q@7Dz5_js(x_fELcZAL(6p>_*R(@!| z@>^t_&p@`!L81u7=PIMDBN3;^VUZ{cumCDl;y`6^Rs}5|O{28~=witjEsWhnc~Uth zg2HJmld!eEOmF#EcGWxc>~stce+%FkCgzN~s&)xg>>$n1>#G@e1s6s|zF$`Xa{+7o z3nTIhCGN^P$Li6Z7Hkx@q6ZEN==~O8*GuB>+)p58e!yea!u_^LP07q!R38afC82GN zN+OyChd@zQm?*z6rpuW3g()CYH(8@I5``l8C(LHmGSaPf!D97iK_iS*Y9zn1yu%7U zVbX!*$C)(ZK6QMBH-(YbU+{W&@qw1#9*;2`tzYGsJ&O4~i&h516#r0>0wnU`wA$nj6($-T$s$Rl{1HOqH2H*Cv4`)|-s|QW zcIp+A31>BjT9QPB2iMjWj0OH#9+EoPAg7p$lS%Ly`zWP=g{GOcFVS^VJ`bZ3&zHga zWb+s?E#|Y5a+q_Cb#{cN?$?LTD+)yX25hGmJ|d>?3mo4Kij6Yfewx3unhlVCQx9Og z9UWazf&?g`^T>a?)Y;{%E{Se8EE;TQU}QkXJnI+IM~sCm-uL79jkQMSDgIA1=g5=Z z)S6{96;Q6xRt1biDFbblmNtEh)jP(ZKnBoX3z_1HbC+4uueA{>-wRl9ttrn0snB;w zfF3i77VQI&M5OvEVq0j=(Ls4P$o1TilD%U3VeWyjNW6~+Sc>1haZcH zQvC@uRT_EyHl2Fvt7EKrwKlpmL2pBmOf7zd0C;=s?Qff$Nl`79mA8q{gX*S6H#nRl z<6=4QLQUE?%-Ri=lVukBkkGB-J~K}(z{ql-4T^6p+|cE*3skHDWTepnwr+I$=fzQm z4iC6R*Oa@C%IoUI%kZ@?60=!%y}VX34&+!8D8A~Hogl`c1t~`>42)Pa3&I|j{s=Ih zKQ&nLf=Ikt!r-L~A#W(a3f1a(vv`k%aU0Lv@2v!L``E47Mb?$r$~lL49G89-4h9Ir z4mD7iCG8+@%WUGafHkC#Ak0fw3&ntGfKed;qbT81iN;|8p4AU$aTT`esWg20OQN+O zGAFLI9Bs~TpvP5x6Qy?HYT~{f*9Pa7DoKi@2kI|BQ-Spba>MXybIs-7W!S~W&da|i zU^3OfkZeA*AS=Nz9I}o{l!$mRvW!I#5ET-VFcQwr+2}PFlLrEIz~ajD8fkcV*d~)` zB7(BG=jaGEHWm}NFh&>(!qKgOTXK9Yb;JeTGpwnrl#?AuQVVIKuD1w1lzZ z>B()n+m<}#Ai@1WfmgUjg+fFyY|Xd>M88#I_Eqf&#$t63JUrk74nA*$&7I>>xl<>?J zp-jv_2{FvApfO*d3|-5_IwF<|9y*$aduNmvIVbLc8m1&&DV}I}C~!Fcj5R4}-c~+~ z5~E{L_n@L^3$8ugQzJ|TH0Zh$Lr~(xy-`3mnMl4Upvn<~Fo0JV*zCYgv-Wg_6DZrd z4{`P;cxqic*%L^5;0bzz)`3Bk(HLeqo1R#chAptV) z4Kqs^(fBRZxXgoeP~`R?AbrWKl{}wP$^?!XTeF_G0gY;SONmK^PuazXpOQNh>?R{Cak&`M@`*ulErZ~sx6 ziNx{lP7wtqUmk_Dp%b;rL)HwZ@h3F?8=aXxcvEY+WdYPfFt)e!;VRxCv@ ziO0Gg$=5{4^w2Q1=SR$S4k?~XRb_*D00$BV&M^5;KtsoljXV1T6b=C{O7Z>`w9gm1 z4$c2n9$g$gLwN~rWGE02cEDVKaM*x95ke^&yKCIw2`?R>lRq?XaG5-x_B?@~^{_iQ846fu#E*Y z6zJYnAT;1*kGydy%n$OmZaV=+Z7f5nU<1qjE)|SB{I(+o-pQz?Ohe zPGYm!``|m({qTsf$sS1*y)6(f2^w_?>N>YL^fdt4CGKuOxknNj&h-Sr6a6k=MGuGv z;sgRbnO6}Fs&HRD%--eag+0TRq3gI{F%NYJq9}M`Vw9K?0bC_PsLd4? z&=QWC7^QhEJ4%8etqCeZK=5F|J9wD7CXr(lA40-LeS@2S)E#_r>Ar{q$qZz~k5!(+ z`7AzYJ^O_HMj5Hng${Ndnpl#Sn}XCr$<83L0?ou+c%fDWh$MIY(9A-SWr3GJ_dBBD@1f{9M6gWB~U`XMm1M>Qx224ExU(+uu zc!{ey+gPn)BY1~5sdYpUxH3a6s6mQ9k6r*r;}wX)e~^S!rjda2ZGP|@b znIAVbbVRh?f{^FNE1{r4W5FTUC!$UM``1 zJBPg>MM<9y$%V6rwjp-RN&O+U08qiFJDFeANLbFYByh~|Af&$-5Bw%)vknE0j3*9P z-n<`I4)KF`F}SaWm%<;7L;Cc#o^e#S=a@G4ji^ld`0fXpaERc(hQl;UXJ0_F=jn6; z;t0~Gl!p{|Tm1^3Q!!%^l~64L$+4KZlXxurA-RuYY)(#pvk0qy>Z<$z)@|1hDj4>? z!OMNR!4NH7LSB`@Ixg;1W=3tI4#b3hs|FyU&M{PQu79&(A(mBWCya28?AbW}8>9ro zRgK}{5amZyk4PY4X&dlb|MT}RTJ;fxqES6MooqtX$EMEkGq!}|P@gu^S{Q?!HKFWb z)AU!@`>j&%@()LD?V&K%`pNXUUpA9dn(jJ;6gB*V&$CL+vbm)vMCrmnQVfpWq${Ke zKZx^?P}f17c)f|La+Ih@}hn$JoA9mW%T#+Y~tL18lLxcEZD zA?AsB%=RM=v()CTO|wB|YDIcd)}X1;ynu*^RJ-NPXRJ)D>lmgH#-SE5@P1;uchs#_ zX!S|0F`Hz=U@UjI%#Don8t>yn`0xLF8EgtvNBNhA2+;{qf&}Y{FeK-E^9n<#wPoHt z20N>6t0B&jF*mlxQRZo)0UZKY&L79EHPdG||KyjF2|op7<|5#ZTT`%#P@ci~y!sFh zWR~7@u%HQ-PtfJPlVx0hJQ+EZUuI)1#uNq>gNT3BSxO=ZJL|c`BZ!k$WPayWaml?Z z3X(1hu`IFHVp9ikHU{BxFE%j}s%s+jS0~cztRde2Z4<*!Oq3#<1NU26-P>%>O-K1s zsCb%umzNMFLo8Cate^gXE=lzgJI}3~;kiOcL3Lv+;?!16%<+!mU~}S0 zLx9Pr08eiE+n`-hH6!CVZQfqzu+_YUK0n9%{oi`XzxI@fgwSY&bgsyCh5%9EQe@y8 zdLltJ!-E%{3Y?fa-x(Kob#-b2Y~YVqr<&(#6IJ^S?b8ZTmegWO&Zqk}Lt^zspp=F+ zV1nKm4@@sqwd#OELNy90fm(YV2Z2)#s1Leg9I;zb1W>xQ)Q%d5(Lr4&LiT)FHyD-z zU9m}pRFymPFgh+TO~;~(*^Ne4zI7`{zVT~gVe~~P6j9aX*G-0EpZAAx9i{d>u0X!3 z*s2qwtBgLm>ZCL=dTy?bb&k~TsGn1SgIvYwDw%lfH<~>Y7UL~i@oj7NCq6jz{8(?r z*XUt(6L?xNbqhi1Xl0$fo)U0BHAjB~fekKG=46eRRmoZXSvj@@nK8czkA-hp(fQuVmraRxiUBvxW5*d7huoA$_>+Q;rY`w|^IqS|tFb*Y zpT0RA7k$~9ohep0@L|c}PoQ$_?M*L_V8QJYp)3k=UCjMp!im|d>p`(6xhJ8C&@ye(vIK7{hvaRU zhD^WHXsk6RI3mKp4yTBx6j4v8&6nV7`CWGXcWJgXL*L`~q(*z!&ot}bIgj+NUUaY< zevj_zSH+lp|%A9eK^5!pC}42;o;n>btXC-~|8 zTi&M)G#3&`$@LUPoqw&z9yZ!@q(5fK5JlHb zIP%H7t_R?YjE*YSHwu0zesOu>6?}jeO`nXl-fisMov!{D(R{l5jHCZfP3^0Xj|d8@ zcIdSCsJA?0+9!hOs;0V3Z_Fl!MMNZ2gtbMaAfBPr3jx27=6H}v)lkUj3 zo~E%wj5IwrKMoI?`q?}dO`~Zj%(gi42=!XWH>_!W&)Wct5y2|!v@6)?Kto3l8wI6| zi;XgfcV*aSGwr~9vqf?Q(LVyc%gBoid(81^>Dn|$<_!(1=)#=rR}l4%(I`J6L$JqG zKp{4AON+p;SLe{oOhOR|6)Z0Hihba)@#nHX?(1uBXJc%{^{6RD#D~bH|2o)FTRPg> zf|>w^ypM!@)0n3Z6+$XRgIAzTzJraOlUhB887Mk-yN`Rl#{!D~mhI`#+Ugt=+ySNf zE%54K-h>08$U$*7v#NlS%>G}3!Q)Z<_v2XNJ;-qYD{(lETt2jX;*EST)9CE$bRK`I znv!(l>^VX_)eq$QRP)lpYJ=>9^f=B?YIy+oFvxCJ1*Q2hcXVOTf#XY_%c~K_I4&BB zalh`qxpQP2(5qy?+>n7NJ6mM|Er7-#?zz0HID~IfE4L|4<(y9v2j+ zYNB?ijawK<#n*-Py1NZtsSYbo^V(+%Fp1PoH_(}sJEMP1O~&Mb$jRQpDB!efI3p_f zS3i~BX(QlxA(fRiihzt9PH|S-1yOT77tK^mnk*Q*Xw556Z){}p@mz?vA!N3FKVs*| zs@q#eIr6CG^Yw%O>Qvk-Q5>oNhnL_a4QL$9!KaRtAfWjqfP;Yzy2<5{jFL2*sHr{fZt{1*oJ@WEz3_TLOTa zhJ~ur2vZ@UQ>}A)$mSQlJgS=(Evcn1&8Mncod$_2;lxlbp_C*%CDcHY%?t&pd~0 zNbHA#02Zq`LO86s$Iu?fl+aDL(vbmenFqpj!Tn`9w&{CtGjaS)iEq5>w|cbvlG3r^ zN}g^6CQrzF4YX3FkIGYxhDCBBdLc)1prYCLcUTzGf5R>I@i2eR$>V&IiJp>RR^O*) z1yi0nWM^rgn{3b{lvST(k0a75I2%imz~Ls4dUBP1Krj0MIr;HQtlB%{?jY5Hih?sF zWrY%HTS^JK@y(Uc)M)haD!FGU`&1LwqX<=Id6tM5;gY3&th?YLFz$TY>nfBomI`2Q zfm2ENsRBVn`T|9)Cmb{o|5vjWjj~6FP0z#~!6>GJ$>XB^C&YZIjPtlO`)u2nkvUMvR*;;qyOpN&TyLcRh zAD-MecXw8m`qCyJLj;Kz*^GF?37vV}i%Y zB%ua{v%=d~ed>ZD(}08yIPQpw>$Y>ltI1ph-ouX$$@MXw&67IM@JQt#MX^?ZlGNc6 z&8h3a=kajGd$uN|SojCUn2^fxZ!ooL?$p63H~HX-PD)q}aq@N{niYsHw82@!lqN<5 zj*&=i@eBWvnD1u)kmEzOdX5rpOoTc=0f~J@6i|B9adPlLwK{2*q3W9EGU zzT113$zGwXXvdAG#@AgEZAPQuu%#2R>9xO~rnN$SI*p61S6nHGO6hBqM2Nu@|Ipah9A z+FQ1iok~54C!$Z6ODt(Gn}PkebJ2m$oCjF?;R}mNN`2vOH0Efbp_W_njSb6G>>GNo zI8GDpp@F_I-_5kyQm$`6-UV4^GU?~jV~3eG!9Sr!18qgiV*T#)BW z!=#X#fabC+44!&UW4(vOhX+p~*3r7yMthUfhr9=1zVQxBZ|#UBoDe3)@pEXFw$3_# z5WF|OOPidGI;#|N!#Bk6gI^@o$4N;O_I%2=%SE?a zAP@4pKOpcQBjXRQS5E6+3^;~uhTDQJqyM%VfDXh;RPP<~n%Dm4L9!9^Q099qDxs3uy!1)XthltPpqhkb9nvYEFD`BOmN z7P)nNIu2oTD_C za~UyxQ$&q6Ll`Rp;1HbORa|LSq~Y+=3B_OTsVCXlrkg%%Y68a@W*p{M50{9Y!kt|0 z$KjwdrU^iO`tr%=W=8(ogW8WdymueY2=T*!kp1#1w}|g0&uvZ6G<~j5A~V;)vZ`I* zM56GW^%XbOB~b~3<8RkD2Tb;ScEI3BLWuydpbDx_@c1mE2{}%7-y}@_ncfllh0U2+ z64=CdYHNgy&m%j+5J-{~fT*gI7b>I#Zf#skv&I~ex>(wA2T@VNwR?5lP0Z`IY$6Yw zX^p@bInVPd)*8Dtl5Vvh369$L=c6OH#H95U3x^|hTjgiPSdxV|VZtJ^{`_a|w&7f`E zb8U{fRy5}m$MEwaN7(1ppbSo1BJIgu9nD&E_h@PTl9bGhLI*}vN9^cc0OEu-m6H!6 z>wey2*AnR9rF&m;XS-G~5@!DI4MPcmI`wuIP`~jniQW{Xs%18-3-B-U$QZXk+cl9O zjM@b5q%%U%4C5}3z#9KoZx8Zm9#_prK(_&Uu>G#HHi0s|ypu4*EM9hVzf(w4-E`Z zQb8c@C8GoD@Vbua5-=TnoJiB=W1GW_9)2eieBtbCEE?=3ZWqqu>hpT}ITDI|DE=>i1=oDfE;5}A#j6Ma_bicsohP^>iBvNOlHO>XmdKfD1n{g>wh@g4Wq7uSht+Uv5Z z!nPTYHz9ob7#VM{Iur@BZ>baetZPiV`@EV4x3@V^07r#Ff&r#sisP<9vAmep8f~Gu?;Wb@a*##z4ua| z3JHoXvy-1klJ6_8PC@e`TB)}CVaJDLfaHrXCO9hKZ5k7p>bvs`F3~1`h{DTirIAf> zI#LyXmK3CbsHZwD2DkLhe6qO|rF=ME%#P8tTmpl_2%Tb&g|+kZ&(+UxADVJ~^NPFJ z7r$<;Yy14LuFbBwg6(t-jmaVLhbgI(8SovhHNr~kGW#2s)GK=;QD`*TE_gST7Xz

{DmT@kQ_XQjh$cJLcqw7c}xfZt=?hs67n+1ueM76Rdla)G}E8(5G6I* zuHd%jKCsNJANY}~&u#V3d`0sGS^7JGm(LmmYhk%6A4-WjpD*-Oa8}Mx?KGRm)!744 z1=aEGsjEE|At2plPc_P$W3$^C6|HA`#1dInHQBUdx~^y~OY0s?LW6g901_W@Ou`q) zzD*3NhvrF_#e2W}jrr`3QijQNNgQmR1M+eAsl-Q>-w?! zLXQ~WGoNs4<;(pf{&@6AcA!7~9CT~IkK@fHRrkpqbBYR<^})0H$Sr1~R^zW!9qWH8 zqSl7gj@18b?0Hq)#Uu8*mp;_d@!U?bs{4av9PSf|^Q8GU#+u4)5QtpleFeb+v?a1v zH!2w3xiUJZ)4FN1q5?2pJ>Z!5Tq1s1Z%Yw*{U&3*WKT;p@RX0uKc`koKRNlV6v&FW zfYR%IV-&vk=^OB_*K%G2)`MedoSfT@wx50AHet03`N_D+WP;Y)Yk<}T;8rW&E891J z{^P2n^Pdwx>lfWIydL|6Gx2qH7DlSIo>_ngAP7A`TlPn5=$}7F2Mz@ z$a4(Bc-(j+@NPpxLlJk?BJuAMWwOPwv{_LQBadp&&vl^ER_b1R)topcDwRclu>@rd za$+&!Txvf|{knry^FPZqygd;6#rAp7&K42${K0W;Tr=s5(Tso{$g(tqZoao>Bqwb3 zLR-h=-2d02C2xIN0ilXOP&;#Y`w6W+vH(bHN8x<$cha`CDdZmqRs&w0p`qH{@P_Zr zAqATH3^W>78sG@3c$(XyJ9MEZ$+^l4niA~AYa?R2zcz-2QBmm64^#eft8Thg`Zt}s zskW<_)fc}SMzzIkBp)2t38Fi$r8c?h4P;2<}evrLu z;PR4E3gv%Tt;xxY8F?(ngUNMpd^OAns2e-3sG0TQyndHH4GNj2d3rSY{Tmh-@(2@) zm&g#%m9|3#tf`8SIXiYXHh>uR%c|d(+<6z(|2^$HutBT*B8&p0O5K{iaKgLt6M)Rk z%#|@oF@;;pu{Ho6|BCrf@qdjF2fr%(7Nhj2l!-o2#Cy*uB|G!S7;rcUk8hqH z`7~RLuQzso#?5BP;a(p0%E3t~$gWUYtk+g>OK#cy7b>+C>rLS&u+KraK#Ci-AdiFKa)n+CPZ!x`#) zqZxG`;Cj>{Fwpx<5xVEhGj>c=m1@`Vd@1<20kl1x1_1TD<<*y$h4O$7Kyp^7(BCxn zwe<&*6TEeRDeiUD>zRA^_z+cMkS1S{CxFjLz*EE4h;vX->0&UMuLkFv{I^eQ~KzR>kot8hJC#o)=mfgwz zJ4K}$04JX?%u3)qVWnkgq}a0G=?(kOT8Y5HH#4V&H~jag15igFWHY@v&Nkbl24_x5 zb7&~a0=F@Hk#7#S%t!Xp7jJyyKCc#>2>IMCTmMH0k(rEy{r8#b@AHqm#s3uy?D^0# z;Er@`m0I2R+Sil0`A`2j^mDV?kwAM&ZIlWSTa3?_U|ys)ZH3{xIf>Dmx1w#Xz`}z% zr+7hWJ0E1<9Kgvo&Y6%_cc)w+AAq++P6Qi*k-fQzFAyePzrO>bkf7E*Y(r5@A?8}SqcG0i@J0RA(K2k z5+F~~-S_j_#ygJfIBp1}V@Wgn@woPLGYC=OL_*RM^I_4I^uPSjPuBl7oh}~eYF*wz z`8+msfk^Ji`lcuAk=&%eR%YI2%8xDGar>@Bz9usU+jAiHURE-#M5<6T#i zaP|9rRUC@>;*RjpK?hD92rfJqHSYF{`T2&CM{O@-`}cXQGgn65iO|HswKj%Lt6|An z)ezLMfa~p z@?^2pL(EuVJoG3$7X=%w1npa-Xapk?V|EKXs&Egk;ttKLyI`R;7|3)kCl6%2p7k!*3k_a$y2&fLPLTM&IPJe&38jUw>-AspX zPldD;E}6TRJ`6hY=yDe$@9a|6+UR3J%DP&7+V6gTx40Y-AW=KHJvoDlfjv1n<>={& zY7JaqPzj{( z2MJV$*ajx2&~KqX3aqusomU8@OHa^z9S`AZPraaA93@DrLl#WF%#sRrQNfT%lA@u9{M2tdw2!^uu|>Q17GEs*3ov+mp% zN;yhGjnwY1{)y#Wvkm3lJh`x$=6Zd2o)W-DU$ThG@h85cZaDYfZdO99y{u6WKj2f&E;Z?en@|jo9Y|` z%#{lQ(yQH^3%1A@3>iqbIr9B2xwO~Ec9RI@*wS@U6y!@rLz9hfBbA9?~wTp6u5^U%d1tGL%ZCL`&cUJVj%Ea5w>LY?J)& z*2w50{4Gs2vITqKf4x@p*mAhmM|Q{vUNK+nWWc zIaw1fGele=5*1LlRi074N!1pe^Ta-KqE)ILRI3ms8UQ*0gqB$`fJa#Q9ic|kncj-~qM zEhqyav$7IM84x)H`zIJfXyC)zd-ht?Hr!cJa(Mo7q6rM(NU2X#%sVIt`hXtsq~K-M znZlc7_9D$QE@?s-`q7-k6KQ4_h;$FAW;SknG>TO_WgFQew~6s6D4%xbTi@HPB9i&N zBMw-z%|?>JT)1;&gOS5o+nq@Sz`69zd$(Y$5~HiQyh&1@`g0{H>*>T%64bSg#=DMN zKszp`G03*A=JqPlvnWzjUrk6tiZ0&v?n$D=sq>Cdz-8*W$?hhH@gE4ndeN>!Z7I^; zW3zk!-JON;OB_9|dpOXZb>v*ZUhvSBexocNAg^mUQqoUB%u64uo5%0ncYN{8>%f?B zv0PkglrnK*WK6k?$=sLm3hA=A@o;i9vJngl`uJ3P$psqNW#K=-ly4h}4p27^WQAVH zkT@9pei-LNYDOR?H7C*w?>zA!+moHng1X$kCeLx8p5aCg5Cg|2>LJo!O~@#RB^`2H zSJ>%q%%#F)HmiP7lvNk+W3D3}Lf$xKx5Ng}emnZ1fNMnq(Yc zeiH!&GxR{;A<0>xKFqm*kLz*|Ij&yJQjpOetqUj$+rMPH4ah(iy{n2?1vTL@q_p3| zBST=dG~P02y^Q~)7MnRrV)HNRO=>@7 zarHScx1hhZzxqp*tu;9)F5o5SIx|i0>n^Mzub2A!>zTb-Yt9&N=QjJfg*SafpnMJW zgH>fkG;B!>-srdu0Z#A^w;}`Uk%Dsq!Ag6ebfl1rEC$gF;#GC5${CYVCYdk5F7#eP zo!R&K=&*{=g_g!jG+Z=$h%Y}phUmIDa*=P z8+4768$E>{3AFm5gm#1w6u#l?dWzZvsX)pr2@7b~X5OaT6+Z&T&01h^Xa&9FM{F;~ z8~B~V1okU3di-7Qe$&{zdej+R2BFe#f}4nkRb1qSmBdE$b9U&IKz{>Ss&~&A8IPP( zhub=m?aFJ;m*b^q$Xe53)y4ad1MP2Cu9ROp9C{kFL)934ZF<@$cC zN$U5%>wn?4$Cccy*5fhrSpn_I0xrxHT%)9splNuTp;3vt+V{1NLwP?5 z00Y-(o*Vw-XXdt;svZv09Z-F(&Kqcy1l4e<&)5IhI>5oc$aRq}-5)+?-{ypcJ6D47 zv9jaX9hHH`HIQ5=hgpj)<3_;2##}pE#fy4QE9%m<4^s}N)Ccc;MZ{1;OXWf3IH9E| zc_s~NfgLs*fO^~-z3)U{C7ZZrv8B}=ie7&-K}e_q`~Tk_Sl_N9r9VJ6gV#j{mr zUe^y8|1CQce<&>TB)21M-K6MUjsItR1`Mx2@cyV>6LqDT;PIJmKdn$eoFcEBMC|pM zGZommdR_y>-DealR5MS&P>ps1C^JB8JP1Yx#Nz-0DI={EDw@6>C*##uOmH|uB{&qf zXFAJ{V;|cTDwS+0I2H9G7iD|c1lS+zbQLtpbw6`*x)mID;)7q*8U9^r=|qDyK5lmT zW}!uu>O2DpDL|tL_C+i;WeQROx<88k_0jC+humnO2YE{M#~NQ4}Sj%{@{q~o!E zY^(0b(_Xp@zZvADZDSpyl|@vJ@@6Wp?JO7p{3 z;X1)beO5pqD1FD<^nk_WN%ZZ3e9E!F^{Be1D*07q#FVo4^7zYx8aLRA^njqZ8IBLv zjEggUa-Wejf>RLBtwjyNCR^3|{<&f5&TAm85e5h_5HiuR9E_M*qWG+_AT=4f+hCM; z`V;sO#ME(1rX}4)-k%zL<36&m_l6Uqthv~TzZ{_BPfHQw4Z;Nmk7RZCB^sIha2z^4 z0}ur@Sc_cu^0w?J=(je&aUrvYClgY!hqL-Y{13289Mb!}VBQY&4I`;i552@sQin;s zaW2{hndZs5jd3`VCJB6|@K)7C1rbNcd*`&D9Nu>|usVkvy2zF4Us4|ROU25*mi z_#I!qqiqzJfjpGaaLwJ}cS|$@F5SQX)%{FIq!2P({hryyC~DM&s=JOL1Vzdq_Nsb% zs|QRj{s^UaKeG_ZC^8&@H+}O*kwNFT^7p7-MJ$rQ-%K#+H#*o*+8+JzTd%13N3;X$ zv=)JGIEtfX8RH9--kpt3@BaX-5^l)`!m5QM`{fN9z!i`{w`zf7=+E7$h02e)#@zWQ z*Oss`am$*NfR@R2p|p@`>Det^8(&1L;Pb90f*Rw_FlXK~v6k>8Z+cG^nY_bZVl67%pm1Yv5=&>(6q)tj-A|pNXI;jGG9Q~&F zpxfM^wC-ndj*N+|PDw2_Qw+2Ab)c&x_s>EVJPA2_&zig+%hHHjdoSRZ0qPl0C2oHB zzry^(DW$lx%$AYvyOi6sQ6%qCqP{4E8p85_{!dO1P(^g5P0t8GI~2tDr`$~hSu?x$ zU3LSFGvwJsg!{o39|;YS!@`)XthhA0fEZ&mrC76mQ#EcP9Ek1`4u>621LS)?<6wZm zvGT41%JhL2sdr*#EW*ZiBH-_rxy_HDRucI#45qnpvl;KUC&CyBTU9t^vIbZ_p64j$svcktZTY}jOH!&6t{tEN9m$= zK+a!!w22`U7O*YOMyvaa)}EvKmtpGx=+R*oGYTAZLbI)uZwzWPL!<2?;62Bi^p?j` zp*_IZ#H7KHO;A*{xcbCkDDat$F>hsFmpY(%^)na8-bR8Fm*ppNtccvP4MjFV7q#-do=MM!rap)C+DyM4;@a!adkD9Ye%(O+9pxMtLHBjsKs=@-$H$;Y zeQz~GTDe!#ll1REEy=x9^dw4HSK1+;a^A_)fImRXae2d^l?83h{X!x4q0KF#*k(v> z@CIX-n$T0@{qWL&!KOy=_K#{xJJL5%A(d9bf(gasv#6l9F4Zkg1>e~R`_#;lZ(mDe z_J``}LMU7h%ta55NRajNT`m6AVhxNEsOhhQO@eD z*n~{B2rjv>?&c2b51ZFPENWT8t>go>v0P-PB+Vo64QEd14&v#LC{Q7&MUN%D0&9P> zo2?J*IBvdctVHn*GL@-PK=lBZGgj8vIg2;v@S>;!jm6Xaf=?-_(CUg+nx5x`a-o zpJZD|9{!g+o>fmDntLbZbZ&Q~P=@sr1l2B$(|JLot<4AxF<$QOS4WU^#JZ&wp zE$G4wb@kX(taOfl7=M8hL?K%0DbbO}7VcQsl4PGQ*2*^ro^!_C?Y?=w$%WO+Qz|UO z?afRIqOiHSzNS9-^!jw}ZXEeaakL<8$#FRzY6$yDewV1=-{O0 z6=-uJJh?T@eCI|wTGWt;$eBAOC?YbTKMvdUp8|-(^lt_+F^?v4N}3hPDRa)_yw?JY z+;<8|Heed*ku&)k0$Mf0VscNEW>x3sF>sQ2gh{?1QnGzvZM@+jt@i^S{{~Pn&D29W zyQ`oN_qV!-oWFSe>D~r?Y~7-L#|ZTan1ua(j1^NjZ7kfOe%~O(Bu53RbjzJeskKo@ zzo0Hd&*=C!%87F9b6U7~mMdIfF|ItC-1w4pnwqxR`LX%Ld>{@~3Si(ZTMgf3W{h}= z`P|3%_e%qBar-(OYG228zh69DNvg*?1E6~q&>PTHV*>13+uF=q4Y{&@wX}Ba58HHn zX*Mubh+&Bg8Z_sG!zhWA*2he8x%5wrDH`$(SueILPdKc%%`Dh3DO4V>6qHqXyNqSN zy9iFCD%)`6C1|VO$#UodO4cs#FL&_pi^swlk_#YgY2%IWQZki zZZynnYUy$RIl>(_`11Tt*|Nx1j_@r;BASCeobJ34zRJcCkJ$JCHqN@ODNWnf@gtGE zY5V%@P{bY3XEv9)KuI$wn#ECC-;I3uZ#a5w(5kX%)W0-rUCqS$J{N?!g97nADa)%6ToPkjRaL`q-7Z;638O{E`Z|WI!{Xlb z`O1(+x}fRec@2;>2LHFivhu_!u_u<(+b_+4IeYVje#*;WaXP}=Ht*);pD<7=W+0L6 zyMRH+bN!HQ^8DxRs3+a^hjp6>niv9iD-b3{Jsbh>uLasS$i{zO1M6Hstp{|d!~zE0 zq0H~I+FTfKa{_2xjT#IqOPLZDW%an?D9%Sl@4*r_n-5pZ54>_???n8r(wC1R=i#xl zpXa9CNW~DCtV=7c1#^G6c#qs81RAZ@Ei15ovDIc+)Ck}4>a-##96;dU#gi4BNt-w{ z+(l}R+-|?*CZu~J>_vLuoc{1GxNOL3sLVO%yT6|{8I?DA@^C@{zk?ccP*{?kom@P) zHZ?1Yxa;-B`)4~Ve;rZ@R^YAIFY{KFysRr)+*|U!x2=BmT%tyvR%|C%&H`}Fa#OAb zCHuuPH<`Yh^nNwAzn%QTkQ{Yud+7){Q&B-Hc$`<7++U!@??`-&K1V%w0TTt_KgsSB zWNQ}fep)}bSxL2Owpir(Lvs~4|0#x32cVJvgsP`j-dOJXp7K zR@GV6*w3!+JZr0COZ|r0d|%KceNE;2y8oEj(BNEMQ(YXGhALoPRvrmFHUMq|kmBp2 z({Y!rglK|I^H@9O=Xj=xgRGNfIg9sfQx_m+j4rh`7`l3?$<+}7MF^@2`+(KYY{v~#ck$Ja7t0Ta8?i}Ui1q9WAgC#9BmhWPJqAx zt8#6f7|vQlwxk_9jm6|IB>2M94U{3qcmm>el$3%;B7yal_a{>?nI)$lm#57g_xp$& z!m+Vu+u3`+vYHvUWJn7ZbfcZA*e&>eUj7+GudWfU3@r%g z@8^vp7k?+Q%7K-!`tJ$GIGzYd4As@u4C7AP7``?#O;$@QnB@#<_UxeDC}5Y)LWJ`<=D8mvav`B zvUzmicM$#sRm?{&+YbRgp8vY7KyoqcC1E3YG&<5|3bLVFPO`6e#^>isRM4LKYJoQ{T1K&wP9B#^)s9$m zyTyVp;b+>w8r zM|rIsG7rir{QBK-8O+;;|At7qex-?jw3+|kz98|1ZDo--v+s+T(ZWy8bX(Gj5GU!B?wVm*g_g{|5R zKr;wJARK}iv@?kmo*x(rK8HsL9?pAKKpE)=SvSJ_vjnIZZcn*;rQA?-zLC2zoL9f& zxvX^#YEpjp@x8@Wd+shjAL&I8d-v63XW=Zc#w;6I5njp`k&w^foJ;=AfQZX_ejRE@ ztsJ=d{3W(_uunmaAlFlLzdEAJ326$LO5$@-M@q+Ps{%D9HRgJTgJuUpB($qOOzOQo z%(wk3NBKxTVTyd9OGb<#ZrqTL9Uim)lq=e|LWhh%pZWf>CeZVK$utxe#+a%Qosj>d zqgI2Ku+)^hO2#FD?#4u^<*ip*2+i&j4PtogYHsd?`xr2>WMz?LDTTC%?TU}H1Czf+ zw-I_bZoTWPHobAPN}?XQogHn4wuYgd?c!)x%H+pLC9f~T9NQxD3M{z{w5@duC|CE<}HphdHI3|Ubb(2S=;a% z>5RJP<=NS{R8Zqx@9xY$@n9REsr_2*K`73+9KRf+e|%uvy+3_K<^3_R?VePJH`^^j zcw6#LH;!!azh@Q?ltgBNr^Wbppe1_(bq3`klVO4tzn3pP=@W^t>}R+$(x2$V(-xB56J=R#3~zPs(p&o}|Od3i2weiP0OvVE(TO-t5+J;#CP~zAV=h~bQ z3$qfIKTm1N_nntbL|!;QE-)ae=cfV@SyYP_QF>LtqvbYIabP9a9rplV2`>`;va=@{=I%8 z9$oyJ7lS_C73@8l1}~!`3&x`)Q&1fLo-CK|JNbLXP3-ZD<%>!alk){ivoNK z1`I+ffy(3_q=Z!6_{z#?9GN316n=2j{P(A)(X9^cKYz+5oD<$UJ3A*Hvn1^k*)Y|b zdH>12H)l7TSsOAI({G9AQ)th*E%a$xJzKKp=CxY3chs#(9l7wpR7LG?(q)vH{3R;; zhaH|w_MY4Lbl7I${&kaD8C=!q-EWoWCyhWc3RVzD$R-{yuM#KBve=Y^0P^gId|OQ$ z(#yPUXAfpi%D9@%-uzZ=FdqYoOEwFxN%|4;fuco`tGlz$#~rcDq}rMMZX^~9*_dWi zYY;Ynej3!2n-w2v>d4#WPDczYOj#DQgZufiXCH75JBUP*FvG3fyLg^w&MpfB&K277 z{@OcM`O;-MkU`L2nW(O~yd}BL3=egkAFYJ8rhrVx<`X}vE&K(6Ldq$2S5Z~Sqh6`hSzshvh`)f}Ks^3%sG=(!>dPZP z@DgADT@%2aE~P^X`-DU);uY;870Eppe%(<^ZxDp|h8thSF7&+*7*X*K@C1JbK+v&yEfl*uCX~jmd3LD zm++q}C!$)IS9baxph=5Q_<2ZQjT#t!!9Nq%M7L}Hv2kvV^RBd&t@V&)53n2`N<)hSvogR>XPa;0oLUmtFE+W!v`R8;X-#@dSc7(WTPR} z5=qv{5y~G>&7f(6;b-{ts$01bnH}KT(HQ{7HW<9h_Wk=JkuAX zy9vRu&Q)7((GfKI$q{iesTBjpx(8bx*rBrOu+k%$xA=RXMyT*8(W!#J)AB`0qxFms zta(@_jmMTqM;2}_Hx02xYUHh=B}g1`&E&2{{=IKJa9I6!HgIPtb;Mq6F8hM)xy@P( zO8w@o36^^Ul^{&f0vQ0yH9!4l4meg+>>5jR-xDK;w$J|rIsDT=+xF#rHXd_Y(iMwX z%t?Vy3s!ps6ua0TY*mVbHj3{siMhGCjjLz>IZMReZ{F+PW+INyOfb|Pk=B{dWy!Cbmx9PvrM$Bq@ZqB~rpkh+j^ zT+yL%Ai<;>4x>Z_i=BG+ZbOVI`xE|6-sepU>M{-goX_5|DbeYrHa08V)8=}qg5I9; zdN`-8JnR8>g#!$^94)ZyM6~FN1pB_9X`_#L(x@aVeP?F34L(53SYa4BU`>S~CZI3x zMstEt_E6c^^Wi-p{)XF(n_0E{OM`3IH}D65!tO5tuUz+3=@s0=M@Ll09s8S`{1PyFFASbg51D5JVp5H9YAroCW;|j}y%21e`irZ{ z4-BB>>gp6$7IrK@jaL5B`#3RBD6D})qfMmlzk4@IBJ0f~+`)$5^h@{mtT2N5xeFwd zjqBC@8S8t+0TSGPaj^Q|qavM;Q8VE#YJ;MBO@x(K9V$p|Yz+m8YGRyohjK_xFlzP) zFm{yCsqIy)Yzy06l>+QMdrd#c)Qvb_!F)1jNb)BLu1o70HvnKeDR)M6ew0G-B+8m7 zPj%fqjUOik+TpMxq2!V+1F80;E+2#PxY;hd_7@($KK`-p{qa78<3V8f2U`cHqSLi* zvjhXO;5=;OgKW5ng%_%pp;=V$x=+W0SCRbj&EvK(d?+CwOvLVO(AF~uN+?(K9Pn)R}xU-dn^V!Y3g6ESYA3&o^%#o?F9g3A=Fy-|zgWLsV}8Gmx8CXWKw-@s^*; z_s$*?vY$!K29;DNSyxB4z|C&v%@c}tKA2=tlSHk60OAjuAv=VE4@9mBGJF2V9r{^t zEHSy7ST~Ufn2n1O_7L1xrI-XyV7BV{}DFHIJ?o2go8d#D5LOqy`4GiFmCOn^oE8 zM74fOLbLObSwtHYp(lpg)|h*GLKUF9uFpQ^GM94UPJ*z+D6ylPelkWOE=Gl2;719n{rcOO!?@ZO71xfKTVY6}e$qz;Q>>pY zf3m(d)cntyI|>S1)uiE~;5mQZZZ3f+X-QV8O$OM?7+IVS!LtjGkJgn6Ym`vtYhQ=G z%FZ$cv}7pV$-|fI*|{K|JxF1g=rm0YD`dsql2yZRvD@&P3{tFcSo(M&b8O^&L`pj691XQb7KVEJtA!Z(C2(AES*P z6;^l_P5Gw7Z&IXXt2D4ay_{4$jw`4#9?nt9V0N>hT;BJKG`JcrU-W{Foz-*2Q3Bz! zxb;OrQ8gn>lnaJ9UN4?SXc}BQ_X-pRWkJ7!sGE!mlm$?XSvGRVMxKs&dq{l zR3#qaXJh*yE;Kw85P#oDi-FvQK35QF{uLaH;%r(RJneb zJq#FoF%2fg!TPiC%t2wa1OdCve)XqL0SUp+arAyLOVSIS&0w83*ukx|%`C(Rg%7GiVTe zIC%w~u;s8rGz7gG0NlrCLQOro>`D9>_dL6vn9$MpC!?o@3D$w=vRdWDC^qx0)zsFa z9~DC|D`9^#N~HmI>~$aJx>_uR9{oBeOhzW8iq*_Me1>&dx*CU9$MVtA2iBe3Na_l+oRs8Ebc5N_H7!_rAoEvj zdj88)z{dTO%0Zj-W&yv;#t?anWiQ=SSuyl)>=|%5>nZdc#k89=~K|Cm9%wfK$f#L8j zR91JiG0>q`q4YF>ZeX;2vAIjyq?htQUTW2DRIgvFdO;|_S$O!Id!MFW*LW+W8&YM8 zn2^rRlQmHXDXqx{~U#hzj{lnUHx) zfe}{Aq20szx4pJ;%#bcwzoTAAA#ozxj{#JR>PL&*=w$Vgj~I8uLK%IM(6QyQ4c)4zxX)ueE`j z!zCo*&R2Hbe_T6%4^T2$!+0n2tUvcdCV^RqB!pBDtLtT_LWh3~A5G#*=q2;6S_Mx} zc|nF$V;_uf5^vOz?bXF)Ynvb#V0M0TDNH{+lmq9DnRJ6Laxlir+Y3fjQu>`IC}NBj zn;lj$-$#k)_eEs@A2((}K(!d_Wv%f=@11vK}g#)gglEQsFZT63oBe|*5-=tWV)5PRDMcAJ+#>C zBhW-eP(jn@myy;TVfReki_+3wh8kWNF`(;ivJW-NVBBJ5)w~Z{t<0aAt3759g$f~O zIA_${JBwDi#x2o4^V)dg_$uao8~T%&0Hq)x$1skkqX7MhQEib6K&I)>Saq_m4iG86GH}B21KVvnA+KRqXa2d5GFk4`a#>!w>eJ z+aNIIPycP7H7|9&wW;O#y>}^MC@a<)^O%Z-b!Xe%5Tjj)wkYV-^ zP(=geYlP5cE;#$1>*8qnIdY{A@XE^`@G4~y3RZ_;)dXT#Duz5m;2EA*gcyJGM%fHx zBMf?J_*nmPLL9W}3;`G7!a6J)@F`)RGk;U>O%409rb|zOzbrvm5GoZm9237`)yK6Q zvf|pXkc&kPUjj0|qKVu%hU&YM&XSt7#07A76`<>SXGdXTgyIa=CMdCTzR0QFVfwzt zQ)I_=i(0^h+_*&)Czo)oymDcnuG58>HFdd0C<>QTR9i8}T`cq96^hBYjyCt~Wa0gz zaX$M$j(sF1BdcF?kYc_^Rml_FHujTU1%y;X%ox!6 zprr@Ia#%#K%PPT|{T8lhkT`XRv$3%*b9hzI z(QseF-Y?GeYLvHy6V#azP3NF1iUSERCT$(&8kD)VeT;xSxg25XpnS#F-Gd^=PXInA za{!H}^BJ(l|Lp162W%46i+2BdD$&r;4p&mATGWx(l`~5!uzzlBa0#TyUI<(4SU0;G zeN@ilgSWss#5|fIP#}w0+VL4m9*n-e{sb(;5*reHpLB^QFV<(>)qB;%5-E}>q_M0L zT)aitf8$nWH-W+ZI8A43py zQLPlbN$GTL3mxKt-1m_{zt+e}v6-!~jxs**I8kwh{Zyj#uNut zhy)*mb1(}Q1D#?SQk892;Wna*WJ|lq?3X`c-`L|yvB9|~6^U_-?~3i+7k8VOuGx;z zQO?&Zi}MYwjlbvDL88=IVngKb+w>z4#^grm zdO3RDR;)o^?oTeJRmN#U(Rp8bLstxx(q(u zgvb2cK@WI<2BK8}KJaZe;OQMO9|3g6YiwQ5Q{=|mUE9Cxnr4SFd+m>(fdma$xdWG@ zsA*{7G4rWg*9A4WZ`{FEWbLZ$|6yHuzI)Io;XvY-MuvAOTvb~JDwkIM&I|d)ut@B~ zHR~25_k|GA6;Af+R1ABFfcI52l$IJkoJjhfekTLoZ`;ihR|PTz$sPJ@HX<{1TcMzI zZT3J;hsEh;rq0%qbN#NmB$G`)vKWFS9F`0-&7DU6x+`C7lPnhMcikOMBb(+_4QWAG zM*P>B`)`w|Bpw_R$7`Jm*`3>mhxm43jfghys156in*b?ZY6Hu8M{4Cz30>LZBE3Eu z!JYz5LT*fiEu^x>{*_c;GPu^(D$L#I&j1@6ih zDB9Mwecv^&@2%v0LVO;t~~%` zClT`61Kus$hYz~R*dQy-1GYWP$87e~%{>GjJrHBN6%_awlpOAj;WheF2UWk+~P{;{KR_(_4Ozgs_4PlS8q4X6fq)Z)9H zyMg4r^{o5b5<4+|SKe60!!O8cwq4;Tg=C$2;70fD3z3)LzlNwmM~haA+Ovn17Dur8 zk74pK8bqFg7d?(oN2$=e(QV%R4sD)ejZtf%H1rg;wox=E#TJnQF^JSqlzR}!JA-fa ziCy0sR1z{)%qRI|^!Se}3%{B2y8DMq#!y_+t1}jl$BH@1OAJR=8eCqyX}HTU!FSrN zv=WUX-{M*kUwaMu3M<&*=@9-pd!3$kBT?FjVl<9#^D3gBl6@EZDkridQlr6J(%YKi z*x%0&Fzmbn0t&H>Cnt6Q7~HA(@ph}*3|Fss?8bYNuePoZ(7pk=$$+tSk`D+(0G{cb z)}VK{JZEd1&ZptzylD*6*#YuKt(+Q|^5e|gpurU=GbDQ(I$Sn}F;Ok;-2_`XkR*w7 zzF`I8DktjdS?ZZPQ5J^$O)U2}V&XVGBvv)YED8ell?9KT1J>~ija$2AiRmh-QUn%_ z9OYqg4iws>JM1-!FJwO|9Gey?QdFFNeQbF%U3G)`hq(a;?bI3z9Y

47G$n0VQ`rIMLw{`g@zsc)6@E9` zPPxmxgH~>NkGG2pRTtS|jfETUP`U*Q($eKlT%FBosPO6GFI+PDYWl;X<-O>l`_QJS zPb;l^(?ti2`}e$jkKcQrKDDR-!XXz|PqGtB-c`)tvJ>y>+lu9Qew)$~2&@6tVlFi= z;nC)+pxSdbxY)(8>}=su^bdf7!PzOVQ0ayn*yVTgbush$louEO?j;U&%;p_w;WEMMh z#`n2^v@v@kNCYNR=6$tlilTssO(A|^^9Cag?GN2)(Vajwh)e9PH`9Hi`-9{8>?0hz z54|}jBQMC9OyxAR=pJ`O`+RMXG@dpA>+2Rydx)>f>99$Sg;TJ~^s+Fd1R+4D5JG520 zo}tS(U(84KfYMuu0}H@s>Bhw_<(%K?`!Dg5M349~y|e8|NVh>bBJtu%^#i;s(0<5P zXm1}9k0j5fkVB8FyE_Q@lhf1e`*R}k zz)Ej9gbSVkDm8Z2IjYZf=(=_2z(mai6l4N^0cY>0@IpGkLU2%3*Hg$irg`J1%LDD{ zy%Dmg&lj@I4Z+#Y_I1{GCq#+{jMX)#{3DP9`ey~W(&!75>KkB$WzPf4_z17D7#D}z zYTDQSH2m_#B-*4UabH2HElM5)Xe@hy$hvEQW`TISDHFK_Di3J~o|9CBO{9z9DW2%Vu_|+ZmE6$`J?cgC*uMlI_k8Z`3Kb~Wxf-X z0=$6@7@HvJ@FM@?BMN&<^7Nf)F->`vcoR zAVLd@q)W_l6;9m1(8oWQM^@na+G36%;jdS7ACjehG|UvVIq=}`&?7-^I=@xxp&!H8 zWrj}Nx+Ny~ZD?p|r8<+@Ai(wI5(~06v=>jh#pg}(IXXIezP}0OgpnELT~4%Zl+Jtt zXqN54C>)F1ytkbI^A>{{w>2YD$C^EWp9dNyg8|m`-phcGmkyRNdrr zq>>k)=pq?bF--o+a0bB$WvY=;w~pb@4wi(NjEtT8NPMhJbnTU^5h ze&oj&uMJG>Ei%sS9D7kKBmUZp|0qZ@|CgY)g9A<_1)?n8Woy=-HH*B zC>Xy)jKC^Ytug^~_C?tTCx75YPX=1`-n?2q+^uo=ZEU1YvrfW|oI%8hf6WX9vMGRQ z8mWzYLGL@n-j{inijz!0od#?p@6RkOOZIKVq{+M*YN=dk)}5qwu+?@F1Av*-^Yw}A z`Y{uje+AzMv4Mdtoqf{xg0nMqou^?kKw+azu5EI0t2IQ{nxPGTPI(5bXGcFOZZ8LQ zPbR$k_5JR>)TsK%tj5ktXe^`T9BNfbVsTBC7h2jg^&Xe0T?>Z>kge`aS5U!>0hWZ1 zKv@63w2j`k+q$Ey(5Xl3UeU$dw&1j@==9YmD2dr!SpmaEAZQUFWq^^3?EQ+X&foW6 zi9JxvkT7g&M&4)JUC1o|w1x_&m)7b)Jq7BkT~=G9`SNm%9L;nnk$*ysrCn6-hw!~L z$sPs!@R@mZrXOw0#-|c_|4z9Fy;5bA@05Nlxc4!uck3D~a&VT_mi2b&%NrvxH@%lAo5NiZv6WG(mOtySbI*3O8)=UZ@4&bta3V(6?9WX1#Uxs zl%$C{Y^#eX4%^d}zU_0mj<7JypO|Rzo3GGf(ehmUO4UM^6Y=W_$aXQi$ikb7H$Z-- z6D>>y6K>294$=pln`Gu89v&Y1wpGrdS_c{?Dk#+jl+Daw{t*b&3^9Tf&Me_JbOe$G zi;eTPAq zPpipG{DHUKeNK|8JKg~NxsPe4QLTUXGRqTler~@8Z!9;844KqOtJ1~Tevd?1lc^%{tKrRrp(Y_x zyK1K(G$T7FluAY#?O4oTg=g5;!=yl&-sCRHew^lVk^0kI0E(i@4nemR|^~943nl# z(LyPs*fB-=6HHjQT!@kQ zVpG)^#ycZh+!+yQSj%)>L2rf;{-*X9LFrzwZ82@Kgxs7yP`U>HkGO7a1aAnE$)V*S~X%W?8gE<%>9J)Mw;D1-@?4GT_wEx_$Zv;Nt@ zrk+DiZ_Tl-g1MljVOjY~Gm!gg&ga}z=nBw1nl{K9yQ<*;PjaQTgf0?672Rstu02BX zlatCh%ozBa$%cXoD=IK)RK%FoaWm z_EoKCg%UD<=iLm)84>U~c)!;~a1o<6*v!4zH|81CoL1W* zRuU7hf?XWb>L2JcG;m-61{^ki*Mdhpo}IM&$P8xFKbPYW+WmI`mNoHMDyINAYf(qj zZLAu1)m&JlzddyRIKI%Jpr0ypYkF{4VuIJ_`A%T8qhQ(n)LkjkKiTba?lybbUQQ1; zc~6ylP=-}8P$x<1jiLJ?p?bdk-VY3zK9(I@4ZeKYsUFlDvTWMvJntzf|McW9q34qt z#g}$YnEk1|iVxqKf3F123b|O?N@l|+vla5omY;FA5l|$mOxM^}T{K3dm z+n(u+6zlI$IS}nYQeVx%rL-;RVX0Y8{le5WjsYHI{ED&gwZ@`p`Qqu;?%$5_*B#%_ zvTmAB6egZce@v~X4o-s=>LM10qzJRR?L#@g;($avIpVn1WAfy+l-0{^U_6rm)H3YO7{x6p@?wy8DMzfr3 zhK<0_q}}84YTaoc{Xpc`W8zo|asTJfpNrS~x}WXK-~9b2?YVa@n?BCDoUmm~i;C{;@@!6rc2|WPkUcO*UY^Cz@6y?cLQ~2{- zB%YGd@|zlB#w-S*^Bw>qE#1$*%M-bSxBpU3m%pWa2>IeWW+&Wiwqyg)}C6fL%$4Wcwsyq1dmS^B#`=7_^}hBfw^(Q{mg&)MU)#^#c|Py`w;q|U!T>rFI3SDrWq7dDW0Tmh*Tj!?Ck>n@ z)@#wAdo?n9(2%U1bg3)1l-d_2x`iZ|T1fXe$l@=jr3HK;KxE^fv+xkEMRQzOsBcFt zA!DI?IR9dG%d~PgNkqk6$lt}I0r=|JIGfDSs_<^^!C;(t{drQKyi5hB0g9+3PSH` z27IE05cWcUK|~nU{U61q6_6ZSbd=|F)?#EDE2aq1tQX{cC4*(n%$Ut<@#>{6+89iS z;3aBuf;j>VJQVsN|D_=Gv+>>frAkqa{;xGDH=)$K;?*qXW_S->u`&2(AUL&s^_)^b8R;-rd;?FtC!Pa0$yeQU z>dr)qJHnGbharKw+Qk+~moku%89e$dns7-v`b4B*tf;cc)qED)!*awgvB;fl@#B-? z)x{@>oDGQ>A3mR%n~@cKr4&(0twggVf=_6n&H6S*@2sNynsg6gkNxmRcaATdDQ-%rCnG|)puy+ZO{MKiHKjyaETh7%>?U1FU7(cBtI^&LQnN zknwpX&F}Gjnl?}DaJzo^vzE#(g;_@@6j@b*Rn|J8Q$7_N_+>Mpnjeimw8s zMok0X5>w^ZkrruA0Z6PeKvayqO&_sHK&e%O?bm^>Zuj%#v-ieKSg0r&$48X)8_!v6 z@i=LnxLm0;a`TqF5UA?+-xlNMpqpxjVIHPi_Li}$mU%lH7HBh+#fE0t#5P)fmVq;_ z$wlW418nr!!@n4;)1!8ssjUvC6KAD;I%C(pMhm0u=+We07XXr_%`LHe8wn-0 z7IKF=s)WJr0@g{cv5|y(1xLtmmbEI<9`#xj*-i(0fxr|kyc`#FDWb$|}XR^GRjc319keDWta zs8WKCI@~?;Q8|R}f13rL_O|{nCyU>wJaYzb#%=Xxnyg!u+dkYSuAP*yO1iw2`TXH{ z+JJq46;YqdT72K*HPGpWg62RXKMKl}R@!;Rnvrl0Xwdu))2eSqgG2-KR5}O~hb{zD z6H&XS6h`x z9~v2@q=ur7~BnIv{LY?FgY#s8tn*ue-_#+ShoBLNCqW)dCw?uRVEV#q|2_tVHdTP9q6vpf11Kv!8JpT8q9vIj>*f{B z3R!$()*Y~%a#4~% zXU!L7))QJZ>(`hKRMQu1Ko*OfBxGx=sbpQ$&<7CT@VxRIhRvSub*c4mEJ)qG3gxEr zGKWtRIFb7xSveJyt^S$vU;^gbdgy-`-PJQSRejz znX>!Bv`|6Hy>~l%tNoaNptu1(uhkL3x4jY6Sa1Afmb=xqN6>;UwS7f1^DLP~Aac>I~N#1`J zn6&HG1y0z`T!#Z24}sRsRAIPMd^36{LnDzp&`=RLL9cqg8T^)D= zYe%Z!!K5NvkF!>;hB9qy>c8pG6mBYsB)&SsQvS93Qzd?!G3(}_X^aFkR0X_U>vRRY z$M!7FxxDrqM6tYOs))Q=MAEiQLZkYjpRf1st$sBEwBcbg_uoo?;{)3%9*$K1)|Q$! zk@A9iY@j4sL3;S~&6lZA$IpS7xzvQ9i6m?o}J62k2r2L(jK!|!DZPK?BeY`>QQHOxp)4aTYKX9?Oix8;H@13*(oQQjrUxJ z%iS@kJ>kub#0_Ei(S&dfOoXG`a`a~VG2k?Es29YBFWUBHvA{K}(6(!2v;rki)xZ0w zRI z9qxctHF?m~YwVD8pP9ZDsW3Ka{prS~sTuDEzW&IjR5Ct6Jbi_A)3VOJVxLiTZ z!4YHlk_#q^LwoZy2UZ98cG%^ZrYi;aLSNSr9MUXCfV5e<$l!Tfp`&a;NZJ?8k4xxJ ztG}H5oJPprF5rP+lsvyXf~Y}C$Xuma41Rj0O|zSK1lG8F14i6`X{~0(+F5^nptL1` z6$Mb{Yb;1B!_Ow zj7+})8e=xQZS{<<@oX1RGcGfZF0WSn_7FV+X1Qn?(E)#!fJueR;b+^r@^w~8Z{C{9?!M>5J|yFaW-DSWwOOw2iY@Ocb^mj7`{JW7&Tv5E{YoES;#0D?F7RHy z!Gw$aUqAgn^L{0x*X;mNkJlybiamfZo44q1c3T;xXf8nW+!PFDAQ4gV#02e`{tMIZ zeLLyhA1RVaDE;1s&u+Y=SN$n{p39Bi*SZrB!Voj2Zudn!-G`Zfefwj$2t*u@0wloC zE*me8cF1$Rak~ZhFq~UKDOM~&?i&m!3!2-ynv~EVeq^kE{B}VY0&V~NDM!tgAo&DS<_V!8+G3Ox* z(&N~7)hk#TNOJ`X8&iMjGm_$E(Pv`R_nU+iTnLR7Zr(hQUe6OE3wl0a*fI6Kzizky zpCDM|IeJzG9ic$s9*dvQTIWDWsLt8_iLS@DF=e+YH{dzoB{JuoYl)q&o`nY$UqWlK z(Cz_EBF}#PyA(_WWe(WV;4c8AuWBN{jIs2ZH|Sopy)SOCe`ZG5H~YHk`XA4ktF<3^ z_1ggFE1L?J`ESoX{x&S4~Hk5&|^jsDzptTB-v{tgsF5t^;JP2 zPzfQy#+ox-zjiqcADncff5Vtk$wbz((qqEAbV*&SjmT@jh)IJ)7(4F!DOZ`dV1o*& z5njfWsCF|t*iNA4kJ_MM8Q6neV3|`?Yb8ejeU!S|O5z3iO;6ZCw0N@{;ddpYQ!C~7 zT+t*PUOT1K#Dm%U8B;<-5mT6pe9uo1)CnyOlLlKC6jOs<`X5n~s@dp2U`w(YF{c9D zP=CJ|l&o8K_gA&AR?IiEnRdHls*!ivI*YZ~5(QbBHx-?V{HF>bivGz6qZYmTI%G+K3E{V~B6dy(NpBB-6GFUK^g-5t8n}^@a;+9Y{iW zre*tG^X|NJ|I=AxJ5#;QUtk3J9WTB>W(%7$uFBB1?K`Ct$^KZJG-Bfyo@)s7%p?h zst;v^67=?d+I`eX)8@4Q2pvDBcWxvQ)k&w8dV18*dGP)|bv=JKjBAroNIgSs*L$+e zj@{>r01+|n6PYLk=1|i5B0J~Y;+hlhLVR1EG= z?uP$v+RNAZ1#~~W;N+($XFDs+<|oTb(XN(?@hNDfhS;9(SVk9AGGq)X7=Y7|BjI8TMlE>~_5F zc=i34FXUzqAy{lD7euqPfUosGOEWzQVWKF<0{GYxC?d<>;68=v&Cg#k`_i zO=|{5ah3&6R0o8vion9^e7B#iDcc$h>d24gP1p-|=YhE2x|&EjOHG>ARF7Xz&J1lm z$d3$tK7P&VUo9WgRBdDt3_yU<8jJQ!INM;c6S+y3O4(W<^ zl_SkM|3lMRutnKMYnw(bv(OG@g#(Z+DPsy(c%f+-NIZZ+TSz7gfj>J zKBOd>o@qvieab3m$*M`2m})^|8n*|_fr{Qw<|W{kiS4WFA~CGmsv9N_7v&q*XadB+ z=*C8_dN9jRQdt-~1qaYm3>Q4{J4IAJ^pfpHv|MH;I@)}?#!be=g*q}z7qWaCXsMLf zmC&09kXz^dA;_Z3fbsj%8(?U19KHq{u>)N%8F$|QBPiKPx7Q?Ny6d0tqv&Dy*Ol`M z8|78MyclkiZp|FY@00m%ccp=jBb{Os1g7y5UxnkS#ca=!Y?b&=i*6^#pJ@NV$o8F2Nkxmf5Odzl>XeDQ(_U;~&I_s^a>vFsU9puoMg}h8z*~eN!^S8h zm^1?=eyc0OJHYhs1D(XL-?%3=;B1U1_tSMmVCZ%~@i@E3@4Oqcj~^A_6WSycevw?K zxhc(aA<6qi0c$S^)(4<3;9b+*-EBC210x`(Hu>axQcpZm(R$t4SXz&g*Wt&HkZ-_G z%r{|Y;q3ePS?irk7iDMiuI=jOxNG@{4HOndw?ghf+RR;7pY|qj7ow* z9uXg)yw~dfx*lgTPRHkYs-q9QKrK)GDz)j%egH@%I~lLRAGWSq0>FCI z+SBnGLdhrjq!F(^Iu$t6{5&Hh#7))F)Fz@9?d==`#L4|Lc=v{q!r7_Cv?gQPO~=?@ zmSO?cUR*~|C@5vqQVoT3pq_Q$i>Gs)=m@QvX#p}LgY(&M2Dzgs2N6^c!I4_THIfl! zn}%G{MyW~+zE9kpIG(Aj6Vz1u8K8$VGQ|Gza1?G3f_3U%9!}T{AJ%tt#jvkq$6)TNC(bssB-dh7CAg~ zm%NgoH}Tni2ngsZ;C{q)H_A5EX()%(J4uo|WnHSP7}F(iiX5oaAs!0@QBs8S)vIk; z$?OlOiHsHux|He&nD3+nctUV65yj15c6QnEL=P*js%PG}i*Yt|F9&UJ(BdrWR{Xyz zSf@${vuVz6WcHV^OQ_s+osmSSTasf~m_13Y@8_|q&t}N9P$afgCj6xcuRmnOkt?Wp zgCS{TQ4NqS=D!;4KOhI$fwpu@v+@T%uBPsMvy5Zy)IXc`F{TeH$2u zJRA6S3Q2^cK)ZA-?)4rFX7ga5UkK~ZPrYGZj^L)c3Fi++1-| z|DB{;d*M4VA^CEr3VgJIGSkBI=QeyS?4pS1BgidtPBlx@cIh~{)H%jlUvs)jqSQti zAz0vKxv0A#Q!%Zia0_-_Hi=x%s9$-nhfZ%Q25Cbctp0f#XJ_CM7vU(?GoQ{7SJ2f1 zR8#i@JF;`!9ulG{g_LTchorti6Sn}gYuA1BfsGTFP!9L*Ntagg;N6bT@2_q8Re+`k zD8t6_u&J(md)_9$ckn=la&|!!O!g)a!M1T3k{DMNN%pf1bNbSTY3Yv#WqDa%nRS=5 zqtDRT73Z8RuGBK>QlOAGS5&+5#kCz@w#2LCra3?^ySg0uV>#=o+-8*;7j7gfp?A{A zOo~Lhz`~NJM!m0r%M=U8@moF3ut$GA!vKN#&P zA@rQYF0U_0i06J30d{W1`+BiON@HyE8 zb`UjR4S=iK`)|ms>7R=s*n7uFJYGz4T29urDbIRIxwImBu(AktiPG4B2}=u}Pm<;^ zpJK~to)|}c)~s)fzlkmjlTpXD)5eWBQdHjb@<-00*;fqa;Y1&{Bh+Uesn*Pvr1Jne z6=weoW76+jq+iPuRl0v_V@`36io!2#jenj~=$QyqwcV8Ziao;H;j$i7wNKRYk~N|`uu9Dy6GHl;-8 zL4fM>T(glePoNS>3H3FMj6`7hC+S30+Q@(Z!sR!{ms ziF_~>lGRyj4Lc!mURf_=%Ucm)EWu=HdU43_4tr!&(ILi2b>WU zgbc{F{BB{CS|{3A*jVl-L)4HtB9{o-tPs$(#Y7hHNLV;>19p&JC+$#RH6VsqvLXUl zY~JSyfn{v$PW6qV;{Nc%Z*O7$osaE1?viHjG4<)wip=;jog5q_1XFSH&8a(COH5UC z4z!q)-Lc_>gzhJ)il2am^q>z<=r_?_FUrkqy@=6aa}H(_Mz4tLzD{AZj<@qp-}~Uh zH{>$+YPRFpH=CLgMm)tPzxeSxNcpG-(B?Ys;t5^u*jPVy65i#!*dpZJFKc1he+fLF zXFLDi)Y9$R8t1z<>`5#E6bCb-ph@LJ(e5#V!NxKYlXl+1Ciy=exrKe#PCOk{A{fIS zowtTE{j8QPes6^Yoss0@D^mz<9bQ6MI`1RWXKBjl*d)hXzRCtf*xGC4zGxGFpch%@ z0$h^p#FT4(FM_LHKyD^QK@Ql?88v4V3=Wz;K2RLW4^;lsJz1E_(M9P4)!juY3*VtE zyS8~>MR42e&uBq`aGl+<697#E_1>m${fR{0Z-2?QVXHNumo$n3ag4q_c8_hwB@mv- zwjWggcwDx$i?UmQ38u%e`_ra>wsNypr)S^%r>%>q_dhdvEdv(Z86zLCk!~*5S(H*f zIbQ;U8}R8S4E_AiqB%4M@Ya48A$~6_Cp^4DI~Ra=u9gXzGg9v1#XYOv_e$WWqwmdt zxy9%2tx_fC64F{s$w1cUQ$TuKm4kss;$-Kfg>Rot-$71B9R!G&eC8q!Pp8OH@`rvPTrO2ib8<-lW&C z(ZI8|*eX~6@y0CoUJ5_H zm0|CniXuj1HP`gg9N+zy^;FIh*l4w=@;KW>%HMc?Qacv({>eq-ST}`HO}?tLFH4T( z>iJY;MVe}5G}`gFlB}!uI{DhEW__bK6j)7W1CAiM3Sh;MX~#W#)14TPi!Kc12 zC#?aS!1Kp3&MS5HBZ3jsnIRN7jd7EmPMH`uebt;0LFa>F{kus|U>kM^&&Ix#Z8n$H zvfMADK&U=3ZvEd!mcWOUo2K`F91oU7K`NKGgXU>?KSydF)bO62PEAW5x2n8Y;FGKq z9-*Ev9`|b`ci0(yrYH)MxZx+MkGN%3O?DB#Ai?EJ>oYgVI}n9%d8eDrXa_9`tGizUB4yH~6?CI4j`Ic4ID` z9LOt(Zk&`6N%$D|GNv4(+Zfie8%G^+p-|T>{t_ssJ2)Z&e3!5)m-}W}E4*Hv0frrU zLz*b!L7p8d0k-Z#UfXyL{w*o0G3RcuZi~>$Ni-9L4o;0&)uN0ByYgFqE4?L`n5bau zi3B3+DH8yurb=hL%tz}=-nGO4dPT}mI;Ra(Uv4T#Iy1y_48v8hFy#JPPBan3rYl(h z;XcpyA}bPrp+7AF$y!%nPED9blwPiBZ>Xc-?h|aRMwWIWm4&hAXsB!^O1E~6CD`H1 zh1cYu91%&x?|8>P_-Fg9LC=0D&BZFgh)=POmy|2|hv%ODt>BfOm>mbmKP0^&n-DkL zb_?k0ZrHp-dl0ZPn81G={G3UOFm+2hQd}b-J5Qa!pKGr-A1t@iQ&Cu7@MA=`(Fpq$ z*}Pnobs#eH*@D%_es+2Cal{6n0Xya&7ceN*@u~fF^EDkIwZL~Zy{&U<%Iw^Lf5MS} zs;uqkT*I$J^cKT#ttC2=hSeY;Da^##4HBVmG|StO} z9w%RR-n>Rjz&aNs07K5==_CucwFrs~g$$-SK2KzK=GgK5{sAyb)yqeJew^sD*Y_=` ze)#dIGPmQzMZiWT981KOfQ)>15#yENABQ11(V3J5ZqtnV)1pA$;RLn%6`dgW? z-iMDe^VtfTQ7SUkodCWHBZ8cq zY8?7{;Z4s_3dYW*i}EA|62e~d+0>oiw{)X%>pa{bH!*pvvI9G%jj+Mm z)@wYgp*t3?P*al?H0jNUjNw9b{s-Q7#aX5wN^#cT*U}-LWOZwksU`Ih98vaU;a#8z z2%^Sg;1Wp@s%vEC?bT0%TDl&%Tva6BP$lzk26REy*C42WtD4UA38BU>zCNT9!#4#r zSV=d+248qt)3O;UsViJDkUW+z;xAgdn=ecn2r9R0nNr8#Kt|M(I1s5RM-Ze}qhmA-S+C{8MoRwk$QqXzGQe?u{s08w37=wTIANws`50I`K0>k1 znY2EX_bn@S&225FJ3pU`=psK-F5#f+?}=I8V_{~R&bzZ*5&=saGr<9is`>#G3zty| z?{CY1VQGG~JISNZ7sW14&>TchtST=t84Syi|Al0t!a}(F1ZPWA?5fIT->g08Pmk>U zwiuF7{PW-SpB)N#0V^!{(_s=DrFupR#)j8|sulhRc$);jXLu4wQUv66K>Ci(-yQ7> zWuxuoqWi#&Tw36}aB&EH4W1WN-! zWnKJHd%-$UbK#O4EePIH-8neDlSJZhLpXlLmH{md=e3TQd}|KMy=W)GQllcS$Z9`Z zT%MNdD|(ReBnCWDov42!vzs1Ss7QFAN1Th_FZ&q>Zc}BN5UnAM4%76+9w*M2(JbHN z!v-l7JG+?CBNZzOIA(;h>2bsu*cU|f;6aJ*W&HnLP{6x2iK9D#*)q2!Z<0I*Q&LM+ z!z`sqQf_FJ{MDJh1o({xmumo*|9QP0YeYNLBN!{hKe8(}c27AqkAk8$`Nj0+<(i|= zC&G*62pY2oFg|G z=$<$RUQ2aNF8s8Oy$Zv|#FnEDkn7$E>0RPFgj2{zUN^EF!^riKhjUzL5*GJVcByqg zwf6etY~w_=3eq+^cG|b8JKfUd3V|sy$%vcD$d9?(-;%7Uxx4kXs}hu+2#oWGn>#9H zeaV@GnBih1@+icYZ+N($&dJg^8(Xhp73PT^CxBNP^^jE1orJqESKp)*)gy#6P`%}? zPP8P1KUotc{4I|Lv>$n`2gYU*1Vq-6`0%t}- zWeNPjpMG*QWtn)V2q8QL)0gZ=G$trSv?S$`FIg^DW%h=aOqP|QUGT*kM&q{HEnnxz z=EQ^}Y)xvCS5CP230cekydpzz#m^7!b$$gy5^N8|8dok1{Uw6bc<|eBM-z^xMZB$J zKrX=d?iJQhhyNT;S`&K59~3CQ`Ruj*0XmgNNc7oMo z8jdgqMzU!%=#V2#eG6?ludRp~(>13y4HPnLiBYl3x1sZvqHgNSCyz*lAz82)OBlrk zdXsiw>Ol$nVPBVd&UNd{v18)Fn#6Bqe_0S!7BIFgi9YCud(@p}EN}ZZ7`bQZ_@gt^ zIX{27N{d)27X4-c-k)L!$R7yP!#E2WKIX-Du>Rb=jHyiMDKuNpy*7Fw6(E#!V7~7= zD6KsMwU$vXgVZ;@!^#qcD&}p}wF;lG0LhmW22Ub`!_>8xy0@=(RHC|%Alff?iAF#b z>5|i0GahPN=jgWN+s^PZK2y9E>xvzx5HaM^W6Iu5l&}?Jiq-AbguI;B(1$^9xBJmL zn8B3xdpcU(@x#KxHbTK%Hy=eFPP#z|%|yEuLLPi@}?t zuMJ~L%$PXeC(L^&OYX14rsffP2)m@*)u_c(+*tHdN4B5{c{HL8|74Q+yn~NV@J$4K z!azRz5hd1)Z`S*A3SEIVq5Gfv^&v5U-s>9Z71Kc$>gPB#BrWvTH|vq(ymK^hqrR+s zdtR}11D=~N1KZm)MJnsAs`8mP-T;!{_VWCIw4bXMyp{6xLqyPf<*{$WWx<$LQu2r(46*{R0WTxd(4+h<(Iy_Jz`3qM_eumhC~gv_54VaqK2K@Te^aVk&JYO z{ceGA%y~A$1g}%)oG*cyW*YxxbYo()lcb@4HKOS`684ygI?Vql^(-hC&$uu%;(rYc zTn7JyPzOs0KHvl_6(iqqRGk;Sl6%Tx@p}uzmYCjOyao$}uJ2`jeweW}fzMQ5jpzJJ zK~0?QI=8ISb=v}e_AvFw79kr-oE@pOq~i}QNGd18i8d@I{pXA{RXY&?$;%vlb#gYo znOSJ31K#4~$du3kAwKp$7#@162%cy`60J&jY{QS;Rx7pic&!uD?Gb;~npO=Llof|eE_v7tm92!>q(GSSJ5q|sE z)@-ajC*XN0!tjuG``4Ht;_zY&pcLm1T-OI6KFs53qI^$->&jBO*uM%qd3Wer59 zxZZW2?~L)5&tevF1;7@aU0pv*#*0CUq5?qoIOK96xlHn9wVT_3E#l(DkHz08&P%(z zdQDEwD@y2f9sNJmk~XDv*ku+GVtQ4TWeRjR5g1Z{GM!sMs{ixYTu9l(Fe;Zd1PHDp z@WXB-!GKpE7~ucI5B@VYY zs;ORAJz#l}I$l(-*c%C-*lUT|vmJ0@&z&~!BIfa)iN*~updVd zt6u#?rKe_2ttRw@SI?=q#kxZL9J_o6Uf60 zxXP{O)o_ znb+&l2&ryDN%`)PP*|E+T;nTfKn0SZ($}aM6K>7EG4J-}#s$&xZ&oL@T%+zTO*ewXHsh1-mBeLTc-<=oiwI&pS) z=rU%5pYFbD16Zn;Ait+%zm2C)*mqk`#ZBYHRdyJ?SLVIKFBigfi?%6>#omuYp8!|L zaBa_qgW0SX&+63we&N=J|5*Ll^?uFJSRTWlQVM-23na=1{^?ppQk=w?JMDsy^#OrS zN>m_QI*&TzBr&h#@Q>jFaXvckYhFvxNpt5-N+YqTH1-e=rAJIA_Ik~Ln*T|@3IBW^ z#EkDV!i1^uZVP4u?sv|5Q7=poUBSMgLNwaPm4sI*ay1z0*&UQIaz2>KyV6-%6VKPf zCc;U$C73x$C!#$R83-qGzgKEj8hOwUu0k3c+?#q}mT7^NUhFc$wR5ysb(UNGNyXCE zc4DsUS;?ck!aVx!PWLtOHk!aim`Au%3{fwH#}gadEw)tFG{wT@9E46X@z#~e5Cpq$=c{gnK&kSyc4da7K&Kf7 z;;(k7aFhEW8SP}bP1nZbT5ngV z%}vsVZ$Tq8dk5UN?zD+68l&fDKEuo>*w{8D+{81lqfD#wdZ=YsP2>7gsaZN4YIb$( z1#&>+d|%T;4z6O-uVSvugUT4p)i$DRny|L{e%pmho*HwMeGSP|5$P_n(Q3eqZmM@z z*lneM(>A4^z!$BNfo_7Z0#mcTCc4C_&E?t^+Wfi9X~VVr*>1Udxq;4R_YhQFpP9SY zq>-w zShRvjvSra$waj$hHC))WY1z@$HT))0$A)&F!N&r4O6Jmbr6xWtU#W|NSq8TibV=Bv zg@l#H6CJ_W*L>fH%6z(hna&QDrZ?i9s_3*GSXPL`=owPR7#nRAVQ!jcrSSOigN))U zRevQ$W)N0LcKmH-^fwuv|YQchEOc49x>mI-radE(@c;H@Z z&67^CDc_rZ@VQD~@8U86SxM<6;Gnv(Df~XF?~l~?x-z&@jOdmHS2FBJ7VPX7mCFBt6P(L=u}Xj z$q5<$2NZ#)-N^mKIE88F619!@%Prxujs?(!H4i@sXxu%d=)Xs^#io!%m9)WLf@QwL zHhu0)SuNtwQdzV_9?O^U{_{yu;V7Bn&h+QbJi*p1Oz$!JZM1WYTa$@uGLYWO!3WVw zOi2bM)fnT7_A||XDtx4`cLE9!_B!IPgY&DRy-3~1vlWR1??LB6_x0%1_v$}*rBJJz z5#A0!AloQ5Q}_@s;GIOuMFC>=9|!^dm>mq zi&nV)_=x#3A^d`;lnk6?g&ri;*9Xjz z5RCS4lTUPdhelEH7%^#NY3D``t|wgw+oZMMyiak*D&Kg|>d;>B7L_f0Z|s?s9@*%A z3+N)G^6*Wpy}BFs+?{KBkUQ^NJLRqBxEb#bEt|J2_0MwIv1P_N3%URZ@>c_8pV2Ut(tLj4}0AM>|= zKPC_jf+-a0ACOVDoFI(^!W|>3bS5NrH;(OGyOE?=-K| zieT5Tng_t?w-ucK=^@P3K72a#ADMfoxA@nP{WXCebommX@2JDQKdFa3(Xklt??k$^{DGIbDy76@LC% z_D+8ykI6DEsf9g=t)wi%;N^ZED3Y*H-+t#U3szt&8hD5)V_+-VTK{9-qN$>UpZVjD z6vH@wA*(hlNHEcjsZcd57(h=ak>ce7)TZRcMupSI(&nqO^6NMMV@xPtj$ZOE)EZkc zm0n*d*ffn6tCd*?Hhh-S=>ijASbQGWj+%0@gZ>Z}fCHQ7AMr~a%SSvye8wKtro0dS zLoR_gNi776dshw=Tlel{);MdzLZf| zr45~YuiwMNOLt{W8*k_4Y`Q#9I{;G_h9!62^Y29R%DraIeuGmZiL6|9q$*nAeY|t< zKH2Whpn?;~3alAEK?tjuZ_gwB%lQ4eL`m$(OjO4_j7en(?Kc zVgvoI{-*Ij6D`PH)smX4(z9v%KSBKbYV#Z;dCj{mooS{pQN+8OCQMwoAPNm%EK%Fh z5gAfod-V~%MtF;Q_cUhcz^;&VQ4V%=UybqPS~e-2h!Mi~*RG)_<&;u+w+@t!GkQz} zAk~OC&Bp*HIY))_EDVMr((tY~hDDDq3cFU4bP`{#f+jXoY>rMl zV*diOxynz|&>k=Z%TA{BwcYZ^-ky{X#2=(cnORtXfOctwDH!Bq{VSsMsCPGU;dev5 zp1j7JZ)q0<6&yg?X0Kp?PdYM}&SqbB0z4BG#2y=o;P0jf-QG3}qpgWAGyV+hZt;T$ zvpp(5ZaFjfRW%p`wTJt&2i+I0f*vX+0q$ILtq ztQI&|y@2&TFJN7Z82*DJf4tXu)QvsdI!DAJmpHA(R`Mzby#*c2@d|gMNBoDYE6sql zUOtFpECeVAGOt@?bz(vOoZtIC=+CKsC(XSxPb~BVnhkB23d#8~+6O=XUQX_psdz`` z-uzk3n6xA0nHT%!QlQq%ph(=e(xu|9?Ky7o*_2_2k2jKfxRjNfeP8pOT0b39DDaM| zE@K!j%b_bI3j0A|L$0kT!VAF|aM{hrR${a;Td}5*N_Ju{TrNKQXXAcsAZ%Ixco3<@Cd>C$9Tu`ZdB z`5ApG?^OlVa>m0WE!fjlztLzjE{#vS_S6xWRkEpO$mYd^%m$fK|Ki2OV9|5qwTz=J ze%S!*4*<9%N_(>t)^^y8tPm>Z(ER^K zL}8YAZH+2JYf%5=17|R(Of|fS=6n0Y^}Wvx*)kEwSnP_j2J2t$2g~r<3ozv1QUlBJz$zRiQ2nR$Bv>-?{iP)Kmyi&A_UOG!_=c3ZK-LD$RVHgI&20 zEo)fJw15*o!7Aax*R1S0l6;$%@#%VQNTE4bdG&A}1X_Z$eCU}A*%@Qai|3%=h0OCu zZg#w`>1hSM<`WXiyTGrg`1p=k-r`MJUe`ToxM~0U29PIl+%m5HYDPX}V`nGrAl(LV zq1uYe+{yD** zlMaJIK)|&1$o=A;6QD96X8kk8vH$g-)h!yPW6~+(`=1akd~l15Z+M5Xw(}%=i61rR zTZHU!0*JK-An4vNhxl-~{hwy7sm310m%Rz0&8HhmwRtnmKvJA!Zer~UoF#MZ)Ui3)>MP)zI)_u11x1{q6dbcj`_<3PkQ zGZDn3n|Uuxw%f=OWd}*9{i|SC>NDmEZ7U0S!b%wmQ5g6z7Zzz(-TgdHC@ldu4!%WG%csV)sQ;Bj31q!v9 z8L}efCIMdFT&BY5hyMP4Dn*UbtXKN(azTNF&&lf@wssP^&wwb#e8x&FU6S4s5!@G1 zJHP;#rB&lTGWe!$617Lk(bLY*n`szV$fIp&$`W^ui|(8WsL4$ol62g`vKNls{(0So zwPZ~;zQbJNz{CbDV7I2>Hz>qCpIQWR+a^Ugkf!GhYb z1pflY0fw-Yi9~^RH^8d1KU=<~3k(NF9u8ek{}W9+a!Zduh=FovsEEYUDSK`I+EN`? znOlGlNg$lvKAL31+7qcMW__I40(V^ZUVSxd5vD%(Hdw!NOGdGibTRL5;i{%)hd(2e$PdEh5>sgfLhqUaw4`S}0! z!amJpvkp($&egYum@iLr5m>aUqsTCx&b?MCE>I!Xk1&p}|8y$k)Qxw~=aK?_AU}wB z5E&&STDG`2;)iSQtS+S!IYDF1yzeuM;S`FI!n^iznzapLTV~ff6`T`Ug8!8d<1+8| z$4~g(@iyX-cJV^(eJ@DcZh%>7)$1{C&jo4l8JC=oYSDhx3-F}}j6?$4+CR{}z1NwE z7FJQF>^V$&^Em)cd!1Qig?8QRp7H!IWnc*%fX#rMWIiY0;Xf08IeC$V%c&5k$^H_7 zYZF|ccHTcaN6|ZuaY?M$4CnQDKo7oE)no$Czb{J47~W3J%~x-> zwtKodRWH^|J(X=n=X+q4PQK=SfoWm!37~r72UziS-_Fm3DK;@cnh5j)(O~wcp)A zXVm^WROhm-<7g33(Ac2`s}YnldFE*`CDmt|t<-D6OGaKprKKU-kg*aMO&iC#jYOh~ z|Gm$9-0tE62)zrU1fJ2mJ+zQg4=aT>e>@GNpHS%4RP`@m#h*q2^R((0(LK7Jcn_w% z_6IFWQdhuS4D|TYm$_5CSml++CKNs?-iG^@ke1D0QHTd<9x(tn{k|+ zX;Z{VZcC6^T5pd+IPSPgXlkM_wwph{A7h+5_#7ET-4+V;e?$_p0J$Ro`!~9LKUZum z)7!j(dfVR7fmX;GY}~X0R^G8x14B5+8Tm+gQXPIty?d_|clSNK^zVxYk@H)Jwx>TY zm!&65FW8EQIjq#R4MJIO9EB-{L3d2CZ#~l$h=*hJLvmlmRQOKZOufoC_!4w+zm7BW zQeW+_>AL@0d3^|@I{46Du0Bk1K)H7ePQ5cj!$2pbL;#u!s!EUiVmZa zBI=26*qe$>B?F7#$v zuLmPRfUD^D?_UKTHqhOc2?{YXLg(C6J?0q|jDQJcaWT{qi^h22d(DcQp$I?xXZ~Lz z*=;6k+5}l7qRzV=QUqZ4kgD{_YhDsdDi&xr%-*%<6KLXch!OIAbT3KHrGt#Zm=idi zRxQ=9Z5pgdzLskYxA5@sZJwUS0pnob31L24dD%X78!QE#iXr=p>Kpof2f=gFhrJAd z!Uw9;&?Z=fW@;30T8KDFV)bv9j@*E6J7nPK2n0OM=rm{5(6{Hqf?sP)3Z5(}SG~4( z_MY>J3-%_?g9I@Xn)iQRXXv1m7LMtjCetK7X&sl1_%khcizWyn0?rNaDgzUTKi?y5 zxHMbw9X_qfXZ)y{_WHXLj{304A4V0s>uFD%An4`fO}Q*|`fh+&w8<|)S`&JsS}>1_ ze(!J;ee<&eBJX@$L@AeFGM5I2Ddq-=+csze zpI1iaibV}ipI5wM5fXmVpj*%!vwr|UD|*#XO1*>n?y$QEP@?fA&$}B`>v8M;ZW8dj z4tcqaJpl@*Zn8A@Ju!H&2rpce??`NyLnu2Qk|N6)f6rPLvS#k=?`s%@)zpzO@BHKE z&$DVQ-8B^UbD?vXZL$=X^x}!#ihhc4A!VM#d9`j|Vv{i5zIeRANlKd#F*74hOg+m_ z)`y<&pr7&jU`)F@X#5;7?a}k_WU6Y=aF=t=HMWf${qGYl64lOhCRVPPNYNx%l*iGD zT4@wY)Xm0~a=&)9p7|;v>kt1og>yf?uSpYmaT47KNBQjh9KPo+?F#5?&h{AIAX*_? zCvkfcf2klY_hs5=X7~pP!KmPD>^G&b%qB!0#&0>wk>4)c@?ivs$cgQ%ehTV`FXttK z#PaxqGnxBcHXP)cbwDkaD+PxpM*Xr8sPs1eRgrI0G+RpEr`xaEu-}ScVO-NFkwL@X z?IkoG-Jx^}&fVnsmD39|+44$jjGwu5`K2rdEGXMYUjKc2gDRI-)T0vHTsqypX>2Zi zO}zJyE?PMlMFxU9+!|HvC=-z_J-l_(fK4_EH5Fd}2$!Z;0LNWCMZ|xI2*Vk-QO}(r z8EHRe-l`kok&%-JC-JbPetw5pe7a!x6mrqOkL(z6l-lBl^?2na(Amr`jDj%$-TLLDgEoujOstn{MiZ(B696C#nWh0BP%{ftX7sCgk zYIE&}*>`MryaRADq0r?us26kjYYjX4VO0!MD{0ca&WN5I4MNjD62Gn`QIY$8^%asx ze3nYx$jC2I2%9E8PBwAipp;+af4|QsM>{y1JNW)mma-U^fUE8GTPi@kB9&Spf?w8YI|avKXG-fvtbd(Y4VhZozNWCc_3~~f zj7HV6#RNr~a3KhJ`m+I1eIu!KvXqAbow-p{P4z0ug!OKV81z9JU|4FWXb)nceN3H>q6i~XdV}8V`>ob zl=9%^eN2X;P}(=xLcA>S1lzA`!zdKvcs~7i)^PKVDYx$6CPp=!<7)M0%8U3)8tJOX z@4Wu_kMxk^*~KcY!}wG~53UYKa+7?l)W?%Fq`QttIQ`6-_~y$q+6i#t^^CZ1&iydO zW>X`!N58750-qRFYx}a~-@yBj=y;-e49DF81Prodj0JC>2@IWjuR+nG>Kyl4g_SeuP}w>ZCj4p{XgvJm?{tG1V(E;s?4(Ani&2@!R~oEnjqRm`J~~i%ZwW z6e3rl-W{Y7@-5o$<>>|yFuoRY@4%9`^ayxSdwG8$yMgIjf#omoi_vJcc-#m)fGGsL z{|X!9i{|Ah1f!cpZ2)YyrVRkmSyp&l?&3;Ihq_k*fl4A>KT4t&WyifvZgmYz{W@R| z(<}f;OD_OP=TajwO^?9WbGtN(tIrXEfCYz%prTesjcbja_Z=Hdg(Uh>U~Et#52=rfQpCc5?4| zm|BAGT2=HR`ooTDn&5`E^-D{H7oHJ0a7kLOG-+A}hRg7;^Qc#*QkbLVsEPEBOSzDQ z9Gh$_;lk zbY%oNY%HwXtr_J#?a;iqQ3Nw9K3Ql2Z*d9}h}_17USr`*%2X49H}j^Xi}ur$YTF3w?ZjtftV@yDy4s%*fLXT~C6la%#uo&PVgB9r&L@J6A(LA4QkE@?Z5 z-5_@EiuHA3OgBUB}1Gla`jnFr`8S9OcB()RuNvj4yC6LqqiWp-MuJtF_8ZmdjH z0d+H)wu1M0r$AP-eQ>o*E`|_-ko#+scG!0#!_Af(^X2TwS--O-*N#+7noc2{J*yXn zicKj1;w2BLPU&Z5aOcLd9=xHdHKd?&C?}xXrYjGutHY{Fa;fYuPpV~_Tmpk=Bp0U^ z2_S#lsZ47n_}G?zWvIzri4x2;7tG4gMkU^*3eI?YUs%k)kRnBSWeWmYNuUar=4vx6 zAwdmzqbd}O**7j80#TypzV?SVF<424=W8|@br6jqbjmj6nMR&ZFdD<6-^-15U|_P_ zYgf@N$4(m*U1{t8o$&8^|0bBM8fDjY{K$M{c9!#`{e}Wycs3re;5t~bNfO_u+Fq38 z_zf{iJ5>_##|QrbqHehKyUcWfV z)-%#P5f6oM`_yK4Rb-{St8f422=QakXOC2+8%$s`_iD zuZss$y(YUr(cWXW4X!$-9MyPDtJcNi1LZ;k0jFM$i>QfF>r(Y3Dy6_(To2^KpKyG> zLYyIQA=Ki9V=i4ieOi%8&k5v0U<3Cy8MBlr6`b`u^A}Pfq~K}gpYFx}Ea{wGK>n*e z9CBAZ2bVU8%U5#21olwlttqGG|3t%}!dKf-^UUaK@$XXU1;kNnVo$>}xPUbTu$QgX zuWD{-+w2Z{5OBZbDWtZ-AD9myoGaXN?fh{Y)>j|8)Cv+*|FF1PcxU6b4YqeW zDuM>qHdGVHK{C(n#=QrD!F+j2^nUw^>PyN4ie zPL#TkfwWH7=o)0&3@Zn$!gCX!v`$f+cnoB7tWPIFT6;59Vf4L#+HP64;kw9^M~)&bUO%ld`Oz;Sg2V_*%%6<3CSo|&@mwM?)jFFF^aAIUb5sXc0bhdBoF2x zWm42uF+BJm#PA#Ka_N8s9e~Y6+oOu9ZAGzEoc zRc!m}VT)$@AmH5MXt|KCgXP>iKP9}TnrZ|#E{nEuMi{g+uU++KIHD!u_a{5M@R;zS zC%X2+{RGWvH%AtCS(I1XWS2vTJa^BVO>nOW>hI7Tg0 ztUvZralrZ7lHX!YhgRUJV zVpgJ8JP3+zbK{yi0VK7 z4<`oGTr9h`$%m4NpEi1xS7B4VP`Yh27~g8pg#~1~`pNz6gGuoWecj?)f8dS_NzI8w z)^6>+=QN{t8q*53De!0hW0+5{ZmJL)6VpX#NnXHM}p22)tSKdMg$5 zWw9;U@t<82(KpppjEerb@i!kNb!>k3N~AS)ybxdelU&Kp%~x7!R(%8hKB4>F{K<)s z#^n#h_2HJC+34LuO>?;ovWPqbL_pYc0x&B?vUCxCurcF#U&Gf{yX{O`o?if=ON3+T4?q+&lF>|ytc{pbr?RW2a ze$OBN^Wwa??(6=1-udQ^75A&rNiQ~^${_LcS!RJ+HcEeiLxGPRI>ra+`n6a%$yO*t z8zp2WVV=4%Wa!@U`(}oi#S^S|x>btfW16$rXM#B;gc;A(4MdEHin;Dxios2!fN3$w^}p^4^6x@qKIT&{=6c zVH_D02au&FduOv$CHE*P6{p&AM{1y79H4_OsGs{ zz-C!2$61}4nkw@)80Z3#|7@`GUz25}D|}2wxi;@VMC#RCIGg~QKC`x+fgvG6LKq++ za9xY@gm^SZppgPo0$^?dtV45(;fn32Ndn&(v%FFot5}1D^7QX>EA7+9D=tCZ@w3cI zsTcL(FWERO3L{$rvOhk4cHttwi-%*$Qcq=Yum_Ys=a3qPR()-WM$uM=!f--=z7v#zGtq9eEu8Mwc|a z&p7w5JpWac`118weA4IfR2;wS4~!3nHf1Pub@9y671ahJmE^JH)LB$zH^IO}$gI8^ z@@85bm~S=gvPI<@SN~57z~TBvBtW}v=i!`_oqf#FErYAqTE$rs8UMz?p$`l1brRLP zC-QXZm0PLbs7khE=<~$t^{Jm|8oz6H9fJcXNnH!bY)eOY(%Qqi`NY@Tb!xFvt6iq{ zyKkg(?U@$0VzICijmUJ$Q8r)05(2u20x-ugcLhq5guoFTrFf2}2{f9cXExfbp&y4! zG}VOirrSe-#maE`?jTP_2N)%RcYFnZdu!>s>ta$Tkg}69oNvd3L8!(FfaKVyqCq23 zKuW#Ho-QBacEHY0e7V!Tn(gIji!(Q4$V@$BgkhmGCz+YL; z3_(W=>R*C7kh!BqD~L1M+YZ*kr;g)W+tM83YLuI@G$Zrp>FlX+8+Y%Mgp~6aC{2>ZHmCe+&N$x4))!6ko8t24C;`ubOXPCZ)dBd)E+eas3Y)b8#24XoJ>7fDpl&hGD>1H>OdyIP(}b- za)-@4V+grIhsK|u`1L))2Wa%VUoc1oM4=!+GAz(4Tm7e#KDwliMjt1a|;dTW###DA6u^y3Gv5qE=g-d+)aW0J5ObNI#Ac>gjX9 z_Unf#iF!Hyi+~6&O*qfw;ioJO|4vk+RyUHv`Ga)9SoIdI64-8~@JSZ`8;2wh91z;l zw}FAKtVr<0#60@C?^Gh(yhuaNn2SH9bMB|@9I8MQ!5&i6m0`&hEZB6<@!3zV`9#9{(gzn3`rZ8p)ZhnU77fN!Q?n^!fCY)QeeMG5~Rc_JRn` zUX9&;-1{iluELqBkfY|v1q3Ew_h9KEuDXQK6%uhz$fv*p)+HUUW_CJ$*Z2o}q@WUlbV z2m^J`Jv}`-(d*rOdQ9RBW154FUW9u8UU=LQ1%57TohI zACS*~ch!KlBX=eyCJ96eRjL&lm{~mWHeKTLIhpnk_GAj~=3~*Ohz^qJoN$1gnM%BC zJCW%v|H-AJGmVUSj_DN#rElB^lXMO22w{{(@>3u9{V1RV$I%t&6keHNsy1ObNrT|| zEKggx`}4v@le{dW3$nsx%sE}$93>K)=xhJk^Ly^4k_16!vS-f`YFi2_`RFxAI=o?u z=nZ&M$b7Un^5(XexNh873iP6&TGRPwBQwH6y$NED-3ecq{bG_dG_`)Pk?x=%e&hahky zC;cK|NG9kSXwt6zI{CDmpkT>}4C>c>LT$5o<)1p3KX>uoy~L8HR3JKx>3)xGLo#p@ z$lzxPz7p^;Xfk&@hw6wD7<`qK%$r90(+M$}+r@VO1o%s=`(5mWfIqoZ@8d(@!_|Kb z0;6XG*bMxIv)|3MHgNm9R$bb=yUDaFTndN3|6N?vOG(uND1gC0&TT+6li4j);02_g z3|n|~IqD;)<(JIyX>n`u>Ui7kW*@IBhn=@`jn@R;XB;ye19eEB zxJ;Fyd->{?qfRZ`+uIm$DM0a-E*@BMJGkRd?T6Q{;=!}CF#XZrSmSTQSHD?FXRmu+yJq9#?fj|n zJ{_c0ic|_{eQLi$4Nl^04@A91E0na5xzF0T+i&Bn+5{+&zMJa4bPhC|uSe9*bSI-F z&2}PqMa`}G1;JCmO>t4O4}FjVxJv_r%55*r#m%1Vply?W@yc;;&1@&?IP;3S>1l8C zosBdl#rmLHJo7&3owmMvH~ovGYwOfRpQ(dYPG}%B7{v<|YFjnr6m!f`zh);1;+Q=+ zpaB%$Iwp(P)Ug#USzKhDX2&NDuJ1crM>ZYQk{xrKQ<-~yfUmvzh9AM+1KyIiw?Hk? zDYA?2F>T`x#RoX4d4b*8A7)(72h2U`6^2vB`fTa@Q^oqR^2IMXC>KNH2j;|6N42pn z4dws%yiT-vkQOu6OjXdBAdx#OQN^)eo}VR=yrl)^<|s3{`&) z3qSjs;h=!CR&+Ov(m@OVDx@UKzwT4^!%j=xa<|`fJ9rzec%6)z4u$t*cU#OPKL5su z{S1qLnrEn^ty*2pjn)qYD1y?*;xX=saX&T}b8-LS3LvgF)US&`5MmG$M95)2AIpNz z|E>%jxDg8v)VG`)`mI%t!l5T9+LKwvwnk$hKl(2w+tASH=p3q@DU?D8yk?}J4u>Un z#v+?G#gSK%bo&-o+By6TTx5K@GsXGk`Z0oNj-q?)8c0~lCg)>ym9D9W6$Uo|fwSJ<613(h*rT9Y!p;UOq;JPl(&jxB9Ks^|cp0eW7 zx~=G(P*igP*zF9+S>z}!8;n>}eL3i>ABTO7IitvxKaf;=e}OYp=UOERM}Tsvzj_8_jRrm`y3s<7RbG27Sr-r)K=DqYfw3b{ zNDWhw%k0BINI+H#q3#Ve`EJ+;CQVM9Zsiif=58k`-fl6v+n+0}g;*x_rQyo&+Fx=@ z-&`rQzNeA>s9BBQL+VEB4%(5Q5sVgy&JpJUm2%)k4(ctF6VZ1Ah4wCM1cuq^q@D1< zf5NCMF;H2;rfMz?rpi%T9u9f*_--fMjm|Uv}87HYi54u zq%Gja7=eJuXJ=+O5}2vbJhg$aGbq#?jkS4KE%Y*}gyYNfA*)aT-?f*06BP+#L4;J> z$=Jf^K`OHaiTt-A3Zx?)w!*_->GOO=1sD2`Psq<(9W3U87@t-8{N8!^bZk!_P-O!B z^y(XaR-rr#(xL`go?)y8=m`lZA=BcB~Wp-aAa>Co1;I#uYI+!^Ssb)W=-_KIigSl)efVy-?C zq9FY_-;ogi16t|!214o$0i(T0L+H06Mfb5(`rODlQu4k(7q7#T5!5|;!NkAEqV#g8 z&}&GEM?oy_Mnk4v6B}q@^4WZZ9R09=Df^WUQiNV+8z!Ob{5kIKEac`Wtq57KUD2{+ zYW~q5ae=2{Ahhv*Gs7+v9Opw}Po`G?x>Oj; zN;-3+gK`x4%3l-=cg$5n>ofA0qv_`Js3Rr%;nFvsZCv6*zCbddT zaNvDEA>@>O)`8ca(CN7ZluB~FP212=E-OE<0|Zf#!@gfF2(I9ye$v7gx}FR61H^bV1|7|v+Qxk z_1`YIkC`nW8$ovrX%*=H2~X>-;2o?g+?Ax-lp#v%!n!~j zXoe4mpkYQd*=F2q3X!5iB@v{a6Tz>f|5eNly>+U;G*mT@%e@PqRL|BiV4A3BHWS9# zpUeHYblF@`UcOC7FLqEWL(xHEKW zK&f=-ZCmJ+Q%l850xWH8Xj@;O*0PUd=-4eU1s)Kc9(uRKaD7-^&p!(6hIGJX_pf}H z;qjaSP;+hr*__#TRRc{<0fn6Yn=Gj~w1 zG@g0SO^T=+)ZO1d$KRG0Pw|s5^_#wj8|QyryA4J^fVOgaFi=6x6P>5~cYH?c*s zxriEiyQ&))0Kj2=BS&d?l(zGUA_SKQZu5J&3vJ%4$negE+C(y0C9YYBZ@>BIZXYT1 zN^DQ(ot^^OYVL3(JX0Afm;S)_FK*`KcKT&C2Y#@OKfh9C_$?9(-up=MFTaOJR`A%r z|012M?4|lmZzVucawF-yPEfzLzW?nhg}d_qROvlvJ<^`B2}+X;to(*oVUu4s;4L$P zS~70U1AKtGWI*mP5bg!2{`t%i|1GC-CZ_K}>CFe`2bg@!ihGo)BAeu3OVqUl%7CHW zClb50ZkY6gSFL+brV2snpPTQF>@%w346|ct{Zl_2nd&k7oKFh8e)j~X4s{XfHP50o zs@>!das<8O;Dc7f1OLtOb#?DtL|pkZChu)jf(;CSHQ56U#ufW_4gg8K(9VhvmE+3L z4pR8P;u2cN4C{_IEgi5q(2w!gQ!&+gvG%+D`)1_NicJ7ldzJye1@@n%OU};iYa}e* zum`aBzobY!3v#d%syaLYV9C?@_0~t0_a88ytgshqp^L(Kmh9*=RB=`bW;6%#IMXs` z=}f-;85g?w*!GEfz~sA#N%D5n-xmA5cMV&iF^K`_r-;)jFLLwv79l}TJy65T7-K!m z=+`DDJ@%4#k+Fvy8IKzcdtO0$IJ=sCQ$2c;=7{CLJZrTBvHV)jwNV~d6o#rfQS&dJ zvY@9MD$$@z{qmK-v922Ok4$`b^2vr5j&$e&lD+>(vE7p@6?DJE@+GA+QB?`V++`MH z?ohcM&L0_EE|&sMuk0k4n%uX+p{qHy0{M#kt<{Q!Eslqdnw3=g8#*DfKjUGh5tYpX ziYk`{dr_W*Hlr9oT%M7IR7bWcw5@xO>3;iKB8cIOUo&B1|Hq-A>NHPKk4r77R`Lt| z=b7C)OcwP^>9d^viF+~Rwf$hWYgipvB{dx8IBr*mrg*m5dJldzA8(Cw;$w@!to@oW z4Kc9tielgE%(Kmkk$N0)3lEqMmlA*P`zF;h?A2p(YJw74S+i~tOAa+Y>1+R#eI&7e zRcg>EkudN47mhzeD=ZTAGq?4|kuKKC-b{I8>zhcTwmjM8@z|k=;%2${=s0MCfTH~f zn;Hwr(;Z1S>G=>e8@1xwgk4Swm{2aL(m5C9^%}aeTxQBd3OB|4!(znL{DVW&7FXX` z2ZXLInbPZL)$kkbZh&J%y{yS>c@ahDy1dm>$`KP6(@-PizrSlU4igO#xhe44&MEiC zfF+iwfE5awHVJx8%8M+nqzyxC>&DFGJFtOBq+J?*f0vZqv58)FrUFL#5A*^q`=7It zh3YC%CHlxKvvzKNF1csV6Ov6c`CN1PdAulEGe*j5 zw}H zX3JYOih=P?b51$gD)oBOOE2}M3SmLeN-s!#T8oq#rGB)3i!$sPjLkI_udxeB=oZ-B z)VLf8F@Cx}!p#=*gg_wHc~-XX7ODn0u33u2RT@7qUwQQuen0+M7*P{co2i>VYhXA4 z+HZt=qYVV&zIr3Ed+RpN{`#qNf!DKRdhhG4PA26;vDY6uUvzxzo>F+v8QoUW_i>5h z=tF2AyJEkFamfu6&l_F|a6SJ(KQ&Agk+B8H7Pi~H>oiP&Q6sPBxl8EJ+XA4!BC25#P>h6x@ ziD1)UTfe}shIejq3Pw?}qch`@vy=x_{e(l1q3VhFj70I**&ILB;^q0BsZXIDk%mRp zxMXCllvbrL-FwP)*}lE@0p zG5S;n5&y8E$x+U%JxJ*D?~evpP-gJAm?K*r0v|J={Wa(2^OM|V^hklob*!iT7vFzQ zO{oLUzg>vpGo|jtL%}FSwH$h)nmggI(caz6C}l?9m1?ksFK3w^QztwCa5;(fwWC>z z@W%CJdI9UCl2RuYK(36w`_**~R8EIzB1R4>O(olcv?IHav*+-M*&Z zK}zQX=&dR5%GiWI z!T7AnwkTt?MzC<)wZ0?8(^3qHnTk1))g9`>n{UZ!fr`nJ=%F4@A00~#r6Fb;d-Psi z4y*cB53p8F{;XLme<27q956&FJCcTBeAOHnu$D7Z$1%}S@ej^NPXFW9piyT*=<>}= z0Om=4fTv)V9nO%W;Ydx1T*bm4%a3wkv#Jn)o5KGDYi&qCyI+@{1O}LC{{;S)o55Oc zqAyXD$2`;lFzp`Y)o{BJT0fH`MhPRk>7>t}KWiU<-9{jE6U4}|fMSpo0`vwm*pnd` z%QXuKHe5NwE{)h6cp{RQ?El`E$6)+R7I*pe@8MY(QXJlmOyTHP900flfCT-Qm3V)D zPtq@e^{#G@h3$A>jDo$$FJVmQ3I9t)aVbr+^RuldOGmHPYC#rVbvq-8l=>~BpmdbI zw8c)(OIQay&`xs*sBz&;h}iS|0-==4!MUSQ{1W!7&9v}d$i>4<_l{W2k&N)jjDPs( z!<$s^tX<;(DTEX5mF&l1Jgw=|a&$^jtxp~SYbEX=1MMu}$PunMbIrI+eR1WCMEPb& zl)8}baR=?<+04mYa%Llu6sS{&n4c?_8B-qD_SgP9JqVOu5j%Dsvq~;9i#BfZpyr59 z(Tvq?o@~Jld+y_h-#C^PWE7b#|9W-*t2PvaiHY?NJrvvmrJ6v8JfJ~cb%|nkm=0Rn z#H7P|14;JgxjZ?(aOPb${OL2~BEo>gD*cvGp}oVb?BU|Uiv<5zc3k%RbY7$uO^pfE z;Eq%qx`|0il{-uD7xRBc{K&(F(fSxPo&>70+hDj?MuqqeByI$z&c^`Fs-6JCH@bkL zThml8ri%^q0(PYZkne$Imw!czNcgzkoMhkS#Q{yPOpn^pmn6M@7ZI3yXle-#GW$fv z2LJXpR(LwU&P(oX21b|cugE6jAy07y&RHmwzF}VlYTa4kj4-Uw+70BHcq`Y-J(<2h zeZ0yBcspw^nm-bZdNj9<4L~2_`~vupHfjn~_~_5Y8v%gjUkQy}lPcrEg6}igkoRjm zDgkTI-hC1*UNiw-V<*AyEW$dzrS`iy-zK>aE?zT=^Sd*(Gr=eZx-2Q(vpBKE!#J}l zIZ8iZTn>AAdm|UI0AKWj7JWQrx|gbZ_8PvWrhWyIYoOyl6Zu`Qut;YwQ7n#p zQl_2l?Fb;n7jbw&)4cTW*#Z=2yxB||`dkTbQHo@c#1dJWp^-hT`o2(AV{(w*X17gf z2SbLw&X4jOxu+@eXJ^{zFQ*RT#sZTQ+`EV=^oi>#&@^0RFmcvf84MHq{Rq!s_D!@#I+Qh<^0<|+o4lk+23iEP+6jM-e)NZZpRvkN0CSs{%UKDJ zMp>&#RT`GVtJ)^3njh#6b0L?tSL<*X!_*Sl#DJlMm8~CCmZRDf{!E zyBni@zLq&WV_4w)r5LlncnaVMciWVGDmHw?A@Ck8PNVJL!$Qxc6p4t4Isn;?8Ydub z`>}DqzTxrs5d1I|dd*!`^|mk3szIFbGjeM8q})eEh9yYOX&b*$N5hZUc3^J+z3<_o z9t^Y@|7$#OSObbZ!Pf}3itl%O77q!Lk&)|a@DEy-!Ltt!A(KS*3a^gxH-IMX&bPW( zn~@~DS^wRstM{wrz#(lxFx#b-Vq+ zfzLMS%5uK^K`xm90Qo`)-Cq*6|Mt`Vbe8Z-9E6@)(cXSR{^uQ|Yp)`%kGiDnzIu37 zZ_zivHQm``xmIfw^7ok^97@jjK?O3!`$NZc`QN_n;Ss)+`=1lJ_v=*!)M;PhNh~$7 zn@ty%s@vMyG8t#KB`ZR_xX@%@4(AI>VMh24E9d{T0JHNaf&<9duvw#ih3K-dT_Lx^G{QVH8Jq`k1$x;k|NEk7{QK;?FAJi{6)*87;uk-z4&P$$f9cn`K355g zN2}Xiqn6#hVzKgGCeI9#{H7&A_G^5__ZgSyGr`gh4B>>C_pQZ<6Q`Cztl}zoG$+bc zeJk*7N-9S%`4SZE>6&xrTMu7fB?D?81QZBwDXDXAr5XAHZ=91S3BZ}9=WO!thM&_X zEfonbIhpr#T6P`yBke}6Z}1KJk%loop;R|$K6;D7uV&OR?*0f+!%A_;V_TNu!`<3= z@-C>4Otbi^h@2@E;A37Osx$AtX*(f+dn~L{3((Vz>5e)N5yRl%wyi5ZSa!cBPVdhutxg&>nXO^NZQP6J9>q>7skw*S%AH4CjNyI+m_lZgkRN zWx*TsSZMZLCkG~pKD^{xpkzaCj~b=$%bk-W>|9B2A3vvXvu?x-`tMUY>7gPRdyU}E zXWj)fhWXV4VN?q5UqPujLv{(Y=h|qVbK7#Rpk9qGoUe=8N}6X`*p zKL%#x_UX`OAPLJqY6D5ZtyZ`{J*YsRRfgQ#;r+rTY>nx9o4c4Tr9KdAg`hEjI1k-`jjNXnImXmSu<YRtC@4#(`DKHUt-Hw??Msxl z+C+{EgZzo2h@bg0K5Zt1x}lgbfMM6XtDbm>)&(BP6a`FUfnPM&=8#Dhu8YSTAC{0K z?8>a39w|V66TNSu>=p>1gz_Hp@+9gV_3y09^qHzETyKdvbv;5tW`G9AsUBNIf87yA zxeEgH->;<6&ZFPEf;J((3%wM40;#=HGhVS$-na3>c^<@{eO3%U=?h7`Y z87ss+=(^>4QWJiG&bpU0`RL`J7;T?7yxHdezg zeLc**c8NKBzoaOR`}wa4`&J?`v-A&D;`=8;<1N-i19|cUNx`vz{6(x{LlZ0iH&^~+ zkDk@v%@*q>;C)3+O}d&R!~)?4He)P4(z+Z0+eGpFu@nVpvPkod_k_& z3x0_aHBUC`?i(U!WQ|b2vD;Jz zCfp>f+fW9WMw0wnmn9Q`vTyf-rEpj;g+D{9Z3`nxGQ4aPU_KZL%&=9}Q3?O{pA!(z zG&S`vNDPo*g&-p6qPT-yYbzl`%(VW875h7>G9z08CY2ZfdNGg6s^a=Qc1Y%*F!D0D zV)Pf}zW}y=V8P>vI5Sz6-o?wfm(r(Uki6Y?#U5buKg9HN7hSzwCMU@}rJC*Ipae** zU)`vyoCGGWw-24@JccWt{ldNbxR$#ljbrj)SR zl}(+^Yz6Vz=5#`OkN*5hIjN|GyKty{CQq9{*y3H5vl{R@e$t&|4k{DuO+(pGrpATB zCOx}-DUDuZ8T+AEiihPQKi`4%qCa$poWtoe{~Y7d7f5cGq8M~((Ern& z>5(NRgGAm3hg?@ba-XY!8B0{S?6=(N zBI4ZXtG?{&xGxlf_#FGY!%L%URXamlRPmQvD}!WoR4C}5^#DlUC&7SsmqYJzf-B3w`4y9zKip(|~&>9HgN2dop{A-|0fiDToV zuL%(nes7IlUMfZNedw{hPvQh4cBz1&|7j(%bx!m7PW^jka0p%S?LCFBQ_!@S;p&@UG%kw zvg$E+OVY{ni+((59%>$hw?VuHdkl!fT%@UK6d<*nDWx4iur-yu?!{T z2^4lKP?161uOX15DyQHa2Z*3G4tTgz!AwvO#sppY@hOXZ09mCM+o8}@L2 zdxyyG)3^!O)dkJ^(D}!T=n|_lzhi?{mc0Qjjdehpn)HBqX!ZRMU^_E9;!saUU5-9X zUQ;7%wQS43d4z?jZWh-#H81>~neR%0`sy1@#4-f;D;IXpCc-ul(+rQ}>s=_ZUN3og zkV-IG@J2Z}t)z=BafCjVzGuuunb?Qy|$hskzszk4rknq~WZ_-pZH;FI9BhQ~Uq( zPh#q;Acr%SziJvWt-=jxFp=QmwB9jcUZMO_hW2K=wz8W-i^#P7MUn&xqHD@>*ad|Z z?g9CzMjeh)pU=qlRcJ_F1KYSGHLl)wXia1oG1_{OwxTvqFCXrCPK~{gohA^NK{k-s z#DTXzo!{tG=B})k%nE(2!!(NL&I8Gk#`(T5dmWV0vRM!TU08)wedEOY-2MKkdeb18 zqNQoDbq3H>hpu9vWYe2JfRI3&6s*6#BSgE&U{dDqhOg=GwQ+EBM(oj^_$JQ-uZS1@ zCm-ngn@n8YXFM_uirv;kYUde$rwqiK;(C?m84UlKhHxb!7w}}xw|~|PJj7HU>)__IO#R6 zn$EX6Ps;DC(Feqy(v8Z6SK>SshvU$v>%_-F$X>spjN(X0vp$}`8piWI-!Q#iFBj7q z6WF6$q)iuHx1k)*4VA&tFnH6Qk4+Fme`J#Jk&}Dud?LR$Rc!_cL=yVpsajj^dH$90 zlWs8@B&xZf0P^$!e{5{*NA3$We_KJsE~k$t7C#Xw?UaBAJt6{EI*c~#d8*YBz(My^ zR7oCPJpE^wXz1(1tUnLQljPWGnrzH4{jH{3CEWD9{Nt~0RO5Ig5zz^#|e)cG+P(F@m(-kRRaP5h{7FzfNQ1Y`|(oBKh! z!ivUA$8ZM0vgA0hA31Q$x0Ta7%Rzf3U5=?09VqEUd0Ztuj|L^>eo*RQ7~H)_F);d) z%`XMz;gpOFPDof$e7}8r4#By0(F`|CIPpzv$!a}1cX)RF#zyDr$YZVTM0pNVmfE4q zYiM=Gi|5Au#T&ag#UzUh?0(QG{Wb<5jH12g^hf!Y1#f+6f>x%Bc0k;xG$89+E5&_2|3}M z{jz`E8}Bx}Ar8|$-FDceOp}RNk>k@%@BJb4M(;m^v?R7s6=4e?PD%yDl6bgl=yzHv|tC$Lx z5EsXdYKp<*?T7>UfZi7dbSEs!i!UiFrOmcWvL}+GE*$FW8qc7aNJ+<`W<3JSHHNlPCv*x`B#)(VGAwpfU++_=&OS!KlU1kL zwZC@+Uo>^D<-m(C`jSb&K26&^_CE2VC#n2MM@8DR{LPqA{VX6$b69)z9oxv{d>Vw_ z1x;kpFk5DM$U_OF2tkr1X=R}H&O9O@t-y_WU+(V1Iqx62F?LIHFHwJ9<(sLJl?nj- zA@=5)wd>Hg3MAWZyzbD9SCfIBeByw8` zelF$G_8!Ow=yk0U~5;pN&qbLE$eR=Q5wnbeSNdm4LHlq zTOGMZA2{uAI>K^qV#qMuCvJ6j^7jyk=g$9=fq>a|Or@ zqP-wpe(-r=0>9II?PY=)ar)5voW94~#~B#F<`+KREoOMKO7W3>03N_Rg2ywW$9}t} zVn?9r+5$)RS)}fpx9>4z3UhSokOS?Nqp~JuG@W%7bp)Dh%|}F`SGr^q?r@9yLql46 zdfhDQ@91|Rv_HV_^Yr%*YiVq&s*b5DxG_*F?ppr-m$UH^p? zmw`N?1Yrh|qq(qw4u9S&F~fP36rV-!_T3#WEZ{O*onAU92QlsF`rSA0a#;f2Jv1>f z;c%ZQub1_Lvy|lPx1-m!ij$vns4jFj3c}hsQW0M&D~KRJnSYQ-S+}GO8X6h`2Ze6R zb_7VijQA#zPlMmm^=HBxzU(vo@F4ADAmB{>E{~wzyhqLa2cTTo9@%39`cKybA6oCn zL_CDG9oWqCbyAWnhh-nbcbVQYHeP?3rKO64al-`CAOsggCHVqp{AmUSEv66)&znPn zwg1#bs+WbM$KUhn8_t3?%63d*BN}uF5s~ywiP@S+zEL3%x+yuq3uy<2ht4gI(89$l zQ^@ZT3(x+H&2TBtGsc}SR0TiA(kge)!VOma>nThflZWe>>QNA3xIH*?PHf89-LW66X%{lyc^#Z0MdO>&Zg z!TO%h%NR4b{fOu7K;gq*_J0Yr_JzTtu?!(`y3%_mHQe*dt!pP7jW4p{JNBZ{-?gNY zyyzBRr=oJ*dcmW98$HbEHPm*<+@95>E@hw)?F)BxwA(w($R1-h6>kuH{8j13jfLcnBTKIQ%!c zL?|jU9umki4SvL!O8%bt`7Z&arj+Jjg6;qpDSvvg<*d=OjdIKi4@_prV(oBKrcs|H zuTlKV_D^y796z;SY#3$5Z6RmG=i*;Uk)Nv2H#=0rXO|t8?e%Oeg_l=N_BJXn2orMO zz24KWuHxd9Fy{fc62$w%4)GhOT@jrL!))mF$o)2{!*LHQ zA>UL&)u#{xeU8Z8Xyca=Fj>26A|#F1vC@EjkNKjH6eZ;ga{D-qAJyj%kQt=+=~GKV zL2sRHK$5AeB2zK^^r++owrR|#Q4rUQ|A>KR+IJJ5g;NM(&eBRi@3nTM3vdUAq*IvK zsBLylQNdc2-O+x}h8CqVWcVnH6gO#PoL~EOFn)0yTD^6aBHTC;c|LrP{)PP;W!Ujj z`CsLg1!w}=wWUg41hoxBaGx)&68|l1ULy3EZO;DICVSgAIaS~oo;M?VXj6thoNw?v zOK}506`EZE6c;0^q@n81COgd5TjcJOg`h*rBpxH#P*C|wa{BL{&%I+=funB^mi5mk z#yS)2kGDy82FYYxet@|9t&bO~-cU_@g2QxkN3094gXotosIm=t)>`qPO1$V0flBXX zzptBEp}^5_`Y&af4W9VxezmTb&`bRITRy!KA4zSd|0ajRnrbH+oYt13m3`|o1x#Z* zv*D(8x3BIqtOmDH4Ii9zE%40yC6~7JN%PfP_EouWR-qHnZ0@oRD@{G1s1j+HfDw5t zM~SQXw}*~%auDy;%mFc>%eM&occ%>%WPl(cz-E$$nc=>Y(oKqG_6q&+ zOAkyP*65fh`z0UERWk2;Uwv;LuEEIsVr4-k;RGdkC#G)Hy|%&Lra|7!L`$vL+C%C4 zPYo=8GL%0iAAI;J^fWeJA6u>?DV9-?jy`|sZXPjuyY`@kz z3dlF$kXK98kfE+}uP%zj4AXyh=0{re*?fpI!JePOHo?;IEz0*oe94rNP;SYmpwr- zE7{wO(NFk0_Fi5;fP!K8X73kTQl_0~ygegz37zqh{9It~^QWA@;0I_t)U;=hgc&61 zV&WsSj~FA9gcq(2ZbZz2G@)sh>=_Fa)ndzqu5sE)*Gh&*CD0y@O_+Ry*FIF>{+qs}t~`AKK$g|x0Un+Nxc3_pN|?63Js!-V*= z!o`TPiU$rQCabAJ(x1F}qLYeBHLtu5ei0?@?P7`hWUH-b1Vvb$XnCU8ZKF>IY9$mO z#Q1|HM-cYsfP%^#)5iunDz^u%-F$Ff(J zYhH2Jd`+yd=A~!En7SBOf3B&=NT?7$Jzta4R}{%(I-yxZO>_=fWn7zQenHhpxKu1- zbrmkIPkhxEg}u!fs$LN?y{-PwDZ|1|I|W-COib|t!_G7iw&Gh$Mln!%7GO!{Ng68j z)G8J{uAsbg1w(=-9kXRb!`~b<6TwTjneD;&ar+qi%@ZJOenzuu;;G|W!Q0Z09qHel z>)#$Uais4!#0ccG(wH8Wa*`?`<{~&{6{D38qZS4sa>b*nFX#^|V&KhAxl?wzH5+(vFkP zPFyaZp@CKyj0xEdl6cA{ioK!0-l&pm`tdU@T+wmGMKTy}RKLVgs_>ezKo;h|5hPV9 zDOq>&pVNq4lU0v-B{PkVKws06}AQM*yAMSmQwb%nH?x zmL8eN47k+2=7bL?xoVL`iKhtfl&uXZ#{W)h@uHnIN&a$ZX`nKv4lx?>PT&EFylf|{ zLDI0@-Kag!cwNlipEi<~vCvL{hIpS}+yijk@Miy9iDs&-LB0tNE zzc~Y%*Kdi8TMn#M+W3?n`2v~>i^3D=Y_Ah{?>VLf4FH$1`GVX?BE|_h^y_e{r!*P5 zhMr@Fh|!0a0txcYfZC*f#YF_zW^Q`zJNiB>&6Y{WYUm2;C+&rYr#`;-xs}QOUr4`m z{S7e^?)5^z06zw`T&p1ZzOwzY14R!D#sUB0IUYUo<4jPnU@}x08%`_xu_vpiqY~2C z>I%e6I|%1Z1F7z-&RnN-h2L{tWfX_$F{~tWP|yG3h{&U+zwawwXZ`g1XLsuI#BWn` zbHoUxg<#&R^dK6maUVzizZs*f(ZhjXk75e%cGe>~Jh9%Xlj=}v~72rzw>37!GNqO38wSlhEK^#(}@kmdgd`0OsUC`QTkseS?seA{%R-sZX~aP89N_3j8>~q+P25s z3*h>J+Jge!SYowd8n+V7zXBI$8Zp8yK z_9G7K8YEyqz|bz=!#1Ci^NXeXo80Gg8)G3#dyKd;;%4J8A@i==?{V9F^55{(bgxE% zRajl#h`-Akx5N@=df=-gv=_qP_v=nXR*&oE84mUOKQ;A)6sUnUr}w zsjRjE`7eAm6dA|5!7x+nZ&HC277Tlt$Lra1dfs}Gp!2zs%Zi78@prAQyyw&Hcd5Sn$W12}^&0 z_&+T`8;2=c#n>%czr>N1O8M^MQ6MIW;3Du=tEeTgQ_Qk1L1hQTuz zjMjF#VWp|k+dxv*M7W$}a`~?Yq86HjPi`XEWPS%5da!u2W!79b9wPeRTbrjOwmRDH z*!=&5}e}?(Xg`>5^^`M!Fdg5rzQk%pxUL2E>$mjV;l8BZM! ziYXVWk6iA%hYuCr%roh%+N`*jEii|359pZo^$Z~j zsIGo)(erI4DJfxwjWH5i$SVnmwynzbKNeXg1I&XnIrCYB&i)Ie1FY=~bM<)las@ue zYc@hU4kM$Dud+bBnvpS&QaDKTONSbXq1H zx4dOOxDt7k7fyyLUA!?XVn9quS@uerHEM9Qj1r4pg;`qc8(uqmM=dtbs^H%NCcEG4 zS6KSMYtQTF*1KVZyU0~!sAnCHQ7*rl6s%cV-VukpSr3sBA*?`s+BzyPiaBDbu>#5{ zUr*r1JOS@gAZcOW^e%m&D7q{Y#3fOq?6BiW=;NnKR`tn&!ce2-fc)hf*T5RrEU%i! znn=Gxgc*MGpx!azOdR8TaTp)1PilA#=H-EGg4qQJth#%7xTy_!^V%9Clt-wQT7^Mt>ZeD-Q~ zmwfddTP1=5wvsRP&uFo^N_)$fO4XC&UsXVw5;En`K?oj0#xf>5jur34H_stIA-H!v zWKV{V+2Yb&2AtHtk(?h9r&1ubO+A{y9WKqCad-Ou?TkAw!kkNyyNHb)OIr)X2c_FK z@SyLUzkdXU18rq0M4*Pm2oiG~BT)#E%S%wO+5-ffHi1OYMr9R!>8U_lx}96zp!eH1R_lG9(rDxCfyqNABf`yME^AwU%lLaDCYP2O)yer^EU1BC!U<`1w< z#>kYa5`TGMi_Af=qqoh@Gp|jxL+NhKtE-BIV3}j%}s3)&=~HLy8o_Tl2;0 zY=>X&uk&a3y2X$R1m4m@@Pc-F72#aUcJo1#fE7t*ai z73RM26!DPJ-Z`b+M2$wxEN=+&*a99PV7XRK^Nsd3zs28m2@rWWz3=M;Yny_lKmMw) zqhk^*R)o(@tL9jU4W4<0LbNIfzHf_(LnI?Z9dLxExPyrPK{Gml-AzZ|%B)|ZPvegl zaP()j%Sse}n`7Z%@?3=GAqoY$1R6xr=!~9MYOiD+7%XvviS|5ea1K@e(#4_JYqk8A zCag(A;N)x#A1grtemM@$8lO=}J^=}QE00S?9u|iwWwu1kA)|CmM?;KQ{|a(8KhsX7 z7yDKAph9fT`}M=Kq?b2G=Wf*9a8QG#Cgq9X<8xFuwMUrLU>*4doCi&eit|oJY_5|FKhTTE7@U`XyjdFdnb~mTmwJl7AZI1 zz2bNP<`Q7#q8&Ebe~t;jjtpB2yjI4ahyY8QtF;!~{y-?37KgoC_+9bZ87PNnyAN4a zi+I?}OO#$nz9KVv-ul(VTX9e4&w#agPeaM-1r1t#txnJSbQJP6hBjFK%m* zjozPK*y+EWKB9-K;o0Sg9C77#7-JoH%s>sHtzwc}oUa^xUySGf!N2r)Pc%U82hXTT z(hh)PHK4m1u;)!KSMC(G?>#?R2L4;dXFW?Xxlckezr1=I58O>)zk4#<94TXpa0W}r zY&mpwp=&mUu5NC;C5ByE*7d{-BEi{$A!OiO zG1`EgpJfi09=}t3@WYIYJw*VX?9&H{qntTAp`nq$b|XX=V7|oM$t8pA2T~pT3#t1I zw5BT^{My-pfCrx2XTo4@)IbcbXGmmvdz%o537!2j6Z&%ri0SP|fE%Fbr28$zhSd8L zh9mV!8xpXdty7VB+#NYwVcmt|Uu19DnB$neCBX*%yFwrdzrnuVFnUHTZ>{mIceVYk z2rOypKFmE~tq!Qo3}sd?Sm4J^+zz6>kPUfLGQ++L^>3yl+13!9yL5a=blz4J5tbNP zB(O+&nY<-DZ26&zVCN9#fJ76eT@-*~i+EK2IRt*Kr#X8}MV;T|2rP|=x7lNM^QmI3 z#%zw}FN5`CjMD<97=U_Au}=f~{JiQumc1t4X19Ltg7vC+#Mf>%lNYscA9)5olfDu; zvR=0NusqAiP)uQ4^a&p?3goSgh;Xe{HOV0VHva0Lq0u-~-cAZFl z6~O8=1U8jCzVj|b$KNSu!N$a9MoJy&8-s}k&T;k$7REN58PqodSGVP5_vg!~AUVzO zfM4#AIpaWpTct(9q#*0ugFvRP#cnHK{LX~6|KYEw$w1)jmv)OjLwA3V!AU6Mlpl$w z?DEWl(XH=?&US3Mf(EaCuv^iN9{@yGzx!P)>Gn9MF4X@b!8H&xIi0y<$WkEQwd|^M=vfuL^qZ<#(~*aqwaeYs6yAlI`trJojI4r4YI*15On;FLUeK zA0s7cuqPRVNy5Fvw}^rX%^(Q%e|Na(`^r$mYrK5ll_R9YrJRcF5UojMZv^r`?XNQIoN8@PP97v8 zP9P6&jq1H3VpOJyAI$^%ybd$AS-nAx)28lb^aAlD^Gq*av1x)b-s%Q2g)nIkT9K-U zVD27!A(t)log)_}F&rxDJs>t+hv|DYOvpKkl)i*%2_#ru;?)4hI(u8jyx)d4$bwsm z-uFJEu&vsSa^85#x;(;0&iQ8^+PPMq^QTbisddTDbKk#`khN{}1!eR`^OD66u0CC_ zBbfmx%JUv#-`S`dg}6tbtY|ztqn87z?fm_{a9?{%;1EL@wuzL_%l`LDe$L|`ahAW* z$GK=*+cRLXK;LM;)Vw`jqIy+L4v^i>eg_2bTi2WrvQ`dySE1X0dljB?;q-~+Uaa_ zSp{k%|M}R0CoY}XmJbi7Epa>a znQUS-29*gA#%8>;&t!T$hKzl8ze^qnZ;g(i2gGd;Re#I9jF>a}GdAV(Q|0RYKMCr1 zMXYJIavnrvl4oHKlG73C3!_Ov3hj0>pvXo91XY927c0pcg?~qSoJ8lIA0qgp%zha!22HVtYwt7mHn9X`UK|o_^TH_~d z=P6WS^1jewVi25eA1XNjs2WB)4@E_5wl@(wj}ECkJ(>o@DnZ8J%Qa(y$a2F|#VKz2UDJFW zGFP&H^8%NYaJ3=Ft;@D1*~rQbE-7i|5VygB7)YgjBJ+D947NJ$`SzJa;-$Y$H0ipb zuktO%*cU;|xW-OIg`Vd*R6@jxfBR_OiTVm;1z~BaTDAk>LS-iMM>@msly?&kIvT7O z`c9|U{cyD3sdlk~HdJ0OAI)=`WxCo)j?7E2>(beJJI`t6KRntxDpyT^&o5vbJI|3Y7&efL=Q6Ap6W;a5m_CUxsw5VSXG9FT+tdCl?mMV&8Z^6dPrmv^ zjjI7@g!(W{nN-6Jfn^{MTaHTpK@eu&!vU}nSr7Ps!$`-BGmhvI9Y7sp<~^Rq?*9HW zv$Owgim?V=(#4F?2mhGOeG&;e5PoFcweDP^6_4{Etmwt^*yG%M-m+)&c1M}dE!<~q zKK~c!zkS6Lkw+RmT#dqVLjao*Q$a#ql}kkRl^49uqz32?t9{O0hWYMapGo46j*sIy zdWP5Etu}<56zAvCJnSU)4IX4&U8r7KO>1KxLLP%6Z5}r>5(EAq@=Fx@yvIU{Y{^^j z%m9Gpk-&VJ%+-IFXZpC0Ip?$8E4(+|_>5l=a7_rS`mPn7Ve6quTQ7_#C$dVGwz=zoy7ZdJXCY)|Os^trCG z6xcu`F0Kqp7916CQoV?JIQa7?Zs+AWsL8~cTRwW3cvad)v@H_AQUU#mO{+jsh-W+s z`%|kl>&V_-Xbs`+kkK@{I_;vbt;nhJGXF3*F5I7_yf|+TRm^jQFOB`kQkeI`3-5~p zw=`uH_N_5a|FSrO zJAsNDcFCyPv`F3i;;{R)Fu%m-%)Hi~+fKpa8*!zs_a@(@Aa_DHW`@op+D6k(lPC3X zC{XT=OZSZoBaO?29>;gN?bpr6H?73@wC9U$m3es%mkm~5n*g_SVqc$+%0&}9#bD3* zNek7&=6x=KWV_x~!Prld#qZP%foMfF6sPK%PTGsbBlsueAp&1kz?5WU%wE^R9eIiJ zBZ0kNKO|an?`!P0k1X${?bVWU-5nJ67rPUwlxC$3tSE9&lj`^f?2wy z{6MSSA*n#XAaJ}^pZRgW)$~6`Yj?u|^k5vA;3N7)E0zf@W2~%NrEPSKhU?sILd39U z{3P#03!?(-t^z&V_iLR8#(%T6hB4GdtlSWF_jGZ;d#W9HKW&QVpCDwy}X!e~i{ zyrzqX$B+G8nt9XbL9d`kLI_j$^XEI%7 z5_S=^dk-Te({4hfuugF}>9c7!0emo{KNq`l>=5g{ic6kc{sP|$Kt2WB&r_$N6>AOv zQKfn-q|EDF+)>j`CuLRhKIz)~WAPShpLPuv z8(30QCeMLul)<=^=5SalH_oK{*AVi+DAKBXuC4p&HE7gc#WD4OB8vFU3;d zA6>Z~MSlC`=3ACVaT)W1k;EUg?YO&omvbm?kxwR-582<3gtPd?N+bis?-tKko+?5X%OmixD(^Vf7k2vOlax+`w{Y_$heQ@+VziR3~ zTgUh^-nF+xanegdW5#F|{3LJ3$~v9ZzxQrxtWZpmMbh9#}nRSN6`y+5TF(m>_DH?`CHG7=6*rt z)zRtIimAkQCWq#I+~UGXnFu#^`i3bOzGyhrN0W|MV1bpAid@7kw6W_DyF?waSeE*m zi5co9q2Be|I+47{>v&N3lQ(r?ve>+nTBn8Dm}{(67@$WyDqwG$emf0g3kT1t}v@p4ahw$dz;-MYNfQ;#W+ z?x=QZYr}(21~6*k}v9m14$?%P^qh8>r_JT2>m$FLv03ix!p&&H2ytth-Q) zVTHkm%=FYx#oAVzoAEY`^v-b4zRDW1;=~NIAYS##qiYZ_=52k&r7oygTj;>m)&0+r z#zVYKiFIzfo{`$=+~wu{z5G4SAvf1QNwt&HU)&-|ifKSHo2PL0q^(#p=Co~i-Dd&J zFTbd%OB{QjR-Gn^F@~f}Pj{2ncE~$>>l=rXJr9{VcBjgL)w1`(by6`&xUEO6M9Men zpvLd7YgDgxCz5EugL`N@<4+I-M->s^ed-?en?+MiC1vMF%34=jG(znjy!WJ&m8BM} zSpSd048Xb8?K|49;kEz&DI_kdtalezRlE4W<9;JOp(Hoy7$#qtd8pmNNpsZin zC{K@6M&Ve3Z)6p={0O4qnRV*UK9Mb;h&qlbt70N-S6M^itSPg!WaUo61_F1du_l-1 zOFYyc#=^g^2E0Npl9M4a-?0yFuymA8j6w3d8=6^5NWHZPRgsS}9j#=gvZ3x(F->p~ z^4Wuc%VBC>A^Xg!xCq9a_;Nq)$plV zgAuOHZ22v!7{Bebd(}m__#G*A<&KLn^&daH=|HjC+TY{W^ChA!Lbr8J`IW>f3Ywp{24rVh;;V? zmO533mK)Ej*{9t#gSJwC3dn5uV?5YzkffE=#ndI4kjA~Hfl86ecis>V(F^xs3^=>2 zE*Zvd@N3x#hz03q8B0Vy!qTQ}%J{$3kJ?XR82rvFx1&4;9vdyoEtTPm7_F19mmI%+ z!mxS6@j5eXNaT}ozF8Z7ejE!IrkXu6%kS)Ka4OATtI^0HPE}UaO!sD>aZ&O4-TkMQ zijv%Ung4sokSH<;DW`&u6)m*kOsiR1@vwe>vGJ-zbuD|nJ!%7<1Z`*pqx&qB^#+Iia`!1Sxz2zYM3uGPQJ$EIr?bo#_ z*#G%a!jD42JD$yB%B%Wv*C?i82%yglGWhX?dJM;wx#X*$acgld?_r$8e=U_bYFY8d zd#0ehV>RSL8ts`o3ct{vOIPlEYB;raRQPte7FX2a3uuJ1sO(_wgwNdv!vWe)}x&b)HNa{2SaUSPaPjLcsBxMA!nT77JmZJ17)GHYF{ zL4DTGn5AI1jYY!yK&}`hBC8m9-~Y`TL#I25AJq_+g2FZAgR2Jg6@s1jXbHYUuh7cl z{VNbi-5M9(H$a6`@K|)D$4gslzS;4s;HI7V;~*C$u$aM%3Xm2k9C1>WRaJ*>Jf|xh zWwNNs!rggZ)L+f{h0woJDU7(5do5OQk3)B7A0gZUajBAeNxSMk%fA0E4MdgaGEJY! z>v0F3&UdsyCB1>LSwY+S`y;L(Wn+DQRoZ`!aY>`#MpNJ~bB6WSJE+AZZDuT!mi(4_ zkG4D;8o57$jIN3^-bp@QrnI&abvuQ*Q%XEuvZ_mZhqvN^F|`ZSDs4-%Km5m&l#CD= zeNK4D;A`heN}h*v4*qw&0~%}E^mJ}O&MIl4%1pY9rTYrMXsr!-hnO!aC#{AX18=;5 z`iV-ALTlDchs-CK#E*XEkmx{MbfhZuMusE|Rm=Z;;@^S0;##ZCpYwBEG2DFv_lwzI zQ2-YQAb4W`uZAEEv^p{(Td|C3t?TGh#wI@{&cE)zH&gYt*iUSJq-#E6v0w~?`n&yw z2{wcgqoK2%=dvJ(2JVS6pSIqhvVM`eZIFyzgB&r4E}QY&{N{SomP}cE{={m+3spm( z7&eLoZvR=ncXb%I5`S1!`{td|jmd40YDoM+tWT8X%G#XgKIQ>=+#ZB&?8Ui_$MMlV z#>`>+W(CZ}$%uXkV2OpqHV<}PB*_z3Yco<)arME3MqpGr{w2Qhe=cLc@GqE5f5CSo zAuF|DmhvnTrbHSsv#w8X%6|)Jm_7bZ@((8XIX!NqM_lNC#p-AST}fG~k++Kyz=EuD zWN075$akwgq>Fth!{CSToE!2)wr^A9)Ja>GRPS2@Bln#I^J}vEMG?&;y|+ z(kL%trdeE^5Tve!HrOv1mG?T&i2^P4#qBBM$z{8vRmdBLb6j)PH91dD0nwWiI8#RK zZK(3jn>3VY|JwhI3#E{uzugwCi1N8Q;hFYh@=z=H|SJ$m&>bVkwq)_<;`{h z?$sV5*3K`l>Zga++&KSGmRG-*)dhzs#r52Bb|8eyCUw2Dw3Ja3g*9D}tr5Xbb{jrk z>tdc9AFbG;;`IW?>wMRMTT;&X?WVQxP_ETQ;rE7VKrof`X-W3~yZ~DE)f|6yoKdE& zFG0H8zugPISkFw4U3diqOtc zap%ru%^xc#zwi32=tmy8*Jv5yEVgq`{>?-K7+rO&Cq0f`R6sp4^P`shFSxJ2jph}& zK3kaR)D!o&v*fbobk_Od;o%sOm(r8eOnO!$#bsR zsGcPz6p%$K-GT9y%bW6k3&}ZWdJ!X(NvIHRjO6ni2+k?L=(4}~@?fuX+PK&>LDcr< zytO$QT~1feWT})zDH&bmhK5b;MiUv@iTs@MBrs5M*1fBFA_WLRRsw~ZS>bM)Oi1-^XM#bs1=8cDP*=>DjCL&FB6 zsoX2Z$T>ywW|p$~hld9-|GVHXS~l)X+p^p5W6;Zs8osbzeg$uDk^K0h)CvQccTN!@ zu*Ley9;zKhUGo*t@|dMd&v~(2oaRKzkn2DUOikSW-Qo&@Nm+e|VI7f}t*23seY-axY?W!7xXm$4aj!d4c`q#FHAOG#qh2?-oT)b!4d1Mr^Q2oB zGnm{s%?d?g)=(Llagu|Cl{P+(AP}#XCQg{}r z{E(Ga(K~X;7>c`RO{t$ zs!I&V!!vMR?e%@iS(Py)c36E6%rx-C1XkVbD@NaXO$sa~6EW!hBr=9P!91R<`R6?C zFW>1gNOpHM6*oU?CBHk)1D*{kgt2Wuz(`kp=If$xkOjZJz1xrF0vK?>xmZU$-w9w6 zpnrXU{(eT0Yeo9?YiZVD0c@@l zq8O6#Ee_*YksHKcS;_1VyAkAfoObIv9126XyRfUznq`ZTL9aYQAoVUJcXC#C{~;hb z$sZ=V6_9~VR~OL3V=WRUPU|H^ zE9TxRF)6XK=d-apXJ8ULFzI9bL36>0V!K~_ucm7(jp*}o=vgl1dc{y?PKV`FjH0VWOBX+j9c+0DC+H%f`)W^oItFDwir#t+%5sGJ94CU%VaKD0x;YAb{x zN~ONea~NNRc95gHINlK8M0hK+SMxUXlIgd3RcUZ5%=y3H=pgJkkAT}+atB`-{s4QE zDQ9Sg@wL=X-wmxz;9~m3J|*(MLuc)S4^8Lr>qC9+@4U{RsCMJ#$-~Ne2HT*{ulr~f zBPQfzEY`gZE4eL=>{oN`P5Pb%@-$NlDpY3>8!l@ws__mx*H1tq4QU69smvT1QS{U? zVjE;(OMp4k`y~eMt}QE=5YswzJSU%@`Q_G= zsq&@n91leSBxCCrAXrrgw$F3-e>m^l+}ympKGiOectSWAIS~lxj-<9vEo4sa1kv+} zt6)C4{9wVKRNh#+x?REdhd&95`95YTFGg+3{`wevLsHLpq@d$7)}pY{{&<%OaS-r| z$o;!+{Gh)2Z{hN}&t<{*gUIs^Dw({C)r6S5tHzfJe$6kH=q%SVY7H2-aT32<5vg4_ z%v4akb*k#9Mh+q_A6{M4hzltlOvq+fev>D!n{eDv{vJSBp!;2s$_76i%V0fGm=`g- z7$**|IJ#>WrfrAhDB5M)(P`7ea*g1p879WJF)2lW-q(Jv$guYKCnntNL6jj*H-hcEcdn`d|j1E zp2?8PC8t-#E9I~X9c~gOTr6RAlm#13i9Q>7-Ot-#OxYI zlfpFQY~#i8or@vHDyq+GF8PnE5774HO1ybDT4A0~48?**_Q$PEj$qfoTP6V6hlwT> zwuox2%ac8$rIf=`nsTAFOiILfxerW)D)MVGGT_SPY8SIJI)u`IosRUi{A!0#?q+P4 zRh5YJE3$!-RT_PfI6W;E?j!>U6;0GK>MtQLih69i!$j?z*jRg$$0Nn{h9e8tS^s`T z-DvYkvRNxF`q5&sxtm8N?^b^a6H_vZi!0B#Q%WGmYd`y?Z*Mf#S-7Y72jh{^otiEQ zz=niCq0&N%c$Bb&$YC{I-K924PA<-BAOg~1E&O-CRx4)D=?{D_1BYx?3Yl~1iuz$$ zI7&bvCNZzTrHj+>FRjH46;h%XO-@C*qd;1_LNyzCOCS8Fr>d_0F6Qcu8K{h z15dDD5NYw{TxVJB0_BK;2y&eE*E__*Z-Xih$RbjktrnN#=v(y13xZfUWc94Ux*NrL zr3)#PJGO6a-cC!`AT@#Pz92d8d&|5qd?R}xI{MY@Ac@xS)pr`-gTqxU$>UAXmK1JT zKNF2Ww*kWm+@J#BQ;nbx8fDTcQ$d)a_C-m#G=p{Ml~mN zyO^B91Me2Tw$r1in?CssH1M%e4|r`%(eUV8xs+97zGwQ1Cw^oZ)u^C;q8XPNg zrdN;maQ@kx?E0>tAbd-#Pojr?#@u26o-^h`KsEQZ95Al~2N{ssk@)vLc+~=Ve!D#g zCQkAEia{Ys+hSb|-{4~SJ}JMmyKC?8-2OJx-G!R1Ok0Z%B6JS@&SG-iwAl4!BLk3z zmcQa&xc49{U#$E6DuJucXO+lXLsmKwNbmdTY{JD6qdyq20$J+hrKnZp@J_z_>p=8D z5j4F%FZ!+lmO7(|<}QOKr9qZ*SQD&w_>!BJ0;Ts|f-E{cHuOun%_OYtYrwB;JzHkW z49XM^HR#xZ>v3ZbneL-gCS4X^=UcjXs<>}K?@l*xiGo#8LyVb^3@C%?ZAd8G!tXd3fit zI@#diSi2I*rw@zk7cF%ULyx1+XZ1e#1&-JB@&s*vP^r=#BQW?Ef&`JG(tZ<*=->}4 z;&(p_mmD&OFa>j4UL5%Ur57z#kt#gdTlEyc%srs0vJ`nWPSE#l-0ak#Y7Ra)2b1t6 zam~MYRN9$*v+Bcit()AN8Zg z!A-{ZEj(#qsYSCFU9U)n9fW~i>9D4U17PI-qv2FX$-PE%=4iuGHOj`@-)7bZE<1%jVXA<~l-lScD8**ME8JD-3wkN> zb~S>-lv;3BrruuP_3}wdONv-#3+;Z;TJF=!oqzU5mJQFXA9#%ndFx~E%KKk-no@== zah&Ko)8rTxme!XZLg3Hd2Vh~+5M|47FCQpuU)n~i7 zOGM@uKWUyCJm@DYo22vBys_L#%jQOr_nH}SADjE(*Q>=x>I96{9JD2$&d`arOm#21UZFwX1|j)e9@!`RK_uU2z=!w=F(n) z*;l`u6o0O_Ztqse4ei*vew131f-rSfeu#ND@tRTt-o+*F6Y>Rtl9a!W~P}O{lSoITAfFfhEpdB)_!1*in?mAweU;LL}c> zr9-wFsa!7lbRBOahExZK&ttB_KcEW?F;I@!(tDwj>*?-3{IgHNZ6^A=L`sxpAx%Zw zJ3{+SohphD|5#d>Pt26g06HUR(T`ig+XXkgra9>yD5Do1?K=ON?-m~~tK)hqj}=Om zx6Jyeh;ly2pFaXj>;I%Z7O)`2=NuhpEYqQrR_lDv{63ml_+3Aj#;}6Z@ZmZdX@KS` zZV?nD>BD+R{}EVxiXI$%iD%?$0DkUU*Bq9*NB3zD?xPFT`{-B)-8qXA((gCs{el`g zP`VLW+`-%FB#7(~r9pHD>?0p&v$5Hy$5{cTGq8ne19m2&^E z1ITe`hf15$$pWw+{ZzR8sj$_su~}gmg-al|VibX--r>qc%ZO>0uX29RTwX)MKTa^jS8 zS^U$Erg=R0BjkJU_ab)^Ynnr+9dH2)Yytyi6L$r&(N+_@Gg38%%T* z7!))I7{g{N9IK~e`ksUpa?9dy`x?u5TW9E_cg8O7c+657HT~mH(Me)a5ppZ`M(`ze zUHYW?X26&z{~Bcsn#h#o>Gi#xHB6d6{eeMSD?j|k>@aTq>Ueo+H;QmhjW+EsQO@z> zVcjPgbKyz&M)X!tx**On)G2UZ|NTpN#iyOTWl#GL^kAT3#9x9`wi+(? zzDxpD7SIo5-d@CLgY#KD)^9HNX8I?SJ$!b82gal75@9Vz^c&w}MN)BEG>JBD-{ za5xSYicR_bF4;HZ8P_UFKbqZ0<^D?93&phKr-I|bvp?V>wjf)lY@SdlNzA0oedz^z z==EyH^Vn)H8rV{(Z+Pp~X0+gpbx8#|*7+2j@sAl_y?4-D-EJoZxYN!ieHKO+P}9JB z`4e^Qb#uq@!v4n`Wn<_X^Sr@~%%R*Rk|tJfhc|OepEzqbYPGQBp<6v}Z_k z{P*t|T9dxxyOS*ZLh(|LAD8xyf;jSE*`^j+ZLU~|4SRWwCf@sT4Oq}0`zSW*xvB0$G%JYpIl#6H+1uWhIQPvb#{9`q$%nJhB}Fzt zZHgfl;7#*Y0N<#~Y|{zqG4#E-3JXY+%^$7g1U-No4|$9t_!=%7EO{F5Pf8QBK=RK1 z-CFc?9FVWd#LFie@}-m=fnzhowPvq3KHF5;ii?*NqqUV9&Z$_L!EU z^Bk$rw*_}NP|ih@N9(*RZ|33dRr+;dUPVZ<5yrj^sHqm@lt`EulcyOkJ-;Ef#DlD6 zNyDiu(C+&7fQl{64G`gY5=u*f{F_zKOK=N|-N)+9KVmwbOp`V8)0k()TIQ$_jtI`> ze;@7bHaJ6Udr-jnqP%eoSUTIH)pS9=tWPZ1c*pK}`YdOtjJi2$c6kX>-a(R@z&4a0 z#imq-jc|gqNX`CT&Ou<|cvIegDa=+-DiLgMHUU~rR%}aitvq z2q-IddSH(;_VpVyXRPjqa@azNZLh)si;j{YA#Q+(x0)ZR*b1+@Je9z{;yQYSQE8q^ zaTFV8bPfi;f!UlA9i8^#st??cXkpSx zK`tt{x8I!L4+b$jV@h~*5zP9Yv#9_|+sVkJ-*@zA6m_+O-ruA*#b%kj!%o{OmdDo~ z-`@IiXhTrXHeuhax^^3OBT)XY;VJ4}q2hg27N2XGejI`V*%g_x9ih7cUdT{h0UN#v zI|UP((}6U5G~M#LWqf%vyTEy*D!AE>QiOd`FF*Cw?wnzq*NF^VWCa0)VzD#)pads! z$tEw|hwx+uY(w&%x6$N|XHgO_yf_DJjI2s-av?mTb2%$0H8pNufuS`ON`wcicyTeM3-uh|cS`QtHGh43fIm_5@CiE9nkYs3O9R8MH)!m^wvNm3w3MZ;!$3^eT1d!X zmkQW6ihYL%)4p8Ayue=mkycELKmWausN`TT9?&cOfdA##CnPjB8s^@P&x$ z@M21dt#E#E-MF_aR`L>~&!VJaKcnSVmn1$`nEdyY_uc?$yPNk9?dHMtVV<+;KpBkQ zI%mmqEs=RR9ohT%q zJNcDBspT+*&eXxlC;VrmUvo?CZ)+QX@{EnzY_(b%x>9@}f_cVlQJ;pxM`e{v!g&;k zazX+WI+YlnO)V@xj-(~g0e#m~m)&FZ=Odv;9^{|zEDR#ao&S^L*bkrpI~YA*WzxD# z!S4b{@K;7hhu(E)QM@F;Da!;foOriIYg#^c zb*8c1R$vT3Czn-Gch^LtSh42R)xP(4W2sbc@-_bK?d%j3L-z^lCFQ2y;nO_BmW`oH zY|p5zWv^?;>{Vd>yj*>FkKH*FQ3)svH#hG*jq$bUC&~g>_b1>#NGe?a08SjGd@`%?4 z(yOm1n75Oy4VU*#HS?lABV=w=6c`)Zo}(9j-zetTWs{!J~o z`XrPm^3-7p82%#Bf$+>b4ntF8 z=RdPLcfPfY21WqPp{LMjpQ*gsbw9IxpF5SV_c-L{(W|O z$_jx%sAy?g1`H}5jvB#WFtApBllbW(0622M(tE7Tv2;7z?OxTRy-}DNj0LeAF>Inc za{a02VT_jHehGF3y=dLX+CHSkxVE3bEw200=XK?0Mh@WJzRQRT$0j}7j~8i8s$ROg z?-o(&=*qe&rlx&d=lLUNFi0;1(ad0NY#(7&D|A+pq2m%)KIWsj3>%zS+fleV0&>4l zQ7xki|FnMUWSIxDa%Y|+09NNe_=jsCk(3rtOb3(- zBNx!Xobhh0Iy#dJbsB2fyAZ8*rWZJGS-amlSX#6T(3T07$rHzuL zs_1PpI(NeOZf0g@A<2P~nhG)RO9Z;bC!ot=;OT6jrE_5SWSizo)Zc;k{cDq=$ap2a zQE6Bjz=}?|#7e-}r6~wS!7?TkPaWBoqm`B3SVrA>A7)`1$HPG~{dVg%!2W-iUapT= zUidTeeuY_{DDqJ_^UeXQ$P6F7n6bE%5yk}crdp;u(@qPZXqRj+`4{AVFUg7G#EHpi zjhw$*`vmQOR(H?6IX2G+EEm10Q=Wbg?~nNqlV2l%PVA75e-JV7rqWQ644*!nU6Ifh zgct$YHl&O|EPfS|eIZFUUf?JQ=-aPtENC6*1olc2s31rC`vckm1>y`pI3CM18+TKc z|5To_iHTd_*94wOphB28CKM@FHO9=}iBs;JaMz8#?o0%LZZ4LNdyqIl?!ag7Ik_6E z&Xi9q*<*yB0$}?ZbJ0kS^{OkS(xCsx(_64b)wb{3AdQrChk(q`AX386EgecrNQiWI zgEUgo-6>MiCEcJjLo*;TzyL$@U-$Fd-uDwAY_7Gg>pYKR-$#J{PL)=5f#8nunDoOe ze_T)(UjtdNRvFQnj}`*xFOU8lXXlB8VX8RMT5FO5B{{_X4Wf7-)@ND0(_z;&*ynmw zMIS_*TiXCcvVA)L3w@Q^YABaT8v=;{KoI@4X+_jvg`&ftMi2O32l#2VP0e#>{kQ?L zfpSwK8ip35-O4sNkPeOi0YZg)m$Ki9_S>Mmg~il!eqJ!% zz&2J-d6?`SS3teW>AD~%-oj?tBYmJCCdnYZ{>l{n&)Q*{9M_6MSKTy9?T_}wo}$4M zlOkWz?NEu7?q}a7TqS*11*gsm{?=i%wzj6U@VdWteg;N;XNC!lmUzRn?N32wWPukM z840QpX@#Et73zjv9=-?2czh9okFdbKrPpV8Z%l%SQz)ZvSIeF0#Q}Jw-{s%;Kp|ao zfed*riKtfEhE4E?c8wGo7Qp16R`4~tyb$9)y-3~-mi!% zkOZyw_xBTR{ldo^^v%*>^#Q5?TRc3!T3gNPKb)R!%2cw;W~7KHGV_mcQvF)!`kn%ZJmeoEhEbh z-p>V=BKO-Ycdow7a~L)BwyN2rJcDyi0+c2EtT?eISNbBdS0}d32WkX6gRq3RoiT$j z-`DHg7B@b4K|m|!U752X-{1SLn~q}0EKTYy?TkNNuyJ?XxU^wbN*{X zjI!(2k|B4+Ax=)HWA{xOP)&+oavKCZYUBWi$27;H zhIAVvFV+qi$Lzra5i~jr!?(AIY^@E#Y%?yJQmS%VOd_E>Zoe2{yv5=VLn@7NAwLBu zwaxrcNm6IA7B|ASvWx5ton;jd$q*uA&~AV%u(JdB6(F16yZw|GY7UM*mvsao(+efF zR*tTe)4K2a#fQj2`$&oV;Pr6G=Rz6XEHl+ccDnrOU{x-0NIHo6f&8bD#km<_ z${t){3cr(Wxqas?>bo2rO~$$_Pk;9TpN37~Hm}+sg{u20ePU0?J(ZN?j73%SRI(PZ z(>%8vt5cR(CZG41_^Uo~__0GGm}lpZHk_}nV@LIziK%V2fOy@oveK&a^H&pbTZs1h zZ?sXn|0Ha>VBGcEfZen`uY`KfS#G&*&XVD<`DiUFeGDt-4KR&R7m(96XPlvM;x?vw^O4}iV+!!EU$dYp*9ma zQfe1GVBQP3rVNTYJ3E6DIS}57?U7Q$R3#wCpT3rVRXYvI6_d#mrf5EHa#>& zAg9`mCuvyIb)Cw0?@lOE3-Lg#(RCN{Zx%%*&Q^)8tk~U3b$l#!0y+@D!iIo=Fnx+5 z!&P4H#M+c5{2!Szdy@RZCYNd(amxvUOU;m-+28RX4>HT+MsKMHH8n< z`bW<8->ikz>iJ#-M)5G3&9?s0#Nx`zb9n(&$*mvTnI854b5#v`?Cb0Mu1p)SA}d!| zW=A2uNy4h(7KHJ9c~l%Nt^6eom#gb5GBo`_i~7G;0@Rm&_3efe9}No0_6@NpL+3Zy zn`pOY5Uxq5j~seX0uZ%xYc2CWmv9(56CQ-S_AH1htTcX^w`*%Ayfdm>u&p+*?XaVA z>_E>A^PPab2GGC5fFf_B#5ErHqGe35kN%__m%0^aq9EvhEum+*ZKq?2z>c^M?1XM~ zTF~FY#6Ic&Y-v%@*9(13564K-+n6a*!1)t(&+BtFS^9c9_uz}@SLHT4xZ;>D84tKa zQGjbS@a)b^r!UCllc-F9USx+N3N4HiD%w#m?6_1tpX55CDfVeFD$; zIIqJjzGD8o_9RG@H^|>-ro>{b65M#Mrq1nkw@3O3uav!BG8Ai_ziRVw27p~kS0uLb zewXV=ctd?AGk*(h`d{HWj|+rSk(m#dJ1_r*veP>BF+FP!)~NWyWiXv&U#xq7(qRwR zbiKE`^-|K2v=aE3M~D3NnOFhpKEHkuIld+QBvMlQ87KS{5?mF^;@cu-{hj}cyU~Qv z*+yFhORoe}}PwjmKLtiCEg zqVI1$$g_TVXRE58hE@mt&t4QC4~qDwYL5b$_!vMFkMTU_O`ZOg452P+(hY) zBE=k?#3(gwzCv3E@uvExP?d&0I*HYpp#jT+&a_w~ZtA4_;nQZ-=gfrHhF+uBEiUSG z=Lz;S${r5{A*VGzdA;8Voa{?d7C);!MLpyk!WyE5whwWJsn~s*9%T(GL9*lJ)9~3> zs=(eHA16l0c!ygc#bOa*aR+nuuHQKv+r6eK%TLH~g6uK8{MH{EdeS=wy;WB}blv{* zHR-xXwZQ!ysV6yGcN&vMwx|Js@JWtcHxZ?_*8@BOy)Gg+-)M-u8<4#u zJi2@*ohgXyZZyd^Xy)WGa$AOSn)#joF)M3RZ6YfxohAWAck+lV5dM`7J@4!`;!f_% znX>Or2=_SR`ksWmtL@ZQ1tyZ=4acmXMl@>I1%n>AxJL4$KklHxS$2p1-A4TV%L;w_ zN_V1q6*f`z((B9HMof!*UIL;_BBX1;lk<9^1Gv=i|$Ce_cAk_MkgneJYJVc%oEO<89fS^) zIb_T$zx(U47Pm$B+6=i3cSQ9e#0@+7)VR8SF7Srzh`PZWc_02+C zV$wqo{r;;wkRTE*=xBjj+Z<(!%oVIOTR=vMRK0W$=dolK`jI<_+wv{lRV*F{7 zp~5P<9;XF(25Ezw0N5o`)AwA_8? zKmNu4NV`Mt5syA`w!8PT1r&7CfL(B|%whD(4gZ#$g;^ctKKsMBqWPM0)b-gxX#?(i z$KWyv|0=^3ZpJI?CqYn;f$eCe^kK+EDU;8VC{6YL&!gUG>Y6B~BXEOO8$c%XVZX9# z&zTmd*dH{LuHQ{l*9j98FW8@=o56=}6>~#wSBTv) zcK&TV(-ha|*k1Ro8j|l^Q)B4L3+*FRm)3WzQ|;6-6>0gtnHcvz1%>@Eg7u4EClsCf5NojV*AO68P_A&B zIPG#tdnq25H$V$-zwYyZ8brF17rjwy6);6HUb)P52p-(CW;@Z&lN0~#SA5;Y?!5j! zTuXd|TeappjZ&vZ{D@^Ek@H&V{5ZtJbt{;5;nZ+Xsrk&^cW^# zn~YeB9NANy_x2ieoZ|@i>^|qHgR&~EXN)BUy&w%Qu>F!Rp#_q^4yKF{R~EZ-^0NE% zRArw5mMCj=h6&23b$D$t4ny-KvhQaeJ`9^()BiE^Ye6(6?N+9p<8v zPWovNnM^WUC;c>VO)86kI~x5uQZ80NSGS-lQ!Gc}DAF}4Z>fc*x&c%YYPSArnVj4Y zWibIJTuSow@Y`D#u-^NrKmDHY-Jn* zF0Gy6ssf7geXIO9kmNR>Y^yj-Wcz{0lzD%xmS+AC)7g^Gi%q21*g~_7>_> zZm|RDR$Fwu+<5U5DM}5undfNpNSf?&&HZ^q*Spg?i&f;?KX|wNznr;=;BN2RNNrKj z=dP9>4Cz95#^I&jp*!b~dTx_b(1b4aXCb&qx@Q_u8YIEP5I5lhgVC}ON(-hqxG)A(fw+XGh>ME$QSc(H#Y}Iv`tle;w#_eLCfXG;>laUhbGv zq5Zxw+VLMH6Sw1{pn!eg=sUC2(oVz3ns{|opds*5*D&5yjMT_ss+}~WG;DhZW$%}% zbKUNQXpG}-8&H!YA3IjgouPRZKXS(n2KZT(l}Q~=n^0hSdEkG+8I5pX5#4j8PQW#j znRS%7X0X zweEiVbCDXY+v9>Bi9IF@>Ndjzsw<|a0K7tiDMQmRUaZMMMh^;yBdHyI)%!1f;s`fmc)T-W6^&uSqHRD_U#bG?%M4$j zd^b6i+p=l>kPF7`pE-L0bQd$;IZc){vdkNdRvtxhJ!He4tQ!FE1;dR`;XVF8O_YU6jY^co%=)SJpzZ!;xazpWnm^|!c5ZZ^GO0gKZ5eJwi(2!ShFYq(Pq@FD{N}w85_Li_%`CiFRo$Zp)Lrc0=mW-G8 zWPFi!?;nt`>KlNKyXOKurIH~uw5EgpI?eHl&dbf+nx>^=C=;6`WPlWNR;5IjfN-tm z>M0=|oo^(*Axw+Q_C-OREQDud#?;9aBG4B+xQ1Fezs( zd)R^Nc**wV&u1L~3}Bnnzh&b-R$j>~Po!QWVBl@UOG-tO&6S<~6`R;##XJY_R1o`g z7}X@Ll0`WS@DhuCiM-&e#%m=Rcar#xWXwPG65F0B@~p2Zs^#*UP!bsgg*LOcU6g-T zFou_B;YT7WP>Mr4iD3NlH4|3ajoeEPLVk}o{BjVRnx$h8K+=?H6^m4*%(8-*T6Wkx zQM*475?iFGWATR!SMW1{7;pvXQLjgTnhPfTxdPm2FpEQ8A2qCuMmt+bPB-fPzZeQ0eQqI2Z5KF{3fM|a zSdDycQpV-DK5A(R*II-xiQpYCh>~<*J^RAFFDK{UYVdRI3-C}T1YFB>P+!i2a20iR zqfp9S;Eb(%7Z)kp+ZM~spMc5e(NY78&04!>!ieQ;)vInE`(QstX(JuMZN&x2$% zNdY$Jt7M$Kz()}v&%!FFc?v*1&tpvQU*asZ26cYmyxw>q)QB#|gKftgF1(*s%2znqH5Q*J3i8s6mGdJbU99NDDsPKi7#!_8EmJ#?1?_tC*n@sFJ$L zX^SdBpu%?@rtiOb@9z63nCHDlH6p>_bNX9woa6iY+p9NMuc6HEBU~LlXWwyjI08a- zvN**3#sd;4GJfF5FE#oM(h1eH_gELEZ!P1C_z7A%Y8LZ-6x;3j0;yO!^7vp!^`7Jr zxLhFtg3wjRyK|A@r@^iOk`L^8o&xS#r1wWd5+%@MubY3YLJLA2{!fshva-eI5?Zg? zOE@!9LR56?d-pvnqw+4$#l-s8hRFiI0@$g5=8|c$mGp7xQuQjnS{sXZ&o0$eVwFM} zT#c+w<4CI_Lr%hIISHrUGvwyJ6jrSIhwqLV^A3kCB0Sg)e*0h9m-hKRtFo@^m~w-`;P* zB!)=0-h9Ok%3$YJ-gc0Cele6%_H7KtChFg)N1MoQAuKGqizRXYqTP7xbG!MPgFdHd zXOsuC++|8%bIrb0?~2Z~P$8Rdq^Fixb0vGNL#_AK{g|7Yq>Eo}b~cMhm4-2On4e>X z&WGl_G1qi7anS%VZ{!R3!|4z(QW_Z;c;3h@0)cGrpQ0b*m7*ByH@D-vca{i5SEe*n zrIzAj1a-nGF4@PD&SVitpgj#R&jZOa>_k8Dnf_R-)~}uCB!4}rMsNoG57UOlaL+qz zELttD^lEtOExPbr5s01t&xxT%%<@z}F zv@OBMp^%-uT0|Kq8=)Ehp+m#cU|~$<{#En;hELxnIGmIVa&Wnyq^RNwESVzHiH2&; zcc!2HeQ$$AqvQ_w$IAI?k8uR?M>bp+tXb+*n8N zZN#>1Rz#_NeH`x)@kBMPCMk81q<17T=Orzdn#r1;LE|jW_{7~zu#pQ**)_#mZrKp} z3>QcwpgbkYe-G{;w|bKqrVMvr+bEj>akVPd#4#nBLEXM@%iV++^gF<849Plzar5)- zF?_!ch!hg1QK%31%38bx9n{YkHIdq8s*xE`d=Y%>(GDA_;_z8lBpYG+F@wYHO*UyZ ztcFL&Ikx%_dR$jP@!2%$h=$v zT}}q0FLGaUHhV}iEOAF0AAD;zOh8N5$;^&1jrvO}|1yK0!qxaqO_&kc^4FFe{3SWV z$e;A~XvU1#d&86|fFEHbD*ylI0&H~hmrh$ITj)`Ki994M z9HC(%kat1z*ZxBcu7u<9u)(P<#7prB*JyUR4~Br3a%`6)(~88VOQzsV%`EnlXc7n? zCkr79C!_1bq!FX+_u?y}RQYN-*R0c2jG2+Z7CTgwYu?6V35n-{rQR5=Lc2F1ppH;L zF9MV>w9FP|+SlrRyhl7*wmF8X-o3uGZx)I12{5I~ZZFs+D9#}A8Bovq-3>jzJX4B;O%3&bh@giVhz!xG;NmVLduni@R`e8|~)QW+dVUcYxwY@=f;WL4G>H?1N7y2^w?<1pJUmU2>(#$5aXqWdn zH5nkzZ!?ca8yZ**tDJly*x9Ltw#MpmU(>zM&U-gNqN()LkSzMp;C+LUNrQ>KX6459 zb@rK81dg3?3hR7q6jOq-?I70kaWC08YfBadEA&^c8G$y6${)r3AtXrl(XEFh%_S$l zj~b&N4^_Gz|B1+dx2XY*KC|YUY$3%cA4spKCeg;;v0c*o#sRB0&{Sii&B-&14&gr^ zI|%#CXDv$Y?Bx~anOjI{R#VKrKX0@{bkM&4=q+0`w4Fn?Hsc|(6VBk9VwbM2qNWCm zWy7ucT={I#mB-QYpEp%|ZjgXDGs%aD*2S(G z3@k$PKQb3YjkTXzszS?(3u+BxD|iivj7!XI+Fy~2e&F%^)2<4_t1qdg0S3g$BPoUD z(g8W#_Z}eLUAylnL#OY-17~M^%1XcXB<}kqP7liRfWxA=nwlE$6e%gW)@lcB84dXw z*m+<6BU1)jHRzwC$6-iTR^qyXocu0iX+oa2I#E;ktSCEFHrv!$&s9VJjn zU8oEBNy(cWMb=z-U_n0)a|NcNFE%E~x@h<5t~3jJygN=hTxy!c0v~}WEO5+X1#Zl} zW5~p2`~QC0f09!m;JW#MTvxXk3y<18k06w|Pn@s<&X*O^2pg7-0pK*-dIb%*v)@D5 zrb!&MhZeU6sjpJ-Leo`j+ zaeMoxUkhnn;ZTw7nK0|A+!8-OVAb-my=|{9;EDtq`1J5Qf#lZ~>*^X>WTciN^HqKA zVT!g#%L@Kg+EF0s!Mn<8Q<)pq^_Bjn*t-cKd|>cxv(YdG0s0LPY489bmQ5aE@orIj zmHb;`ZW*qGw6Guh+$0U2NM<9{MlBbg^IPa*;|htK;R|+?C-zR$@ID*P59CJ9{dqi; zgm?7W;EPV5eAMXb@RKW`)z#I|-!v=*0cSZF5XU(ZeDhaPtn#kls!IVG>Awi8`979) z=3hwIR+Zn$b2+b}KzSawFhhc!d*ACsa$^aFUqg_*6YxNlgo~L5q~Q9$+k)R;$>;Mq zIUH*9&Vg_Mv;AR)ngT7|l+8*Sa3=&{K!JBHfn%2Z0DTOPz8pjHeJ`&_?5JXdFzVYF zX|{*5N@c4Cob5Bp8lY`C%XrHwu4=lg{ZD_geLKx*FW_AiFAZNOz!_h!z}Q0x#v z4M+3{YTLj0m!ct{lEstHnLd#?(cK{?vcYk7H6>1tnxyG{EaDu^z$0i+^Dp!Rc?{K% z!Vu}eSKx`EdsVp^y}gYV@Nj6Vl}5j={JGgdmH#$DhGyc9p=0W; zdhW%=!I{@PUEM!fTmo8*HBIL&E3@omYok*d%MHq(KKk%(%#>8y81fC~=H#4>jfCy` zq-sqViTMtGHw}oI%Lh{)+VVdtNf`0&DE=c5U!-s}|6kLQX6a@5L6O^LC{YqPQG{8Q zKE`*__e8u+f>bbo8jZ#AIcKXPNk%mdO0kTbb)GxI&@iQ@uc1hio(lNtRI?E|=6r2V zh$WE{GS=(#1%>_YmKn>QH(-~Dv|Ua9e6-S@ha-HKdzWMI!L>wuvWXM$8uFriz-89; zXj-aISFd;AAlEcjbeA>W=#)RitO2%4=>z89QhIg1>Cx1mo@68#{n#gE4oQ@58(hMK zk!{a>4Gj&|`Nd5BhiH(Z2JtNS_xj)^NAyR!@hcUYN@7B(A+L#P86k?3LTe3u@?PyZ z^Bhpe%q&;m`+<>>s8bDwe*NE-8SmLKMobMB+|%SyfMW(U25ChfFCvC^&>0;PqHf(< zS?N~Ftl{V6l-Q-MeCd)$FqHztGu<+SrU7<{SXALOF-&H#s86_v^{)MR%unL?8>-3f zdtbV^R=cNpu8`~kPA3!hyId#8d3Bn zp3i^KPFLNxuM)MX2M5sYQx-`SZoWdg#X_k+nK=cJYK1Glz|%CqZDgPBD&bVgOl)JM zt{_g_C_#~%YhE=n#WKjRIMmp%X|yoVBLzki3D)#niBqZ&(^fWHi1kf+5$TrS`*CKU zkAq($Ws^Hlg85V>Au#?uZu8Pw*5dZp!|rzo^5K62hax9%rn)KA^#abs>-S&#G?kT3 zR?oslyog`EE_J>*@^Dq=dVybuCh~iFW+Z%4DRpzgD!De{qwP2yThAM*New1kw&8%T z7|Kzk9yCSEc({W&aqg|UZrZz2?ZK+QT+^(R2uptNn%F;a>N~N*6zyyArS@RQv|>tF z`&FkcT@BO%g=W@;;WK!8M0$-15qjs2Oe8O))kql(MUeIuHT>b_#uXrzBD%>SB|A?k zl~fhAz{;Q~_iDQmS3)$yX@>%i|8jJov3heLe0Kx_*RAh@7Maw8;(0n8a<69cHs5px z+{N=;btQJj89|-AA*K3D*6=fO zHr0Vgqu)=_wI@Cqsk6eGJ=2D>QnWIdhQnx!RrG{t=CkMq^okU6g!mOnC3SVZdb}d} zMWYPr^OE+M_Ej&6__wYFxE1K61Qvw^I~AiM3T#Piq^yz$=3PDeXs4{XT%rd! zXvXv!%Njz4^HsWAU|^~65Ho>U#IihxWnCJd_v|`xuS^Oo9VWBaNqc3o%KT#ZWCtx= z@O*s6Ms`jR%+snBy`4-FMWBPxaKZ#^YHN0&jWy}9vcD9%zCyC$ekGb4&a5%%ChSUxXL!> z>KO$NH5+L!! zDxa(tn6>q52R09Y+Fu0*bHLg@2z~!mZ|(}rUoh)zo8jp?Eq@L1`}xB6Pa;IqPppPN z(aO4y#jslUYW>#@lCu40m6Cr<*k?+hTXuD_zFy8vxQjNV|CE>qE5|f*|s+j*KP!d(BN|4zPTzTLN3N7jKFT)dwR1F*9I z#v8Q{Az$>u-B_D+%iqn*E4_o?S5v|H$?{Az@^ zgS%UcqsXH+9tKwxIKF6nIs7o$ce5liq)x!_L>1- z(7Rynjghx-rza>{3cry_?e%|?%*)H@!zwbXVo)h{O`8BS@DwF)Ta-3Xl|@E=lwQUa zZCw+IoU|+j3E`kDVqMMAYxgp}9v^UMAxmuK^g7+3@4o#TNU=AkrGx1dD~~IOzG*B< zBd*VN{{Uq3Z?4rDG)Y;9hK6WqX@3~h{L+V>oNKJ?EMNaw zo#w0aDU$`%gtxK6w>qR`8kE3n5r}FluD8r%JjsDSspdt( z2!}{AqKG~-XKeaG*dUm<#bpQicPH9T-F(O;Q%aV#GScqaU3#B+{f<;x3E*X5Q&Y}< zhVlXq3fI!sATJu?cPx0;faJnW&@(@XO&d*V;0B4z@-T!=t!x(7tLG%5)<5&ZD@u9T z)Dkw<5sge`Mjp?lw2Y+xKH8@LoEc$k%(j=-Gmy^$3$YDQFA;St+*bt;r2ejKH>sO5 zQ4X)t_;>1aNfU+v5n|igE2`%m3G~ZLv>bBZCcJfZE2cC- zqa1|<3oL}k(b6c1J#qWJWK;24eBITAj4Jo-42fQAkV%Y*g*PRSTSNP`4;Y!C)LzOR zSC!k-Hps+n?Zu&Cu3GhPNHL$Ygq#TpvU%$2fmhvVb=}@h6SXngJEJHvU(Xy*3!LD2 zA_vMnE5!Di&WViC%1EM;9_ey-TX%YObr$4b7a54m>F-GBZ@3dp6cEEG$*;y+PKg~7 zJ$*rU74prT^otBuAMXk}nqoAu{W zEp1X_e60okT%pe4!9ZVCcQE6yR*NOq=ofkn6I$v*1+%~ecb}ot@vq}(#0T4am2%!H zwn48(46Jy_1fWYq9A=y|KYv~MW^PKTkE->|o?Svnw)=#yXknE-lLumyl#ASlN z+wdtZas}MtRIsu32b$GthE6_g5l`w&!sQG zg5`^lA-Acq%TM8>3HO~G=Rl9U@lsz8&97-~wH2e!Fl=LIvV=$331&8<3xOV}GT6gi z^?(|WbvbphS+$9enCl$ZnycO3l_O+V_5W%#%!U$wpq}9z{HQOj+tvsA4-K=1dBN~S zh@>S0^D=U+h9-Gz^F{u_7z}dRn=IzHRp&dJOBks8T}7oTU$!D$qD$uU6-c>NNb#A! z>lhDR<6F`azpKpNL$k4kN+D)6saH5+VM>~cwdsG#2oz(23c$GLkX)4Bs6Nuy7^0D$ zIpK@GBf8Bi$K{nTww+twx1QWWQIic+3fT6w7;Lywxuha#gOfOTaedFn{V?09Vo;1p zJ(inQ%@UL=bgq?xq`&hC1wQ{W0uy-ZK%}I;HjgzE%qp?wB#%k_{${e%D{BBeg`uSR z=X3Ll@wrzVGMeeQUrghy&a2@-16@9H_n5Pfal^)FU1vZON%r6$;!VK$mLl3;c%*$h zn*^0s{l(zY8izqNmfhr|ppL$4LgZC6h9jU?b z6xBSM@wscwtw_;%H{U8GL`?dy$1YDgqa>+0txd%sHvWuiO#~&x{2Tl+{XMt5t6z&V zwDj_B|M7JE09Bo#dBu&}CBJsj?EV}&$U|H6>_J+XD_~Zj9`nR^K4CCEWJLr29vp_#(b|C zkxqv%Ba7Va_C%R6FQT)eXla7@6y2&6iu~Aw{fbVQ$U_)IBVb_-yFa`Zl3W%QsB3qY zayKkDWLV;o%4@{__+v{BS|fMMx+rYL4qIL_`>p3Qd}=morU7yxBCeB{|Fk+LdoDy1 zPv^x5A?riQDJMyLUhw*w6atUQhBX7+V-Sbj%BVlEFZ`shvCy6pLyghgL|LO@L&{Xi z9HBI5{i$wf+gUM~)jv9(fITRIsOb6KO;V&Ui)pg(e1RXm#JYo^z`QhSRTjP~U=(le z@bgx+6K`*pO8v2PB${CyUM`DK&zm#*jKvUUQ$uN6RcTo-oNq6_(q<-BM>$mmr3ZWl zO6yWFY{m4|D(dP*u3Dopno_)Spb$KClPLZ#IdX?D57daGz;9@>J(KF_&T2`$8u8vJ zqhn7Z)90yaJ`H`z0nU%f2Vp>bsBs?XC^XKuWV>xS7NfAW3{k|UDwCXV$p6s2ikmkW zBA;(cH0K%@IvWBKWpc8Yo@zb z724lOy>Whg77k6`kH99&cFGG){JBxZq?vhcecxftT`J}!Ni=Sgl zf6%(|R~+R=x+s5jAdN^N76wkt!ewXNN~DCyXi58LU;Ig173*}@=#u958WG_ zdQsFkvV+Q!F75!&R>>>n9QEijPOSNlzqoy%G1x1~dB4N)o5$%G5>PzO~?o zJcq`~Obd3MNdN4F*G8pv0w?7?giJ>y;5kD6*W*$$%bJ1#*O7sGB{b%6%Cr)lV4hYjq)d>u!u@#Kme;nG&dzD&>`}5SM5_hK3VpC#|a{2 z3g%eO2^-StO8EP+#8W2RFVCE8y}h)gf-dj=K>a^`>&oH}fr#y7Z8bIW>wf)bY!-5E z`UxKcT$8#HK(Ig;8`WOlWPL-7mYx=vUBn6&vQ$90;#4K~QP<9Lw*F=zv5BT9^7;_K zF5v8PfdbeUH=b7uWwG$s3uZlx24-4JxQQNn9}^Za$QSVqx|w{N@zp2oNcu^NmRl@W ze}ssqc}6iarXLhA)<97Q3@gvnW`VKRv#&4yySuLai(u$}qEA@&&c3$P(b@J+@@)dP z@j$LbGzXA*zZI9%=?FQt*Jn8mHp-3drn(Y;@3L+B{di7T0>~ciZfzA}nY+zURQ=8i z(#RK(e|9-lj@$yf0g}^3!H&!Q7p1?nZ@NsmYP-?u_?6eNwmOg%r|Re;oeKv@TR48t z9K@!a82|M5GsuQN-Q)&=Bb|E#<^oG07#curZNVakg7RA5p8-A=Jcs?$W>H0Z>*j0g zx?>qmdrs0PAa!)$=@YM&^de%#&EM04KGShjrnqGh4`&ly~Ses&VYU)phiXk zsZ?ZXq>({eY`FaGGpS45_Vj-#3{l1k&8E~kRRv`YQbKO7Egmnc;?NY zA~*e4B+@V1(jX|Jt$UPsE9lD7|6jl0Y6bdWatFwV?j+Q$CObTg~+MENLR(dc$( ziLFPq-rH>Z^jNY%*=^%M?%iB&k@%pX6`--5ot?dr4KOpFKOW>g;Q*G-DZm#w6_`7( z(xcRGUN4FJ<)7tF%&nTHqCftwD=)3{mR6EXr+e;Tli%3@#eY`z4|d-7`!50?s!TQE zpC2FLPr3COXNRUws=Oi6bIrnbn##0_@#+MiQQ+d#u~gJ<_tgC*DisvsnXjx2(>UD$*m8V z5n;JZCVS3qk2)RdejFCauTgqfZ0KLd^n@hOuAdcSqKnPb1k`R__RtlQf!2G6Qn5+vhHKK@_oaA=9mVKwe#4_% znx(h7)Sk9|BEFeG?%06CEcp(G!5;EtiP4#5+WnV0;t)AerqxSyxMigDI0M*r&!^>1hbco5T8;gY z0dL7HyQ+uhPsQSfEWq)?IbCT4YfXVwX;gLFZM*B3tuk05ij#^0L~CjX#NyJChuLCp zWMtzT=u@m0n*YQVe{z9t8$b8TY%Xacw<~DU#KefCxDlPM@2Xx5&biT#Sw{osohH`8 z23yQNr(gRM>~~H+ce&2kmtayJcl)Mrb2FZo^CSpy-Ct|-Bx``XEFbh!rT)SA0VI`b z^+38>y4yQSmF}n}^&R>aDSbK0-#);^GoN*+UYLY;7KQ}uGojdoy(~}S5t;n9Pnxu? zBdIuzx)Xf|@?@c$T<6NobIZ+d4>Q0}qsrz6#qdF+$LkE(zC{@nki`y>>FTra0Lqp2 zPLc&)%Cin+if$BOJk{6GW8FUcdS;V-r7u7}uNvx3jG8`5QUQ?|L0Y-}7#3F|VYmVU zV`?gS)$URW{|e8S=YN{mvtWb+d%OAOYN59scImN0y&@x6M@%o#=^e$D!-vB@eh@Ht zUCE9uc65H@I$uSmI>(_lk8{xKHi2rUbgapd6!`E97)DFMxt>cq}}(Z`K?m; z24^HtJhu!0LLn&;#~z`xNhI%W*Z*?$THq${&u9H#tbOoJ0`zu7 zw>aOor;*zjs;~G&YZ2RplEKyO%l%)RTY9IofZ)>Z+acwo`8p{5h0oZ{A|d7G5YX7S zn-}x4^K3!&IZJQ--Awn%vwwe+CVT+&(Y&Z~QEOMLRg-?bouJolBCiOJ>OaX}zsd@A z+Z(Q9K33VTL;&0rkGJ*c5UkSEsH@98P2c#r*Y` zf1|5@3<&~VY8WtZHFR9F=6}It3&JLl$+3gd__orHD!S8&80W=!z zx$fTw94JU7>qMTn{e0xUxh~#YTxH zk*m>4yHj`_&oT7gG@#ePKTa#HFsu-z#GraDxFxu`9lht;MnIbwr5rCY$MX&4Zz1nQ z0@y~DKu(R%<)zWTXwDkdVsbnB!wq8a@{>d0e-(@pRE!*{t}AiEgU(BS%Rcxs{f&14hR6wb{` zVXxkdAuQh0!>+Q)Oh>m-PYbKDX6GuNsT5`nE8hm@+)B@!iac$U8$uMQCM@~)fIhJo z;o;@~qvf8{#0L zA;>OAHg2_?X}Y?M#1Iq{#_KpZA}%YNUD&lyKBsm{yOYA+@o{$#{~WP^2;%4lj8rNb#!-I^mLO@0_x7o4Q zGaY{JQx8iqI)`{m&qVq>hAO#j-99wXff~U zym;*VEU^A_^D1-ts2lRkxnFgM9`8R1ee_A zbMU~ZD55bly2m87f0EV_A+pn4Y4?c)ee+xY>i1!Kp|g@*<|~etGFNR}kPZVXACfg+ zc);)D>gO(6Qm;=X8oKPuY_)h|f+J z-F)j@3dI8JTdYKgcGJQx+ggVNC#GB!w9|@A^2=>C6kqWq<{d7W!vAU=M$Oqs>ZR_q zK&AIjw1WxojvUzk5O%Y7kLYE9=%zf@o&0-Jox^ke_L567*{wDmNODJP`q`>uBpGE> zkoU*nKyhJ6GS|pH)`Cx5P?Sg9+H=#}1;@MO(@*kf5oq1*AiNEE^MqVct(@(2 zfPH?Qs3((8A1Af_?zRQ)(>XbKfZYSoS;=*DT-q3e8}qF;)%`yKaf^a6>a(PLWahsk0%#FI7sC04-ESE;Qu} zKXB<>RBzKPoB0u6&2_iE?472~YY%?+_5!uft8iPpj4>#7>u~>)y}`2o2qbXvVl3pb zeh1Y3xiWOKqd`!hh*8z$o87Ob+-FV-`P?|u!<&E;T8!i^2XE8JxEZ8kT3+k59ClN| zUCtHo(^~BqeAh>|gSnEK+NBz!tSAkLv=X&r_QP-2N$1tfeAT?N8Vr9yHvU2hp6^k?N<|#w zJI&=S-$Nv)L*+i>>Fb}DQf7bt-iMjiec$a!t1CYDxGvc4N}P@AO=Pq-!hH93Ek&NO zaAI0Tn+5OlKp)|w11JA9_r6gn-c27kJ-f~;W=-)&=_GAA20yVWz13FI!Strn(ExhO z-oX5vRd(V{tIX6eJvF?D1=U^CJa5r2>Ls~LOrEgsjw|qUr2x@M-V;cuZ2O(~ z_%ELqv3@gO@Cc*X!Kzc;sqgX{*{HKKu*v1~nHmWq4H?5B5V~kt$tT*b{GsYEhe71wxeo~*dd?+$k zAvJJWctEc=yoO1DBqVt#YidWVIdpj4@NTIzw!*W>*fJ=j_RtYxfH{q&~QjzecGCX;m#=IOs39=9i)op2z^iGJ&Weu93 z7TTZ6dg9cyR0@?%bzFFB>xvVSslzG2k6X9OE1bPtZnJdX<(TBS9p>@B08*1o1OfbQ zA?<10>Jb&Glx%KW(XGe11~O&zfM;{v)g9>x^I&5lvM%;--hqhOu0+LxLnwRF>Wxr1 zOi-J_@=8W`yVvyDD<1y@E9isF=VeKxc$^Q7w9_7y>K%;GdCC%L>b32y~L%~%FiQneeX5x*k~{YH%vRbxsCdYdr9i0|M|ic{|$#VqbGRKm`&k%uc@zb#*#v8?1DhR2DqQ3TCPqdf*)Obd+T8{O9P>UMjs{haFr`?0Hdt7cH^r3 z=YOq)4mkyVMV~-%yZ86fpPY^XW5VZAM%sCC0fDbv2rY%%LPfp0ZRnTV=PRgKa*<`kXue-JIE{BciPm zNR6iM{`uR+c8v7s^t}_PIelY9oA+pfz2Nr#lv{Qwvx;;#xcZ#g?EVvRTg)7$#9ZrM zk3d%3%TB1LEwP+75uiSo%tif2iseCLH|Z|4H5h}q`;m&cI~;SU?N8Yn1myV<&I%Ab zxA*hKZ2x`a&KD2die+GkfjK4xiv`3|bl*L)<};JGu%16;S5*m!i47AD_V+^rOZ9r% z48xNzlR7Bab8}Odm;UTeiRLMlK}ByoaAfhoe=y(0MzrZP_rXVMy*1A>sl|&Os?Pl{ z)3Cmhv16IkH!?LCeBjfGLsn<5wm_p6GTlnA}z`c%s| zJXQPx-g+5OWi*_9d{Nnn7%^Ec3(X}62 z-}{>n&GQnnTpXFHcq_Tbd;qbuvB1+4xq)8d??ii%MOsu5N_J1Eo&YSN#>nc#w$f{n z!TCxbOT}+k;RZe8exBZYia0?LYqIDkr=T z9xs-TcUAl2m*5ZM*frn)4|$dj1a)?JZk4~nKGc5jx3}S6wP8p#cUZAU_CzS!nTosQ99UGt#yE@!~=0aJ@A4HXT*kdp#cJPVS{s z-mG?@P=X6N21;TkG0+gtwtg;5HNtwpLbr{%QLOu4e$GVOB3wI1zf0N*dr^V$8M zVMYzs--InAP8RR(1?CgVRrqLOelN*E?C<^PpAlE!F{lPPbKd~AnkFsnq1Dx_#q`;1 zHL({U&nqAxc3|Z%wcgBF(B@jl9rDq!oZrBtm5awTOkj_AsM zp~a6N)*mKJy7rRKlDK|%97#oz%Uy}sW!$c9llho(%RP^rD>)&!E)*LOyqM0qRr@x; z)3lruuiLGqCF=*35C)xckaZHDZD6`jNE3{HSLRYiY9{Gm6igengknS03!wPXy9e2lwWGwwu);M*JPuu z9k0I!6I#*5v@K_kxnZL)Pkqib7AG(?$xM(`y|8ApkS*fqbV+B6&7W&rSGcgF9JjQuZy+lXfv>zAUeC7pKLed#ty zFp()uHKgqU;Sb`+|B^22C!HD`DK25nQ(RV!Qe7fs_v(w&NuHx!=V;Wbw!fu_SKo=D z3X9GLc8q*#JA>+Yew^8u5KP>%UL=hWML(vWA8`C^;p&t0e)%ME(xDaX2;_Me-3PsR zOhxhwQ_+ouX%G7m#cEPN9?@zO$KmgM6DwHYQK>&k4)bLKs98W1pqS;uSYTd#Ex6m% zEYO`a@eE8*>`HtLUS2Y4-w!{0lpNT*4u-^q0SRF+2uz=69hcdb9^Xos3mCbuv>tW zFnz!V7o@I7N0;tO9^IGWPm#x1Rb?ht(1eok!I^!hsAl|NstVfhZq2_%&5GhGYxx`F zeVTuLs-*4A04Yb_%<3YVdZAuJZJSovfAP*Nd_pvt)KG`;61ku)O>LUt-R`a-`ZDw}{^LFPK-WkUB8wfx!OJ2gi;1`84P`KYw7 z+mY~GF1mawBx0oqGiBa?7_)~S7kdp;^jxHBr4(By(pT z6|!#4H7%r3DypR|VP&gm(mFd_<*tB3ay>FHhyO5{V-|}f1x@I+v|x4M5``1qieKi2 zG_ySxFoD~d+d+ck+VgPi$Z(Ao-1oc{;q+LX#PQq79frKBYCzY?AxE44D(G%{p|)Bw z%iw_KmwoMEWdOx|dFTON26)I~6qRD4hpun&`pG-(WaAu)i)wA8*E2+cMcFJ4%W}Py zjFQtvs^}j+5`?(W$_pPL95nwx55pwJ^H65~{EYWUDox6Z+OxXM>c#AuF zkC=&m0;9T!`PRcW7+N*+Yl+Jp85Zl%nzTHTcMsa61Q}>do&NB{nKB;~%l4`QB4786KiWN^-3NfkD>;d=^X8Qo*@)b zCC<}#_oEp;{f(A)e*KMg;}iEcp7DMup))d0eP(FwH8=GAi+Md* zf_Z!SQUBN$n8h>6r-xK04;OIjhOZk#Ec)q1Ll62++~1k{iFb7GPd>61Q}w%8J=T#T zU!~OD1R^zb{;VYW`=c;3-*4%SL1G9sdGupo1tXb+vI$2hjwRjD(QLYD1SO>RHQxvh zPrJ?h+1N?U8Dc|<8DuEb)w5wD;VEof z1@B180K=3wA!x%U9`*!W_|-MOTD$z8&|!gbBj&rj(6HC?TV*rp-6g*YCYvhrUVTcU8uBUaaD;wL-gVHZxu|Ka`VW z*rbJ%p0EQ-LL+P4NdM5l`I&o?dTk>6c8n->%T4OhBhN!%@;2y0O5F<2`6o9qbFrPO z&G_;f>{S2jjAj_xy#z=%rI%_4H!C+qj2IWpqm}kiI4wS~J>qX$?{(;nV0|FQi*u5&#@8zB5?(ghC z+12WH#D7o16M|;pn!T($Iy=fPcW7^Kmmm17RSF;?b5`vabKY~a=*u{9QfV@o&F7Tq zHR%@^r(b9*e`BTsuO@}g>4-V`u#`XiSo#(iL?tN%^DZ6A_@-q*325p%s9+KP! zD$JL29!D-uXJ3zKaS4(^zOaXp4Hf-p&t(g)auj3z!IlBJAVYKY=GNWUvzT&_pe{?P z7fz{&^Ygm3DFsqWsD4Mq)p>yDO7Af%6%iDQn|j@|gX!V>e0pf9&E`bpy7$cnf)(WJ z_k+K9iPv>@s99V$HD2sSOsMNN6C+#`E>$%GJ+ATp( zY{eq#tm^})z3NoqHGLrJwR<>`;RXKB=?|=ef~P%9&%L7xF+!9_3|>J3j$&TPLg%01 ze%tdMZhCH;H|o0WKP9~AHvQK?9dqNgn8R%jSgcY3&yHijU5?wkE-9l431;F?VAyhT zaoI3fAjO?tp$rr?+~#S;#G>_EyaNg`>*^hW8OoH0DcU%#b+xh9Zqh0RrHNMmqV!KV zaBfzA#;zk0=>){SnS4LIRA8?pwd(feb_mfjV&{_ojg zk4)Q#dt@-Vo2%FI&dQAV$B4I0G4Ge~3b16K^%4#@(*dl{BQHvH`nTG$x}iaTK8lhg zk?@g?nL}TBLt3uafV{18b-!`fncxBkod8DN4p;qQRG$k#_cw zUH6}PYC%S^O@O^|!m4He)hfOPKn=n_P1EoA-}dS#mKioqGj$U{vCgL>jmvOcFQ|zh zzT6SK-CK(v=8b@%oPge%fY*hB2*XOUQL8xF)5&)1r&xlSPazw97)azHD_pYB8*!ZW zZM^(SH(o1>O_^$d<(o`)2^nNAftMO?B}Af`nm-T+9qWp3PAz{Dsxj*1&-%1x4?vYk z0CdUSi(!HU)HNGB`^)tphMz@}XYVc$bKbw89Yx_SSJz52<0H8%dD=1;%QG`#$)<}~0Kmfk;@^Q#fTOry4nR{O z7xBso4TayoVK}@`u;b5#?Dn;LK9*s*EF&9e*`Cg60mceoHyX~zqQh+5?bYwmb$Gg> z<~)4&xbCR*d(VQ}7Owk`QuD-p1AqIb^JLfKaEpz9JcqVJp3Dz}wAy#<8Jut)hRJ9f z%N10(&^|BC9rGm`Rz!aE zDs*tWo?qGXK?48yHUVxF=9xQdtKQ$)zVuKbJJj+^E%MoC*(E-if)$XQr#q4RtShD; z`YJKs8Iqw0pgOFF_Z&QqceAq$r0EyW7^91w=F$7(h6Xp6yWYUVb8}QB8u9XG%bxv5 z-P8s<#z?{CKPs70KJXhEZ~b0%)-}*%9Xk;|F&0(=)xGiZvB#eEith1v};ndci<6%{qY-wlBOc9Ii@RhvY z*x16B+yM}gb2eH?5X!Llj(0zRcGQF?%(STqw@NMK&n>)sXFcXs^ z1RI~8uIG0YX_2s&x3wE#zUfOPNfo+iKmG%TY3>5B1)XxLv(?OZsv8@LI~)v#w75MH zy0w2`=)|^QHOhr|5WHXyTYnqix>v*MTanlCGhxy%^e*iopidzQLF$bS*Qhaf^h^xh z7wj=Xi}+*4%G3AsHM66$)2zdA&v0mJ3e9Nc=CW-Y_~<}yI*^y3q|Pc&^Iz9GdT*%E zg3)f$iFvvYK(mUj7D+6)7|OMP{o2vnW9IIv!UU)5b4XYcQ32q!Co%w5QHEfT!kEE# z4M5L(d;*F>#VN<2o}kOt^iE;QLw&{Oh5Q z$c-*R5u^97Ah4!%QPemjb_fW(7_dz{2nhGlMgbTwNLL!MEec1+6S=gRbk=w|p_(>8 z5j-m+f;$h3jpYt_>SBKejxTec_=GWwf&G!hj-H;wy|?0P<+wM>rmM;snI6Vdq;Z=iT1~`(5u4Az)U+u$r z6PCUW9UlJo1BS-Nw_Cp8!)7+y0wWWXyH)FgoBO{{-v8zzr7!uP*vmftQGJJk4I)RB z`TpZ`t~#;7w&$O(y0ya7)9eC$okx3b-*BoQS{S|;E5#s zOL0_)!WWB@Ne^?T5_DD>?N^m+%D-u-znR+g(8axznJB5K1+{!!9l-jzW$oZ^J-;`Q zjtO+${&||1-%W9#VAcFX|O*FJ&ciwjh{uowG*t1DI1uHcCY=B@4k z6$)3Ys^UvN6l$Upa@vwPfrwyqN|RN^9aD3)VPjz(4PO1=fDZlZrImt(r=9>~?M!xe zzx|s`46)~=Q#buE=CTT156>sUM61<7E3PajH@DP5VXdGW`wvh*C~V_Ve@l`$tKoMI zNB#oH-x6Y_Kk@cZ}vLi+I(#>;kUECT}zFoTn6X91%#y^4zF0TR=? zKg@Wm^+3VUr`y@y6f0%88#<=eFmPPO*NEAP@95izw`KoI&kh)M_NFdbH@`)vpff{% zBx`F^650mFFTgEScc)RPhRlW=_kF;GZ_d#jMAm)FHHrtRYWDq*n*7m)PF~#; zK52uk#eLLS7@g;D6@j$epg`d9T3G7n7KSXC5dZ{lckx$ zAUGB^Qi>yA{ZsOjk=fq2G;Jl_uF?cC#O5q?bJIu~cpJ#uwy~k&iSpf}(8_LQ&eKa< zeMcKYjymm30FcO*4EaRYm&QP0}K$9#6r3GQa__VgrO#UD)&sKL5{1}yC zVv68Rz@K!IyEG#V8H)Ky))pWT}vaTM>v(~C%#bIDUl+r9?X@oUu;S1}uE zQ}Mt}y~rlzw}Sp#9Rb}802hK>)Cac*q>WH@o(;Iyf#pcuJ%^APt=^b^&YfSz1I&0& zdhnCTQM;oE=JC)Ix${}2i@Q58@9$E)?+04+RAC_lYI$S(?vPFaH#x6>j%BFL%LZ-R zLl0(%5F-do6}0q?=+w(S@u}MWq95}7&;L^((L*JrZFq||Pj1x>2yjcky|}*i9{;rl zhr9(g!K)5*|bLfR#oqUU6{+Sz-}-tO^J*sdmsj2D?o*xXn^0^M-lJWrVQWHV?;qGR#dQK(pGTK7G@w!B+o)>@Y8>nJwv5fo28oLBXI?!Nwux#0@364I ziaF?BGDRMTvvKzKr=Rih!`#YZ)#ZhKp+%M{kQkz%g|@s%2AdY?+l>K0;qh->%D5t^y-AZmmCUC615;qW{AFVp8rHFL0`o;v7Lhh z+D9qPq{^q!9W?zFUZBMVW^^~D&^W9x#;1zjw}7knua9r{x@p~T=EaM*Pk@XgskYHV zD~)kq=VzJOC*pFX$!x}tk#bqRbdHPm(r$R}qI;`NWM}$l8ddEpz%j&`6-R@iCDfx| zd)n!aK$?OD7NZ%YfSY{?5vV|jPG-AX&8?~u6cMp-bWGH;C~k~cx(r!gXFh9JCDx|; zik;Z_(mT%Xv(@bl`)m8(~u zx_=s_!?L#* zl?FW3*B+q^;FrAn2bqyi{v@gXDZ|YHSBu$x7g(@i+p|dUwJSluC8tBbT(o4eNQkcR zW7pEHo0KEw-?Xy2;KbXG8@fmQ11IiTk#SY`H~H@WWQKP9AYqtiWYPJrV2ZPK?+hOR zNA|OWSGTwK_bK8y;C_ve<^)@$vO?@@m%t#Ij}hlX*|9nB*kJ$=!jEtN?KOStgVBne zP@|$$eJ$&)<@pXZR9}bex-G&Lw|dAC4X7fU`Q@PlrbS}0M9c7Azox?NoELaawH(p8 z^Qs6JJACuQxc}aBv)($j_5MTm>v}6mG8z!Ae%kU)Jar?E*UI_ifugM@J96pX*9A_c zD9tUUvSAX6GwsoD>NesmxV+nifML<7XP47+hS1t{tfQU@cQG}?E!pQ&+epuRN^N~m zXsp+SLF+&DS@$6a-R3249E9!*J#GExZDVTd$;8+&)J6wb`X(iL@mXNyMVbx$ZY)2Z zlQa#~?+c=OVV*fZ{_lK?{uRyn`>uy7j@eZ4hH*RIB_}Klv?IO!7TrnpTM|wq*&SiO zunKkh2XB)D6B9`#3G8z9PLR*0A{dLAFs+XB*=GF;3kOGEiMo01G?=mkUqM*6Mf1;$ zEaIJsc()q<)SFSW>M*qdNr*&l^}JBV5g#%wb%=9%P!Un0*W-o1bm2FH*DZ7V@aKfX zDc+P$$!sR(NPXQwQV^(+LnmEp4kBDk%5br& zNOgA1>wD}ITFjdMR$lFO^+bajdT~@ubi{P(4DIP{|@?M|^@|j1PV^X+W3V&!%S}%!%=yw4&Ma zea-CY@$U67;AmZ*_cVGWR$8g~Ql0xWHDYEmG9rgH`3F~W+|cQ?w~XW8?7#7xxn`V9 zT(eTQGqJ<_E*mQ8tEUF{t91I6Txh?%c3qqwMoi#FxJ|Tv9du-F)=TgH>VHgz;G?FO9APg+`TC zz>%!bzFsvfMKwg^9L6|#$gZ%PvyFao6jIG6<<3&&4}vyt{$BI7Y4;lR%l>pud@`kD z5UeQEcMyDNXis96(|Q;R6k1<o zeZMfni}3~?GeQ|1+pc5HQtfdkeXX_R%Ce8^(P{@9R6~}D+$c~G;%HQ{wtW9PYyep5 zgrAW))4*Dj?j~>v`n6Dz$oca2I=Vv2m>3ZiK?D#IXypX$!An}BlG2(Zl&0pa|dnoVADa4ODZaB2tK@aXRDsqATEtEj$9;`!l5+UR)g!lB5BXg7){m=i>qli%=49S_ zlC;sGMkLtatY*$Jx6t*b^76L$1o<`RR$xfWP^)H`1b0E_*rQwxa@m+g3SRY#luKk? zSY?}DcGLCYmn>;rnXE8Bvx@LaOhfM&)RAoHmXeW%D`7OXdY<}+3ZTD|zlucJ zP{~Nx6p{l*cgC*0Qj!snF4O&cmZ*7L|m4<|8TeGxt-_F zCr;P)TYD*vcUo+B6N-B?0&!R&pTPe2uQi!d9?v-xf6=Pbj&#a;ynE zCfHSC64ao#@JQ=KRtMm}+XY4l2fwud_G#`s)vTG8s-8yt^Z^&|@zqr#ccVL?u;`E> z7Xlb;P8J_si7t! zLiCo!w+9aUBgTd6AS!#ig^{b7*$NnuE{xI_&B9Vfkxksfh9-QP-)HW`)7C@kD+xRB zzco7~cd5NU7YkC9w5f+lClltE?-LEDrwaO`(Qoh1GEdA$~YE#1V;=ao6{AbA(f!X&querTrwh)d`w2ZbtFZzVbX9V3vK7 z@?N%!gVqUt+Kku{teGfm|0ux)$4YLNcSLsETj5?}=769iILKl(MCncRF#oA zcYr0FH8ViY`ReaIgWddU4pkKS zs58q2Qd#yJv#!>9>t!x2MAcV?=^>P>ALzb0+ zP`5EP!o-zJMplgPB_bwPUd8kujy&Kd*5n#^58WPEuurHWG?^Om$%>9RI5;3VgGHOc zYAFonA6b8)MzRI44~cD~uE)P0dJvRu!<~PB>f?;4sx#B*M3B&wio$R+s+YB^enD|` za4^$Pa>FmaQRbsC&Oe2$`5*rU6>NKB2!fPf9M?yG{)Jq=FdUBGW`jC?J>&Tf--Hno zYmX2Ak)#=PJrIM7Kyq=innz9kan3;{i1@{yysydPd6AfNao}gsg37>=d;aVG-rydZ zd@A6tQC!SM?8kIVZ{^r}Szhth0|5KXQ z=ZMI!KDsZ@HB&dbp~~<8IYjy>Xf7l`A!4S76IYoB%OH9@d@77P+IKlKUZepTPSp`_ zl;@>Ogg?577SVrHVn%Vrx)pPWFeCv+Kl+4Ge5Ajc;~7}-6ToR6TbZ>Ze2n>#2Jdviz> z1V?Ba8`I1ySYcaiJ=Vm^D33t7s=7y#JmufR`srinAw>yC26*DJFZ&z9p%UV+j+Hk{uXMFsj?Wt=wIP&Bz4cy zb8f1aa04<=U?#=8x1jsrOp&efs&WuYORjy<jP!*?B9!=^t?}zZ&y2huH4HEY_@A71iutxGT*KYKu{VCQ5zGC}_Dw%c`69l& zfHCgFI{9u+;rMLgds^Fbk9C<>-;a?^73R+&73*&QKr0&~)~$g$|9VO5&zN(X`9m8j zp`{6!&T__;-KId{O(7pddktvjcSFD0m)!H>k4aoaI5^1>P|J!pN?H{8WRaMIA~8Pr z#Q~gjIipIBA5piK@Ea+Ky{o!?mn|&E#kmyJMySOR9Z(Ecr*7MDv0y4Vl4Hr2sHTKz zL|#gKO50*rbpd7RExo#0SH6%F&*1a6sa4rNg;#yf@@Lb%g`{VtQGcbkLew&yYe+y| zOKumJH9xJIMfA_mt&vp(n^WOfFqwQTFU@NM^=ane>qeXPM3V;0z|&0swb0(C9+=px z;0g!lX{@WR=YQi6nSFRmvdUiLkFT3_Z-L9kAO?0=q_o#tFtmJd|4$kiDvRodCvxO7 z?K78v9OzLc892qFw}eu(mnM4!#l9J3}u&%=n z466-52PCdo9H*hlwv&&y>b7sEJI3(!*_6yZYU852lAT?RZDTnM>N3-HHB}VvkDWOn z0(K&wqLV0_%`R)k@C`dk8TYf21V_BUP3`xa$eoU!j$NxwyFKXS%vf2R`ikohH~G%O z{e-dAtkXo2Q9Cv)YeAefUA#bPYiSkJ1Jb9IlLAtTg;w|6bAc%XMK`m5bfGGW^tO)p z)|KG@uHLc5Yjv~D>2isxHaUEeXzAxApDgjDgjTRhS4f>RGBW%imq0}gH@SE~cmFKT zPC>YvTRabsjV1#tp6)T=j19@jAvwAe1iWn3)pmf+XdoSS>Nb9Ja}(iYxRSl#&|_>3 zo?EpqSNw*ahOA7#AX08Bwn_;0-x=zWJd}b|+v-8FCq-T6+HBK_cQBJ?{8BtUEi(21 zWJ?wYhX&JljQnx^SK|{Oyy=I6tDA$yRFS>5;4!#dtFi&qE#y-OgcKDO)~ORMYJgt- zq1A(*VvU31(7zQg_461L-j7S`baQ#Z8DK9hhGe}0Z928JCDybWc2hb8K|f}>d(n#L z9LlEMSRiw^JI3cCjJk2{@YDJ&9H0ZCZZ2LMiQjAFY#*8JwB=& z13F3FHNbi7@{-km1&ek^SdAjpBaul76!!NoEKr*m(?PtvMF_0bvbF-R`w=^SrO6l8 zrB%cr0nYJOkZbs1+XJMxg+anjeuTYbMytirF)-1Cr?@Khsv-)7q_73;vJz0EM>x0L zqcQ`cs(vo%ZdA8+lT zK-_W5F)6oeJ8b(2w&haXaUf~#0{emPqApiX`RPo&*1_Z8h=Ee6m~;^MU;Jz!VoR+P z!k3AJC7-dwAy#W^0R z(b3#;CaPKbR}cM^%cjO23Om7=nPm7xUKQF+37-s~qn+0-dZPR#25$KB&atJ$pbxir90l)o(raKh248n(Z?&j8)xRSny9ZH!LBR-Q>d~jQ@h>Yh1sH)S+fUA3d|%{s(E84owWif& zK4iNhy!Ts^5%($QHlWJzzljy4r5IOaf&4k|1capG|gb%%jl3|;&h zkFTj${{;@~Kd!QQ+?e8mmxxuMCk4O5P0!4SRy2>&KF>wQ1H*y>zgva= zT+zEcP9ViJX7SVcy;)U%$@sVf3?cou&ZANXB)D(P|JyN05q(grYB%|fs6uAVG8gQ= zFM`prVNVVKw9TxoBY~|hATdn=wbzO(?jruLsVONb!v3NH0)^*70D}}03qUsRb)IkW z%JxLG?EO75?ZANYC*gQC3bDnwR9oz}u;lrHU3RV8dU^M7{B2zX{=4UPlB0n%HG}8) z!xB8r$2eKuG)>}gq_G9DFw7oHsrv-CWU*~BrQ&z*NqeTVz`DoCUzH#_Z{X^R0bTYB z;S#FM0NADr*y(xZJ8rRXv;s+BfE)R!=c&|fGU6MWHtOpd97RmZv%CDc0rqGR2n4I7^Bg^{^)YZgEi27x_UilEGVk5pegbr&?LD?0A9Y#_>VJPh zpg#-wrmp=FBggXcb1!56F&d^uM0cemC0r~)(68NoDoAAHeZOndiLSy>r9);*{QPBu zmj9RlE1(oYhcvZBY>b?4t*-v}yp3NNtvLI3{emR$J8oUy9s*u&Rj=CvrRMcE0{1rYE^Hb&1 zfM4(6^fdZ#X66C}NTtNdC6dDi_pZF{OvihHPXlt#6EH=zEs^`J20c3PZ9%OCT}19Y z_vgTi_3iCgd`1=(ivy{j&?nekdHX201nlc^#GUZy@h3~|XXsMb#{UK<^wxoWY8X$! zw|1yS1k+EyO0Qx6il(NQNFp)(TH2dGv2Qzt=h$Gg&3f(n?5#A=EWfLr1y4UVqgMX` z!u9jv{eHc4;A3^Z{^=}?2(n+SKbN40zN>V0loau5Gv@KGU2pk} zj;YceC*B|m<^|L|^7lJ;H2>8a{4U1dCyqc?{o_Zu=M$CK#;7@qKOk;1E;3GsZ&fHE zs0t0y{!*wF1Qjd}j?Q&4LBW~) z_dGg|8#dH6%L_KpU&+g{SW|@yt}`oHWSV^8{290xZU5ePGoK?tAYI!MgfK zdq4%|t0lHYrgiK9L96cR>9M8f78G#jp>GxDNY>)o)%{hOp-3FjPzaD(`2n@qil%+Y zb+XwCns)Wkc~rD+&yBSKVT2x=7$(%3079vG3eYZ)WhKCzLynZQ<3C0_5BaT$O*Y+S zdj7Z7?6U)pX0Cb4iNh` z)JY-)_`pV8CwFbrnnFAq8CSoOl{K@!uDaQCFOAFd%_@)j_2=0DZv*&K04tXpugPyM zdrQ?izjkDrrsP^*wp&B`1j~1Ybo7*wSafu1zN}naO$mz3$6O<@e&MVu;sY|VEX;pT zpTr_A>Vfl)ot>L97b@Y#tHxM#c|Ujh2@p57d_6oo%;rj5SfrQ`|7abJe<3yp9jMqk zW)mj(0I0NwCGCT>U=+EwllFEoOHa?~t*zWrC1NQSW~=YDl>6CZQ0Xx|WMpKAOi#e8 zYt^kBue$9uLuBg~)@+>t{T7kIFJ!Q0NlUz|tLr5exC{Ww)SXzb5zC*=RZEd<)Y~lS zeOKJ7`#ZR}4frPVHIr6k=|M-Hs+{1*vK~qsv1!a=`+|lV>Gu}nO@ty+8&V%W!jmV! zVrJTC)zVHSKf1Mfro4O7DK;SmOQvlkAk?WJQSH0arToU6MA+7p&A?HlS5!j zY2yP8$LQ@?{NuC}^$*_8~_0A1(yZt`wPzq9B#mB)+Y4K-qNechn< z8`YK{I`$iXmUVRcxxVN zh2K|af$giZ?!7=zn^(;&-oo5AXUxUBNzOno~)$!hzmSLb}AM|ho3t;gL|B9F=glRGQ&RU$$_Q=q;BbIXzT>5QccaswD zo0FbLPYX%DUY&ko#=LauJOHeR=0=VAx-3r{FIY-_f;!s|OgJ9Q4HPqno-)t^T{`VP zQg#Zmq#v18UkS}VERh#J);4xQAg zZn(5ZvToBwc#&vaXI|9$qTMf6Xki*YuiE)72CQbnutRfy^IreP&H25})sD+7QEQW_g4++V$swU=j zj*u#Guk?!7u+LlMrcHUwoVB>dE>C0Zw1nBgl;Sk)T~gdMe8(Sz6eIgYI?e?qV$*$0 zDez5g?dnN+;_?o?rkivE7Y`JT=ASs2lj`4E^@Fe4#=g^s`9QgKAHlB|u^;!Th05!g z>9s$D+JQ(JNZ3zjTKguDreOhL#0)VASn= z;Fnw9=fAuPmj5%6x88<2qXqU*4Dxi0_ErgO(K{dh!C|b($kL?%4-*>l50jyy^tw8(LbrBYq`Bi6I6InL-WR!j>uW~>~ zLd#Q;eOyL3wv`#t-v&g%Df-sjlc4kQ{#guev;Hc52d0lv zdA(J$ZztUcBZCazGSLK+2-D(L?6>~&Yty|0ia+jGwTx&cw6$iW)Ydxe7#a6&k%hka z5)uPN_i7{Srp#%UCXDME{9pwAcH_5DmoLNxr0S!Kk{qe6O4oC7UZRSnsZc9pUwl&1 zVUC+NN1PyON*v{(xC{7wh8FKw`oFF-{a+6ur$`BeTdbwW|n0%?EL$zsm(3=r6e4Jwwma8wvpSnwD z3gA2KeOQHB_Yi!y)#UHFRjt{@N8pLnXFPkuNb3%T@rXR_FN}Lu`xh4-+n-n%adDo2 z-MoVPi$=kdBjmsdq0eO@&;*Zlbl-zNhlu^JPgHTW5$)M5j(XjHB~9d6nt|ebsYJ|1 zlZ&POk^9%P{=?M0kBsl5%KxMSL`xn7r7HhvIV|sT9;UVa%v6ymD&72&CIg#8 z+V@LQy8kDqT20NQA{B1pfqpG};nIBjwo3Q)-v2>Y+fa%vMisy7<-pCq0d#3P`;G4+uI~$L2n}g?yH=+XKqy@cqtlmQ`AY( z2(t}8nkOyY?S`AX0HPQoFWT-|qq zL=ceJZAzeqPk{qSpMQUFi~>J7{!3Clv(f_YXYk&3|C=!01^&(3x5u;kjdD(c>yS#X zEaA-Ab}S-CXqRI5*fm#O@bI!o2840kzv36WDFKi&0Yx@;t0v36ka0$4%w21v|97F< zf#wMVZl;(qP$upegfF8bJ41@vQ8nSH7WUYOayt3E3sDjxt)3NgmExESNrZlbIjBy0 zUiM8Ei!Uj~4wCRTvkC-|I>u1WvDP22FjHbs%6?>%=u<=$`L<)V%S>@67hRQci>iVk zNPq^7*o&s6*ZE%mJoy|U4m_SOpUF%a2nu$o$~4xmrRF~UAu^|zn&tvZ4!!{gv7Qd} zDmqx@+B2;y&7UzfRD-1Xtg={PuR)NDxQ^NGC~6^7^O8iFkrT>x3RI| zbD?e8S|l*37cd%4_zrqDSqYFKTF6Z5Anom>S{&@CA4(tz3LrMJ%uE2VHQLV3%eBV< zB|ck?{l311CoYoHJ5tEFczn?ngv7iuWdr5Q@QjBQqyaO%&RR zKNwkLHGr$ZySgnmoJbDy&gUlham(Ux&`gPSq z?|;yMZJEI(i*!kgR>vFb9Ws#M=BH%#+((qTQ+}y>r$9|YrlD0Gl`JY?T0KF@NCL_i zMejXGU|u-Zo>$gLH6)TyV{`S^2<0^nU^;1y9R|9EVHQg##eEy~X&fyCyvAh9ekQZV z%3bo{rU!+{0(RDMR${nfaNEddc{ynWl?HD1ZOXCjd*-L~FYOlRTLme@t)!GD^qrYN zv%zn)eh7F29f;{A*M}OlURD`0&jd71v>C@PPh=kX-7$Z)0Kr%o4O1{_dUuQ({{}Ur zpAA>%-3dUPHqQ;XpHHFkgWJJ(Ex|m9SEUWkHB|OWdt>jQcp+~3#RttketP9(bVSRc zieqO(8{0x-kqkz8cu3gs)@MsQmdetgdh5|^*z%WSuO7ScXE=yRPS?AdS# ztgk0pk#`~L!QYp|f>zBlfgl#lbdI>33>Us3-SNMF3H=^;u1-=e>dGB-8yXy8OyXkDkmKYOAKZgxhB@nRxhzpso`-NDD< z4#q`yeW_DU08=Xaga^hJ&PVuIvnY(4qz@c$#m|2sLHGwfJkV+P4L$;ivXFgO?1xkE zgVqTj#K8-GBYt_&gwB#ErDtonBBJuKn0oHD6G4@}*2qQHyALCGKqPXB8cn>kSM{$k z0OT8iOQKi&P(b!o@3loEz`_`Z{G4afoCFt4Y!Lb{U@?USkMmq8gg+fzizj0mZ;pvkyAg|BLBfD9#5>~(6RK((_XxcBr!eB-oymes zDuO5sw^>yl8HI)(LuRYS@Z=p!OFoSue}FQnUEH)EUDRj{@t_s1#lssSFo)PT zCTNK$+>xO8hDCB?Gn*y(WzebLSsuPe=-_=m^@Ce3a|1(!R}q8@F@mfJ7d; zu_K)KU(hdo!?+uJd{L6~>++QA_=JDdxHxFxsSAXcjE}fep{;Q3GQh0Ud;Mb<(vY)$QGuOV+mnOl+z1o}LpN+Wbn5XA7T>FnyN1>?&vT@OH*AVg37 zDqBX`^o0)}Z`ShK{#RHvSbyXHktmoi>lEpwJx*t={ipR zzN4#aiL-)!6g191*mo{mwND)WjJTUX6Rk8RhO(lc!`<2>Tvm4T@R?j4MMUEV63RaI zOReN9$>eubH%YuISa7>b*y;y*tip@t5eWUOs%o*;tu-EHRVOCWR&5il=6BDIkGWaN znAHI)%FBNBD}CC(|65a$EG@T^<*3Llv*Qz7tF6yMEgRHlcr$f&Mg;5~)IjMe48X0y z9)b_TxBp}@Qm!Lzsk0gV>23v%TMrtL*nK(DQ~iJROTrr^0y z@bDhVcYh+$NS(GKs|!T5J@H;`abpw-w{ zej^1WtFqz3Uj5BzK+nT-D1bl0;Wt7IfZ@g-9!(jrUs07Sp|A|f3rTLRCfa(g#))NN zq%8xLFeM&Jiw~k zlenI6acPT&_XAWyN|=x5;6t#Kyij_m=o@v6^4y**CDy$lmQ^{>!GLq1cAM8hDWUz+ z#NFYhA=v@x0Z2IuJ21jTt1kU}pcS+vJk?V{U*x9!2ynXPO4tsh-S<2-+26afwOSunYlXO&zxHXV>>`-}id=_xH0Fy+sY$Z>nv+8tQZ zjcWjTj%k@2Q$GVci7YSyL~DBRvMPVk(si?~Z%P#8;ZUfcWs$dZoL; zf1C1i>j)PYBb?ZqR8bvZt6azww z&l(U>>86otdR)82rAT65B1In@MG5Z@8)FM5kI9Hf!$g~^|p+uDssb3 zVKV`b6Ca<~7^AO5Bjy76jlFF%&fLXU%vg;?w}j{x03Nfocu_Nl;JJ6{HzkzV75mLu z*&>EEkojI4>t=bxBJ>s6zwE#A=pHb@8_B{!bCNw(2zv7#tfgB%JIU6EAfr{JYE^vm zuHQePEqCI++k3;q&Ao3W^sZyrv1vc`x=HbU(*Gfpmv7+e>^$&T_zZ~GD=!52?;V-7 zj(E=L?94+ErJz*UjMY75x39HJ*JFltSDRINm$l7V5*vwYdl3Ri7uccg!|w?1b|MxR zLFP1n>l-{Yet(|f69^uKRuZXd*uex>Chnd6`H1=c_x(k;hWoV~_}0(Eok#j}NQWaN zc)Sbl1`(L+{NgZUa)l4f@I5-B0lGD@D-2&>BkuV>041_NJ31mop8MLcqCMEv8)WvI z!7|r)Q=qL`n`rq_1>F78clv&KOr8~fV+8@lY(QD)TERJZMSksYOn8OkIq$qV?_uHh zE78Ud!E)=@e@sN=>&9}#U1(0-0@ZSUJU0NA<`=|I*r;@clbEUrnW-mKh8P){Z4hpp zG(o-94c}?dX^buki8U9o4COku^ALaZjcNxO-ynv4eqOw zabqFvLw(;L=ICZ&1f*Pu_pm6*B9QAN(|O;KN)GH zK}y>ts@TZfH6)f>FLyfiYm&%tcdK&>26^QuppNjXe`K;mbl1SJ{DuM(JXvdDj6mMD zZ^l#+aqTs%a!x~n+PY~cSbQc})AVsz);}6ttAao)x z!{tdjxw0)(vqGSW$`6{}_t8A=*hAuaPZedQk#m@Gj#}bh9%p!Cq8WCd2EMS3e}XA*W5|#5!93(6bFXcoPFlcQZ#>r!dPLkIlh|W2@3?!R@X)rI{KJj^S=ewtbK z8LcT6x^a^^c<_yH@S^s1OW9T*lfwk23_x?hA`5mj`!wXsCF|a4_Tv# zS^P=Mm_}ipoiX_b)k}&y&7iDRgS{d*Tkmw4GevD&3gmT3@cuf)@NcAj3YpH2ualbB z|LtZ{^<2cx_ILJCFy0HCnj?uo;E;bK_{XNG(gtHiCAqjyEHj3pJkM}F3l75UgTe}p zYT=>4qrLRk>_6OWQ()DTZe@QB|nsH%tcs-|4#=kx6Tb;?wd4CRrWm>A`1V$a(<@oe) z_kXzn0M2R=`05%$6n7G?9>4d##4%0s&RzLuuUgXH1f<`9#HBrcW2@&a?E`J!Fdhw`MRzLo6fsFG2YSMnyPG3b6HJ-AE z7wb;iCtE89!<6OpMZ`Qe^z*;+SL*8?$@kNvqOrOrKUiI|8{0K%U5EB1bKVsbYyl}w zR*6UKnaR(UAw4z;sU&E|{5a@&p&kRz1o;urDpb3F55Inw*xcy)fyfYT@h!_jwHr3F z%QINBo*S1alYrZZMl`|1#s;kw@zZ!?p<~Mxu`c=%*OuWW(B@E(pLyU6-H0It*1=M% zA+b_J@$`s5q`D$aRxsC^wP@ECuc8eKA$nx~rt{#JmMBW0^Cv#BkpUY7;l|Bl7?KbN zHOwCq)%i4A52{jD4QrIxXN$K=6>&QYcy)TmO=cY_(+`D_-2#|u^3_#aOL9OoGTSiBNU^izuiNV{H#%x_i2}0gUSJkW z@KF=+zZ~e^79>n2m%6d^!*5E%S!uO_cHO|{036ACXrPyYFCUcwDNYvrglAz#sqGd# zwif}392s}+b+4KRb**+B$C4=Bb4jW&>J4MO=;;*EYq|^&Cv_27&@vj?9{put8&gdT zN6FXmngR^H z5RmGmFa#lBv82rt5vcn4qV^#L47vBGI(5QoIyt(-2K6lRQe;Ta|FROO*xQ#5Wn@M; z(8OBgcjahSSRv*|Uwtsn)s0msd}MC1tOi$%9r|SuqyyEPK?ikkTruz_{dkP%h`sZG zTE7Ak3j@@zr-iSQ`YYZi>06SJ5SpGgeP0qnuDB|yQ{nNH3n|mLv>e3$xRGM27eOpomWIUemy_cevDn<&FX9UW6pwe@=x?`4Yh3t; z;2)lQPtk#hzR9$OE%`XT&%f!NVB`{O?ec12+lK(fHRCI#s1>$kiT@rS0qD%`QFkkC zW-FZd*lo+1BWS@s4IYbBzx1q7 z%(OFuIAG%v&epcPy3YHNuJvs-2|c%HoFHBjAbXmr_p= z7mhvXY9#d0&Ch@vy~?$_e*Nkzt+Bf;L6xGMgqQ?L`%y}mL}Tuc4n_`Mra3TDm2cj| z3ILAY6o6V&8hu0Nnnytr>O^6Pn|FvoD=A2($y%l0ZwPU;_bh(t4jU)ht#(jXnHVft zD#Lqianl3B%CX>m=xjp*v=l{58%b%xTGWZy!pyO>Yo0yEmzp5Pt|dRDZ)jCTqtsL0 zPsaW=8s|0pTPjE+g*<_D&@@3v%2ZUTNN8?5pqO#?ajE3fh|$qz8`yO!Spk<*lHHJu z=RKMYE65BFn`xiD0<=~-zjuw}4o=@K()x(!W223k1jd5H&Xv($ z6%qL7ABYQqGL>JimR;XR!$EE4ULz+%2-HakFWF$D#J=t4RaI>)VIFU ztIU@lJazS;Rk!WH*twtDb=9-n*cv|@HuqC`p+Y?-Cn{O7N)~f$8mnDMF0LmT@zH67hbbG8UEI%8H$zYrv>dUR$1`kjHlVbDRO#@ z`U^^sJ9~P@xFvK0<@A*+Ec2})8M%IYxr4&|K_77YG1lx>Ou={FBZ~(lMd98aKtkFB zJh?kiULZ{F+YnQ1gC`1<%}UkP0>#RE8U^?Nn@(0y4t|+;^osmr;@VZjB8|uA!nC0s zk)8}Zdrke4AvK0mT2&i;fvgi>TeTI8;)z5a`s8U9XO6pG*m3{uGGlt$4ycWbLM{*-9CZe;EV|n7 ze2?$uLT@MUJO>o+@$5YBb}$VL3l4yUZek})kVqt#v@4@xPP*XB{j8VW%rL7Zmujyy z{go19&}=_W%O@k_B0tVZr(%(8ucOgUu8W}{Lr&o;?UH|xBsM2$3^HTfB-HcCxO4V# zKh9J6>t=MAekDrG^exiY`*~-(a&@p&nl&&Dc~*{JFg{$=n)wJn5yJ9Ldf$1PZa`R;v7Zt|`sbUdLr@B` zMOE&zLe2xE1)jsw@M1y|u9LienF!#Bsl52so0;*-Rz+eVbfYlTqB>*KTkx2&#*V@;b4kkVPlETs#d0(rYxa18uX3ZP8Y1aCUnjF66rBu9CG-Tw%sO@O+BA>FE5fqHt}M1g zy3@|w$1~Y%kMDed?Sq70Hf10-kqc#Hxe{vUey#8>~+UBCI9PH zEwG@YR?gq5I+sDsw6=DNJIC?WLm60PA8VWqfW@0?5(iSp5;5pJ(dBj~YQV>0o}YIydZL`V!pG}VwcXv)5>F@l51)VH{t%7k ziiGtu>BaUUzLfoIOxuyqJ#5e#P?8?7f<}I?MtT(t!|S7NdTd3jgz;DUA$>&M z437)^+@v3Q(uGI8EPsk$t(4{iWD{SbP|6*0D1d4F2vc$nC>wCoGCn1?*wU z$cCmk31y{PpajKXi&<)Rd0kLG*dCOPg4{55@yW>+P2{R8UO{u#goG!nsV6u!A#N53 z@<};XR51lV(-e~IW72ZyB}I8K6_TqbyVR>=(_zsm$HadrnvF@|daHrfU&MtZ*<0Ru zYa$Vx9Z2oYZjC|N)z$)IeRjdevvhc)CJ}ahEUhfLea8jd?+4IDaS~Z26=`)cN*Kz) z>N7PR&Dd%0c2zJ){F>4Tm&wrc#hN;wK_U|gC|YnBFW1u%p#XR3{Mf6s;3iznc*oV@ z+HR{-1O#MJ=F;s!$8Pl3I;R`ae$5pLw}pD=54YR0oSaizj zMM7mrL!zEBb$w@W9VR8DdhyRYCk}-U#KiB*h@Fv3L##b3S z=Scn5A}V6`Cz1~pkUz?bn^42i7)GB$w%gLxH7SQ}IFz0+_sIT^L{Pk5dmRR0yUsF~ z)0*AH-qtRxE+7FL9yu(fG-9iCP-Jz6&$qqp|8!wB(Ji1@z(2X7?w#N^<;-5TwaaDWms4URhnv#nDD=BgfDN zgpvQB!(&AS7P-U!=eD~mD}hl>3P6&PPS9K z=TNOHOGMB*pI*IlCH=t9X6ez_)}%Bb&H#CR**hF|7QwoT2NOdKY?Y ziL?34+_Qg-Poq)b0ekEI6RssD!ru1tVpf<`m8sc4TF>Alql9^Hk6LkQskWSJN>fI? zF?PLuUQcIn$&Mo0_qxpC!&XM4zinjEkzeZx@28Wk9>vGk(IHz$cRlHrYuEqp+bhUB zklV<0;9viFeBBrql*)ia9=&YbRYt;e3oRPL&A*BhBaA_4|& zJKr~@;U6_gf_P2ewP$5+3N7v3`xA-=vg+o^D~+kd<=P)YIc`BdrsXJRFVZ*<)^=o6 zWukGuo%In;4qtjWT`t2o*us&H@$DUZtxJ1*aLT^=s+C^&KjJyALV@w1ulD0 zi4S+-VpAe#hb*K1mZ_bdPQNSW8C=|T zP)K233%inSO)~af72Fv0+>_3x(5M)4VN`&Vc-(jt9Iz@6Jd`sPng+BbW)Vh3>#?@- z)OGBvx5HpaOfD_)16`H$oL+j$xf1f+{2xmTi|Gl*Ce{gNl_fCM_tu;D<}!`>y#%~N z$^(F^h&5qsDME`-=DyAF31s!7-MUvL^QTn(dfyV`TiZhD>~ASXbTM*jo=*l zK}@(fAV%>+Grk_i8Xq&7pMBRw-nsZ-c;}RU(%7?091}CzZ^%Sk`6si2%y2R_B%Xrp z?t4V!PLt0PcUZ2sP&G7r#FfRXg#J#A@G=Ge zLu84+zg-b+F7V`y66;mfX2q9tKyJ~Vyb#~ye;TQ?H#`koX<(WmKL7R$35`5e=|@yG zCO;Pq5g98$+d4yC(PlKzIofQ@D+j=l>UbNfekR@a$b9nMPo8@AnoK6trmsHd@>UY7 z6e9A=G#&J%JCv%Z`mU5MX0PDc^`*9ZJynw%(!wxaHdxB1Ss&{ef+eETmmGa6uCISE zd^Ix0(CW<^<*-E`g+c|8Am}U*tF%Q%LVfjno`cP#HUd9T6lIl*sSMWUj1KJP1)%|PS+cPYhyrl1-Evt9;D?9& zTPy;VTTZktad3IS(zAz;+#z|sR zcL=i;QGef{_gm9OWGTZDX9>n#zq4tu@N4-Sdu&DY>2wbkOqv{EnC@x-%6BK^5){kp zhlUnX1$~!xnZ4ICqVzG`Khj6k9a^1j_0s;Ain~t97{^87@4->-%|UqlFP{%B!Rhhc zZ$0fvkkA(d)YzI>p-JbM2o;D6FzU0KACw0<5GKqJA&Y7I>s$6Q2GK*B{^}tmro}SE zsbMax!U|#tlw%jQR$MbK#LW6m{Iq>&t!;Ni9H?cA zW8!9vrA1h%{Df_Sw5XFw38Jm-MZ+JUursovnj<520%bfX%%-JaWth^JR6$F&{3$GS zlzomMX_G;*L(CgocU|Jctp7HzU{+ZZ44Ci4hh~aGxUfb!<*5dxFBO&Th6FfhDK2!H zmEgP+ACQ<(=TKsk5pshRT&iHNR97YAHjnU#o1)>$2ZNvK85o;8TL+@hAXsNN`&W)$ zl4$_N%G>-M<{IgOxF%$w>p^p!&44AxWzs zj$|<7xCWV*sQpR@i*?uLnyu$;j(cU6w9)%&1#z@wDyZ-z$>2KxB`mnl4g9?`YyQ9=X|k=|o?z z{R7B7W|1ApKO#T76;C0}Oo$W4r~F=CRuUiH1HH2=0}sIeY!)02sLnN)wxo59;+;DU zbuEK?LXpWDIiD<1NRFbIv8pQ^dr1KFW=lR|Nm*ouxFgdC2@y|^Au#xN)7$3IpJ3wc z=8L`MAl)U)ne?q7?u^roZ&Qy_o1IdBYsEe9Pqh}IB38$kru^pQW>S$HX_pcZBd!Z{ zA;0CICb`H|=0h6ZZB&?Tl?-3vsth3$(w8FKOJI0gT@U7QS#7d}*hDHvUh8O(sJ z#2kXiCw#<(mGb=l5>sq{r$pvmiJ!?Oj$JWC1^sbggE%^ufstH0#5(cJI`Xt)9@Sno@+JSWe0xZ%o%N+-i^;4NK(*7sD>~t zSuf1WrZB2aOT|Iv;wMZ-z!s(99gXju-!RsL!Zw?$8H^+^-I7t{0^(S zM5yhUvo|&=tg}BwI5UnDV)1WpA>}wvHEB}XDCEe&BWL-{*gwb9{6gF1>pO?q|G3{@ z4EXu%-9UNVh3KR*vbMZ}Oq~&&ELBkbFG3bn<0F7dwCp#E#R&(=>V-~5*Ed;ba%RSC zjK$7)!_y*R&`Ij*FQsRkKuNTTr?!jD*=E^HscCW>TItzi36z`LPJjhk8YdYgE(K`W zKf%&EQton>z-;ebb3EL2-6EaLaxk`1Y-LRJ-WIqcLklxz?;fTQUX(VqCq!W#lGrvj zyQZc^jR6xE-42o`$_uvxUxN2mn{$YCH*tc|)R`Ca89aW05%<#l^^FslA7multVL)C zuqECeLF0fyS^yEo$da6T`G7Vah!leIAx){G2`-$>W%y{4Nx3*crRM1NUXSN%K@8&u zOo=&Q_w^Pm@KlMunR(mFoPg}g`7*g~{OL;Vqs8b0PzUK3fDlj~At}%K0qI3PwH`;DC zmCW5tNI(){&cK4Yl4iy&ZBy#vSe&UveTw4Jg)uU`Z}@ZG_X-z(?0 zCv_gxXf%i3?(hDwpl6=p12BdFx8xdT0KOHow8}hJDh=&LF&Fa;0| znc&MCJ|$_mj&k zVuKpQM} zBmXN*oSz`2PA(Y}eFvX^M*Y(}COr4E%Q@Kei+<-1*-WRLHWT2^e2qCBdGpd=Xq!q? z`}H5u>G>1S?%e`{&|~4wn0n*LDUXp~-*n^G7KdgdHby7|qrs=a+jb_4J1Q@=$Q*Q6 zng)y#^BdU=natm}m#uvc<9tdmx?P@>+Qu!DB@mptH6m^Bx$$7+qRuCuG-H?5*bug$ z*k_mhY4@WAM)W~2j;hJqxs{OKj6)YFd{Gg~K10g%2c9W+7LEeB52A( z7$WXkhlQARhRCkK4oFH_RD-(LG6>-;>kv`|r^%iOgh$Wamz@EYKW~Fv$}Sz%K{Adm@+UB(ZMO5T=hX zMrDW_394*j$@L=5&qfE5t-r&36hNxu8u?gYVrb;@@FLn2!TMkm^oYiOB_S~Roc{vc zQgX9@qFnIyJqO&JME*DgE!b+A&BWr|G!ai=T_Hj4dk5?VJntPp3%SNn6}%|4O9sTD z_P`C&plW8ID-}bsUt^dRwZ`{@%8JJZx#SRDDw@o|XU##Yv`kobN&DPJzBcsV8>v;f zewJVL+zJH*0ky`)ZgLmUMPv)4F^TkbZs8z_+uTS`eW+&2g=_#u*V_M}7WZjo)&^Aw zAcqoDBcR+VMOcXm6(3IysJMU_!&BRhLd{MgS)$OIm^kOAc;43DAr`;!n80b)V!Cho z;!6urJHaYhziog{A){WysDhHHS{ZjNT;Bj@(v-ajaing^tT43WxG!HpqQ2-~^#m;KLKive~D z*+}_{tc-cKOvKFso`mLiZZ`+qJwK#m33a#2){UyNn0*eh(tFH9(@K^;@Sl;zehI~N zlj0K&s^A3HBGFdHh}e~~eg4}?R^r-vaI%KQg8=MhSmR*cq9Vn51OZr^-(MO8NUKX+ z8R7_IVO2f69_h*~^?l_G~&4*epyk%BzGj2H3ifu$} z5!wV{|I`;VXgp{ol}NL)y6YDg>i#GX)nGF;VQ9CDt#tCsaX#N@>u*{5{$)QI<5Lj` z$>gV=Gp$-`AD$53JvKGpiD!jm7yl7EW=#&Oa&ad(*~x&umxI4WtI7rr{QKbt%hZL* zCm8n~4|c{LU8T{6?24uB{hD3guy<4IB2CWJB%≷nemGJEA?)X5a4}_mh}7)DHU> z4z+oSgM>cdhA%6ERqjZWK)N%Jr;6_=iW^$ZTL-d<(q&_dI2a~PT}kn9qUP`AlI~?a zm`Aifa_A79Zd|u_%5-b^nfQ1DLzFKtxc<|o;#pw2*Kgj<=~)7cZ`$78Ur1?|vH6st zy+vYgCTt=f#@YIk4plfoq*_OCc=($g+t&}UrMN&dU-X;h~Seksu@w3BC#->`d*muT-g2AN%!P+Gp>}4V!Q?M z-?>K|QYoKc2DdGUc6o#_V&u4UvLOqp8&dN@OVTV>5k(`*&!sGs&kCD)7>x@W|Kp2Q zN}LWAX%H3J11$AvxIZynfZ&d-ERrG-D~VJ#d9s)Ezqw<~!RfF~>6dNf1vMfGUDR#@ zv#$Ch;;#!ti&M2?>1g#q94u<^J+Q30bOo6OIIJxGrIt~gYcSM?Q?@sFWL3{;IWGky zK{_}jE%X;hplJ*>QIounq`EQGSZ1Y9bdv|TgIb6p!muOtJh6>qLDWV)Ve)8=lXFqQ z)GCHGaao>xJ+&Y7vHn2;{=tm7QA8#y8b}gkA=SsdqBPo=_cO%VNzsFR67o8mo^3RA zcT_x3q)uAccm*Mew9lk%A4sfp=le04C8D2=&@)4vBEh#4w34lAi$K~OCO#YuAH%Y* zzK78+`@gHPiZZ9|(QW$mCND=rLjh+)+=8x!DYA(2+^Wd*}R&yAAO5`F5N!x zW7}vY($ZA%S}~-EX3}^avPbw=x8%wkIDacx9CHu^B?9i>Y)dWB>^9hEs~}cb|2YDp z)0oa{C(x_3N}`8&1N`{cT5Wv{ow=c?xAA{@F-1BG$)C;nR49U#ldy%T%om^=iCO)C-uone z@rdK?2JqjQv-cK;B4gkK%<=QON6>09Y$w#4ZBZsks|>&iCM8jjHSq~t0BXi<5CJ(j z0Xf0P_LD3VN{1)(HBO`B6Ro~s5S7(y%DQwUysNU?JHU+$GLzjv|l6PaDNkfWwaNeoxv}8vdhEb7~+^Xu?5gNnEY$M?!g8k!q*Oc9QG0 zE_%kRIAf7Kgq&kZGA1eb+*b=sw2vp6!kJPqnRW|_#!M+ye~=t9Sul|&AdTFV$p_mW zahA)nqB$-6DqXykt2sxZsGuIxD|@$2F-h;zYn#%#mepcEJ6@egGY^w-7|}Sk;Z1hz zGzgD~cwMg;Ocga*QP0dI2`)I^Xi0II50J_>xF8-|ZiZqAcbhjl`@LDqGQ}k+m6GS3 zq3$be${sc5zSLzJ3mvok8;6Z^MVKZ=Yoe#A4BJ~+aA@`QSC{(@>$?Bgqk$5OK5t?& zlL=24J-+E4_%mx8nY&a(D84uog3tZrL!A*`(7!`}&b;=)cbW21a!!E5D)DiN2v*~2 zGYxtV+E2EnkY^Q;vWc!}d;IheQLZeb5I;iR=&>rgO z(6a%3Cd=xC{Mdmd=;ZZJ?xJ4k@~dIOl*DvXDR``lV-6KAG3(`?n!@xeB(R9LjY}_P zk5pUdR%U(bF1T)#`frXLysP<_pLl20vdBt5Sqch^aKUVF9mv6QSJ@2C6LZ}k%bV-p z@Q#bUMp!&a%IPONAQbHu{Kj7md!fX_t~x(z3UTsus!Te6#A6G6KrDL&CY5&per}S? z{nDnTj%%@&ZhL0D(cXo26W_*`)l)Q~$Tp?aJT5o|+B=n27fQQbcdPo$5LXx4 z> zH)J&pz7fM{$?uvfnW6T(PjY?=8e+%^W*8x%m?xZHf3C59XXclujq7A!hgxyo+0)?M zf<5;?!+g(%dhPSc`CpPT-OGLN*J5NkLTgr~zi-*XED|f+R^TY;z&G+5khADi|2Ly%Bd4@qrng34iaB%`T@21M&?Tr|^yGF5^OQMTCk(A&84FZ=*| z5AE=t!)qLLmXG|~E4=?7oyV0!EP^M)kjGK1-3QfpR8J{`v6p?3@B33H`SHIrgY7&@ z-u**-OzRQ)%;l$4HKMHfDb<)!A>$bIEzxn9votq}YlX!bF zt`ax~kg>XUoL~IF9EYB~!cYI1oOdm)qJAS9E*@1wDWRIP7paWdai>QizdQ-)wwbnw8!vd7&00Yh0#vBap`H z-S$P}z3MthQ8Z0ZEb+v|krOYM#_RDpc`b7q@1QZUQR}B9&TBNl1loAtG{z)EVny(C z3}lU0#_W&u4=fHaQyD+-m%oEMe_)oG?ka~FVz>72fB%bf{6GKdlhI%{SbC9Dm$<41 zTZrydO=+0nIeF&DjYBd6;>j#n5sY^j*+%V)e9t`{?mzN5wp|bDKFea~Ec^XMdU}O- z?Eil``X?V^=yEa(Q$M!B=<*JK`)_=O&wO$p*4!R}lMqp#jOI$eQLOLtTa`7>gBrMCA+yQqpNN&nB%cP0^~Au}S>^HK19zP71u;#GAkqIx<8y zwpo4b1vb9A4;h8@*Sh4AO#GgF-F$Bnz-Z~4gIlj!C0I!&YjRo}QHs&eLjKYMr^3lVR+_mzpxE0pMw4 zPW>1oA;~^TK(|SCD<>MIFyVB>WAJlDEKQ<>fI4qJgLW$)E3J~xy%2;I@@z(fL)qHH*yNy2l*^^9YRhW7K@*_~B+Ck}A zfeC7(Zp@gCSGC?S24IabuexvbcbgXU1maYU9gKsq%F8R-weU}hM_m~;dZj9%N^ENo zU`>-X{7%5-B*4&AAa*mTwfZcHkg?JTv7O0~w$-;?d{R>EV!Fc^pxGGo=J5Jxuu;cP zjg49d?#eU#B?f$Lib!3xuJQ|#Zj2Q4g@UR-D7%jlq1syb1XXFV!SvJTl< z=JuWC_=(T4;4aZ+7|Ir4Vl-SxAsuNrY{{y@iy@aQ9L|27qYDPl2osfkBSGm(m19$| zz~rn?uGG@|s*J%%E!!n*4h8i|L9fSNt68TSrx5kzSY9z4J+{m+TjAv03t%MH$_?!b zt7w{y!Ct;}cA2l9-pj_5z_Ux}XcOEzh(k2Msg@F7IX))W!)q~^TKdM*tDT$XoEmQ2 z^XboE^kqF|-|^e9D-W}}_W_FDL!5D+Y4a>Yw@GK?KCZ9NM;VmH zxEne002no%5nJLdkl|GD21>DvOb&jE7fx@ncBLRgDP&0B3|Uxtmc0kAv6v}N3S{Kj zR?ChK$>bv(>V1;Z2+lyhV7M-pZ2CGdTlLgyG@7B7hiFtu#-onW2)tKvEG2u^HA%-I z$T0T4g2u=5EIcM0;vrk~`5Nce{tex-!*DdjWQNNdJw~#D$bD7qzN9Tw5I|+9){-@W zw5gmyElX+*q&8%mKXL6E6KmHBLXMY=k>p(Si#Y8vDm)#t!rE{zWq$_x;Q);r_1f|I z-JM#w^36@J##WJu-wjIoNTtWudTapI5(wl1U`mM*&vIvnlif#IlYh^)ZZeRJ4l@xH za2Ro@mzXSIahlO*hD}*uq>Btp2C^2?gpEagM$p~^9}7VUwR4@SO=-`LNA|}fNgI1i zs8gp?-2|isNorkCFMtq18c-mE}>p$Y*EGS z)9bR5nJ^w$(3C-m*C*XNz1O%_m6UN-zn?Vypj#$uM637HNK0);R;S!c!_JK3T*=fJ zbu8(*#JNaowQS5ovWp!^S>Io%U*j2-b6j41C(oQN`SjXhZj^VU%o3udlkJiE(9|o4ZH&%Hjr~dMFV($GbEA{; ze`1cLsrQ5kN>|AWKyr`_#~dSSu+pQH?U3olfMvac$U3DF)?LnK zF~pWRUVFeWln-OlrioTzqxP=GwQD3tGzTg0b{g+b(8=y$VdVjKItRFLY5_mG4vVYk z{DAU;1A7p&+@+W~igu;~C~mhgUdXmCq73QKp~O>+f%{4JzIkLy3zD{Ui_&Y|z)8u7 z400@0nFjBTQEIrrSbbu!p3H0s1h#bdNJyjCwO%500R#4;z%fl zm!a%57`2Z^ZxBkN4$Bb1<20#2$!JR+ofPZW6lBf5G4WpW{ifh<{+?9Knuc%l{TnI4 zob|Ct&FING!GAJoJE=J1%FyoM;_huoN>kIc1;JJ-SY4bT8Pj#TN8OfG$u)Yn-R_3S zjj_0OT7EK~s*lEc+3Z(SiA;B`@1ELg;&+-O7l6=os^|b^L^|6z)z%Hi5m|z#d7B^o z(fjz3pD?V=J<0mMi~Q!l{sjN*=RZ!Te1yU3BNSU*x^G+N-oN-h7B24aAO7ioz;E?q z9nt{1CX=u(GY}OeCx{O5+GnKe7&DCC_QsBsSO8zB6x7g*5~~yHW5N%J5kvTB5Z9y- z>UwEXQe$MCI*^>JtnjFRCtu)Uu4YdF-8zb|y2k{lqZzQtd%jQknZLD&Os&vcJc6<3 z;~^@s@9MEe7+!&o|F56tu}`iux_m$M2cSbzN>Bj1)4KPJ8_zUe%UHWw`evfnB2${z zO*(keVH5@!GIvOL@6W!2@}9#y>!%rIi+pHdmd|V)qL&T0cVWnT>=!x8moPfO#%PaH z!tp-A&!y2|izZ+cXGS5N!d)M>5Ldeh9v2R719AiBM_oR)b3Y&3S!8Rd(7%HCIW$(o z1R6#YjIY&bsA%)=>Pw78!|Zy^%Zy`aFmB zF!B8{=}t8lwOmZ^3R32%J;eF1?C^7c^?Ae=IOoIRNW(=oFB}EUDHFdA#U}{42I)AI zrhL}1Rxs9r-MDw%B1uEx!XYRCT82Aaaf^JC@8c{-IZsB#x!C!&q*@Q6M1& zT0Ny0yki)*+J?Sr0&R zBsaq1khP4XbTZa5CBG$(0% zt2wC=&}&3!j@w;HPWXxU)5vJ`JWsNrlEsiNi?4jsK5S+#Hb&Mr<+N`Ecuf8z3QjPi zHvB}}qf83C*HG7;1+HA)SD8FI}@NgCfg$*n##S2#7Nv4I3F*|kZ5AFr8=qA zr*U_bbovi4Q)>U;P{Vc)V2qP>|$_(rF7#H)mv5_BP zxYx4({ywAWCDzW4(4sb^6JsFg`eNmGJUsL0n?CYfPeKq59 z<2cqac{dssljf^V++*CBozxh2GX`G1t-eykZoGpV``*`2ue`!06|Bi`OpfVpt)-Fj z&{P`@LKgd3uY!1F3o(`kLpm3E#QyykxcmO6*!CaAm}Oqb*ZH(Lf|z$Adyc|^5`B9I z9+{>0YzCbYrHFO!T%!fyCz*e$Iq8%~q)Q=Pj1*+5U?PB{p)k9VW)0ogavdLuX6jOU zQr*vq@zOz#{rzvn5A-~SYL z>i6-i;^K*+P9W7j5*5sFimg)vcAm{ahM*UtQr3uKP{CE6`^o*J6Mwh#%}1|ArreCr zHa=Gc2I$l#dhZp=2cg{Ru%mN4BlqC_Q92o%zw$NQ`Z>O9aghT{1rCQXLox$Ma4Z;s zRNEBd-_1x7X|}wXwiV;hz2J;+VSSE|JbxFDUph&t7ZAUO@grOnIg&uH$q4(VVd8iB z8yYDZd|hk28DY~fhd(v3mjS>%iDlDOBfBatfbuT~;{Dy|}@T^6c~Q^mAviEN)Xm0Y{QXcx|(M)NU085C(W$AQ>7OrbHtI>|34dB}~Q z1xv&b+;Op@wx$?g9}+4WL z4$hqk?Gj7KNQiwK8zN0zZ0IJ9NZcx;PaAz}{-p70+RVG{r!=c|Q6B|VLt?tLXXGZy2?~1XWlAZqm){pa*->~d=*yDAX^1Oo-{W|hj5{U2<14hR+(R! zr!(6{aCEGrV@h((G1?2Tbml2D$MLtH<-q-4q1-yjorhub$~3Fzw&@QYej4=lY24f_ z>arTfuom$h#B@-Uk(AU~Kf7TClfd$=Ni9g)(k)6~&jx-OPtpyHqIrEV+{!XzyPV;w zJIpXU!ZerYvJ;}?#862f$Ow7=dwBj)(f zBiIvCv293iA*GF{s5*@i7?XzHqyc#|;XA2F>;~*L@4ef-CdX+v+Qk6em3ABJ-P(S0 zLH0*7$X{1_wSC^Lt&_rNQdoJEVSKNMe<$T2)z}Fq*Lw^i1tWDhzl!k}$l2yU|Dj{N z{gH1++ax^+^kkEc_f!$_p;Xc?BbTD-TvfL;sC?GsxJx6R_=ms6(_g#{=a)fJ z{ilgBZM>&af)4PyN#O^0cNwIJ#oPsvFvd>7Yfvt%nF40R3C~(GmL@iKILpldn>UBj z@vTc=&-_dp8+E###5!8t&K2&opJq;#ySh20S-_AZV(1qm9{tr1@xT0=N4flG-_7^` z`3KpVKF1z8!y#TGC!D-YJIs{;03ZNKL_t&=4m6`WVP4S*_Md7p$JS^tmb`Wt=oEd| z0Z~5xxgo#%Pe0Ap>Hs!xMLXZTIZ9`c{SI)+%>zsPV~ni zPj-_FlQJzmvjugzgL2d(oH>c$UQ@V_k z4MaR54kI1Z?BnvsuX6d+uTylk2+kkH_+Ciwi)r*qfoeF!Qe2LIK@jFqa;o)SG4n~j zm-^Tk+Z%@dW@Fx*&q)Kf)@wrELkGynWS&yDICd2N{y%;fcinfL(eOH!EMy|PMZ`bC z&;IO}`0d~RGDz&_u2EjE)GlfCHyrh$l!(2~kN?Fx_~HNRc23I-Um6_ZrT)VlKKK~> zSmem#j>rDV2iaO1v9aC3op(Tvy3vjIzoE~&@u*g|d{fgOIg+&b+2k5f8tFLkbI-NS zRet^#ew~$n`vgDz-+vo#{lPAMzRY6x3JWGW)HRk!tQm|89%UUbNuiB{0ta`jwwK{;eB%#H8L{*D|dOgN#S^zg#;f?KALr9CdxxDhwf=#tyiEl!BQH zt=Z`^`olBul?|?Zc#E}i1%KrLvL$#%NKqgxqB@K^by_i6FZW8fZnk+hJ-cC8+)!d} zQfIkYzmv@qdMHu4h{Rwe(WrwhAkyPQA9#*WK6;8ggPxtoC^+v>|0%Yv3;q5+tV9@2 z>wBkC5dr2dDDx4rRB-aIy@!L}^ENugfV+BExW9Xj{dS9v2k|A&;@lH-( zoT2PJ1KdN#G>YQIp<0FrG?Ud$sKA`&3Eg$-{f&Zhx4zu0kCT1f?Yfr}*spXynfUva z=(Rj+Qoz3&!}uFPuU1)mEy`C?ay&vx6Kte6Hd6RK8J;NuXxC@xItYeLLbT-E@)>6K ztReg^op|4q+Clg(9?$+HM*BcXbwV=DO0!UT@}swQPPSRJ!q9`L#UdD^SReH5CJ3rf z1>1yxH>rT0da);8cuJ{H&y;E?LKclu5Wrj;@dAToYGB~09rVj3V!LrzeEncxvNo@% zM;U;Pk+`Ngx+dTQV#qT?MuxTVBuWT%Ptys`(wO^HTd}c!Uw_c0r8l0MtNUg=C^@x; z*y2U*b_FN6%(m@gWs0uP5i(ZG5np}bIX?TvoQvP}UY;+%o6CHPJ4M;UCbQB9U&crV zNGWCF8+#;et{738Yy|NJFC7MEi7jRkW7*ib!sgRkuwEkCLtVyL>gKEFr%hh`dhp+y zjpJ+Ot$&og_D0B)Nf4l(i>mUVngEm&4mb+VEEj5C8UdeyQ9MJ0HP9;*7A|EcP;)OY zc8;+>@1f=ts;BWL7)jP=xJ!z^IEWxiIC!gyIMOl#ugPgt0*(&zpk0bs?4_Z!Fjhyd zshenH4sV#Eo6K2r+Q*hal1G8Zho^^{jA1PoO!ZbddC#NVbKfV}ap%eC(h)(*lN7~m z%r0c{$vL5Rdcloz-vl3T+~3tDYQorQ9@^rrvAFLs4m|Kxp5_itxnaex`Hg?wkOLkai zP1cxV8_|9Mdk})-J06@SKzv`-Gdn%v#GR+f_-%Ijm+5q01darjqf&9H@lC1|t$U^Q zI?mslRfn6Oj`#Jo>i;(aelORCnqKRkd%0_GHgA)3Gp0Am7hpV_qghaD{5v)5*lgc! z_nx$UC;5)YF~Z?vuB8xcj&Sgnsz<9soiymlWgiCHaCL;rkkVbn>X0mE!i6k27XjG1 zVA}YWsH2sW)<4b{(}k%XdNTuHvTrY^OEl~QQkB|JRzNkL`JfhwHEdy)wTs7CyEw~u zHjO6)uFQ;$v8~p209;c%wx>YZLZ`Mkb9cst?^tAhaD{#O8RqTpa8ORsV@Q_~MoYX5 z*k;6Ky~6e7Ip*f}u`Kdk^cIJ6yZAO}57eJ{UvR6;M$`3c7yCly2Zv+3{20F5vS0Of4JCe1_dI zpj{l{RLNjO7(@&+(_Ok*R`GXZLT$Fv7Ys)w!%;9)UjC4!oAqxuMgR2za9*tv@Oskg zVHm$&^m@0UdA}4nTGzC#3k+l!$(fq&(dqUm+>pE@h#z51D9P>oHifKK$vU}aO!*ly zxr?6bBQ8WWYxO^snmT4O8n6b+kz;ecKy68HI-LX^)u=`d@CwcixF#OxZ!4wK7-d&` ziw)50!c;dX-~oV)cZoF;!%5w~IzYK}AUMPemM(@F@FAL~YEbGyr94HY-dONm3?+)I zGI#=HYVpqFoue!SRmb(U0cD|pjo52Lsn9q$=>*Q#1U9wwtw)pK#iSzcuvx~!+zg{) zk)_#L=8P~eJ9KpwtCn0dgbrRymgivZzyW6F58?6^24;?du@vHP>ah}zod}PP&k*Y8 zrgh%1al#%^R15Ec$>$H5_50l;KorodTT-%SR-n*#llj zKo6Vu$c)7oeegr9SW3zmfgBCeCO@2vD60+>d5z;*fkHyX^wS60_#IH2@N@+*cvrB# zc8S%k=Mi%O&B1w~FqDHeN(Yc(RcK1T-RGy-Cexf4L_$Fe8zV_g-o@mzh}mJ}uCu`$ zYYZ4wfR`zIS75?8HKl04XjYB~lVak(#k2OEO1`HKQZRwmg(_XU6t;-DpszEdv#&`_!w-s?3`=GjBwE5%I;O#nr$Y6Oudd_{iX4Oaz}Kq-GS_CHG6H z)Ny_n8XLv=SVeO=j9FbjW$69ujeWIqxt4Rjmi=GpIIp+u8_@@URoyZC{9kFm!+N{l zifZsX{U%j|vwF3CU+FsrV>672_ZVTl_1^c^f73IG`t)Fm0art)142QUGTEo}WPF8e zOmV1`y*GRe5J&w{+B!Bi!ByYa1-?r2GNdnnzHL5iqYs~dneFKjF-(kQSQ{!m#TXEa z(-b8Evl+uiR2+SPG;~$4nji>Xm2S67yY28X*li`yk`Xgh$0oZsLTpGy%iiDF#n;h+ePjHEV2y*7pO zmuTmCWiI?GbMfYv5lA|ck*q3J=VUcSPv!Gq_%AOl@*Dr+SDE_s*ZIMpTg#3I3c9Y1 z6@nAn^A`jkOWg_}_*{+8{@TMVEVU!MONlB4XW}3J?E87(ojYl_ z3yermIs$p__;>%`6a2v+K691vUdy>wqj7J|Me#qMT*(2xn$uIguI2AT$Kvq5AY{E1 z7&5GBFf}>JfBzHrao2r2Xck?ryZ!~#eF|d>azfX6qY;?Y1eH2gGBT4=lY~qH4{o3R z$;2F?z{^u+3zW`(a;}o=;C^g$whBU-)^)p;sZR zY0s}V0%K$FiBAaM`5h85QPcB*rQ}>Jn>R^_PqZA&w;bn}nsj}}>iGw&Ihh7D1;$X# zV>Y*?>@F-~siieuJ=Wx3{;RXRcK8g%@+poT*aoCnTgUk}>SJ@aa^C`j9Ysga*PBm< z^+x%3$o31_Y>w-%+r-cQgAX&et`3v0vSsTZ;=)+1&JX{0ckszzKA`Qb10(omtk<~$s?EA>b#w0Il&M> z`no{r@cmbv2jAZ>Qd!a^M9+Ghj~;{N%;^<={^!5Wu3OIY(?4yv{T6ujuyW!2Ikf!> zi}M?R1S`S8FB?4$uGuWx)TT_z z7?bG?6Ui(Ibxge^r75uS*nK@;HuDk%1{5|$0$CugNHVbvxH~P zHdv=qj7yC~l9&WyFdCZlCOXB0Oi{zq(i}2jX0x)aipzvf9ekpwQzR+-atS#JQyaFk zX3DZ~_7%DpTKIwa81`4+{Ll9YBpt~}R+ZHNQn<46P`oQR_38p=R&w0g8>mTvGEbq) zh%Yee0#GCd^%fCfJWJUw7b(VHPjfP$?Qf>pSpp^zxEt2?!QF6Vemx& zK#dW`Cxmz1zmAIwZN!}G&yx_lO9m&qPy%RVgj1achl=ZXu5}&rvW$`rHd*e?>oB0D zSTl~YnM76)?*eEl9>k!ohPoSR&u`}WM?S;Rmo9;wh1O1>f!DrS(SNimQSO0_BYAVl z)dFkU>)lWrOIUyX6f?V^NEa}T^BB6JTv`Kw*QUEf%8e^!XZPu=TiQDeGnYX_qq1o<|7#k})d;miUYAH8DSHK&^s1M0a zUQiEdS|?BEX-u6&&ZHO_L-EwdQZSdW6Z^U2o?Do?IiP11S` z0;DhkNk=l0t4KAA##EN`)x?21Fk5Nlo0x2Vh^%;x#o`5;-SfESGHb>&rY6R~8=TmX zktVQ>*J#)_3sbx4yyr&VxBg??aSAqd3}Z=HSUc8X#*VY=_Aj$2&){k+0jSczhvL2B zCy!w26S#aM=or^-P_LGyGBU)!aam0P56f!KR{6f%KCGOEBbw#sj*vlG8UhJ0hG#wA zPtxWuIWu;S6O%7seH+pjnUwQbO|TfO#*80h@gyLImTPgTxxiv;iQLEX^d5(2aM&*E zPVee;oA1J;Z^JY`$7lZhSzb8`97Vs@Ivi{qR=yA6_YC{{Cos&g6U zaCUAp>(*~#RJ8Xsen71_qK&&=@9A9P5PY1+qjg`b-- z&<eqPg z`6I0AjFu$?B`|t<^lBBU2D661)@tN!XuY*PsHV(bG8AqnMz(YD#H;-4fBrbxrUg#u z7)wQsY~dBozv6+Mf}+2_f&14CjwAk`nVsMle&Ji0n;WMn9L89X1g~}4)=1IHRYLnC>k5+Nsvoy*mb*fiEZ z@4%Zi;2)#8xWw_(E6h!HsZS@UFXE#aXg12n%xGvl=(PYTQ0d^M1+)?AfM$e7Wg{Es zuZIl#5&ghrzubNpK)u%emXfmN&NaOI6PvK=S(_MM{!)|u`x2xGbUu!Z0!wH?OuR=x z>7sNHEQT6Z!Q$!SL&?09wz)$2OD_}@+;;P3e(Xo@XKH#ZBy?Dz(^Wbh!@@$F-~7!- zIP}WtFxCNmQ`IMM<$$jaedZaTsPS{Z@ZDT@$3two@i$ozhp#0V3C)`l%}KQgO%T=L zMd(U`11v6hP#Q9@i*yY|Z4y&EhLJlce8%idgP-}C2ibMK#nnH_-W&ft4cB2k1>P9M z=Va~@|j_p8p3e1zhVD2=57UB+4(+(5n7{+<(#RZ^4+gWlCMhuCh zcr_Hjl3ByS_6?k0x|K5*8syFpxavaQsOgQgADIprMh4YMTz3v+2QTk?g_oc0gs5)> zFw3E;_8MM>4Aa8n+9{S@C=Ik|64X;2Sc|a2*Y~}|(=RDDu~0S!sMtJ4LK%zEz_HUz z3}hx8sMQDtnYaKRT&DEnd-0$iZCK2f8Cv6Kxwuj=Vaig+grZo3TUo>M(k$K9R(vsu z6duD8q3|>hGc5`%;TS)-SCGal)bZ>E$0d3-I)6eR|ERZ2EA#LuDK$x34eA!HVDbREg2aT+PyI@e^29wsZ6SvcF__y721czy{n z>q3)`9ynU^#Fb@~aeRp-we$i1NC6{d_L?YO4V|3GFXsnO{W35%>^HdACAVGqy&Arl zV*WzGSN`HTr~!>>uohNMLUSU5o4#_l4hI0jJd0S2QJg!$#M(=|^Mm)Xb-Se~a*{;A zCwOP+h;qLE9E-I_sF@>Vx=c-0u#zK5oo+rwJ2wS6unkXh*OKe#e$>KPCCCBH2x;oGR z&3X{naI3MA{Ff4CFdM#qW%{jos-V}ktT9y^$ALM@%+__>c<+rEg;_hn%HbMfLJq&g zqm_U4yBY-kYsgWAEU~0ELDVCnIB}sdq4$UytRy5-LrjfMew-cG9p+mW*{rbd5jw>^!{MA(06R0!^KF<@#L)oT~G(n$0Ht7hS+ioag%cZ{^N=gv1;q zO%`!Za42F0Oo3_##YI2I1YT+lkhBrSIp}u4`&qiWi9$Q5Nyw53W;cxSuJ>=`w!6>L zwNTijDCd~gB+&IKxYC}Zw5}YvBwS!C2mDq}E^X)Fi8-FzH&5%54bN>Np{bg&h^?U} z3DpuVR1!L4Xp>T;HB35=NIk|P``UB0q>?wYj6l+njATHDo!r<#TtY;3&z^03|KGTu zMx#bi#Km1&*u>LmcKPJ*@8i&sdDJ;53fjpA4%Y7BTsFg+NAa*_K5`4*LXF4EF@Jpx) zBG;pC2JdpbXzZ$7mL~^RJf{{DGh=PnLc0MvjVo%g17!(@R1F%~N;l>Jp)NYNlS$vwsbDnb-USo3Fk|s%P{N-bx)BqBBLjM_6r7aSQ8YOT9mtBHO zP$@iTiY0LAS_ChO@isUZr0jdv@$%6ZnSXXCT-t+4HUylr(D2#=+R7kJKLap4^Ok@v z#g4V<5GsN{&?RoACWLY@}DdIa0}>EJb6(xJXGNWyg2bn9ovi3^nQ=tz#ps_`rR; z_^$7|4QnjoGVm4$oUOGvcw@r8>lD){n5IP|{Sxc+KVao7Et}wKhk?BybGS!n$TA`}1{o&2j%$6% zdspr695mfU&;-K+kl&6j)lr#3+&D@aL0Ujd*6p%n6-u{X5vC@l*}ii#xtwS74PS(b zU!k34bnP<6IE*G3ox)1OY;u}uP9WL=^&ykj)X8NN`;G~Zec{WTeLAP>3an(PSiFhP zp|A40j-H{Byb-Aa`vG*%Rj`^yhDcDEdlwDzQ&H5{}d*EiB25w%-5Y`Vec(C)V$RqsA-#o;QFD&q*-@C+3yFh~Z@`IQa0mrf z9L^h#+uQlliMx6H_m;`e?8W4p$+C5z3F5(f!T4GT?1`YR541XCLLia^FLhMvNLeL| z>EA=Wxq0(H+ar*4BqJG+VW&1`IYC<>4^NDZ4P=g%+k<;Rcm z%5lJ?ILVO2GMRcLQ6|uy@eovniQFq8n{bMAWSm2iI?ZH;f)?0wBytf?hk3t|=iL@A zx)&3p?{Q`NuL+FsVrg-$T$FS)sNZ{r>*Rki8t-SE;c@BR4eB4bDpdABb1vD1G zpMm)?Y-b&ziCCGBQ^KP3{_dY$$zwPR#X5?jG>B3{J0*ZlFsgcvvW=>@KzehQ#kTi8 z?lVEw&wjN403ZNKL_t*jMx5IgzAG-?$N+_<3*-}VQ@HkAb+j1p}UUq)2&Sy+< z?JmyKZJpu3@xvT=hY zFmR~>H--9fI^7Nje4X6YxJfQBCoM`NT~sh-;K~H9TlL}RIU35+jP&;014%W)v6A4m z7Dl370`Wyc+i&FYLlb=M(Q%F(-T>V-(5>|{5_;WaODc{Y$R+V?!X2+AAl%FBi}!Y~ zBX=ofx&9~qfv=)kV~Qrze1?R-pp!OP9G|9>T>`EPK#5iYd>T1)eQ=kPWD=ilWXtv) ze9sTu%-Y$D6uyHKOV`(FcP-)#84bECH9q}?mpF1b$56v*d5%QDwUY4@PAHyTRgcDX z7zd|(Zja@>lVtlVLvi5eap~JF5QlDV$jvFXyM_9MJO>OE?YBfduN~l~A zFq%X_Dr9zhNpPCr6+9`P8##J>n$Lai6z+IIx7ZSNm^wt;sOE9J!`VC|8OgOsv`0!F z>Bv4xg(svaU6N)IL@btc)C7kIrns=PR=CGc~**ovqha2dpYTD zpqrcnVrCi|i>lxJnP&g>ND1_nHgK$V($W+8M*2~dYcF68XVvjcrwIxhiWcWPv0R?O zXRAHGGzL~<0M=mf>aev_-1%)azV#zJgMVG_T+2=fV7&y&IxZGrUZU&T7?ZGK zJvT4Wp7(Ad14W@`mqzJM``x~k_@o^ zuy%Kyw)Z5Ol6t5~le#!E>!Xtw=*Cn$LWYs8oIFzFlfV5Kmo6+KICOa%+qQe&^BtSG z{hkGq>=9h{IL2JWtBsc~jKwQqKIvxy3j!`BGrQ;>zm5HW@Dzw8+r0yl5VTgKp|2oi zB_ODY^DBai;uUhK;TZ>Ngo?y|o2~wJe{1NU5lA|ckqpQ%=;VPEYvvHTq>Yml^*_ap zpCosSsI);^7z3@bHl6y@XnHrffhH-oSmXxt5TeR9In9_|M7>go!4t|J69b8AjMy4- zrs%Mqy0-D&gUNxEQ?i$b#=e~wvfJ>cfpW8sG5QOPO`@SD(nY zhzvy<2aLi}`BqC%tJ}a4N+8R;(lYZ(R4~+fO0ehL_4ZRWWQL=j)gw(n{w~Dd2}O>g zEVuS@#P8vve;#S?i;aJS(`dw_odj*J0iD5gr!bo0alMQj(~AX{XCjx4sEp3~=yLW; zYQkBEF2f;U;7KVvp_ZmlfH+gi3{M5TmQiO<-OIeTf!79rq~6~pvZmFs_XB%~kGN@>g(9f; zF(?6EVs^ZT5F{D#DSq>$vewA(Jt%Pr@)$9Ag<)MKm{`_sK*tfLad=wx(>VKij0u@B zDxQYvaF?HFw=80`Mnf#)dXg03v~1&evYD274X7b1SbWTj4zwl4+Zd`+5;KiYcH+$h z&OVE;e;TJ3Y1ta*nd73H0$-!yH(jPHj@h+LWT3liNBMvb7Yo8P?j6g_Nj}c}s2*9F{@}psK`jN3|3Z z@^!tRLiKiNz6))wp!p=YONi#c64sqVWFDo}%gP!(KO=c#QraD5*1xAup_HOzkWa%U zfn*(xj*y8Zmkh*ENSChl%$toY$Y$D!WnP5+b|F zomBi2F`-G1W^t|bs223I;;VM>wOq5x8YBsr9h@>Z(X{W!0J~UAYR;hM>9}@UkQ9#r zX#sf%9+3o}LY6U&mpM1_Cmf!54c9F|0?@9Jdc{QW-I9d+RxV+aOC7 z12T)s981X>&W+8{&cLJ=BVE)5&!j&;ChCO9$K9hnTV)>eb+B?jlFnf50nVh`Ia1q5 z#}`-;8syCCIclPat`MFxA2@y0M0@T|eEV)}dj@GQV`$*=DM-)K%D%`_{YC1@;}~fM zdH@s=-%nGKzMk{F>JUrfC)riZaO3<|v-kRpYiN3J&mis$h*I-#@pUzm}CW2Pl3doxsXZfH73mg#u^$x zVLVH24PS57nbMSvW9L{*W_c~y%l_;gw2M0K;m7dL90h6M3viFGg<>b61hRS#*Se5t z`EMlGELDS|e0A|}Td90p?HcsK_%d^)1W=3^tk~cHs>TlUS5it&1XWk3LY1o#WFq_@@N8#Spv1y()z&}=x@978CU59q}MzKeCWy@ z-&+U@8!&|CQYryr^(A&AB~P1FrX@nkYA~44G^2Mz2ScbFVZU$^dcci^o%iiw!(BUR zi=(E>xfho>^27>BH%HxBiteR8_$nakW5b+izVvXUN));rTj{vJ;pcKB|22yAz{X%~ zE1`VXV1v=`JEY`v<}J_t?qN>dc!s%e-$t={h3)AfW|9@G`u-DF%|IUby9D6FbJN4$ z4d4T4>c!%;!E(Na$Ddf{rK1g=`pRaGJUfXyr9iC`>Zq)0D)h4mq_@H0sE@;4-*q$N zTV`LP2L!juuYFu7dS#@i9x0acwMiQKk zQTR5_?!#w)1g48M;g>a4Hi>7mhTvHuHP9M4<0O)inhen~U=0bAP=b4LEi_V)h^6bg zY~P*m!H;ia$KKPVYyJYM{W*zQAeD@SwPZ{q)Jgqj>QeCCKh)rz@4A68JH;12_Y%)M zF%L35ct+)#TV~P@&r3x31^GZ{5pSqfIyOz|@xT;btQ9pO~# zWzyG{=q&V<4&ThCO(W3tjY!nra)$SRV2*d(zY`ZLrjx|-?7ky>_D>F>Zfgu;!5jAg z<9h05S>Bhh{98v6@wAKM)SkPDFBCET0Bhh-2?1QOlVsT>lWR}&o)2th)2%zW>DHGR zuN}dsaWoOQE9qA(f)NOnaxwU%9%J(mM8?wahJ+Q;$t50qa5HEL@RH{Q68AN$F5G-mhX(gT?ERSE!uKzzTJddgZP05jvYgpYo_ z&c*j0WN zK)OUu!EiGUXQ}r8l7W4dKw!y)(?oDFkJGVy{4|^_TUZ2gbgl5tlzCzrzwdeuVu`Bjt~NLQ zBJ*wcVcvDBz5tdj+%SpY0nPQt_qKKh9bBs7p>9mg&{&ofUr zMAr1Fg38y+RIOBAg}_T!-ka5Xsnp>DWbtzsc;;!cdvB8;{Hb}SW)9-DOKy~Q(#4p0 z#ze>@rRxifq=+OWJ_$NQJ*dS?f;T44wJXA!cvGWY><6)3??t&S+(rI+8U{h)g_xTBPnOulDhzurB5Eo=8` z_W$dx+rxpEYn5;0`_*G!d0e{ce#37}@+u$r_LuoPfA2IM*9P^}lQDkp_m1(GpT9tN zWfP8+?qy@Vn!fDYI-#L~!8~>Xeey7h<6MzKr$%4*=alw)*k2vTMp|Z?sr6sy!5_|f z=l!0PGt{(6$RZtNlNJ(0Q-mTkOs0smC5oDEXzoOcu^HAR6cewq{(Wb8Enne@m3Q(= z=N`76Z*bwrGDluIM{g}vTN!860c8W^G9WEP-I4^~r4aIEkHKP8v8EssC6z9g9Er&; zsR>PEJy7^i0T-H36_I|gVC~kN5B~TxTW&qhtU1G^gsLB}^eB|P566$KpGbTbC}#j~ zJOz%f zAbygQPoLn`r(V0l7|YDhLFogIiZw8~c|FP0bS%v% zqkY46;4H7f&Z{Q1mA@1_hE1kP>XS5PCdjf&te-x`-M7v%K32o)7%TZWPdwM;?7YLP zAu$=L8ZMnX!^*|uyzTAVc-y^mh-n27T3w8!j&tI)^31aDAZvD zQgvkFG19;PG!C|?d;I&l%x`!Rv5py+vGoDV+uB>1Zr6D2K*8t!ce3M-uL+#1r>u+uz4MugSMy0)7>oBA(zR(j2LZM)&6rx z<*%Tl$~A{xCaJ_Pg@l2?9qJKGl5)r0?_h52Jv@5yVHOXZ1~b@9ssGHD2MYV|(`tmH z=N-qBpLqff?5EHUC+sUc+xi0g51hiw%@I(|D(7DTUss*0>SxvU^h$E2b$c}(H@xjy zL*Rs#*{wh~TV`hBs8Vv#q;ZtD{91Xka>-c^%Ac?uvRMcA)uEKXEX@3D4;Y3~_Ri^w=agZ}*$oX@GfTiJZ; zO|;r8Y@?E-4*QgQv@)PV&?%7rC_TNtxxyg$uxj7&MCt zM=C*yRd1j8VK2)x-robym;uHSQwMvBTko;F{k|I!yTsnR&ycP85`OGClpHHv8q$jA zU&ClZC^>eK-L!un1m3qe$9@cJZ{q1E*YfBWPjK+bB`DVRM(J^2vKaJUWbj$)U-QBD zCAfPnw%ADCIwAwMNC>{i<~^d(mMK^L2@al{<_j-+=GIKGZM_9)A_y4{D^08v+^|*o z(Z98q{K9*fKem_8{PAHHmo?sngOn=Om4?a|8Q9YQen04b`Dd$DEe*=me38|_&0$^h zde2RDop__q*I(s%d_A2ud`|uCswrRn>OQcKQfM0mtW9|Ki8_V5h0tuM+)tGfXV_1? z(y=8pg=~Z8B75(u^Nt6uBO?NYCPyVlO%cnwE%*t9olwtcY-+G&*O#d!7Z}$CGR+A# zO_@kk`XCmO6p;d>O+-9SQwl7(hUQSHq22a8_0oBkyDfI!oG~+fk-21n3tpK^H}m0- zPIB+Ack<{XC)xMZ(Rdo=xtHfvnRC(J$HF4@sTJP;(LHS3`*!wh%vmGnQ0b70lF=rm zi6!A{k97F@6HS~K?zpSQyT2vF`y^Dt5xU%qIIv4}vqN-hFM*!L(v6;cY{n%2?G^A?<03hfs-a`xiUamGLl-gB+jBDbWO@v zm$vh%)}5rCn=t?9V-X}Bz6R1e@*t^pY3_vYx>}8V_w~q@9T+DFHN3OX>|&SN$mzq- z>Vz)x0-{|)d1NSEk!V2m%ZI^f!R6O)cs_=BeN<4^Q0R?FZ7bQ1Nha1l$KE}U^S6Iw znf05-Sp0Um~N+TEEN`EmDChhn)y?aa>4V;)3mx8%UFkwfE1m z=IuL}!n2WQV91@ z;O!LD!WY=_wj+8PNz#YBY>RQ1!9&Ok>rWhW|j>+@J)@!Z9p)bV98-W|9~9 z`2CjFt(G%iI>iATLV{9ek(c8upL9d$hHE3Zrj%LNZhnqq|92D8z>|8)jq|X(5Axd~ zFAZy3aX^OWhsx`ffX?CXUkN0-k{%gepH|y;CFgRraSd-9mf>@Fz3~kH?)9AL{(U8) zc-7F@D}EmDvdSnb;3wfSn8?*Rtm}g_R_dlEmYlCYzQn$L4O(pBdp_|J?|*QNhN{B|bYGP2=0=F?}G1ZqYQa=gTr zdm=cW1m{jRa?X65|L{_SL&pjxO`YQ>p9e0{TW?Dss66{C>Zx+w4z6f_9)wVFPzTl{ z+JNjy?)ktO{_fA!Ft)&R3bn6MNYIfX1d(FBU^GG0U`Qi(caBOICyEmrt0WX-5{z9> zjgPSJk&XQF|FVd&t`bm;z?FLX8Cb*3Gpb{Ly=P@4Z*8f7JSwE|-Y7IuDQRrtBNpst z9=mWWCl4y`-{aW0@hBPX@SJPVM};cecP9M!&rDG_DK9>n@s)=zaA|p*jImg|VB=j` z>Jw905&P8Jh{w!&TGVkj=y`C>e(EsQ`yf+*x- z$+bqCN!m=HW{T5phTnR`aqiL{erjWbyQZFGT)xJg$q6Rb%rNu)8>xTKhxuRsk!9ag z$KqOB)dgkZL#ZfB8{eUvKqmL`vA_2rZo6%qG5-RYZ=*hdzlz678*9e-!slE3n}6Pg zuJVIF)8*aoS%)LTQm0Tur`<($g}j}B1LKoGdtd^8ciFHBFR^iFY|0sVN|A01ge!?S zB+bdmX>C&MEe30*$cv~uN;^zU^jkDuN&!uJ`cqK~cXy!LXA zkfDAK+>PL7`T9d$y6z}<+|lNN`zCSPj!F2zIdR0YXB3fwwR(cJ<}?XP-G?OqNtwra z#i`*>brIMOv_Tv6G9${YHQ;i^8=TyJPS9!!xBT6e9NJ-HV3@y)-tj{|Nch`G68Tkz zk5%qzkUYHq-dDCuW$fhT@&L z&0W$7xM}?vCgvW)kAv6iF>K(L`)_0N`VpDiYIT|0e2&_>Cvf9m1zkX-gYlQJ+9VMlxs3Y8LS2PT-m_5^G(jae z<4+%&U|cWo{QkXIn^3sm=;D2daF>gK`iil|(BslCv0nWd8_AnThS#uuR!zyZD-!sn z(6aGSLE7(lZ;r*7^Vc7Am zmWK}OozlTv{kT>8q<<8R*WL6u%gST)HC|7S8!U35_unLA`>WW!Lp}?t9=?k~9GPMxq@NJNY68RmF(VZYhua|>CiRYfVNLn;` z;^A8mnIcIHPKeKRw3Cb=k|2zM%%U{W;u6rI526m==l$&9k!~4DkSgF)t_(;(Z&Uq4zfieUy5NIO`oE*kWhkO!dZ`^>(HqkscPu^O_tKc-G0R)Sw z=&iFduFIXrUa!acY(M8}>JJ zXj^%#e$!Qt$IA+mK7$=QjLotL@PSBym}NxTh}ICzLQ_AnA>fCy?6$J+rJR$e<`F5l zZqF3kHajc}q((6snxmrNNP0Q1fm^eN>KKkXHk;<=J8om4c{^(+USfh}ru7KOYeXmF}3MYYRN^`k|9Z%{{iF7Dd&aiy`Faa!$RkUw%8G)oD8A-W>#7K%%GA#tdbI%@S|AAL2@_8Qk zuyF6&=dd#;C<@=x69#2@A?J5~;}Va2wuaF?Xt9^VPoX5>cJRa>w)xs0Uf>h|V44Ts zF-?;$9f8Cb!P$_Ikt3p5A4;}WgX+sgC4iNuqd{Mu4Cbe{cKOM-0X$_#%`;m?VIeUfZN&`*_C#lic;u zF2=zOD{N+&PyNRhzp?*%S~7{a9HEG>LkSF&eUHj2fJqVj{hV|Lvbn^2{@bF($)%1s2(R^96q9=U!!M!&hj@Jd&JZJSnJ| zHs0ja^;I^G{|-O&Z8woqr{thYRj4^7(oW3Z&5T+B}L^s9A#?f0i?w1-U zxOzQe=4}j4sf2E^hS&_jC}@h&8U};VMe!68^pR-HmLzb9UG8WP9kXXkP-#$C>d&f^ zTj~!R8&i~F!SZ`1?y+BmfY9%_zN(bPlZwMc4eF8DWU@a@+q=I?t}~;agaVJHz=Gr` zizLkQ{F4vx%+sgo=}8kB5K$Ct-JNpNEw{2}-P7d$Jn2N2ANWy&|HMg}^Sk)Pzdyx+ zS3>h6HG-rblX`G2_-9f>wT3H}Nq|Ix9pN!pvz5-mck;=9{W$v`Ie^U^Dj7|3Os*tZ zgXo&#BnvFO#Zlh&&J}*~mu5&BA-kt$97Y`~8nSdqaNbZ$GL|l^;b(txiQ`9S5wkgf zCN`&bmtpgLv#i^ZA#^FrgL`3gRg6)L`tbaS>4iSUC`ic+o?tYMrAQn3@}JG{8^5v{ zQ%quAhiu%CNZ=6ejIL_k&P z4sb&bEL7kUx<@_jv1L{^DP65cpx#7=d>A#OS*4u50~3lYu#2$@hGmtw0iz4z)_GIef?uV3t*YS#zn((S$9%c{#!BHf|K@=rRq0HDCJhWv= ziS1solepcTj-B*}c2?WVaodTz9Xs8z*6PV|;?*mIJDs#G%W+$_Wm(i{%_1q1GDQ*q zNq_(z@bG{)-l?k2+5O?1s#_0)WU0Sdd1n!P_uY4I4X4hq_kaKQe+S#Wj5dyL($|=jCz;8HWa>$=81ZNfKqY{YA)@OfjDQVhvJL*$ zTO1?*DsBG?soM+%i8RM(s0c3*3K(H9HTW!yr3ZqZyEO(e2JhCHJAQ#5{Mql|o_kI* zBTvv$kGEY4EfE}nmmOG}PWwFej{Q9LSLefCo6ezn4Uqv}p5)ZMIY0fnWsE8=*f-NLwmam*S#BYA^0M~~n8I~pZ3?xBp8u5+V zdaiUjmH{6MZyzVeOZ<=e0AfuwtFuT>_m zR)8KLVe1b2OdBok2A4wqGVN@Rc6ymI2@8C+WlT?4Qj@{(B=8;J=i?G$L1&QBoxm|% z`87(vLvA{V8ZsG@G6)8NO1+?21Y-4U7Z-O)db2#)J&86NmL!qmGOqRDax;rcFxk8_!ybrL5zuhdKkH>tdiP~fqlIB z)WUPu1g#itF`TL~NyuuB*wfhLbU0RJh&MW1L@`tqFvls+Rmx;Ye-3VdNQ#jOisWuK z?1QL2Lf4)}^@W&q)0DQTjMnO*ek+dYo)i1+)tbN=>|QUc-*-QAi4{wY-(jIV$CA8? z^P9K`lo=|=vI6>|!Rs}qTE(!C+PJ*>$d)sR`Us3EAJ7VytcDAa7;{fehEF&LSNKl6Ia~jtt z%6OV_0I&uqYY=O9UmJX2dBnZXXjK@($16@^PC(_XYh39Gkp91~Zu@M#~|nDup64!;SGu~hGwsP7!vWkiOuj_?dA z{REV6B|P&%=zAu>On}evgFbn=%urtl>EybDB%ef*7m-$hmkcn739KUT9HXMZlzp7b zL%(Ya=LeV=oU;|&=;tuyUm;&R41?3S!GPfOJA4etmRb_h(yPANps-&dnY@7QdYtBg z$wV1!A5BnAL2b~?h;ET?ncBW|*XL&c@HirG+1jG;Wj8PiFD$<>$38l8vAzTSH=LZs9?m0 zfDyzs(S~aGJ`{s2O^Mf%LR#$jhq=)IUM}Po8Le`~tx~jq2i2D-StpY`5@-s%&rvCZ zAeaKuqa{NuhE%SSaE8Ko`ehqs0*wTnoE-H9sf=&eR{LKZc|MYdl#(K7A^{up-Iv)+ zbB5&>`;zq-9!`Q5Dka_*sBxeMF$E?)joKIEi6s7)BgrdB`f^=l(-6dos__=$mNBQN zekQRG5$upxRyW4R`E8hWMqlpH10)}%iMUrYBU0;m2Vt>Hi*>yROwp- zX-cY!O%m!4NVFlo&D$PGy4Us^)m|ZSt&qsr8%J0J6Hd6kKIBh7dXcHQ9m;Z8vm%YP z^mY=~*Gn)3zKm?On(ZefS%zs%U|R;KIZBDaU{pyYM6=X{B`6^{aG?r#NIUcDdHR`x zYu6wj6})=Rg-XdjI6J{N_2E7$w`f-}r?AlrX}s&|eZ8?K*llFMcvBR3&G!MxBFdM< zqc~cvE=LY7Gu7=f7?xbPyvojCE2g$24e{u3T(7me7%Qt z8ZM*Sp$yKU#LtXf;IX5r)P;AN>CvJD$G_^g$}kx#CxuO|I#cz0tFaO)tc&D$a=-Z>wd0NAFAKO`Ms}pZ$UNT*x>`b?a_n_7dLt7rK@0)@XTXxA&yQb;r3I9ne0xG z2p}Uo9+&mel z`%WQ=!TAhjp7|wVX7)N>Q;;@Fi&`i`6epgM_Z&aDpEtebUa~9=V&U!(_uacgVpmWN z6)35{DRsJJlZ{z%@kE22qLoxc!xpXjUR8qOAkA$p{wXk~#`RSj?@E-Y(BN>o0`()L z%rVAe3{m7ienUc(zcQSS590kk7V!~p5NQDtF|ac1QR3qH0yn=b2i$)53EuMPG_Rgl z&YxRH$YSO~iE0nfkXBqf&_a_@bMt$?;k}^25r1vWo#ym`xI%~ZGU#V%P-0ZeU3VN~ zd1;COBzexhvc|;=YjNR}xbI|RpG_G%e)Z3=miWf}4Fz^2z6MAmL@Jad1kLfl9Ie0r zt<(8$e4ej;Ul?yK@o6!3Xq$!cn#Zcvy()D+ysy>%5cj^O(rC3ijUD&E%n8AtgbF$h z%u#`8vsf*u;9#d|sJbpf5i>;$hJ}TBmKPU6m9(RDCkjj~IJv&zc;Utl7`a(HWpX}22N~^d7Azb|Ae|tW0;eOa7N`gBbF3;4Jh04c*V9gO zj4ANmGZ=Wh6I!XzX&W3Fg*wV?ojdQ_!J8487FZQf8`w9o=R%UAMkxxz{jYl+vT-M( z2N@)u!SpQV!D)`3I?3|BB}97l-AM#hBo6 zr)7NvISKuu7WER3)7V>T_FW2^#yMC(41`dR<0c5yWVP+Jy$0h--PJnPU=-GiRj`-* z&JLr?Yq+g-GCXY@rUH&Mq=Jk1kV~d8lcn5wVwPdjMf5h3^+mSVh5jhP*p$ncud}wc zfl)yzcCA~{Q+dtmd1L<8H&?i+=~GnxNHrI#jGq=@5wT2k+uU={G9r%Cr!TX$RpLs6 z^NNuYRf}iL9>w4?#xp-bLt~T-UULW=r;3x5f(#KQBM_1* zKQxS&YJ3p=m9Z^X$sQ3gh~TjYu^eq=Vfre&1%n~s{P}_x&#iL$#WgZ(NfR5TEx`h+0!^#!BGUqpmID-Qn@o2 z?*q$4z^TPai@a#@{$D%8r#{lhq~QC(@OKWz^!LhGkNlHjgs~U=_iL!5bgh zdM-EvfV%2FT)o*;plR4*f`(5>l4v@hm2t#a!V9Ri>}mixI?z%=Ecj48y%6)%x);Kc zBNL~#M?y4F#DSD(#agMYqh_~ieIShn>X=DfokS_M;L&%S;E}hyjo>-E@v zhq;}@%xKE*fA9%@`Imo>BF|CXWbx24|M;Ih%F^;Q!`ua6!3;^~KSkkkBuQeFl>m^U zkT`~eHQw?4Z{fSX`{X#y2*tKv!A$;#$j+kvo0oXsO-4iWQAsr}qhZ?EoX70%7}->b zxJ)#?wSGm25?25Y_^AI@vGTxUNkjU+c#12R*#7hen>!<9G(uf9mTm;Vn!kT5hQqhN zk@25qyAeeHI^#l249ZCW;gS}Z3~PkUc#ItbA9aAoj#oU5%xA4Col9I7oS@$0G_Dmw z?a&miMCtP*f8$a9_J96X-v29q!f*bI$5AHY)dn_t#VM@zzc7iL&Qs&{Ygz+1tR3?k z!P4sB)mbVzlnR^_l$;;>@dtVPyY6F@4{@dN8~?}0`R#xEsklai(85R(n76*Uel*Xc z^*R7xHKavX&~ezmJQ^81b>Ie1m9QRw$3}|f4Q_oCq}r`tYHs*@#jKBjTHWha-h#$+ zHyrNzZ$5t0G`>|`iLcL962R^XpsTYdH0+;L&Y)`KMhR#}$D}RDG9h=CS633&cMSXHl|zdqhLWKZ zeD@^DoM4m3Q9lf}l(8`rA>6lU#S{)f#-I9o-v@v55k`e!%fQNvlCycw+6fy*6%@VOa<3Z(O&>j*MG*71o|ZAG=J)DjgiCP05m98N;h<7Lz#s@VEYuwU1u`vbgHGhD|nR6hPzp~El!!l(G^Gdm2_Q~E7bHvxws!N%1z zct&GC$5Mr{Ok*9cW@iGyQi6NTMo5K+L9BpJq@W%Fifzi8DDsLMB!k#qx`SGv_Ze;`I%o?=FW%POc=+q z^`y86b$iqXAJ+LwLMQryPMMrJ#9jB^&pmfe^Vi?IM7F%i#hF_uWt<5IhTRmNKVD5MFXR*y66Cy3TFp^|3;8Jjo?Ml6p%zRmmJ{}P?$15Dh} zCb2^931F~uBo$-SR70TxwIkI>Oax68jD+BDe3}MGO-TB;(UKtYzm*`8^zGjEK+?Uo z*KX3Pv~R_uDj2b#`_SQCmZ>?ct zqZinR^#`5=yB0@WIlIZ$^%12H;8c@gBVt4KU0`~?&4GinBqki+5I6HkD=cyo zZ2-Y}&+6I^TiZhf*uONv%v2{{rjVv!6OABg(4XDf+Tp^54T{o%FXH{Aj4Lu1(J`(J zvm5a{sdu)}yCz(}HF)Ro&V!MdTJoANzox4z!*3k$_YBiBY|K8*D4k~J$Se;%d<%?5 zSWR&vfx)69_MKc{^LWPAv28NH$)eq0)?Q>jJx{lDntjO&%xMo)=*SSOIVSrGi}Je^ z-BXOFXW4Rxki`}g^9!VjFt>P}Q}@0^`@ly@7c!(M5n5mdkbMs15~9O+&0#DAK2r~} zKSO5wq<()5R2mAzo`>`q)bvm(sGU8nfQg$h)#@Pe2 z(Rl1=!*@x@U56)M7_n}ll?xs5i1k6oQE6ldNaOfEn6i!sf;{YgacY{rHu=Sy4#=1KJo8v7+C6zLTqdKz%3L;(VIcrB@lH3hfRfXR{MRhat&bmB5br;zw%nZaS%xo3_8SC;8t9Q%ADkt* z+M?g{Wto{ux!xaeVdWa7ckG_&rtY^2=u~ysBtwyq0a>#_n-T>YY6%!aS(b=N zP@gyUYC?d<`&tJ*7$G5hQ7{}lIK$#%C;D)qhug-GCmT#1gH_}3?p5XzkCUJ&o~n?l zLCNSb$FuSXPjyewaaTBMF49fTa=iUGlFTwx;pk$EGl$>Jg^6Q)xO0%{-WR#$+{c(M z`m~LqWd)0+pG@)M=meiT*JY#$<)(7+`qQxO`PAvR^3^G2(VXG-WQ7hnrOT1Q3tU+{ z3?^ZD|11ZWr*OUu8EtBrI=Dn~`vm=y30sR7*}wP&7CWD(uxIJg!#mGNO~?n0tW7Z< zD;`xJGwZ5;tH#B6jP3^2$3G2KHbLB@6wpfNTJYWlP}74k^Js5^@=BW`dx$(gf-@n* z!CHgZY7A)fcVZb)t-#t~Lx@)IS9V$$*+vZ3DC&alwlU!zMcwYP_ifzvK+?Uo*KX3P z$e+{;l>wbb{OiHp3RIg_(63QSR7Y{O>o6{6F=lKQElb%+>9yJnk`7i=3N^HiV6CTA zgH;QX#Mq@LCuK;79i~XkDSqO=_#33}ohFnbFyLFL#+16Kv!)tApiXy^Pkihp{^8I4 zK4qE2>hdEF9-QOnf8l!> ztACaG#WsCka(d44wdIuc)+RIF^8*jRp1W7>;$Qy!AM^MhuK<&X*ywXtYzU8YAqD%s z`%d!XKlK<>iz%7O$xIpLZVUt0;@lNsI8u^C7;G1O@ZWuvFMa+3HWl9TJ+I@TM~~wZ z#TrrJkSRj0tG?i$^_{HNe~8*J_E_0qdq|-jT^BiR88(7 zW)!~{!4V(t-jo5IF^!(7brR#aY^3jMG+6^lDzb^i$3Vf29UPvM$Asg1LctarDr^$j zLB^zf>JvSF^Vgqd>*6vxT8`J(1W3M-Ce~itYk~PEF_mrXKNiqcp(s>n(c3^91G+;;B_Klcl_a^$c_eGx&gWDEpq0(J{ppJAu8 z-1}YM&&=_^MPe+U{>U?Y;9q?lb=CS;jrS1H2o>d_VtS6R=j*I!6__g3HJkBwZfKSO zD^5&w_`84q?VP&j0Bh+Q?$)oeHuD@7rB&X|o!@ge`)|90R&MySKmIZw{@st`MT*!^wp2UTD%0N6eT zT5kND5{fN)t$=_gvotcNs*3K_xzttlZ6S^$tqU(zAZsW{GAOD6001BWNklE;^=KoT3jN> zvcXXAqzkqq9tM+n4sBSde6`os1Ns^n81ut^Tq;W^oE{5*GgE!@S{b z_www&_&8trlPgfBjX;|r5oxTCLg(_ivSD`-lIGa!E z&xY$LL*`ZA!C;8e=gHr{fIj&}PQ3d8-u2-K5RolN}y)U#Wh4tEy!Wra zl^_1$dl}{Zz)Vy~6#Cf%Y#;nHT<5cR*(5guoR+A8)C*RHQW6F-%_X^=bM3dWzyCw}6s^anX&6H2vg zWhtwZZS3@Q{LII2t>2?-S5O(DUg?#=mNH_n>d6uz5r=3IiUU?_cx~@U^J&$5pIvnm zLXXEs5VPLuteucxj|g5JX=2FCET)`Bx8DGx??E|;w^hA`5Xf+`cvi)1_Eo};Xbp;r z1ed7Foe3ndDD4w0aAwH*Hk`A&m}d<=nKvXHYvVf>uQ& zYAws=rc{A7N--MZcXBRYh38+Hz!kGhcP%FlTc*u+SX@y`fuW>?YI#a3JIv?`iTN@! zhcns-4@JPq*T%U>8Nea0cunvwVWNF2OV2B5s`zpWD-(DvX=h6uJ~qM7y+AhkMPLEs zNF9ZIZG3BYzl@#d7GqtSOQf9_Ief?cEG{d9azLxAOsAerDKRLACR-eublh^sQ=B;4 z<@%Kl8=L*Oi3FBwlBT3df>)SWXpx<;$l*TS^fJ@-Dpoy?39joMoVm8dMh=;QnKjSc z9mhC+eG;1{bnZCJtFNDCy&Z^$C#OA!re9*YcoCzHjDsAzbd!UggrIvy4U~ z5G6~4Q8UUt;%yx%HjRGKUB-{WQ?fAIVrFKJefwrGNrp+=R4J0CE>JS=*_&YnyD+|B;i&2aqAXE}cROH3`CW~7&}W{8N#6ULdS!HY$x#%V0A zr5dAL6R75h_@7@!zi4kC@;EA5n)EMFJ$h$QD zrRZRpt(OjfEkR-tnwtfyZloa8nw)KL%3}8x%=TkQ@f93r<6#s`OtY3C(SdQSw=Q$` zsN==CIaJ{4`W*Y7U7)irw7o?%)NAz#jD|UvE^Xi(fg$0ec2&cO4~tyW>Tk@|U3zJ+ z1$HXNy(AekN2loA<(aVODJPx-d6mo*^o+7{>;x;bN01S$Ja5p>0E)OjS9;E>j8m1z z4n~RzaIZS@Lme)>ewr%=N*iM{9+n-9o=PdD#8?Zi3aq&BA+0hgBG7FtNs@42{~VoG z64;_Bn;QfA{TyS2(I_X+OUCJ*<7;cRGNz}eNHa^f9bsH813>OzWo4VeFekAoXi1tH zlJ+F3mWfHr)P#-C*C09up^XYgEk=b>a~4i6uyfxcS5Hl|pF}B*XhQU7KTD*C~@LEa({~^)i?eE9Yp>uhE%0O4oGIwH@-)C%C${h&2{tp-d0* ze7DPfF?{FZGaPKsFpXoOyTVrM83uX z6S7Sr8;FA`@yv8?VWM-G)LcURWm2wU4Tz6HZm}pSBbi`RCfT$WZ=fYPGt#5ud#JeJ z(2|2KYVBE(pbIY&6=J1f&sFnRf-_s`UQ3(@!5K9elTsEVR<4ZLyf&oYpCw6dMazA0 ze#beWfK`mGGGya^78BjaVD%mb zn->AtIrSiE{}ev^Q`BCqL6j6FVE_~)GDO7TbdzDXq-O*p!uF9aug-MIAD(63l_e(f z4h%h+wQOz-qIPy2u-s(^R>pn^lG+gQz^MZ3 zpwAQZg>$BD!i?X?v595+rzUxMYn~n%R=S+OBVq3T8IsW=r|vqyU~_KwN!kFnmhYif zNo|XR^Iu_Zc8)`IIA*Sq$YrhyY#u(}%yzp?jv->5UjB6Rhei!?I1gZE2@3fqepR&XZ`5Qd72N znvGKY_9pAYMJ5+-L%IhjMR3-kF{@8Cj1#SjGpU@hiZfq)3Sahl@U18L@&D!yrtDd~3^4>H8YiKIgry{-N0)7^*~Fx0C~1MjqCl~B zdtmgH(I-uDu0@%?37_1JO%+?rl9*|VLO_;KyM?A7M_bQ=JV3Q+?$)2V5&Wr)j!Ks; z77S1YhG^%D6fL1>Z{mt==74FR;!Wte#49!__|gCR5#IZr_wZ}~!}EOXPcM^Zvv>#2 zDbsVaEFU}wQZjjHiF5V>&OXJ-?sJHJor;<_!5@fM7sw5DGsA8Qj>8|au$mrilLQsFpPja5Hv|3?vbJX zijP$iA(H{q?h+$+f#Y{5Klb-eaCG4dbZ7qn2iQh9)kQ|=xJSnQR=v0(#Wl{%z}U6B`nhR#RN#bz1EtzeiJ5q zd4No3@n#rAJ|wI=_?v;G@fd1AJHS4W1#nFZZk)mI@(JDAZ$G8P7bs$}jz+4{`l^KR9YaFyiZiA2*o` z)x6dldtnTY0vJh1lQv~OK-IEsa;{FCVat7jCAq+)Tqo0QN||C~<^mTdC-IuFd0-7~ zZ@~8S7@UogD&uHV_}vn!GAk|wR1SEq-CFRHA2Bjv{b;F>x{Q1-6owF26+KD_jEf=^ zb(6?pHy-C5)6*^f+n;_X_r3lWoGU0@!XJJ3GEY3YN-Ilw`Rq%)dhT4tHHHOoRB(;K^Tg%IVC)EoAS)$7Tc;!(`O%_p_Jdlu@Z`B;3z~chTXgk z(|73P(>T3`Nrgm&q$*5`3zPsah$)zBk2v1yhnzT7@+sxyPu|WCz3(Ki+e~Qnp_8@w z;0K=O*Z=va5g*u=V^6EHk#8<`b@SE?7F1)uA~RI!_C08Sfg*F1$wkCpMbb@5_hpO( zi7u~0O4rB95~aNxo%sxy7H~VrB%%hvp{5EFj)APuj}Zw|1@ACX`Pqu1x`{Bv;joF} zhraJo-uv$F;?hyW;|n`vk0reMp+%-k!`a!A%bhLWGCRXNZhIGLUKQqzfzK)cX@p^3 z^4lLc&zZAIl332X@ElhzuEhOI$NO}nFV&YI!o<`J2M!$un~-K1op#ER!x`^;&rz24 zwJ6Jwk*6;BAI2)P2hP#ww~)>=fl+KcB_5SN9o?kkw=p;{pFylcu-*)UbWk2(N? zC?*lS4K71gWH(sY*P4bJRUVMy`PHmZg3JS9-3=G++WHFMwv*P zcNhv1DKRRcTB`eS7H(N%;_yXS{1U3G6y<%W6QD~k+0XUP2}IyZGRF%^ z!Z2NCDtVqobCpcD$z+p5`Z?ZcO8PQ`5zE1Bnv=KBGF^1=7}~9EMy-pSFg-*Kb8?A! z{W4ZBV8o%xSDD=RNtTx$V|9CmVR@8MzJP6K^xOL>U5}Al1>MF;m7eWu<4vP}-WV+N z%q+CHC|sd7Ax;ALhVfi>dT9#;g%)OefLA z3lYTt8cTdFG0N!cV~63=1Vkd^SxOXxmymwETfjUT24Z$$8_mdTNZFU#03DmdQDTBn zV9W0^s;euII>kiQMW|DP>;M^vGQ@DDHP5EGpVcgh_pbHb7rTHRX}sQRd+o-yi#x!L zpdj^M9W~ojGrY@CKNAOb4Ea|MSF_blm=GBKv%nPK(7a9QI*brTQqnRWTT7sZ`C2VR z6RdKZ{WO!w3SNczw&C`L7Pkx%W=lxD!K))_&9m80Fl>ZVYZg{MX`x2(-Z8F_8@+(n z6nVOF{)~TDHI%LjC<XiQaQ8b@L8LvBIIW0KaewJl@nHfs#*17$nE3-|0{*3ZsjY|2J9q|g=cBXAKICa8}0=Pj$ZD#wqU=G47? zx>HInjx0@>SQ(N|e*sv)7hRlp_|81Nxg+%T3A(qgas1&S#udTFho|LQwN0**q z&SyC7P>Sb(-D1OBVxN7UNxg{bI!J;zhu{z~q=X=w7{TJ0)E=ckre%P&V<9giKBfbL z$AeLfjMy*d5U)(j79Hu~#Zts!;4!%9oO>zg=q5oIkl_4kjyD1tssV>oLxOV+jWl{; z>~uEfvsPe*AZlZAk{CJ@hZ;o%%F!e%r>D8_y65hAEPgx%~-u?wjQ3piNo|?c^|XpU+VlpxSNh zn!ESQZ(jSbIqsYDAz0Zy$~yV7hi4VBz2GmI0U|vxG55=c=|957or z2Ao*#aALMi<|DzNVhF~$o*1P+C`mtak@c%@pu-%we~zH@95TMFk*GcCW41%w-?U^{ z8b+N1jM51-F-%SmIJEd8$L`KKe5}LB=KqG3n{RFvf;gd4zo69(u*R1rk>ssRcsIDRIn<{bdi*f8CQJU1(58D&NT}z&FEy0Fgf)D z_>t$3-A}i_gUo&bBbQM|&9w`s30?wRWAG%DL5WO5bS{9KLg2_)tPZeRQj+6zfV8@F zW~Q*MMUqU(3rn^zNzWJxtsLeER>jKTQB8|+Tx;9{7#4IW0~1jYN#jB*IQ2NSh_uIx zEkx}s1IE(hW!AC}kRExCxdR8uOp5q6n$A-0KS;5B2qPT^a|svQLNB|EJ2`{;770Bp zBaZ8{9PwvylHetPwMh%|EJWZIOv#&N2$5l9DM+=C@j>6sm@6>xTR1(BbbplDeJ2@u zA)U#vi(N{;$^6lCuyvj7txd`z4WMAOg|cpotlc5+If`L{h^MsI8KfVEWy`=_zNZ7kP!Dp_tNNGkKqj8l;5TEx7YLZ}dhyhKB^$F|as}1ALOE6fCNHjc+LnoI|;>W5Uts#8viH~i+_2KH&CijVDXVP z)MJ8|`Ug1OKgP?w9+;Pa%Y+2Wf2VXjYq7u)-mKw2aR53n$t#kg(Il%ii!^h2?S!Q2jKm(Fl<_CpjC&oP=9 z(8H10gnnDFvoF(XzXNq)-Lz8^6id_OW|h(ON7zmcSu#SjpfovXNeiKnq-K`}MziNO z94A!~^>O7JkZPY&g5#=^fGR2+c;9GM+)GGUXPVz*(tIRj42W`s z67NS?Mx=~_^9ZPonK>d@sbp-Fgq#_!$8qB@l0?_nQ}dr=YJyq=TC%9;SuiUkD5(^b zRr;T#RM`y<#cIwpYfN!H4ilwPRjchNPZVa;2$Y6%R0M|P^i)`mk~V-@(9*_4=$O7mIgg+H9-Xf!5NKe5mGy}YO1u_aBimtFjh-?+FtwSTNpu(gmt{EQ>tT-x43d`nQk|sGdqKq9{3=sg!l+R2D^2R^E}8k zR9jKp$m4NA>Pm$oO&O(-^AMwS2}$~BJ`q1RP9d+37np~YhW$5c&GFy-y^@*2G?L2KR(seuFLl%OkK*R;`G1e~#SkZ1@DcIW4FN&}IF3~O! z6-u+pPWzKgWS``XGQ_LLYPjB8;vq8&d0QwN4AlUVhV!SUq*R6F{fzcMgdKI5-k)In zB>kO?Vb297J|Wno*5JJ*X#mow_|7ptZhv;XHz7Da*W3>!S zeiZ0~-HbL%@b8Q!sDL*H6_5C^mMcY&?vWtQ5IoFa|2s6+2?}Z9YFeO5<{aJ#BS|T| z!Ml_Ve}$Foqohu86O$Y|1jB&=YeVc&GK>$JnPLnjaDAgsF)D&-KuMyI(4v$c-5HOa zpQ1C>!AX#)nP5o93Z9_VY6yWk=-?tQ-nBhCI*i1kI8von^TfxRBzglddE@F_%I;Nq z40}t+*iaYtY1Jrgkx-&Iw@Ak8NwRw=&G)cs<`}f9z15(`jO{NIgPyx|?Zd{pmKtIbi0RCgyX>pPXC24P zkf2xMrG?i7BLfDqLvlxlhkoW^M(G4I%K>cdOlLfGWSzmvBK=mEkiRVimPN%V^;Akg zL}$a)_ZW5xji8o|pD}Sk4<><&c#=jkQ~>2rA!VB>Ugk%C{1AWbT@TZ8$C1)f(q_90 zqt11#Cb+4R3(G^Uwk|WpIZ_{3ucauK9WvRbs`{rCh;=9~26O{#Y_QZ-{p#xxRB|wv zDg2kX<*sA=!(V-ve%^s>fN!r;&?n8O8D2Zgum96O=fy9yfDyK^_f>}DgmGFI5TmL9O6{ZvFjwla zQ&|V$9;;f=;~7&mA01SUno^#qgG&Txqa9MQa%&i>I=(ilPW#B)iz$*J6)1qdt#XFb zAG*YU{Jjs;f9WWirx*#$+~5FI{a&4A&l%lo-)d{_3vu?2CsD-qs?bOEe+g`t8;;?L ztZ`C=E}kj=Kla`<*s|-o@B6L2&$+{!-|HDYH_$+1Y7hVk5CjBqG9`wCNUCC4Dk^p? zCsI5lPAV#YNTu@Kjw?x}%2ia#kxPmqIhJM3q)ibdK~e%iK$u9(Koe;6JiYndd(Sz0 z<-^+hoO53{K!B25GWd3(@$PW$8TVepf35XjAQUXH5~e7_ZhW?zj+{qyP_tp8YMFQe zpd^zOT+ECSN<>CvQsPx{!Q@rJkb}4F;D7$#Z(?n5i1liYmGkrb%YXJYUVLE@FCA+% zRF@>D3zOCbj=6`e&lF{39a}|MTUq5d{^`HP|Jn;k_c`wW2Os9v_f2xF`y4wa2Mk@# z&~+(XpEA#ht(NV6IoHbIk+H)Bm6RumL+LVPQZFHL7UP`G={Zj)yFxBIql{@cS+Wkr zJN7N`v%maty88-tb}zD^C&(wSaQN7>1UX6G>oMDTl#hRSn)ltc2j@EYwaZLw%#v3* zPCQS4cZEOr(hQ5E?d*TwOMLvj&vD1X1@hi$d~5s<)Bpe=07*naR9?_mL0m~^Dre8_ z+c-bGi_6b@iVLUsu?IZ&|NI8)nzMI1h@L=PiI)QJ3eW?y0;6O_+wRLDPc(_OTd-ZJe9_NB4tZkW{re6f1ShtmqZ4( z7=?^F#JE8rf$bWDR0g*zUWRxbMIgqtf(&4;d=)DoA}^p+_1S5#`J%xgk+V(Wp0B2k z*i@TP>sr$%UV}lE&auH1XV}YWnWS_%gZuz1Q$5_&dm%rBln)7Nh2e*9cUCr;PSq;H8&O@qhk{MGn7r z51;*;2brCJf*_|X8!j4Q5{=r-RdjU~C#!e`=L{rODsUCza{?KjE4X}$roRKU0n)|` zO7PL!9dRAE_Eifr%-+p&A4^O zXJ@})X6Nga*(xSqB1w>{$$g?c)ez;X;v#*J+4)l2*(sSv<6gvB!imrT(kM78JOy4Q z#;ff5mSmO-?g%U0c}mwMuU_SSAKk@mhYvt$S^JjJ?8!8zsxnr?ByXJe{OUjZ6HdKQ z0t+afia=n6O25L#KD)-pf9@8xAAXjBo+T9xdOR+;TE?3SwdVj9V61h-RUB$9qoWN0 zq?hS+8(L^hTMIgXSC12qQv>BkA`F8kh%m@IbdMZn;REkw*x$#-gfj9<6=~6I+NT3Y zy-7THy&R%`cC^-()YDj1DD8m*fzmlbKcmb9-|JJkJW|TNyT=wtx;3`OTaB8OyRB@c z`EJa4g{uwI=DpAQRIIS`=$~@@V`m9^nx!J++oNet`n}wYXPOmqS;I=;lfj%^jPd>1 z88u**h$mRCs@n%{0;*O7DL4|xmYEcG z4oR&y5h;giUYiyY1PwkK^;IMAHOXuPOgn5auLawWI=JyE0xx3>T^Wm^%SP3~OUBYh zMY-yjE^~HGpQ0lr3Y5_(GhmPCG#L+T70W(6SV^0UPF-wjm9(*n@x7>=V`k@Xarbp! zA&57pk#4SBDp?j#h>%<|$Ygwajs0NrtcxH^RJu|t%JKQCH94pm8JqWM zMqmTmTe1Q)C;IvJ8=iSFDwBYh~{>7b>?V$ zjl|WRWJ~Q#wnG{vDgh^ss;qeJnGJYmJIvh1+JE*D-Z-N4<}cIfEpckC$Av+kk)Pti z`UO;$anAHr5Cia}c3h;Eu^MS%63s|Zr3{`*e01_WtLvU(amf1WFiJb)sstg+J+3>! z)PZeGePkztBQLX%y~J%iPFGJEqh}CA3nu(`IKJtnLv?`nFnMS@+28<^>udD=1#YK?I zG3edNPku5mGj|5jv#1z#hN-dyh=Jl`pO|3PPbr9@Pz)XGMGr4MHU@d5qiTaSn?cUd zT9ZF$v=?eyCRq?pRVb^BOBV|yFQ}>!-b?%rQqq7XIpBoBhV93I$;2n_8vkfarx8C* zQq9GECu!6K*;O5@D?=`xAJLh~>BYuci7 z*Q~}tt}zKlFc~KGbyv}MY*!jWYWyRKT(dT%tqM@0KFP!qY+UMjq2R=GVQq#-SC24o z3+#}~l;I@~E~Y*aaCt3CKLyV?G`XIVV6jbi8+jjTyuK2g${ z`W{E_ewllJd>2DDC_?}#31YrRI&Tf8LsJ!8s(@?eSA6#MOC6hm?Ma(dSBvpzY);qe zDY%&66Yr@A!!W^>b!B5%Feryy%!dpPDC_OUxorokHog3q9&Vp9V9HapwT;wzNJStQ z2twrrGC^{O^t+HxjQd*e(y;}SZjG(+mgB9|a$EAWw~dM{Dcz{>CwCvg@0r2vdzLHu zELy!v$fnuZJ%Bo8nkzURL_y5B6jh=_lOl-Y;;Egn8E_PuQ@CkXUp&ck|Lc3uRB22uCVsv0#vhjm*G2}Vz^<7$+_BbH~t!$VvAnZ-lU&OB2()as3767QV_Seo4tceFtTz*t36$QeKJKE*c#% zGlW!G1hg(6Ow%}-bQ(R% zl#MB4^E^$^P0m@{-;MV@KqOU9*V$ai81yLZJ-0GhrJ03eoTbwIy(UGDNNrFmW)qBX ztjjE?^eE3PPjh8m>8;Ik;>szg){$x&Wn}9rnjluZ6KZqtYO7;wY>hM$?9`@)*bHEp z!JQ^^gn@q zO)XYi_e)DGAI~8&hqyUZw{ia0USRzz&vW3v7V`U#^YCvz$s=EU43!C%-f)D`0gwrV ztR)-babx>f0i3t{7(z*fuu=$@s!2Ao1yn1h!zX%22z&Jas3VZ_@)0U zV|g@U=kzqbyT(X2$VI8tnm)jYPG9)kXZLdNvZwp`UCgd$96tO8q4)-1x<*_TIm&5%{12_qqRp!nFvr<9uH%>g z;j47|LxLuKYgJ~c!F!#lDawf#C&BMTs~(BsqOnFTp#=vT)Uwi%TD=Lhbh*~Qfk0Wp zZ~po>_|ijP=kx!~4nFzQeTwh`ZmiK#Q#n=duywtf)LbZVdX7#wMF>hIU4qQ<+0TEF z`#*FHYxWzn=VhKyZf9=CSw`7c3E_KW#OeVcPkIcK20GH)f6^SwwkIF9Q7mn}?|I1yReeNcH=L=8p{3BQJGZP&D`~w_+U@y1c{s#=g zbJnCWHh&VFC5r@U%$aoerO9b-+hgNHTK~U#v{miclT1E;%H|gHpS6N4+eR4N&ToI= zNgjUaIb433>C}5561i zly~>o0!g>V*7z$KChVMZgb+Y-irKx4_H1Kg`ZB|8fRmg|D)z`5Ebs=CvQ9UwqKO1M zST>`9tpRnh%t2CdTpWR>i=I}LL0P4X^K-ipkhL|MX10qO{9(Z-4iPRMb7p9gut z?I3eG_xqQ*j(@{Emq?{Nu9Zod%7RoqPOO~Oa%@T@ShvoK3YV80yX^{k+t+bCidV-- zMy#-m(~8;SQ}mB}R7yfvrP7Ni9Yl&~K&DL2@hnUY)Ey5cDW+Dx5k+xgo!CW<6H~64 zx%}3n-deA%)Y~vdDyJL+VO5RSG~T0eS63Sa>=Z(2pE+~16UAF<&Ryq?wN4<}1qoNV z*40VOv@tUA#Ou_CQK;$bCGd@8NarGKXWSdI(=W zg(Far#bZ^}y*UNYj6lZK<&9foYowtK(3#4~>Y!OW+p=kpS9h&V5NKy7@(B`mQQr zP0;ULX8EOyy!yF2*;##%*T384`+o$44)_URJLp8@|4PmES}#~yz?f{O8T+YyO zC4>adWvG;hl*WbavUpxyw#^3aoBbjqzQtvPCEYS*F~&|0Ry{t8~ek zVt|$_l)8$SK;cTNc+COh2hSqai*c#7ojh&kVgx_l+MWC1#9Uwp@^q6Dr;`OZm=`mKGT!v1Eyfcr_tYXKD zP--A}zXqfXbm&tK3*Z%=ntb_jb_f3>dDQvacE_gDt(ZHQw1s#!`AM zShE^HDzsQ9443gs6HFC-@~U9u0-7a%#Tox$J^vJftDA9ZW&DT)IDZ))f8jWT!Dkqp ztsuOJIODtYYK8bE8pG1yq93AHo%6M>A%#c+*2o8-T_H8cVEF?)^NmY!`@-~b zeE{hp>_C|$k$Kd~7g5h^S`)qawA(QJU#65bonj690vf9t z4T|=<7eDv}Cm%b+^IzHl6Fny1dn@^lZ4CSn3odl9CZ6%kvB?jg^^}zU+7#3-Uktu?3QDjjcgk>nUSW-~P%^r54xvMcS7WA^40c zpCEWgfupDj@({oWI=V`iiXH`7>UNwWacyB2)8A8>axI*rV;~Y3g@S;i#7g#h(noXx ziYXIxDtPHq#S$(nrK^lDs4SXmYL$k!6@xjy)=(j6FoVE(s2m~du`ZJg-2|m(R1!N4 zibi29HK^t>qr%1S99;s_4BSBmom*JfK4n+|4&$o>xN;hiEOJT;K|a>!4~R@TqF9em?EFk+8+|9NYFO(b))}`&oW_VPXEu=G@YC4zraVm*#9QSe1)HN9P7|fBP{1vf5RSW+}_mZgi zNvAiqCgWb>XBO!eN^(|oj`R5eE=^71Gbp+{P5NG7D(FCG=nPY0!mfu2&KZaj!(du3Wa7A>Z5^d%`+@} zJVb|}AZTebKJPK`yIJx3S(6Kl6e=z7!Aj~x0+~Rj13EgYGf(P~)_w#=HTkNkOi`dI z$tMZrbb~NsztsRSI3R;C&p@`ZqB{tBJ-Ah*%F(j5@QM6rSFO!-$0Tx=8ds%?r*IPt zrH>M*!UDohU=5dLgsNx(w?ZYtWhuFk6>Q5(Mq05Ujun|=mcE@w)X}2maN1R5rUS&X zO1+ebE&>-3x>W3=kVzoNlOdEOMnKg7dJZoaK`V+-;v^@y37a2M0E*KL=Te|A&YPH} zEUkNN^4I2(Lz{+w+T5x1-khbjLq9%`Tlr$|XlUzi8}`s^eEZh>kffn30D;h8pr&lp zCH*6{&aDe!w7suu9Id5<8jYxJAGFpxWh^_*B*T$0%>>j zgLo&z9OT;k6q680I&#C@r~*MdjC6u-$fJFctkUs5+WBR)qXUWdPfI^ijHsF zrfyITR3R8`PL-j>PI3*vGG2P*?hr5;eY9xzgsQ&B$p%fgSjKc@bi%Z)fyd9DSd}`S zg{r8F&&EYQ_;>l(0!g>V)?icC&pXLBQ0m`}NAROTp>W-G*Dfj{`YC-~;q zp0%t81T?E1nuAA=@aa$73)v!r8@|iz^b+2IhKdkN07J0OcrIoQi8^}044xnXCC7(J zyv(y}ewO!irWlH6V&-O!?3?3#{SFfoFQB1};Fc-tiXq-5zR!ZWyw5f!5Ma_7Kb!rh zbrn%^s3e%8w=$L-<0p+qL*y$>tV3R;Hqd-*O*M+{N=9Cv1NAdY{7EhuX zOC!|TkK?X=azo3Of%takX3HB)=T$>8%{~llN$j`U(vb1{sIY6Nn@u{iK8`dO)dKMo zgb`X_ht?$sHBO6a3p8eI6;V?TNaQ3H>MiRkF|~x&ro^B6s#60g7c)w&*_lw5L&ER< zCgJf{Sd>}H$A^SYpRm!vvIwdO+2m*f-6H{hbA+w2H8zhQlt~Kp{Ecfem5FO>-Hsd0 zZKpGRTS4lyi$f^sRDrwJi3K!`nyp-fx(9waNmk2@zR8+wNWKME&*P%m3rU9oL zhz=S+henE^jVu`FbW~jCxa+PvxcS%(WDd@qzsSiqF0#0Ig_9>=k6Aa(Vin1(qM$06 znC|n7zxW}J9NJDfvio*!c8#<5R800~`P5H8z^9MiLI=x`NM~j=S~|8OYq}dXkW(@t z7scb)b94IX!gZJIW?*Hy6Pe1btU;oBa+s7eUdbj3i8mTb_H zK!r7JlBAqcZM~gPtj<7#We$sAU84I0?JyPyzUBqA-*1h-R%7#|{f{;_uPe2MBC#or zkzJBx0AjkL^p27DATb$0!x$i{F|Z`KxJD~fO3F|f|EFXezwK`R*7grEDt9n_c7};F z+sVrj-H!6&^Jn>$FMNa1u)=t(-;Qi~vu)D6ALloPDpu^->&8|#&&wgPk)VNQ_IXp) zwRw0aRH5YHfnEI6r|)HIqKBq(ZNNF<%JK%k|A&uq^5ofQ&j*}`pZ=S7bKm_paOC!a zvivSto|+#i;x_RNr_8@3^CIBr6>>F#sDUpm^HCkprETW&d~ z1g%gPVpsJFmDv7H9UhO-zE!AJ(Pxc3=kdO%`e=`*W_;9{{54%%0v{u|>!SV$Vj08$ zKF+IL1RoSCXHCE;P%S743?VLcy1R7}GVVjwCs9{jwDqHH zsG(wFex3vGe}L=f7q5Md@1n5na*h%82Q#0CKbf8nhph`|A+j!%J0T2D!v+TKj ziO>I|dl)RN;U0YnsxJM7Z5;jRZLEY1c>G!X+AN1ZaGc5G(-fn19=Kt^;T|+3lWNZ=T}N>Jmf$5@lG%`4VF0t8*F^O2Kwc@!sqi4siuR zxt9VR0e_oPNkX5++uxtch6vyDkMas`@yJgm^8gMt9*H&P6CV zf>xbU*){Y`edi6r|MwW{*)~|;31J8ArZVXcgt7NySMYWo$=3Lh8b2tLG;NcN*g(p* zG@Vk#@3ZKmM#&R{5b7W`_d|26)XK^R#ZNM%!@zCBxjCF(!bgKXs3Sx`60LAz;EiBq zksShuFbkR_fYyN!@2%9b3;}h4%z+ja7v=k0aIfQJ38y6?TSDHmo&7s@ za9Y>U?>t8D=qx*a>JEGkG7sg#5_kF6nBX+Ce4lMxVoEPF#Q={GG-(X$)9bJ@`$_|) zIz%$cSUg(Ad)3te&IR&NVz9T#8jZmxP0q4ffG{AnED}wff^8m!8pumDByIA6NZz2- zTcu`JNvWB6;R$M$D5)=$%P^#b{ z+sDPhZXSN}EazXIU}cn{KC8jcs(uDaC7|MBA!@WuqAnBH=(f~^%>N0@4ZHY|)9=mk@SpVf zzy9y9Q4M2IAxamQ=CMSI#I#NTRi74htO`p;WbEipUSGRqe8!a*ZQ7cTKS@drc<VO6UO#vyQ@7c7Hjo)j!uddb=p`Kf=uEH|fE{U0|Cig>#8pIh8 zYcZjUm60$EQ>;h zg*~0uIXL0yRR-QWv3*w9{v^bJr_`FXSv?74)HGMxYpT7kOu?3QDjjd4&v&O-CC!;aib3k!A!uVP;a6Qg1 z7F?94Sy_LL-~yC?N+GMLSczOEi7473bPV{6gy=#nX^@IcQyE_be@Q?qeE*JM7`I5SlJBZ z1T{`JE0wqGiGm6zC67I_$k)Dhnxpr=&Rq{4BF{Q>DrK@LS@UbS&Uw7Mh|?iX1HlOu z(J+$0L4B4vE*Vc3!UQX9<6JCDONN%zkxX%dlH)ZgGXc$FIgOA?jS@6U-{xqiSGK*%&7j_!*va*X&ag!%vT@ZxJUUWD_8wTf3#0=>4@Haw#2aV%-PTB@IqP@$JhsM<*x0O7 z?A@lBALUANJgkeX^En^?o+O`F0NcBwqj1(uI&r+E#)Wq1sMplEZ=IL8)`{R~^Ex=C^bwc{SoT;57HscK)8BD~?u=(+ z@dWEj=cAJAf_CHG*aAtn#^yD)*?wuQyJX_T&o!jCo?@t+J9nA&`86gMlu2>qswib_ zHj{ubC963t9L^{ES|Pl~Wcb&F@J)hKmO6#;^_GX3*?%v;_}_nsPaEzb7@DrUL1l)@mQle~>4*~4q2egCAlo;~>xYzQ76Mnqe6&u0 zIfR?~%BTPCoqXzJN600kstU-I8*cMlDE>9t{~9ho!6=s2n_kw4Sp^)S)&(XTVj;f3 z$O&Z)40qB~v-?gg-6mDHSpdw%?2HT|_~i^-6JPr=74e=#(>eugtO;xub%REMCNz{f zQtO@y1vMu0nx|Eq>A4gX#(pEg<3fg@ltH;r^f{O9=R#)+{5mtU+t{;ff%WVRqw+<* z_{XQoGGRH(cvTiyT;E1j7WBIXAAImAH!KX84VO7IA^hBDAK<}b$JyAq#N;jKx!#?j zqsvq}qEBf7%+R-aAr(PO1LISMY-{C=0iT=1Y7>@>HehsY6thJ%HdYcX%(qty(xsr7 z^*bg`5OpVW3uXh(g_5_x@XpyP~`0Ai% zO)CK2Q8Q4OwkO&V0?x7K;SCAQ)lH+`y<-a`-5OhClTdqe#OPWh6^bPUC;@Clp_H+4 zX&IJYzzsap6Ht~X(NG$pxd_2EQMQnpU1$IoODUsfv}BP;q#l)LlXGFwUUkB#5N^8V zAcu~}NnSGxXKUQw(?<(s3j9>>4s!IK_2(ib>AX(KSlvQSWfli6T3Kj}l3} zqak2Wf_626^pwdPyED{NA_18eKW~7L^m>e`L0kkB+obSm z14k;!HzP#e!qNO8=4Enn6;xx!S)Hyb4a}u<@;pjk$k49?D5|#?fz_oQGu}o28HjlW9j5)&S2oL}EmwDok zz6ROffO0P>yQKh^5#qNM&aLs`PaWVRpE$~> z*dWiWq|5f`YDNpufG-^`2*E)aGvEhKd8L1z^KynyC_Kbz9{6 zicYL`L2oJ%Gy;ps-l#h<*BLz)(5f+3XS%LE1=D`osAA&JZc5@e9ER2~quE{7Br!5s*yP)-Tj_c3ys*R*qHmk7&_$C^c^np3*@yn=qLY+yK zbe+`tqKa3UKm@BU$skxpojQlh93AQ6*oly-5R_o;(gaV%B;DyfOw1@(h8J01Jm1ps?Y~5ukk&xLEP)i={s z$w;=fI2^)>l}WnA5q7(R>*Oqxx*X?h%p??BZ4rXBeW<}rK|$O)lkPc`XK`BEs#Z@Z zUuD6rV3Icsh03<+sf&^G(MBI=9EN#S7UWpI!4egh2|7N8HAEWKgUwGgEbvO zxj}zs7juVirPC=nJGj8V`Qul~UCw%Ul9RHXur?3F0lk@Z?zwY6z4ZiDZtDFA8bKc0+1cIZYvRWUkLGYg zg=jMm;#{%-Yt#JF9<@ZuChGl+ykj+k;g5j-vjviFjji#Qwb1Kuo9$Bo4V6VRb-?$& z@d~9|;)c7FJMP&|8B4(hC2M>ZL{h1CwC38Sp_`nBPgyJ=(+$qlINBHWK9Zo!+ar(6! zoN;SGVZt_ZP&j7QbF6%wefmWv!{c*@f(cdUaUqYY zp`fRSm>OM=uQu=lVX%}@_J^E$t>CFgSJ}1G@%{&A=uT&pbPzH`3p_*P#7Rz0G#(`0 zNrN7OHAxZKF)u| zy4+?_mIZvUterqb5No8T;+V>pIKp|ntS}`jD3*PLVzNd&s#dBMLNwwvQ3OyM-Ny4< zneHK@aDZ&k=T&^R%CP$!8fFMS@Z?mZz^*;hOmAOgC3}R@KT0OAk%d*uw-;BJ5vHt*wlEnBTWD*= zwz$MJmHBDo0EE`k-o{Dpt$vTH{07_Uk~zn*a=<=cQAtM5hy`9JV;I3UX=uCRy&6B8 zbThSfmJDb%Svf{sQah6-^)&t_sissBkhVy3D1A4Ucv{;MwI;j9%xudtZO&bij*!Ow zusX{c>`P7`q>{<@{(jI%z+c+8Hiy`BhK)|SmJHr}P2&|n=KM=tLNBdrP{lGjTQmWt zTN)6eZjdQZh*F@adV=I+p+l}7Ei33LXU-1!=2tHA` zfb!Ar_ol7!Fd9E zZkcD-{d-wd5IlXSOyB+l7kghs@-@5)UOR|ns02zWxXCFy!iW(iK}(zjawp7?<2rqo zFwm*%l$;?hyNJ(DTE$Y5`7QyHW`##-V6+BM>m6byt4s7Ku|_&^d}{O~QwMs{Mk3TA zsg`{SHf`$zL4(nv2pA7_t$SnHc&!Ar{!Q|y5*TGSS;1E1V*44kAC@e9{t91{M0|Zf#dJpL#5VR&*N||H^r73TEw3x{Ufz9b4}`d z$~uWoRsxB{4=CO9ATKbdFdc#cNe(InG%)QlW)Vskpd&aZ%sa=Z8lu4y+#Q^Fc%4Un z{dMHRK`eW-sGABnpA*VCGM!!2)A0FHlFf(|iuG^dqD@R%eMuP{1{r z+qE;RDSIoz&UIFU-QSKlmacey^9z?a@zfb8`pEJ}ac&yIT77@6eQ(-xVe@BOV{5$A z(Kw+AmUq!ehJfaal=+iX-2sI=h0A?(W+J0=%rdZSc%nm6qJ*eF9KB4~0ic-`>Zzl2 zW`L8jMKrI22cfAcsdC0;edt50kks zvm<6|c-9%XX|mqkNaucz-hCq$dxEj-n>)ioPr|#TAoNxkH>|r-{u*m%3aD-&+w~yQwT3A5sYe~wLa;3mC_>^J zPCVk&07vU`9npTG=9JY+DJlq>lWC7Y55(ii@!}|J&_j5;&u44Ao5!0;$;~6pnekA0 zS}&K+UFMPh_a$b|&Y}BnVmP&f8?sBxP0x~Nm6Z{@lBP3usO_?LQ{0rCV95gB>^@mT zv*!r@c~pe$hv)gbzx+4IH*P@OD~!5drp&%aAp<-adENyFAN{G%@}ZBukN@qTuJhc} zZy;{cWJ|TqZSUF3fBR2JO0ijS!_pp0bGKXU}Gz`Q6#i>KQA}&z+ip(j&Ls^xm zWT;DEm)(D<FS{Xf%oFXA0n%XqHCDN12;sxrxV=Eqb;0LjuyY@jr>b zy=rcasSBz9YHO4Bi~9JQ?zvDoM@0^~Rr~c29BUl9|0WI|zZ2b<;(V5~*4a(vcAH;Y z*^ZoAg@bnjy3WkhL-b^YT!;4D{Y%h$i5|`ZuUZ;xALYNv)x-@i^)(THU2^)8503% z3n4K6P)dXmlyii^eQ1%>8O$-^78r2>uxtPckq1P|x{*OLZ0l6|;H+z5%$gjlLXO)S zEEJ+s02zTiDqZ`=xEWOfC7{llUMRu4GE{Iz!EH|`0t#d0+SgQkKgfuz zi|RKy-*2Tv+pc+Y{B%C5soXC?uYWm?%(eM--`O$R28WsotzBG)c7PC85#|@SfdppI4aV1iH%AjMLsQI$g=55yb<6_z{>=xv&h;qEbhk1 z?TF6c#8c6YbPO(@dDwIf*BV<6=hpaPMtj~E?Z_B^6eXesS?Y znPW$h*3s-`OZL|(`O^Buwa)YHTumbb%@>kdU|Sa9RUy2;@JJka$(~51os98{zV%rr z=*9MCAaST6UHiP*I!1TLbP2p2y<#AxJ=@R*NTXg+r&OsFk;uQ-h9sg>>tdyfh*Bt2 zu3+TN7RqIcY%~j39IXC0Ox#21o9B@BWlkov`TJ5yvOTvls!-cD(J!PaBamoQ&BoJU zy3#o`gMy5aLPAN$Os;CpPV4cw&Sq-Ws&`zj8M?i&2hLg;y=R%1xGO7><=w-C`EkgbpjuLfe zEvwO$1T9bp+Ix~J3k3fFg^W<0M~B;i0yxV?DB0+~il2Rg;4V;wA)!)Swwq$&2!rx6 zssjif%jnJ_Oi+#H>A9Reoj;|oPas~&xy+=0hAuwli&&OrMPZc!K!xe6+UJV4s7QsQ z#OI(?jHn`WSTHVEA}{5b#FnvtS6lQAjM@hF8ZdgZ@1bLRZg0{4wEn*d(%4MyFW*;* z5PA*Pb#%b2E-_05I-n$H;Lg*LQ)vG&=*}|fx^!HI3z@kFdAxrSFm&SR$OfJ4Svs7@ zsZynYre@@>#D$?XM-rn<32HJGF^k`1buJ6-6R_TLox{*`#RnQ(CDa(eJir z?h(!Kc!UlE-N}i;Exe*1WW(QshDn+d8Q)YJcqK?(<3XZr2@2|**?Jj_m%IRxI~ZvI z(F*$R)^F4bg z`Y)4X(JiG*r?Z*2`Mv1w^QQs5f)LffIe8ofwPuo-w#|00!Or7}?~g^HO)j+Qb{POW`b zXZj$m_mLYf0;Db;*Er*H)~Dr5buy6H6RorEz<~U ziD)XZiBU}h;t__3SSFid!5bIXpGLr@F24$xA+I^=LR~s$Jie#NvQu_`1UnvCRDh^1tW&58Elxi_%NSnjBzF4zR)& ztHagG9a;ix@*vH++O~jP3zqF9Rg;ZD1Q5VtT}qNz1hVeFk%KPMfhG!r0mpdJXf27} zyJ+*X*YCC8pMSrmu|%0)wQFh5$GXuNlo6@6jHNv;y!o9zW_9M7(A*@h@w{D$`#S7O zTQcw9x5QM~y{TS$uHt2@PSdLD8AJh!BK7a$-y?~2I#%Na77>P0D6-7?^YEP))_LxG zAE#UTgXDuh$FT1xEM?;lMXX%W&qh-WOyZ#r!{(<}&=l1Ykqsu^#TyISMcuCf&1U0B ziM~wODl6oJ_pyHvy410~d6|u?7YyugV3&m~WOp+E+_{tl>}UE$;+BK4*P*0jr^(;MG#8A&_6xYW|3cU^>$pEgDjk7s27`f1ZmMA0?-|P}!ic#AkjA%7JgQz3*Rxyu(noDfDcmyV-xwSNYnX zx|cUz+RroJJ;m-zB9~J9 z*0u?BKvk0E!xWH7FvWjxWdV{dWFfaC;Q~i#upv5;(O4+f(VhZj9b}pB{py6Lzjc9O z3P1NJ9_I6(`Wcq?e}}?JprOrASJOr7toxjb`|0kIr`x9T`U;gl6e*5Gn7}7qjJoN^{H_!0MmmcO9 z{@i{J-1Q>sM}M28v_>YQdW8oL{U(3*55CGIy~*EdgDCzrr z<&P}$$*&&g{Qh@XUs!fmF`l0BN}6cnE2tZiz1|nC`w^WSM^jeB7%;6FSAcUj3ijVyX`zRipKIo! zhJcKb-|XkD^A*JXkqI5ZOd?ress`vpmQuj0EuUN+hi8-y0SGv-Q@|HK1(hW(Oz-2D zUwedCUVDOzTTcN~O1XqE7II9ci53LKbqnqy?0Eb8>;A9m%r@hON)=kN?gx z>F*}GgG>D7U;HsX{`gro_-72m1yahWEP+fs_$*AN7@uJtK&c>KAwlYxFd;|w3uWwH zu8?%A-Xn|a)!Q!to0~0NXE>UFSU@RWsPDmn5WB?uLbg%$LGeV(AMn&jTCY1~& zF(J{bAd*<6XQf=BV_->zteK2udi2tHqd>D$l?xP_xxCSHIuDEL%qO8`Qe@kyWl9K; zONWvffWaGAiCAagy#!Ek=_{*9qvpqK6}L4pMnm$NQ;Q%@{VL9unHMoVS_3jhdvjYw zsio+mR+S>V44A8~r__LMJ~%g-2f^pB^K5y3B7#qR0WP*^n)-z!AjZQhsbK~81-G$G zGQMY-)Kf7#XHS%}Ecf!(TZj1H|IftPQ$J0A-xtZp?+4A4Z1!HnI!7l}dJ%@2N$Tei zS*7CVQ#>e*Zc_=T0-FHCj0(6YCltefUNG>i_iPyz$NAG2nB*h;nLqal{=gqO!RzTed|xtM z{v40X%N*hyNj52L(>n||(T=RP;8#S+T1dq-+*I(GWS}d;lHy#Hky$!8%>b_IcAyQR zS+uJj@hs?NHYNP;uuS9YYF8S%vGFRmu}Um>zIU;TRG-_DdK5K#D@)B8D}#fIou||n zDNQD$pxUF}j51*jehq{!Se<}T5^Zaymldm`WT^440hm^W7TK+K=B>{*KWFvAjlace z(p9ZmK^?GE#@MDNdwAw)5}`{IE^Hm+AAkQaPrv;sE=)fKll`a;b|&K04wa@Rl7KwR zvktKZw&S|a44x>xH$ZgoTP5sKtRmX62)h)1QfCYDT0r-&+}g$e5s(E)x{!t3vV_y? zt1iBh8u=2oYbwc_CW(+mtJ4wsQbfqbK_-DRd7WYWTK))!k9~rzw4a9$D32aE#z#J~%<@AoAcuaHZJwpD;bGDS`_fY!Uiuw0_4G0z zObozOA*BerT~8xOKEcwV(;QRbm`;tGRR<&`eJ`56hDhOwReiM{wvQ@U&nKajUmlBX*o39k>h5=4!Exn8qjJ+S{PD-1v6*lu) ze_=j|odqFUu(*ERgMV8Du(>FxJBz+m6X+v&CeX-~!wT|EYJ0W0+y!}G`^3Wmsb-0!DrvXCEjY3?NnyI}9zy_{jVkLmfxf%}bQJ0@x$+)W$o++%gY^4 ze*RwWzIT~^D3%rKTx`~X-GLcKm8hx=qNHMreU>q!9uyWtGetXxzq}^cvt}xvsfT)l zWKIt1^--@Dj)4u@@mS!buhQsc5it}BL z&5w4cC+7(OX1_as-P$tyd7Cl@skTKKpChNSvDa4Ss1li^$?i=rHyka1l_siFOAN6< zC&oisN{4}yaB&?jZXDu;Q=j4N<;S_S{uSsBBP*6bnpGLRd$Fi321-)zE*%TIv5-E_ zOvN9X-{vA16-|53MnfvKE;N*s*c$dj-p4RZQMTy2cYtLBk09(aw2*GexJ!^2?;vHI6*E%1{6N zaUOW+K91bApJN}n#Ma?|#b!Fm#^kds$uZEkh;H$N<+}pVX(nqzidynsQH!M#-e}1{ z%MM{eLUC#V4Xs!F|41AdYpzVoCt@*aTv8hCLzHYIqs^6>YZcr21(=IxY`>$fjcSYc zE>>v?aDvM<8$|&zhl+Yk7cFiJM#p1!j77AO9a^gt+~AroQxNSLB++XJSPg?U{|#U{ z_}*h|V{iM26Joy9`; zd-!pb`@Bit;P*bDxrtxn;_c#kw2O0iHfTJ@8t38r(1@sfm&rf(&x#lqe#tPMeDH0` z0wi6?LT*`HTj}_>wx1ON$!6eXVw^X0Acg0?{~9m+;v3MtL0>NM=qDcGD}V8;oV~l} z$k7-1V}~wtcRmgDuFI^^MI0$skQ7Fq%Tx^GlL)Fhdhci~s$@~57@w!4?5kTDO~$>Y zVvRjiw^-$6zH-;E^W^cD7+7NR=n@Bh`XH+e$kOvD&$FuM=-95A3MxH4y=QM&@GRBP zO}ymOO|e?JG_s9obb7{1=L$Ngmr8h`p|(b7+-OapSQ)HA2UF3F%RtH#Vbeo z#>ObhNZcwFRX)zWv`>X#XV{ZaXnKm4`*4u@7w&vUwo3GznkrJh4bk(UKlQrmX~-e zpJ0^@4$FB|wkbs^bVNfVP_LE)8Qh8|gEl)~crjv|=#OB>AN<`|_>%VV_qmQmB`~if%NFT+og>^%f; z84oOTa_boX>Ie7p?Ab4KYVG3)$K6)-kcA$g!t!C@)v*8>eYa*tXP)1>BHLsE$NejL z1VKfiFUDovKK{w~DS+BSdC48q{Qiko@02V+(uFMKmZf#zujBBm5Wr|{aH9idnkZY3 za`5P9dH9L@xaWxnSU&a>aQqx{C-WSss?(tl*I#(78F)9%JFr3W7$8eqqVV0Rs<^ zFs+kumO@Xv(~wfO^H4Wz#mDV7K>bUW@HDys3f@q|vU}7C_>2?DdA#bDaa{FM)p)

tCGW%D!_pQ< zti&vu&h)yEX+n^_z_8W)@4}Y}dLk~}!Tdg8&4k}Sgs|TTi zm!{P5Y&C+GM%!$u&>FksAWm0{J7_EwwpU3IrFG)Tk= zU|-f$kv^c)3Mp-9`E5EndRb){R#}&$988J(c%1`WCIx@J z2vTe@G9|ZHeri_f;67{7=)+cZTLF@&)2Mk8g=ozdua#8IJcq8Neli=&j2bfR_k3Iv zTSRJly>QKO95nnri&aM36*JY^$AFVZOHMPYIKPZ>tXsZm!0#iZ+l6~#fU92@)kw{W zSW;b0&sK}XaY~fVd)fckAwKRobvhaICpyHqqsauNkFv^@jb%<>SYu*aL4d7%hVoTEcB~YuCL}rAjHEgqY4xd$@73MnSvn<5H5Dw27(sP}JX_}> z3}}$UD+x&kw$>n+$mCH6+RU8J7gdbc?`8~um-RV7Dm8d_E}a?}#_@ML?)yX981BX+ zyTSbVEg38OHZxkmPx0)4=n7d>#>O;}Rioo7x}px)IM*BQG)qD?8;_hWar&hxfA7D0 zfs@Z1r@#Cd$O=szCfCmtZeM@!oq&bBmm+h&=cP2id!V-p0Gaa3|KwYI;~UR2to)E; zKle%Q{o2R)(i7+SLr-31l}*3{&**HP3M;bCy@v`9{=|ow-1jy1Z#~36{iR>x^659} zmW1u$0)OEbAK}mcCvQk-rEqP|$xd^-6YpXhIMV2m`2#oQdLAHDI8VeIUj?h?-Z@DteZgq1 z$H0F^Z#KGT?f`A*CI=bNj90vskWs-RyYR1b6OqNR-x# z?c0D-4_m_t07X%3nRm-JgT) z;R-@xa8N3V-M^w^x$%rqaj-GCOkMF-ptNd9Q7EN?pw;e#*&=jqV=;6r!xk+h9XzXW zY8~oHWO@#F143d+29|Y=EWM2>8K1E>Gog5fdieC7VILTiJ?o>=cjhtIOIDR3h*NRI zNQ0$w9DTdIRP~|E#u_y?gK?X=Yj>?pv2A0i?Y)jw;tX)>6{$d@1|7%H%yK=y(IQy! zeaw^Bs}Ys~=1yH`XA-|4{$6}f>m1qMVwPoQW~z_j_i0gOs)L8V0xVHvi6n*tZ18cu zcmC7-^WQklxhvajbdPYMe1z>`6?Edh(m=iGXH1}@mSYAIqqh{&*vYUd?E>A*vqp0a zFX|>qA@n~L4b|lD>^$~UOZ<{_%S^rSt)FWp( zn*J>h%dc@xif@3p)Af=XLYIPRWkJ|)_-r-Kwx=o^`mNMv^ z-kmWuew=#NUQS7XU)6R*U_1hv*Up^G@S8j;eNuWfifzCU}PydTT$=jFyDYw!QLt%X`zi)t-Vsq+&n{WXKsgV@L*bw8j) zNiLBkr%uIgtH(t%$b{4hnH6OF02?Ph%J!+xAnZq^H$e7=PDPA;{(Kg)klP{e7GTKS zwp*z7h-|R6k=fjM0^~9JOFzZBevA*xzhf%j1J07X%&ZXLQK2iB*v|#h(v%DPGgCg! z<+DG}`pL(UyoBn%W$SVVJxtMcJGw8HrC8k3Z4e6@XCSVoL`zg_DO!6P_5`VKLolK+ z`~U3O&p&ys)*PMw>&f+=*)iz4Uch9(8_>^fPTg9@^Vusn80T>v4av23XJ;AndfM%F zwkvnmrdS|-tD$lWn(mxQI)6P|yCQRT#Q^LIVc6TAG3u`?ZHrXSIF(Ey8!=Gv#vqdD zNfeGU;n(RY9}8wVq5nXyHMX%R>VSy~Y!U4UWASgyH{h1`sc0Gc{rG(L|B)sC|H zX)c}q2`=l0+1hvo)e{t5qgJwcm0D7%6$F+L5fY0YN@P$MRbOr1`xF%z(q=7~9{v^Nc!hS;Pp5#xC?3WyLBrWr;O;g4g>$#k1?M)(=1jL+3Y< zdj3X}9op#p%FC|FGk%&IFMv*MMr)wJ_<6h+IU+Onr;L*%iJ&2vjiFQgvyXqjV2kMrRVA7f>?V<~l(kgvrz%XP&ylWIn!6sf>x z99!Kmt8@9((h!0=Jc1GbhL)ye-}b8>?8Y{#qb?m~2hG?z_wLx&qgAwYhv2k%T{B|w zctPg3+=av#JODA?v7I)Y559ID(ap=8QJFcW%)P$e%={?H4cs&j6jh_lNX@{DTWY`7 z+5qgT5yayBq*9xm7}mBU< zd=|2ho0oUfEp6wP3@ia1T9UtBfdqNIpr_6<+;_=MjfJfuk-KgSL?_imiLZOL+vsQSf}k}RFnan3 zDHkWe)PEMTkeihj!YU{ODcNsha_HzLOWb?^0hS(kfTfi)4B`!VRLCiLsj?!Tah+>c zwc|;?P+(L{T5+N%jjz-e4!VMPoS-vfyrCxbReFnc@Jwu}VVjhJoCeD%*MKO)U!}%W z)X{jQn3&y7PAgzZ-(k1}k|o6iuXSyXSh==sZqnSS+Z2wSeLe&m5i~Uu$v80 zPUS~cGmfQTP11m5+27T!MHPeq68`E3R~8`YLKbpcq%|=*``ZX`APtzKnlZ0J_~Ms7 z%76V|{b9Ph_wm{h<$|uWk_M7yM7t)C%huh#$wFoBXjKQ+>;#$poM!Py>VFV^Ja}fS zbD(%>^lt2->C&;d!OCNX5GsRw_lkludiDow zzV*+!@@FrR{=j{Rz|a>`_JB?cDJ3Q%96fk|Kl+Eh%on%6z}8#$@b`bEaOtHjlEOew zN><^}rzu$`N9JUEOo)7X65Vv<__HwpN{5zF8IB6uKSaPTrkGa0BQjCK0$o(@h!yJo32r&QDdQ1{7b_KWXEXaFKXQ`lQ< zv10;ChfF43hrAP|!9o_YTWO!G0!%5g1kULwlLM?CU*^yJg+qM!vp>Vp2T!x5FQ92+ zpSN1b8#1L>^{zpQ7|;}WPx$ds>Wg}2xWzz@F*-gpugUC#Yu{}EKk-Myxs4SeiDj2& z?NJeWCdT$z`H!)xy&@xpOi@ovY4-1+Qp957pltZWpq^+h1k3bn33q!Q*VDDS!#1}= zW(|w57w+k6toW{uw$ssXPIhZs#`7D`wq=05HmaZbX=BtesK)Oik_tt7N|`d0gvtuJ zJHYFwPw_8*>)-M6=1a!JE6+uU=u&G<~EM3Ycu zcU#uvbk=2DLw$Q07)0JkXsfH5UXm9Od#is0ypBz zMEbpnaNxiyk34Y@Iedti&_rQ3R+bbZKkiTbMfSUrYq|lI+_@!y>$~#!ccm)?E#@|yvBb0 z9!qJHoX-N=46+Kc#FdS0PG4E$%GNe3OUlYpMw2kG*aRk9tw%ZJd$U%+pcfLe# zcREF8zI}5+?aUk+ia-f^8Ny!A8qXPMIIfqpP{GZNA{gxE4EC<1&6XZ*_FjYP$ZUxc z+5oU)TsFgPd3^(vdZ3sTgaIuBSJwwN22jatmIG+|1h2jQc}|}A5L;{a!4*KaV6q>U zmeD=})UIZTjq$9Ix>WrS6@iQaxt^US4w6>dB~lX;i&xY5`Kkk?ZK*vDCV5s}5wV2s zu(?^#TuA%yjH87tMize)6BzU#u_V z9u;!-mRHRpUQ6uI55=28`My)GK&d!jDhC9!=<1lp||FL^tEh86a*_1+*hK$aI z&^F^R+|z@T6b2k3`v`QHdqh!u0j3%9A)fj5m-t(+ zKgVZ&azFpYFMfxR1C(vx|K178K5dx;F}V z-(4bnt<9x8XfJVXDpGgtS$O2btyrYWr>D^u=|-G*JMAFsv-s4t^S8S_3D&_rC4my9 zxB-fWJrts`Q>i?Feh;aFWQs%I=gzP3Yu|jEm*3c=NapJHGM6{*=bh948EY3mL)l#Q zu@@MUp_>tiMhUGnz=>GqP4E~N!9h|lxkbkc$Cg7bf>@uPXg*y0wTOCYuq{TaXKqJ! zTVxHXfR+N20agm+wrS|i!YB**{VlUP?&F_)fWP!tzRHm!huPj12F>($oniGOzs<1p zZ8~||`8z#c39nlVDoQC}RdLjQ1VR8gmYF$Qb2MuiQ(auJ=SE|U7RWSX9v`u)asZsa zS5k13sz0lVK_~PwK`2agn=GYyM0G}8nU5RI)EHx`prnKm_zK%5Zrkd!tPZr|_Hou` z%=!YepJ}trUM*WYQ>}+v{CIKQN^_KVm%Z!qk@_T#v6n@&uxF*lIAhcH8;y88THHJ1 zb@1ekO6%Y=tg$$y4uC3}#2X^}eJa8L4AN1GlC>js2YLC#C4TL>^Sre63!KTHp~zuW zI#RC)#V94Z9>WN{sacT`^o&u&{T!jx^E8_A(ipJYrD$~wGH~}n=00ymGOm+`nZ8Y9 zX!aMT^Y)sOk;P3#$rPeN*X#+0^U#2jdkl@^J26`_^Ueq@&w!>ilT>}h93$r!wQj;* zR*whzMXiiukj$X=xk#cE=!c$^5-BCNHV1}jVHi3#`U%tSAzplQh38-RFsJ|h8~otk z{1CQRfk%L4Khu7kmx>lQgy?&ig`MHzg)HPw%Gh%je8s=6h#ckOi341G^;K4vGne05 zqFdQub8C}sx#P;lHm{yL%nK)v^4wFu!fo(^DK^ZK^h--G6KQ+w92p^ER(Y>qz$s zSB-(JjOJOf>wXPN zEyOQP6HD`n)H0%FAZY}(iM2A}&8vra`ND_z<|{{d^_fB^`|11rT;2R6^moIs&l_rF zBr8$st66Il%){&3>9X@)4%wmb`MQ+jk5U9iOA3o`sr5-=e58ohoIp ziX#~Yx=A80Wu_Ezbnl)_SUzx^rImeqn&X8mWG4~#^A8+a=E*PL%Ypl0V{45`8dzI7 z!<+IuY+QXFnGVngFqzN-2M#W?vYM?rPBLg_pa&^XET&0l@2 zJooCwd*f@P{S9EtW0$CwlaT~Kg6~uz+7o6S5GmfwcJMWk(bKKA$>SXn9V_VOT*g?e zi5N;EHLqs%hpuS%AEM3AJa{m#{D9PbC4(?QD!ONSM*luL=NFe9?iLHSM>y zg~-977Zs*i$Z3q%i|@-q|1p+No-`Uwkx64_>IYdCAn8IDa?8?M#P)A<*vHbc0i*}n zw%igf~um3kM^Z1XS=1>0B2UxvF7*xG^(uAxlh!!tMEfd$hwO5-ABe z8AoHEdj^4`%Sg&(HtBTR=tfKO?D_~)#_}&K=T?ws0oXl;}f~2?NTwHGyqkZ11v#|U9gK;{Eb13Z`oF{L5G>wNV3a@KFXij%93zGnubBlW~sra>ZLG<))y8g)C$j zG7s^^?_xheiGn~m4Dw|pALF%WpW|=-wckRzDWw#o6Q*Tgtv|w=9%JLoR}m?6AhfAAA*_ET0LTH)%4_HlOqC05h7*smv8>aH>sF7` zt8eq%Yai$0$^V$m%}}QbukfsP-z5W5v+K)xe8o?-3z|$~JTZk@V6%)lD zZ^gl*2_XU?7F!izoY=Zq)26iAcI zANw<(;LAUAFVlVlmJ%s1xosF+uVl+!qabQ@Oeu+FMF)`M3m<53Bu1QNKOzIcYnuF7 zwaREEsnL_*K&%}{;$b8fIXW503`kK#dQ{2`=kTblOy{NmNpGah=Uwxe4J(>D`?~(! z+LY_-*}cXb^B%Fze4^KEv$N;hZjqSHSl_+O#$kK2&h>iu0#=zxPMVi!g4x<=k7_*S z*uc=__eL5iT7W^6sX{MGAp_Zgcw45N4g;^gagJBsxC+`altY|KALp6%pXFSBf}%&r zS`Y^3vNc^VK%U{=1xrwxO;4eSCoZd1@Prwaxhocn1(_x(MVh;4ta1=&Vs#wsrvk$% zu8u(h7PpN~zz149y@P*U;nua?*hzz?v7H^;b{gAuW1Ed_r;Tmfwr!g`$qwF}?>y)G z6V_V4d9OL=eT^~xua24R__a!^Jm_piomc(wLhkJ<9X_JnRubR@x}Ts}b%nSFX{-UI zbpYK)V;^JA45%S8m5$wGT;ZN@Dy{tP9UYnS7)P0J@aQP%HD9H~QL zLq^4hyn8Ar*mMd?MUvvup>cF4st$U81LLUs;j6nn;Qhr0bhlZ=-|*Qw>1$4e0dUF3H<`kKhN=#awW@s)GHaaMxDV+c%xw;Q!?3HGN z7e0!zRUT}F15J3DzZGaFIfjfzm{eL{958B?xJa#CiAbCiQD(ujsV_+0Q-ce%mAcvU#ePOk@>i-0i-Q;SKWb05z^yLDSq|{3$=~ zWMnN~6$u~>t%g(|2} z%?^{U93qRwT&q`gxe#S+?u{<0o6RTi*9~<8t>v!YBVIS8Qar5BdUbtp>|JYP?|UP5 z;xd6~IirL0joX**`Bh}yab2v)F{yS`V38J6VVi1jT~*J))8d3E3ieL1m<#Rwo2#pC zceE=7mUD~Kp$$jC1&1$*w(bHd35 z>lik=q-&$|5>!zw5IKS|OP4antyx@R!akxS8R`+)-kJxRSs;d8pQpnxO(#c22?22q z5^v^Z`pXho%2W0g2rj|>;7%Tb^$-^~S;d${?ClJM!K3zYwI*(>j1ct@aXS0e`kq$H zjDQ*IRrKQHRlui|DaB2jPfQSW^Yp$>-HeWhgniFJXOA;ZP|c;UZ&dLs?hVw=BRye^ zD>u!}aGzel6Ol@WxltQ!F6v-TmM{A~JxXU=HhPjW{#V@NF)G(L zQ^LYwWhe}7_K;Pc0Jj&=rpZ>T7Gyd?tFq&-hlLJ8G=l^PnRntD2BN#P`4;!0U&82Mo`pJMyMGZfhF{fIO#`-cHWPIbQ0rrka=wRD3DSH;txZ7}vc? zv*3%E*EC{mPqx2g)C46%rKZc%M{efJaA(JqEHQ2tPPgP4*15f?jtgc2GgGDqzvrTE zj!Zv5m6zM2Fc!qKFE{r`LumfyGhrIcD)n}&FD-^45`CF`1b#3qj`QaBEQhZSf-sya zq%0gZ3QZHgCN0A6Hbu<>t;`qbO<3{$clp&`Vd75x!jgs+Qf64$?8(Bp6ct+&hg+M{ zR*zZ3&F`fz7b+EG2rd=F{n>g9L6r&bEFeY2n|&-s9Bf{zfKn5LL#PSq3}gjp=q8~e z#8GDv;##_N8LrxFH1&2^ASS!b7i6kwPdJ$*w6d}yzErI9E9BDK-w8MOQ2LX_rW&89 z+9$K)iTfbtA26;sH}GD+sQV4m^9Dd;r?k+vL5mM+ASHDc8_~kTnqgH)P^Wxhv_Yls zkr%RJ3xvo6i+efl?JUWeVG0y@;>v-dXAUgN*R%S_xv!K!VZnSmx)^KcGvaC8U#`^e z;$z?6H2I)v2PW9rfLs~qMB72e5}hNBIrDG6u1($fU#$*rl&4lc_Z$r)f_S|VLK1#b zOaT;rlJM}KtwEkwMZMFHZ|aBn1%$yjy3tj-9#Q4w{7viEuadL+pDu z9m*L{gX37Bu&-RVUpP(DLung5ibxV91c2NGNpdCVED#R?M6*~yRMG!;Z}x@zJMsyB z0h3Xx)Pf*L&!3bzxi>O?@5|I~d@wIiPYx-ChLNKNSb?oo zH{_dUs#Ecg;QFtv?Js9vQ+-mCWI=`{r~l8k@w8}EHk}o#G8dMoW_Ys6E5fmi;q=fmyBOBk6DX?su?yp|3U5jEU|QMIU+*dnx@gl zA>UxW!;F`x`_Q6& z36Ad*mirw`8l?@1o4l(qy1(Hbdt>ZJZfEG%mY9c>qfKDli-*{m3LmkY3i!glrBOun zoDdWc4?&8Os*XL zo~>T|1zGPHn!Zx^;1_rRhVvS_ zQY&E=QL2eCN5aDUc%55s3f&Hrms?w=v7U?dqwsnW1gaQ%Dg3aq*~d5oZXP&MlC7x&LVr|fo+H*tA*g)%aIa=C6~Rb$sTG1ARp~yat%CkC!@}5Ii&6H?J6eNY|RKWuYl?dpk^Q8HTh8woytY2K+P^ZbM9lY{z=%I*tnlH(`3m-*1ya_sbOIhaTHOAHh*^@(}eXxD)6`fUw->CBX>pAQbicp zRL+RbDW<5Jxyhpwf(ip^Y9vJC3DJq7$z)owc!i6`J%ys*Z9}r+5AD4?B>YT7OUa$? z2h$9SX297hov=xEk)ZAEk?8YSK&z)a*CLm+5WL3vqPnFHI9CdFlRH?XY zt9sdGY;5gnJ)SV;)tiuj@$o@4hJR$g7cHkpuajQKV(X4vyJ16cA%Penz-f|7*Rh=r zDs4DG<=r@G9 z#ajDbk31ri1Z=u-l2#J~@kki(@>V@)<}UMqjBAKiw#~l^KWD{zdLXJY_>AV*;a+ye zB$xAoR0&H`(@C+08=Y-Nga4r?$Vv7nVEmCig@XQzc=XBG6W0)!F2%C?6EmV`r^A`e z^HKcQQQr&Sc|a-3bk9Y}-7hT}paeaM!@w}ayqp1=(78suGRcXly`N(EpKMpe>3_en z9XODuK(wo`m}V+V>)>vdZ7U7$V6J8?rE6@ra5;`OZ)x%mG3Jp@akzkhR&Z95 zRPA8bSbEEN{jAysH}}E@k9wHTaYQ6c@p^_p%dk4wN-JGX!dM;YBp{2I;AW~9OW_XAagGsQ-Tf5}5tW&-mo31QfipR`+u z(&d+qYwam(f9XF4eFwPw`3#ZcuD>HFZQZtz>BxN*c%Thyw%L zEJ{RTz}39FV+>kWK}XzQDLmL% zt)SEJXDN1_s08R%0-sEA5_*G_jIVF)DBt@%ReyhB{pSglO)mfFQ+iHnm($M^Lnqb~ zY!u9mQm}lJEDv+v0~cFY!R%_crb!_9Syxtv(#Zc2h7XtQWC>j zgDr=FpJj`gXRAoz@jnoORi7XJU{Td*M0Hd;4|CyHSqi`+JZ#6 zI@8rFQ~7uH57txAhz!xmT6JfXu#|Bcr&{$`Qm_BArrI6k;eQf}nK3wdOAO+8d(0Q) ziPI*d^D&*Eskg=^W&$0L-uTDT15*8fP$oA@qY0YY=N|WyA{e@5!;BrurQ|oYZ!Qs+VSKfBPlyojvSl@qxqqxdp|lr=4o>VzDbyC+Vgq-&=uR5WbB z_;MtUU0Bz6i7zvwoLau_&o%qa`2AEQtn!(^>&T@u561u#xs(L;~aIPh)T;jrYrB6y`&uoM$2w5as{T7 zQMLsbSTM~8!ZGji0UTZa?NBpfK?}p)6e_a?$whxl>aw4l%${N8yR%!`*bc`QX%9|= zg$NH`WODbVf#gjcUY*bNN>&$`(kqvt|E&cFI5E`?k4v5EUwl|uL;&M-P6&fB zEDOOZ!ECd37^_9aoH_;12E6^pYoCPW?sq)(kNF9Pw__CI7sQatHi`3xGvZ1ZJl7sk zl2{~oGEJudqkvR=E)g8WZwN#vVRPf`8eJ||&6_ff_)gcC4V!OnPX%Xuw$_Yo_%TGH zQb8rNSb5|I-w>SVG&HObLah#ea&y9Y->ufm<&v7pvNXe!6wXmkMD>l+*%&IFvvn?Z z=%F&PH+)<65p^}k_BT@O5Ki)i7yOsBvkoVhHQ>K#tjsKPM_lxtyTh~H)`ybAHBBa; z&JWV%yoEkt!n%Uu{%14T^VeVsJJQj-@^j)ObK1>m@i;3Dex;xl_{GNng^wE4&n9>2 z&}Yb_itTazb#~_vquR`F(B2%l%0*n@6t+B+TW{i^u4H6u ze``cwE%dl{mAX(r_Fel04vGI*Egrw`9sM3kk8q2!3|z!?ubR||_>JqU zW}jnL%pGAfdqAH4Z;NUSVk7YPHhG0q#XI0$JqQtw&~v+*ACY=a*T%6@`AwZw2IVt?*17?GjD6|j*M5J!L9IhIAvsHeAH>wKLBEeRo!L+nprmHw*u<+@T;LXs7JB|JvUD%c zy_WF2cjTJz|BKkZUesxd-=4ZBbKxn$PUV>}ozzgXJEa}8ltpBv6Kf?I_K@>S@$-1> z*J;aYaWo6MMEYwi5VRr20Fx)%X|xG@RW$lsL!FMjmcn`*IpLqmJl7%0WvH7!^9Q^L zOwLkpD#Lj`%gGxBvi}3t+V?D1CT9bYCxqNv*{L``?_|_ zW$zssK%0bdFl|dDIb~hMR^I2_%motHyPWz%dxKGEK6hulR<_}#`pkzCs~fB2X?7cx zY0tGWgxd6kqi^6^?Na;8erMsHAjsKEL21k+{rhtLH?0oVP5c&5U!yn^ram0BscN z)QejNPcr&~Gfc!RsA}0VU}6?yl2!cr>dN1I-=YRbC1C$e% zH)tUfK~p$D0U=FHNy!$51=kMklb)b7Oy+`|h{GqZTTvdi?^Q9JF|ITdaT>j>EP+cx zcb$RVNCMsQQ}AnRb9#oq=OjKRxHRGD8Fxu5e|KhQ`qbGdU7ZW=@JSvZE2tDuwX(lo zc&ny}Zk&WFTIw6exkH^p4c};5i-e)1vJV?(9xd))*5z}^`*;R}q9C@I&jKvqt}M3O zZ2b*JQheZ)lvTb^9wTaXB>%KDPX28zWK?S;$COf^rf$qX!vn^JSZGLIkqHNueKS_Z z#3QZ%C84OV2W-oCm-=IC`;8vxU3ZgQ%{Ou%wvkR zA+ukc${sV68Ic>4ep6k@fJ`d7UGuvBPJaMwZfM(v6QN}|-B~}NC^jm&PQ{L6-QP50 z?5she(pI0Yb9p4G&RN-8)aL@Tgm)Z>AqVd#N9J|SVEBLmaeDIBixDSkCctS1d9*96 z2%AQn_)8kz*t`xXa7pq6#2g?&F>61Vz{{+Wwu#c9tH6sDm0-dcMLUX{EFou9A-%@C zc|F;=5iMU)I{hYEU-1JQ6QmZ=wLp_HIgYgXnHLBSGwAZ0_{D`bV*?XdA}dwqoPkQg z4!zy=)rOLLrGy786QEJF`?0o3jJv<_&_}l|ev^8Sz6p{&$9d++wJiHGcOZg_H^M+- z>z}Kec}nhkw@inb0ysS4s<+ljmPj*E^8XQea{O)=VErpwGFt^@d$@5FZJ* zovcDK_%E9rWFrxX=FbWLG5ygZrMPuOd>oXZr6hOkY?79+!m2@jk}}kWRzbc$s*k<>8}GL|rtgM6-a+D#%fQ2^RnBRE}6aVl{M8@_3_idtz4dl=`nJJZJ? zc>gSk3SSkP)T&O2tB!_YnMtpF))a_E(RjQQcPK)L%!Psny-xKSjzq2IAhL0?6ixbZ z#8i$`hF|f#Or2ZlzaliOXUurD02Dcvj1KwdSPu13?D>ZSRhc1t;TrAXt%)3ea3a+2 zUl2u)O22Un;(S}jWbzF7rbn8Ah8lZ)0g}4Vlza8<`e_&YUuj~@xVHkk{#7x-#8tsX zI>;CiDA_8{ecEC^5! zp%g@ot7wJM#_p*zq*}`Z;Aur^M@j~=3YW6Oz5yp{NoOjc2QtvoZ@~uq6$a|^9nEdm z8W5eWYFcS5nEUxyg)|{+_iK5-&p9CPRbxtueNmLTTVha!;l+QY4P}EurUb?egJ=r$dF@z+}NSjfQF0a=|N12<#kK-s6m;f4qdI(Xair(#{i9GxS=$n{I zMLuz>uIncgc4Kcckb-#5QFiVaPi@Pst=jN0+eKlNkPIYIS=^k3y!Ac#ttq=Iic(S% zTB41hI|Yug+++%o$#m5xoMh=_Gub-=4^BUuI=Uvy$PyE0w;MpSY!^q!uDfZDLfM$V6Iyl`b2>`}n zkAdl*tO7sm$WI7|KqATSkl%MW17NTu_XHX7)`cL+{fUR-O=OyiR#If8vWm^>DP8M} z%g)NwRqfhAeL?f2X%JzUV;1>Q=%`}%+<)>feqyAim+>=(GaLO1Q zs$43%WIC6+CD6~%!rIJTA@pu=MS@ln(IX;0J{q{MD9ijTaOqjxtM-R3{BFohI}2^e z(CJ7xq^WvR>fj>%ApYD-CfY6ti&{@4vzE_I8uf31g+mK==51$;%N}yy)Cx}05EM2ocs-(SNxg`{3+idCH5Oh-8A|C%q)pY;3b z(=Rf8}r#nCAb-v2=m2s zegc0a1J2f^4Z(fc%0xc#J0hsLgp3r7Q)=)sj{)nVC9<)Gzxi}=O>ApR8-Xh0%&Mqm z5+;eMZBgwVA9-)Fw^di7aizKI2Aq#P-uqJ^li%Gbs@hTsd)uqTH z9`I-YKVeRU(@W|G6Uvggq^0^y&LQhB@o8NwevbXMIqBJA?>-woUX~9uc+1z15|^>~ zJ)FlWm}ujc8%92#B$~>Tdag1{W}J?d7JW_tQ6Uf-3EZv)792#Gi2u7J)Eu9dTZrO z3GU}@Tn)27bWn;e(#8n0y`4FI{8sMwu6or~#d~)HHI>5`jxjznZ@~V8G`s_nmqe

c_~kX>9=yJ;=PVwj7_1M^_NBMu^KadzB2BSvBvIKMCgFJ9zxGcw$1SKyGHkr zN1}+Cua}Q=_&=eX0@2bC2H#T(dH$_LbSliZ3aeyjsiT9eQoao*{b3ki6JeFyg=$|XpG7h*V;hB@taj0mZr= zR$}w+h$NZuMFRG)IoDVhgHvu>_loh28Qy(u6If{J*Ky);()p!2DwriTnn&aLXsSwR z2CG95y&OP044~YlLURm6Hhwp@3)2E3n3lR1`5iz^|u#0fYQfn4i>n>QJU9%Bx^i{qkDh+~{L#Ss>S4q9R2XHkf^BPK4>te6_+E zmSPKXCi2J{4ZORz$6^n&PpOn~1R@q^Z&+Go#-X0-gX-v`64R(xhiY&0hs_k!d|La# z?2y@yo;RxHGg~Rys(L!<@heR1r-i^EQu)E(F;-U5kmZ>T9H5oBg3MZMftuTFyzu>z zIUXOk_xd@K;!$naupeXEw#*EF(-N~7p-J14wiobl%rko!@D_!Z3(Gn}F zR5TVD3L_7yoH`E=G#I0R!n)<@)y>=*H|GeQ`osbm%r%x-zAeux`%kzHi@}#D>OOUx zx~JutjRP-&$pp_+4>lI9#df{+7B^LhO3Q?mT}XMqM@+x_Zr_O5&sLE84Ft;l1B?2L z*JuB7%j+KAsq4(k&v@%;1v}rQ0c69ROYeF37Y7}#_c#u(W5@Mx%gnESkDE-rtl*PX zv}D{i#AYrm?E5f0UGtqBzMq`_kJ3#?$m~P-R)&4O(aK-N`HX2!u(DtMb{Ojb44F{W zrz#}EXe+3SrwVh%+)}trFkF^c6uu@ORn1pv%TJ84q$ya-Uknpa-Bx2Js!;8i-NA~A z4xclQ`DF8v)1Pco5C2lyTK!@B-2$J(mErB9S`HwhElc-%i`6?y{bBqkURLvyldfz!{4K`_qv({>-{EJOp;6XYOhPt*A17om&ynu z*`11-cW)sl?mO|38=uQtGTc7k zExl@P{#Jh%)?nu)5jl*l1u8gV-yOQV&~`!0t)Hh z-5<5L^L1^LQUJnTwkt6e0am(amm9QPaPk6OJGaBO4vt>E>K{8{j{6wXewQTOFXK0T z&4!;LkqhO;#G6R>k@oHaNst&3-*Uh%1086KJLSA%sg>5UYxxz=KF7zD>(6{DcwXO6 z&cTwF!xuQZ^J}o}mTt2H0fDEZE?rZ(c?7L_+( ze-MMUB&lcBPa@;_Er_KK?frTQeQ$ByFO{AYE3mx zPDbCiF6Q#cU(a$udA4-(3?55F7LP|#Rs(kPBtO_(AZo4Sblj9ic<-iA>Oi+Fvhztl z>8Cwz3!&Wf(;TLCS;#b%D@;o}_W9iEi`|^4{Jvc{(QMvDO^AXoqj8|wn-J(PIEF+JTQ~|h2t;VX<%O;0DbaS)sOw*}zRjUVdjDY%crtHwy+@OX1STl`Ns^_M`;%o< zzr2^`LSzI(&55ll+4fseuukSogW3!!fh}Z+KB%ig{~YXM$(4{2EMayzfv!YDx6bTa zy?SMOB%6vXXO9L2AtpJncrUDqBY zGvVr#3k_{u)TBB$oyJM-OO5Z3ozd5WRUJ9v``M3EPWEpeXD1-Hk12Zu;L`x7nRlbK#Nl5=0@3C94Igz<2Gt=dz2NOBxWxmSd7*iH#%pyh zZ4Y7`cwsK;!rDcaSg?oe-By>*q*hJHQ_h#bCtw5s5@Twfe$p;|vZ zAj{=gO18GV_qbEF`_?Ap9{m~)4fWbyIPllf=b4PeZ4J}LU-xYnGW z*2!&sSg#k%qtIc!(dt;7rEPN{%8}gb{HOnf)YUFa_dTn?=Q081HSGJAl*xy0*W(Mz z+ne9Lrb_b17>twzA@o$9?AlOcvQjDbZ3@8;2^a73%3TZnQ?hIgY}7+;PapS`Jtw9> zs%RyHPoMnTCTzQB2g(FL4RyeAF*v%$m&-YK^a(vWAJi!(8!${3m6;}di;WZsUBj5G zLFv0FjV`lNjTL#~iPH4AI?7AC9|+r4NB2hHoq_Oh4g^2$h%krdQY69Fh$v%?SVd~k z^l>rF-KWq>F{jnxQ++lOZ~3wrSJ5P{<$D(J`x(oMF`lt^|~^fWa|>jlAY zH}Q=p_t`D}(C2MTpu4yFW3Bm10$Xv|^aUTrimmi=_+ZIQBEyLI&&-?4_COo zi=gk9uK#JS-cs8!dicV_mF9<+T)CSyP&KG9YLUkTtAu55#|ndPssBK0i6(+{06H$$ zfV=h&P);<*ro<8(_Cj4IlvlgY*DTFpDs$LW|5k|z!?7h7;RT!VE5gFc#jng*B*Avb znsLZ?-XZ3`%m?*LJ~-!5Xg-SgH(x~2Gh6ZK`Y%0!xQ63OYxoRSsVm!y`m9FgMM4CyF0BX|986jgLNJ=>`)ypCZovE%m6^8kI+Z|dy4%c%Jf!~euAxRhRs zUk`q2!wnBMkB({DA7aO$RzXe5feXDD`C+#4?<9%_UlrkAi<2&tH%-r|YF)+cnF7E$ z9GSJ>n(Tuj*S8`W8{@|c*3UaHI%aAbXpB1yw&TF{dg23f{jT)9mLJ;T>;aZIfwoLs z$ti}?_&X_5E zGl%o9;Inr8Y2Dm;ryh~(_MVV-c}Ban$n?EmXafNalEkzf-urRIIW5AvfK{W2i4gPL zmeECX8q@2`By9oYLq*YUt8Ha5Ws>liup$j~Q>3)boV{u-2Rv(YcCGsEb?WymW~tj9 zg4%fK1^c-w@t$Ac(<@QyRzEi9lCKu_3o8A3XW!&mypFY7Ku0cjpj^Xix^2<3EY0l1 z64?XH;{!N3r$lNQ?#Znd@RaedFj}X?LB-u1ui)%N{KQdAF7qU-f~T>J=?GoyzNpG? zcC5$MHQ=%QB&0J8Cki%mjCt!72g~bpLX~{-d_IZVUPYr?ibq=M#n>?KQPmyK>^VGd zWL}}UJ7J+xFOWu;m3&~sv2A>H=fX@?rN)@`(kBxd>_R+@*G?|GR)*V~cKKP;^X5DYnFfp3f}R@gmZh|k zco891{C&)(*FvJgF6~tNhZl7UxY&NNTj1q~*ZjG_lg8505p>KFT=%uvGfqj6?8qe# z;fL>Idcm-tIgxrO(D*7^ry-cQoFDFJhTpV|+BJ(}72Mr^T%n36W0ZUM<|b|&M*U@J z5`nk3_}TMCQLiF)W?GJ9E?%1H_jwDy1Gnu2;GCt%Syl=MjIATL`2r=4%zI(6jou41u+Y&`y8%`g9&!cz3-G+ygJ4|vqs)PWeAKydUYQFO7cB9wW+US75o%wNAWm+nt$-JjpagV&P$8_O;BlGu-u!t}|z>JXb`s zvD@~EJWOSk0ljCeCnGf$^RCtuBhir&VCVZ;nGONM3O2v#@ddR_8ls` z3YwgTaI_3piIor%3nrX*aeUH6B^1+ArBkbCPM0-l@Dxke5?zEOh$Br)^Mu$cz~^dw zm_6xW^{^-P$F0KC=iNU!Ra=Q;o&AG+H){Yj+Ms0pw@~$$pWQyuwnx{hVqS6m)_A(_ z4kw=?8fquB|0Lp)EIkn-xrH7vl93PME)*TeJ>bHxVJwq8zZaIvZ8Bc(8+UDbqR8b{ z>3sH%;#`3ZO3ogb^IwT~h!cD*XFBLZJNl*{mxp#N-dS$D*dU_Vt-^6j@EjZbg7jZ= z3B{V8R=AgMuRqmucPqia0MH%$MzjbAG)O;j;<7B!Tdjy;Vd@pgE7?MaqY+rH3tr74>Vq|b}u8{lkz?% zfJEi)(dbnH2xMv(xuJ#uHyT-M@j>UBDaH?Jn;`fqUhj?$5mwgNZfu zmrCCps+fMtQ6cWw62X9948hyDFCd<{)30-_LVMGb>~MChZrMH2T%1Rl`X%UtqV4WZ z@|RcF&Q4G<;bQKxAkypno<%MebBjh`6f1Vsr^E%vd*a$R(IHaep(y%ik%P_rUj%Pf z-pOrw@*flh8*z&FFuBQz$r+M|uTupFrLqtfh4>j*zu~NL2+)uv?b*r(L;5$Z6V^;z z#M>Q=u6O<3ULu51X~!1mVQRvyds^EmZhFNxf82im0N%w5Jd#SLzU*DU6El3=Z;Lxx zAuSec4lAeW3y+bL`S|A_BR@ZEKjXbz{4{VC1m>X2US;4&MZBLgll?%>5!hL3etKTW z?aqbyxZ^v>4q1h~2Bjv9yI7o?^FODPzI*fw|5&p3hgKt+kgq_=w}h4Kr4{hd%6_}A zJ1L^$-BQ;s`tvO^D5@#3M|jUVqAgn*$(rf;#dw7Csc=z%w10PdG?Re+kTag@Qct9` zOAo2wuFTavE~{1)=7Xf}WuN6zR^7U{2egOEUidek-S5ftx94dD8;;sAe#QcX6*e79 z)mGYl2qnvy|!af9?K? zMy;K7HF8%|9@cHRDEFgn3rfY%&idP0D2*nlHW=87h}?^Z_2?YMdR$w^hknHA5n~ zsgN4rEBiu(g8C^N?Irfd6&)=FoDxz=iJwfN#P=d>gYYv{O@s01;u1HVB$IE;XGo>A zRFbF>?@0#*!D1+rrP99i$puHeYukfY$vAS#6Z!J~kb;Eq`3b-2JDHa2WLuy1;GPK9 z!TElB{;TtMhCI~M$hj}5Li7-)3m5w#YOZp5A8f=&Ji4@$FZT?f#TH6X6W1}D&XQ4cyTE|ZpCQepSScah+8a{ z;NWH*A#Qx3o`s@aU`(xTgqbhGUR2_7QIQ&Btj_bZ_#R-}6^T2&-QOEcjW@NMK5XCt zflN<)eD&A$cxAgwblRinkh_$AG$LS81$T$pNBaDgUXK5f4FW$z#E~W?n;!pfB=`5q zeZbntT7`*)CaqW{wXR8M7#WP9xJf5YR88FwXNlZwjrjw271w5r0@4jR<&oB-sFwc~ z^SN(qyPSMW91Zsiv!-p$WCH!56^#PR;J9LbT)X3+%@6szgDcf8@B4L|Ut8m|2i$}U z5<)=gQVErG3v)2_Qn_zWzLa5)B?|RotM%Pw8hI)iW+k3A3qnR&DXfy)b**LFPG`HD z#N#C-D)89xUaQ(4kn;MzIm0=feWTgv3sOd_aN`Y=!c)rUUMC@H!BK6$%)jGZC#B;tVksU0L5Bw(#PfzR(+DYb zSWr)4Zm6u=Mj2)=nn5z|`BZC#hk!|mwTVp)hAx@7ejUlN{@(?-T^JL%3T@2Dja5a$ zT2xzk^=WY1mkKJ^gK(m$rHgaaxZ5u>_3G7U#+uBtfTBQd!p0RrWoMwUxz6Q?mxI20 zWcO;EjJo5YlHh4eocoRQ(IE3`C;Q}$Am(-WbUup)z3zc%^+2;hFi=#y2KfZDb$mhV zRN3U#OR5O4S!<7`Z1C*@g2^;S)^;ba^B8(qFr1|EUrr;_L{dX;P~E`@99mYeDuZT= zuGgH6OCKvsp=S4p3Cq;fZ!Cg}BSea8On(P#h-j#V zc;QSI`?eQD9NR28SS5YHm%`kAyH39##CWrM_FDoR>bSg>-&f4SO$UbHiDgCcr^hVQY$wY$}^8LLB zkIdyJn2#JTQ--G|h{nuH;c7msfDq^t6?_J*3+gg5!W?Waz4KF>bRhXZfASg$`T0E?n!ZqD@!@; zDYQvU5~A{}UNxW$GYP>F17=&SSz{!W)8kqsiw8uaKAm$AQps>%<@}`y*0i`I+6sm< z(AH2I2r51^DS{9(0au-|K?43uA?KpD1f#T6_3C{Qi|>laQzar-smJGtpKQFLWj58D za_scZ>b#UmLf|_b!1Mwo2Zd;8wwb6Dm&k_p6ln-5H2!&c^k|r1pI`;X`@+^G(pgWDmrzx6Z0e5IyS|Ph|@H?wUlx99j_DpmF2*iFuc9 z`-&o6w+;MsAlPfWvEN239o_`EWE>Cy>7<>{O(JM#of;}23WygH4}DnPFHQ@=ekS=Y^c>8h7K zHJYeld9b=)kY8KGNPC)YMg7aZ-W*KvKfkpQZRH$J&os)rVGn7)upDJQq*K>|NwCY7 zeEk3`vUNmjuPg}`P*?OKWDe(Y3+LJud3$pQr5GvC?@uuUi?ee$QHN_P=Y&x0LS)&1 zXRzqs&WX%e=vB17Mp^#rm+P?S9NYi@VI!_w_vCp()h0AFPJqKH{h*HA`jV+H)D8#J zdUGM*o4^XfQ_{b&iHtgdoDDW9l=C8ZOOL&Yk@wD``~b?|KUe!^Cl%x2=LF@4&K`Qq zP&exBm3aB{cLz-bR(b}>!Rw}Ky$GoZSqYsd(5Dk?QJ5;ix5|CL=FTKn{$VAZBh|K4 z`U7vp9kUps4w{*_pJAjEQgW=JWYuD5$)fScPX@eJDlkh8PpBDaPBlG}`kUbQscQAq{j% zxmrg1@h~r5J{S*a71D^DYf|?^{q-Tk#{&$P4)2JO$Diy$Y~NeEPx{Ykh7W?uN?Rl& zM}!9B87%z69jl4L;9;f_%m!K(3eI8Ds;wQJs0SDe^rfd-xrUhQ2x69%rwuUWnH!|HnW{k;H?*7>+wc+(@| z^SS$zD)+hGyoJ**hFao*x;`mK8bvEjQX(1dzKzJZx4!TR7C!?3+Pt#|(B@Y`OgMAm?CI%?Iz} z`<84dkf89y<#R^+HrUO$|HTjFc&FT-GP#;;S2f8Y#d)Pj(RMEweJW8f{cR!$EV5Kv z=xN2*vHXVPSf5T3N8VZx+pBH8a(++_Dak>!lBnoeM}b_@(NJjfxx%;c_;&!){`m#! z@Jm6u{^gR=8`JM^Vw;{1{V%9S5nV@uJa&wHpPhqN)u(+e%;j?-?e+(G@d7iS2n++f zNcq5F?X`N;!vt3tRv`sGxxGXY9TID^(PGN!P#k_R==;A*yo?1=xdJ%xJ=-tNK!3O` zd$tkiFW!Z?>RQY|Hr2u6@Isc=1~lBdD{YQ1t0Tn^?RJaaem&REr>C)p+<>(G7RvfZ znn#0dERmt7ewhg0|KTY`O*>%>53~5Wf4gg9x%haeOOlKDUxYQLETLwev62cHV z_k2Tu^Bw04W7hB_?mF}SdNp$IaK)LaOByztZabkH=|998s0AgePLNmlwy`6@NW6G% z!ap7hvN`-9*8jJUtu_HH#V@Y3MB$~rfM+uhxg;gEzU*nv5DrdQdUunuh^5UvEBt=*)gk!8 z%J)K)4h<{ZPHT{vYtucRb$?CNn*e$M(a1}oM?tG~Z1(jtxVt!2GgoeFbdTBew|MJ? z&+ryN%L3{VU0Q&c?2dh*cTUjQ&`gKOgu{c(?(Uqv#4@{}OUl^`C+Ma^(K$*Xr%WPQ zkj(4cEu%EK33ZF-wk*J{^-QtzEZRYuQTo$7e|5=Y{kM3kdka@i@35_KxN``z41IU| z6)_{~%f4%+qXy7bhtBVar;b5XdIX-fa>HtbL0X&86_OO!HywFj8YF|0Af73z=+Fad z1fuOGRLdxha}kE$;~EAz9XGS6OV?Dl(@wAWJuX?1EJ)titIha+kK^r36h1fN2q?v} zFH;h#D9ed*ZM*W~xsGXfhF&V?G;`|3j_yKl8PFWE*nb+z0`tKD79b0#OPDW_xuDE3 zNhAfF%u1G>Ip599cRv8Uhe=mi_Rmt!yuhPR-_5ct**SlcX)*DAE%#kXO;s-hYdaSReyqlG_09@QHSX*}C4yETG7JxjF& z85Ob0EiIH38IE3k7R+p5BgF$^;uQ{tSyYGpA5W4FmtLG?)yP?C#%EXq1+jz~&5b~9 z$*RpAANw1xj(lsYr-nU>YZFaiYn#&)b0$imqt_i4%(z*Vqs0L%JD#3D$d}3|xtxBC zKA%PrassMQq=FP+;^&_lHd+~?Xrg7Fwxkf3CTKbaV>!8))v;7Tbvu;^_H#Jzup5$_ zUBSuDFl!bl3+(5f+sJ0w2W#7R*sh>HYq1KJkxYc-^61>l5WOkyrIXK>>0zj z+oNzoGA^wuiEV@vD_gLUP$p2fxbf-7c=R{EMS1=v$R#?RA$_7yQ0ak=Z+!6y{>PvF zUHaMQIr+dL@Bfc}f^=$1Ssrll)MY;Kj>@Iem5C@PCr51Q6{Idalfp7}L@TN3lH~>r zlUSk1DvAtnVmha*l^|wdL_u?+H+FIL>+4fC+U&~fBjdI9=k1>(93U%UuP8;KYB34D zG?2P0#;9dX#?_Lw!?9PRagmkrn}ZXdw}v0?aKsd#t}W~H5sndF)`L)sb!)F~$ct;i zH7ADvs+gmwcK@hGMBSp^ecfX&h3nkQlgn-Pjyewd8E_h8h9SDhMzb7Y|25K-tmk)&Ei+ZeqK?qmefx_<4$14#bu*!~RI#vE_U(H_d}H=uJf-i%|_rr20t zAjdVBt>t7UT!`+OK?tr@#2C98S(r>zCoBGxT$TRM9&36)sBQ6R-_= z8|s7n*57)Z&;G*G{LFv$c0T#%?`64ofy~nL;U`GV6ctjQGL-67(|@i@B!VjfRBn?3C#q(T_Z zNZabjfX@#R4qHtAxPdq_&AF?jLr zE&hwY`eEMs?r&4;5|U7=(dQ|dZ9!akX0+ahuAXYP_f;w0QCb`*cX~h9U;a`4kH7gW zUw-0C+8No^fDdUN-j4HELW-^T+8q`|CzK+W%qk1MtPi#Agf&I`ZC9b3U9IBov zWp9|&js|8oALQ_?@b+K~&(uO;krMkT2Ph>e^RlGAZNjC$bRQ>ae6(6MnI=J83$jRRb$)}{h(+1g zK(Ho4GV~lUb!VrVT`MEjG_6oZ+M6PY%r?FDNb2aMqw11gdrFORZ?87<>oRz;c6}Ow zR_mJke7libSxMB^yO8c;g=W*yexO%NXCHI5sWq%JE1WdqYTw0r6>Fk|y^B-~m*R08 zQAs3kN~|*DfD>Gick-EQ=Xvzox9C#l+T!i(&)!FobD-9=OGO}?ESwF?;;j-E7bhis z-+91Jar-A>$F{!!HjGtDmfQTuiUl{xz$OORp-3uH=j7U1Y+;khsF03YV1gY)cO{b@?sK^Hf8Yxx{<>nZL| zH`z*+`?e3cn2*?DpH85Lh_|bziApnIQI2MUY-?v5r6KMhgh6RD;StIj&WYS^)JIc> zPtnTj7HA8dFIkBaw-0Klh1x!gcw-36Sl5J=>x=;vqYP62%}VKy(<_SqGeL2NffaY+ ztaQV_pIqzC9n<9W0C;(XI#?uQCG+M`REd%tZRHmdC7L*;C>E7Ba@0r&(-+DVPP5P3 zdG7EXl)WvE<^r4qJ!#*TBcNx99%}=Ss~OKhl7?$&DKl0Q8D;W!B1!AuT*#X7ZjMHf zq-%tau@{6p8KosA0>2F`K@YL0acbpb$CE~zu^DgVF}|ncIeVphU7RAdQokvXsPybp zB5R|Zx5g?n4iMip!79*!|i|aPoe*coNDIFfCGYun+3lE`v>JxiRfr$M>%N zVVa}?uR(umrRxwdFB@V*(;>oLnghVEa|m4W+@0g(R4QI(X4?{B9o{Tdg&o8fdxecsawe2 zBi#D(d2XKEr7pHnT^ji+kwp)t=V`um!ZkjL5@mJFp>6FF;<@w2b#6ThN(p=t!8f!$ zkJdm)TPc0SIs(H%`0w^+tTm2+5J@CDvUc>PXSp=lt&|d)W)}Pca!ZA(lU6X zu@;(1I;Ey9_UcKV;r)De@d-XV@90vY))|scVsSCUMFmhXIzD;#t180kS^Do@;ixE@ z)z@eBW!X`sSSm});tYH;CNi}#s;r2@#lr86k&*Fba9pn=d*&puCS6JVG&>xZZWQ?S z_nN)Y*k>G<8JqEj9;@tLp~dtX$+rsp#2txY`ByyJsv})5#7nq* z0aVxBi7lyV04@olPzeP6;s3;Y)(r?N<2=#4!#wqr+NtT#I7hN_wv{41B+GkiDLhGR8JgJ``|x&4s8YqK)- zPjr5-yLQitbGR9s@n#yYOo*q05C}EAH*{vW8 z6-J*qh@=x1QifVkFOe)!{i{Eff=L)3X8r;4T?onGbieP3a} z9#Yf9zMt&Ai0d>QkFEP*a|gX`K_$C38i*toC9~8iyK<5f@4bg^>mKT zXk=qE=)=Ud>m?Tc8fQ9@M$I^!eXJgC9)N5amD{%)74JGpv+Se&RwtvIuBfB$A=)E zf*{R=)~AvXsosfPkZS93jl}R2)d?VxVPDPHjmmGwx0H;n}=g0r_A@6?Q1(xAoYe!UVkFS!t&#ytmCI@2SX3KCSE8lD{hw*g0 z*eciTvx;jnw`7yfX3H1cz^Zs+hAnrokH8$aU*dnRLLy#G&l7E zFVFAi(W~e9!tNy=Tb`iii!8hXz?Nad0hXO=+9*}TAhAl5i-~=Qm`_S#RfIBNb%2?NbB}T@GRG653B$`Mc?+wg4dv-_YTh zM+sAJ*0CW;H)Av2@I!{5?tj!8BFh7rWJ|Jl9ukYFKOMtHPO=> z7||e^oNCnxXb0El~m5fSqQZ!r%TJ}c;s#G+(+mB{q9IX}1X{bW03YS&~5|Ky)LZQ(^ zJCcz*=*GONP_zJvj%1CaG&%4ZmDI2C5Yil(0n8dfXxUE@`C%`?sMX>I?jVMM* z9vQ~-Ni9g}hEKg2R1NzY&ZQ9+Hs!uIb*D-S(d{xwUp$j^qBHJ3ypR03>%8zg&-*rZ zP?ls8GvEG_h{h*Ir#QNYZznH@j9a0QM^3<)C>@hF@wbe&t;1`LBprW#^{U#|a@)J* z$8|$i7Gt0t``e7ocry)I`+3~!@mwW@&ckhjQKd!@8AXu6s9$sC=z2fcI!-TDTd+yaiMnpk?Xo$5|}hk;}5JCbIzRmn=3E1h-st=82%vOQXI zgs-R7wXmZ?!Ll-Fu^ee7bE}#EuXd;dumDR2d;*lkJ{(9zDSBJg1B?nJCo=0uR;Mj_ zzGyqa=2WlQmNwmmL?tuue4+)_Op%FY&8U^ln~gT2ROA`X-v3Kndh01f3tfUDJ&StC z&BYbw=>QQAkZHnd^6XxzEx1>k9STF-GO}v&Yiif0wcJ4jg>JH(dZ}7ICc!Bfhu2Sp5Gd;~NMW6S`{!=Y(A8?G~$tS{q z3B+Zw#PCdWag$-L>O`b8AKKSE1yVFKO1?CB@_|p0C9_nj6k2(;ubn2hB4mYmg{Pl> zfG>RZr#XA}OMLi4{|XhM$M8s^gPPYe?PHCJy=W|dgL!Y+@!ITD^0mkGu?J}s%fua| z0Su2>R=kKww@|Uy1Ol0fXX6^-ixbIprFu`qh-AY+LuRHOm)pvu^mwMRhpa=Xn>;bsyz(^SATW>m5gVisS(@anWoxsS7hmGJ0F+l zYBnX-eLtSS4`GzsdOxx+VSmQZ17Rw>l7;iMg?9Rn7f^@3GHo*QCg__+~Iv`m2c4|L`30jQIs#36A zl^G(HX}85x?nZQrz5>$INp4`N!@*NE$D@)VneccPGsGI$2pyascRVy4l+i*Sx-8M) zsKNU9yheHX;1u2kyiKrBMQcZ|vsuog;hD<%l3R=vV%LFjprDZ=S z)k>OlEX7LjRf_B6q*ex*bkM4)HPdTm(JwvXn#iiiVIr4{Fu7s*H%oW+sPvxw*<=+~ zh?lX&K0d=UT09M(RR-rH{?^epSo!`cNh+hyH7{`VGe~MDjxqYCm9)Aew|=FD6R zLM0^!Wfi1mBpWf8nYiAieWov!q7{*jEZKk$Jyng`wJcIQ4ru@*vLGD>HBv7?hpaAP zy87#Qmg1FS>8(t3N!DtLGSV5iR^ypJXWW46r30Jk;vd6s@d1 zs!MDeMQmS#K#yhGSjJHyNl(&BUzUI{NkU(5GOt%S(2CZcE+tA?P^%){4k9O{)uzPh}uIX8-b`9b=-Hgq6El2pT<9oCzauR-3%9Y$PWIeYcBJ;Ku z2n$tM^icO87t*%UZ6zi;Au*xWN?(d=GBPEkefJARX2Z$EO4w;Zav-RGjK{7(F zmbqV(1;+}|FM9yG)OnLC=eYHdPFvN10=ZRhH0wMHe0u$csZhygD0PWci{fhS&@{EuJ3TVP9lKX`;3tq%3$R5gWH?$0rBic8;`IiV zBGc4?agyQOa*Aj!o_T3!IdOQ|Dg{}^1q#Wz0pF{o##c>-Mry~z*E znZ$)T=KhnlpW{0>O5ewl5z&}wounL-q+=5FxP7qpz4#dpeZjJnG9#1F9}$?O4fSC}t-zTXY=g4(0hP6n&C> zbHPluDCv-#EbDVoj_8*?U7j*aTLxg$k|c?&Tcm0L&!k2i+|@!~g-K3Gs#q8ID4q0- zmcSxTpqV@hc8sofW?FmV_SV*jAIy%Gmh5$jUaGs z10ffb!5TYl#%8>xBW~KbaqH-xHw$&lAlVwGWpO>uq*OI>#u}<+^3FD=-+31o&sN@c z=Er#O`8lVSf@Gmz7JlW^pW}(go^y}ipT(pU?J=1ZUy!NnobC9~N6&D1He=_(he)$s zmMN3#1n9}N_n_0zyfetRLLzHIv{F-#B=gaO{Irb2p?^VjBGk0~BT+(#6oITmph~MH zT_o*^>OE`xG%*ZAL0ORKNuJSfw5uZY$ue?9EjU(5EUN`rl9~l7LDss>N2bm8#oAOcjAE}BdhP9VYGKLT zvhS5#VIq~KD7^^1xaH|QaV2ANU0Pkov{H0QElRE(NTtt9G+WrMS4Cx;Wz9VQ{L>sB z+(dFmt<`K#n(%yH@VLyltPiq#^DdAJt*Kq{YpTgJ`?WeR*|#ZcQzu6JHeaYMz4i$3WGhK9U&1%-IVvNcR1x_at%+K**~5`!fVho~;6VZ;c{GfhN?5id zo?#!|7sp$VzujOYv8;$X&|F%DgCphIex^>gnC2x_msEAlEETfLijiRH4V_X>6jgFH z$E8T27t3^PU5mq=aU&xd#Gj ziX^&D$T<_bnIZ{Na<|a3CmUXKarYskiUxSCA|eu-dFz(&+21?h z(Jy3pW)9bG!TcGRe*o$w0*NXMCrJh!(KV5RWA4Rp0EW-qnN%IWKK?g;P4DoT7!pRRaupo7`>-!{#Uq?(?v!*>{i8=@JYiD~J?Z#MLusBvCbVr=4uY zG%9V4??5{PiU>%xra&6AU7Kwg$~nC}uAH@-RLf?{N|!sTB#so2LZ)wxuBtlqAWE$TFniROLZNbb7yjUL zTfBJfB1baeNH1{E_w-ts&5Zm_B9xRyeI0eQ3^$bMK8Rh%aT)&jZf#zXv~QCWE;Zm+ z)PbvkOD8@WAja+q&lYMVX&RBBZuhkv%gAGL!n9^a=U|&mBR#;-vW>Fe@LMe72?y9R zoKM&<4*+az)n>f*!-5X$ewIj-YDYCz_RKtn=!9oqk}J{NO}1yqeOq*wVEdhC+1ZEf zLzpHwbqHs^@D$xsFEN`;DJ8QgP|L!z=ZZ;YS!o#4lT*$=yu;qCa{8WaWK=a(n3{Zx zCKj^IL<$oz)jDQ~0B=i+(DTuG98UZ4WOg`~vJOSCNw{S@;%&AX0ZmN_) zGZw(AO&Z2Z$lGexstkM)W@k3xgCCyqu1EHmO3zN0>8m2igMO)a<2-Clped}{v1#%i z2}&^TI5T<+U(rifwVtWkVbApt^z8NBn0Q2~x zW^&*B_GCknZpLQ(u^8(P^7?{1yk-l&G{@WCsg_|w7>708ua$iy&<@m`fkI~g<`JL% zg@3|tfA;sGdyXzI&{`aDSoVqtoVci*yj$qA^3c1^@Zk^N$JXQoNir&xWm>Y71*vvS zy=!rR)Ip;Li#U24tMvp5_41JH-?sBpj{uu~&i=uY-~5+PbNTuqQ%!7DSSq}H8TM}~ zXYQ_?J`W%J$US`EkxOJZW11>OOqtL;+&H= z->Yg8kVFcsep&IW-}}8g<;|P-4BtHGdkl0?i@QpU+UN8B1pptPm%s{iH158ZR{Z1}3A?syk8i@9O4+B`n{<2jnP<6l z?L`WS#WFK2q8>!z{>__w|GVF{D3gu%*koE|;)FGo35rlpj`)B7*Vp;>Yl4m^PA8&_ z6;4T{VZksKzVelG{LR1p0uyTrXG~HVOXmJjVI0@oy?esn|NBS0_h6r2`uD!X*FL*q z$;iYZs);OX5@Q43#C2gf{~`;7p%XtL&oP~8?q26a(eBMCQVN;T9Q2eJF)*<LipWIO6H1w&WEN?`?b{P?y>-lT1s5(=4i5IXe(egf6mG3g`PLua=H6|K###(Q z9fUI!in6E`sRkU9Ei$VnMN_3FWh{kKAu(|8-ZR`f`s%SH zPUi-;+MPx-4tRzWE|$%a91tY{@Oe(P=?QH+v7p)@6!BD6c5T=Glv{77&5())U4;&y zM)@QG9-@$JQD;8ffx)EQSLI}-d@zjs?y{0DFFB~0&)=#18~^@S`PnbO#9kR#uM5BS z>;H^D_~)i+L@CA- zOy2u<8^eQU|EY zB({KdrfZIlZnG?jYX_HD4hgBL(FVj~QSwDTC`{#uv(u3WrSjnPl%#784^|*+q$XsV zSRbFTMkowkKrnozYKuapGEO6s6Yt&_`QY7=r(ald>BWQ;ILAJzCPqedsNB9Y^7`v1 z><#eJi~F!V#~ohe+tV-c+Un<++Q$A0bE_rmNQ~#vY7*hzY&ah9K zjt(%hR|?_J(Dv=EqLx12ZEwsg?GifcCuL({&1?@pQEyko!d(q22s=;9Y)CruW(SY0 zh%K^Wi>h^U0=}S)NJ7p&FFdWG7Hxd)K1^nhd;)aJ4kX>RUHe3|#{p0JG5gL(w9kIH zxK}Yp3_Yf4fK{Mk6C3V--UnjJs565D2!h342jjtPjT^cS6NHp=Z;?Bb6(|VnlcHJ6Xe2J)3!96UfR4Kj4O_p_1n&m0NO8Eny- z%!NLFGyt+c&*M_<7RVXzMUubE$v6;40Qb?^ljI6?MZGS$Y*K_MLE23g{NM9 zm7|==`vZ%;fkI`O68icN;LRVvE$^uJ-x1yv>+nX=_23!2S41 zf~*r$T|=6vx}dV8sHM(TsSerBi-P!2h^L)SC{tC=biu@uR2H0#OK!_0?#Lxh>%gd3 z3VZ=-W*VVP6G$af83f9DVtqWZpANb8gA@Mw@4UtGT;lTcOU^wt@Y1>GIlnsO!O;=_ z@LR8O|3+aU**Lj}WPH?9VZnqIXw0N+fUhQH%9SDoC0lfBRo3IDnZ{qB^7EXQB_oAe zy+9#&G)yI_0R<|#shvkvhNl@yMDsX+$*g5m1E8dHE+qn;8kLWBYj1t(VO*ul(|0vv z->FAtrP^CpSh7T~CY!1jRU`omf*tt_>Q4)hBp8G2=^TN*p5A5gi zd+)#>6c4H}qKTXbrjn=?j*D`fDrYjWURTZpR7^(Jx`)c5Em}+{)M^V-$x^-*7*!}q zP+5Xjr~ZH_>W2zN?eB=vFW&W9V3K%kv-vMn0~x(gkt79~NGY+d#jcwLO=g#xB$T;g ze5qs#xlWMZVUd2oA_-D6s#a~?vJeU?wPj2+c_$_SRfSVsa$hd;AYJ7Cl=<-VHrJ+` zTv}9CIZ>+lNXS4@50??IRUk`_Imc}lyj%9UGgSu8I5#dWvk(JW&-9F=lgd;wN^o&c zs1)h$>?$eceTxJ8;7|t zR#-8yS8<9M%l5FvIvWdL^k{Ck(icqB-bnw&gaA(dBHoE}osJthZFlPZH|iVhT()OTLw!T1cLDj!^Vj`wb?Il1(| zlex`mA~ZV6&vEj`9(<_C*-dVL`x^gr?+Rzj6S5`_ zr)L;ne+s$z9H-Zu&z|sIC z2S08$JZ5Dd#04F)9-%*tJ|Q%BZzgPmq&@J-);9Iydq5Rtqa=eCM2^DTc+5F=ZPz{t zt$)7^APtfc+mcxi3+|rVU^3#9y zBCqd#jo+@{;G@MejF$@6e(?rh|G{})(rX-l_;=9ZE}{<+NvxBwNSR1^v+BLZ17kp# zIduV|wy|(7x}+0H*A^-2a!zE{sDe4IZ+!cNfBGB8jJ0xjuJYWAiD5{bo>cai!n4;a znn#9}aQ@O2@}3pID?YyBks!t=CRCZIsw4&nPDd(`q zjPAJBb%mO!6O^fXv{YhMGvl3)IC=dBtLYNu)@5#Jk_cPB4D!eJifz4rQr@%IKhmarCX_JTkmQMp&0RbHk!&uAGS# ze6q5S$?Fv*2Z(i^m9Y+&>>15q{FddSGOGHQo}%Z~-PZIJd6-^QP13p$Yoiki=*^hm8H4RggAf(046^MGByD%EdMvp`O5k+Jn* zpaH*6a@&EVyS8he_|_Xe!OiJHzJ)D_ucQhhUW}ttA2XyR2n&=Y$^^PH=cZQBeRR5l zQVbV!vh&11)d7_~#t$ws-dsUSJp9Z{eE;^uFnou~O@;-e?3EEyW*8QvWU1#`&AAJj z0P)m~oaWWtS}UcN*;SGRIe6IomsWBfxVt{#-dmOW?Q5LMvmnaJv|u$A$eHQA%S^W( z@|&;!Gk$A$3q6HffBTDE`io!XZazh250wF}YpSlDD{gjPBIR#lNzDfi?%K9eO-YrS zxxwf8cK#CYE?+fAZSvL0Ds2@oWg+d|Cx7Z9=gWBxA0Be^oo{n`Phhx==I`;*ul_C{ z{rW>F6P#R!2QR?sd6<-Y-#y{p2X|m8paYz);NH`4{0itjko)Fs^CG+r@aF_R1$b+_FjMQ67zfLGW|weM$B%+PHYS33Jd+2q0M4U67jr`z80Ah+iK z_P(_HwVzX3*io}`Wb63;+B?T|*Pf)-&-ZwL0vruK&P+}V^4>nv!2!p63my!G^+bo zy1Lc);qoBl!Q@Bdd~?S@k}!C+c5sZVg^L<{TzYZEt3Ur7k`uRYJ!ExW_=&GxBQ0Ur&%FHkPqDY!XVgj&)3f`4gdfk07*naR3r|W)+cc59^Ajdhwpvl9@ilpzl88SQj&3*>XIQ@RIn9h zQjn$VI$PD$Dz@+xj$#%f|1hb6lR;fz=ke$rNyddICWFN*yEk9ar>aVAX|k3+*esj| zKAJw38CmtnPpjbU4(MY<_*|p|km8PNZO4nubEqxgcGpK7pwMKCsZ#8IB05RCVl;|J zT7}-zc0O_5RE=YsYSadr>K~Upv1_~bL$}^m+I}g*9x|J14yp*ssf_A?vOw!#5%U9< zfFxqsN4*UuYJh)L&_dEeR;4geQ{}EKIL?V-Igk&9<3sq1fAzDx{BxgWuUG(vB;mcc zC-e>B?3>@_o&WRiQPaB|;blYaeA4>6__p;ZXXV_NuTVw!WC^^X9t_ymY()@|Q}27X%6DgWGD5iy;j74TvoQQf{(D0Dzt%`R!c zZH$8?v)y=*{CeIVzb|C4l?b;{4$;R)9Xheh0(}b%!z$CgvSo)sUW|ou$9H4q= zOI3|}x==Y{&23-}&aYXBbc0Iblv+n96-uR?T;hYpPxJ1%i#*ha% zhV^CO=g@Qy%EW`|uk!ngf0u6^JfzBC#g*zA!g`~!?(6`8vZTtw#=sqG@#V(~9LW{# zrRz4<2{fe{SQIlLD^O&h>>cvq;RP;^D@tAf4@g?5M+2OF7E)o5J!D!^#-&B1%3%Gu zeE{hISee7Seh6}gq!GcYHcuV+i7X5(*E1FrPaRE`9+I$CcAp>BQ$TAR%e>n9=p5|1 zKASt~`_9J`TapK*Wq0{7B&rnEv7zJH-`_dr?b5*Gh9 zDgTTYf`GcJqy@j?DA>YY!+ z?Pqv!e#slhUqP#N=C3kQ&uhBfieZWYW$=V zMIq|}i{X%ha5Tb0E^*2MsHLbE&v#W%XSWRTYFc|xsvII`FT?3mNLe9^!JOKM1^6_` ziylR}gmM9qeXpjQfq`5>OQN!BynYM?O>6fL_n=t86u=@~uyLybS%(R=MxOwJ)j=2AzUN|o$`z{sG#5g6UVrklMui)fb z;qQ@X_6bFZ=MQ=G_UMi!{9`QGBQyf5b&a$?fVRI|&+O39<&^B$uda$NQ~u7{lIMY8Ns z@*Y#E&Up#wk~9`LxkOqYP{(sHDaZt}b~rs-igzrEQDDsQ;8~+%7zRv9C#V^f#JDUl zcwwgjT+9zn#A-KUcDaA%U7C@qRpt;)&Vi+18Vj&C@r>VR)EA*cn!V%yAjO5Zt~CRd zq$A6xuX6sS=g^`Yyn3CRtE;@Zc!v8jLK3EBHKhj(lE^7-Dj}j$Z9&AU8#gYP9I5s0 zPgJi)8Fwy9EtPUysYkb2r{_qVqUAQoVRL$^qZw*?4)kYCDU~(r@h|ai`f2_s-zTcc zrnF{|(u~D``({qpfudfd3FixPP_6Pu;-}XOGNO!&Nk+riQcW zRWPiGNMUOCGx)uAd}$l=Z@Wb`MJs=$ZJ$2+bNd{r+a8mm-*-FRzQ1nmwkey%pJD}h ziRc1l0Zh!bgtsl9&HLE3U3)Ux$GofA=rVFT;Oez!*}r%hdFmPu1x~46lw$xfQ0GL1 zV~HH*1ZhC7Tx9PnU*O`kYt?v~lj$6nLJU<%)hf2{AD=^x6YIMdxqssV zluxrx*LY|74Niv()M`$U2;5mJxA!Zg6;i+8T$w_pq6_tidUGUF!?|2)%Sc4i_scx- z=4aQ6R>@u3;#gI4JcI#c!SZu2^74Q5S2(D3FIEiu zg6t_We8`$3##E_fM3&BLHhBbyFXE_yb8D?kwX%|dr7Tc{(fgcOnqOAc3y@e}qYATB z<3=Sb$^d7F$avm-Qh>SyEId<51Ia4)f*69c$3&4ik955Ay z0jmrhAf%e}nlvFbA|!3pg-8gAXXMp*)j;kV;AEl$tz8FKC93_-2*1qYKK_n~Riyce ztvYuLCh~W~QyR%}T3_Idv`3FzvPe+lB;0UfdwXWv+3p?ZNZX9#wp5!8J$Ra#3ycysk`E03xEHThjRuXLox6yTU5CPnp%-MNg;pj z-7F{%lki}n4jlPARWtHJVt*+dF0b+_zRtms7|jbN#Y@fzg{*}ll{yS8uD(b){}Sc! zfbn2r8cbdd%LhDs9=^qSrooDms#en;GTZneXO^0I`f$bSD_`c~wKJ|=`336j2S!&` zY_aX;2WK4JOg!`Sf`hA-31yK%bPweP&Q^(gKYNECT)1wc*Mli$vr`b+L)f>>JO}*> zlMO4$xJcEq@IsCe0JbJ8#Le_H@8s(s3xrISY~(spnV3*b2rE<; zOrmH}vRb}JtxJm2o#1sJ$Ro%_v>br$x!f-HJ(;W-#)*kyvNTm-fN}sjSkOy#ovc=z z(87Qxqzt5D#g}Tv?Gm@rMSYE`2M%L#YNQF!YUfYRw>e{i+M+HI7va7Twdu`-f^a>s z9W5$!Af?XV&99E@r2v+@^KH009dOw|Xn$|;YlP1lI-^mPNe9Z#QKTB@CWUJ6K!C2l ziAL-4r298JkaX8}?GxX6khD`Eo+@Lmlt&5@5g#7j-$nN&$*AWq2oo0T<0)(5HE<4q z$_ZYVwyA59lE3gNhQIL*$V*P1T`(Rj7*R^WiffEkotK0cBJgxgcc?_1vsA(uaAzi* zA$M|6CFNwRi{8hHLdkG)20HD*v`;A+>Ynv7B0j(sl+39iWklDO`l3uERWg+ zVo6&W#jZWp$zi>L7N@BJjKW;B$SPg-%(Tq|Yqqg*8I5*_Y^Jft)Ae&91h78G?e<3Z zhF98sRzFwl*QaFlo!K_tKhA)UbBCKO-O<~9*p9k!UN|{K^bF((7~QytXA{6`54Jwp zM#QdtlA15{1V>~`RnDO2S)^yV{>s;pFFwcntHOhYG9~p0pbR-P31+7dW{CoULK6ay$qNGNc7r)-5hyW8uoLqwV=9gAAl>BQ^QgDa9R) zObFyeR*T{+MW`vksHi)qB?$~_h5MF;l)a!88BK#nbB%yfq`1hd%{fz1rU8qt?4!iQ zqJqtN%Poqk0Vd(N0fsaN+GyLgiD`=fOYX2)1Wfl_L_jlM;i==n#?P$gz=yN!mv8JU z%?2{iB_&0xkQ@w2L7$Vu4w4|}hAb8>=BbSV_KK%|TINggb1|pNGcPzRoBV;10*XhD z3N+`}c-BEgNy%V<WkU5Kr&EP# z$$G7SY*FaBE(r2U$x+&e#V z;V)&F4%jb0!Lo|;n_4i+ga7XX9{$FX%Rl=J=f0kJI4BqQ*Cf`|DxBs--MhrJI>idQ z$!xiXxMZ|NzSa*b1Q;4BlI8+f^J@|Ik=IZNKs4-w zHeDjT#q?S8Q)AIERZEvowF5)xeh0`ZwCeS}&(u}|Qwv&|kM$1{`*zpZe$8|3z}c=7 z0#=Nx@T9|tPxjsI+OF-|57A`f_bg8%deHb7wWXMe3F#VXbz+4dBsV1!rc#9#z+fyn zdsrmS8Nu~pK9v2X~B7Unkzr~0>vGl+8ifOIZxR$BaDC4l&-Dn62NFE zt#DTSU($@+E37}dOP!QjE0Y%LdP3hhgSQLZIRIJE2!u2uLNO(jJyy`c2;$sH+IICXaftXHg|PUzscOwt5E<=|nX^IIB`7g>|xisrYjXMo^Cq za;sz3gYjMS7THv|+xu;AkDAmze=?E%1k+%+E8hyHgMu(S!yz8qiZyaBEd&p1RI+sTp(uhkLL( z57PsXl{woUfdqKeUqrB~rE^R5=s$DxMd$kz=k$_fE?`oNY8MUY%FhEXkMTl6A@gTx zYk;Zgg!OXd`^)25l6ilG1v*|}nlfoMBEy=J5;@r-q-bioZjP51FD7N( zdE#L;9ikDf6BTnSKn@r#v^v^waMXzzkW&0B;dHL}#a8_jI9ceiFZ%5b!T4>#^bTGZfX%Cp~B z6DiU~^~EhG5*DnHWTeI-T;qH6`U0XnT%2&c9QjZpf!i0hT*l?k3d7lo_g_vNKb5$< znmD(3$iPFCj9M6li&ODy)37kRWZkgDp%Y&+`(U(lbo)u27dzd*Q>ytQ-q)liwzUK; zfq-VC++rZAu%V^H}yeNqlgvs}a559Tz&F;{wI+ zK{PbD{U5eMjp)uE$aS3%$G5!xJ^{`Sradsk?VWxi^oqLwv)6g;WPV)Shi^~fqM-7m zw;f2jYrFP|Z@p0TNJ|`KlT1_}mjFsNn>Qt?ZL?HL|2ra1B|BKxM-3WRj9qm$MzRW& zO#Q>}qu+W1YUbQ8f1OJ|eVsd(_t2%MiX@p8hle4VBkjPKrwxYQ3ni;co`%_9NJvZrg)OzxrMH-qFJz0rK`2b5rDY$~Z@v%zZ}t(9*SCjQ%4h14e2xao8a7+p5of)mq;3!1~}x5R41}7nB1>Y zwP?((k?Q2xMoz$MWJN`j+OB=#TL@5-fR<7$pk5%NrPO=WXcsXG zUWHHsJhlCV>|8Z7sAX$&Lw6o=9qC+YDx@=^xN=xMsGMKBgIwmrX6qyrM0Mx8a~MKL zxz)0fY9_YOc7Ab=@tMyu9VBFJ`<1)LJUq+PyQ8Nm+y%8&P%HE_P!pX0^mWcZdxe}U z!>Tf!opJdmo@PvyL9Fyr3P3>pR0^7A_s5j20|g3*6$ha=6q?h`Z2XDXcqfH>58(G- zLtncO4+at!sT^QnbnlSE3<>^8b79js*@ScZ&+&J3P#$~yqe}TtzGj@$W66B>q}c#@ z00UB$+(Zy)bM#(oJ{qU<3YAo7r^r>GV-ueW_)Prf0sYoC79Q=XET?~=UWmFvNX$PIcMi+Xh$7YFAo z)1mrvOP;oBa&3PEdF><4K6;1@1H4z^=o;zt3JVU9Y(QNBq*RhtQi2kh58Gl+*-9Gd zb(aqi+8sB`&*rNUi=Dc$Yp8zkdyBx}WY=ijhzAgBXR7w>H&jPFBsU6LH+;-gXgsSM z^F=oAAtj?TaMUHD#lR!qJd)Y~cRwy7w<2=YImtIBkAt(?M>{np7fXw6ix82LytR%P z+>g3FVRvoUe&iPOU$?%qA18)D$n0IXN?I*QtHh=2&#=1uD#tHf=8v8d{^$}sSO%YD zYID6w`s)9#3AFg<)?RY42)(3I-%p8amT{MnENIU z^vMQT+x4aiEk8W@@|c6SXX%t%%QJ+;sVJ4gfS?S{{|Q;FfS`qGY{r7h*6;1_AKkX~ zR}6u4Y5ZIJ*;upj*k^xW4w^9VSS;c`{Fe~e4bb!XlOQ7SC8AX|QCk#g$l0zdeN?YR z|AoP6a!#vLF_g-n!c^3X6GjG#sAr;di&=diky(Cv=EX*fg)Zs(*gx|C6H}k2&V1h~ zoWU3d?Eq|ldm{62!>8zkIe5SPy@_;@jj7ksU-WZ0&e86-e~;DmRE%|BB$qjZC;9Qw zhbO%4K+;{?wNHH8_Hq)Qch^AA`NxfYjR@0-Hr?LO(nQ>pAX2{PO5qS`XbGiIDTo*N z$WVj$7b}mOmKyHN=W3QL~HxPS`SQ>5ORzxtmz`OX0MUxKtEr6sj4+NfJZmsimE z*ykU=x938?bxu{>hEaP%`SAc{>h|3}vv$9G&pPfPKBuki{qYSc=?3p{eXzn<0lq$J zT0XALcP%VQ9Fo%+MOVN>Ho3WaCt~N6?%I>qY<_F+#E_Uu;?{fj$+z$D?1if=o?UUK z3(n*`HBVMqN4$!#Ky^S%6|2rI1^{YG4J@oJy2oW=6;F@u^i<JZaiGmrp^$;PUzJMqa^f^JESK z4~FPOd4OuOwWy9=8bE0EdTe_QKsBZLJtss!7m?Q@Kj*$`+Xt!&TD{{N(Wn711+dg_ zk1PQ^+TSw1+G>r=*NIniW5_(!I+7v^%8ARcNoR_)DvC<&_?jQJDYvcQe>uo1I@;UM zKWyv9rUywk!hr(}_l3$KK^j0HRb@~t5W)-DHo#6C7LH7mY<^RdrC2e)Tm&Y8GLW)g zLS{^qRJ@zciP8t5r0#i(nw^le(_5~0E6oqvUI`Uf@{%lQ$5PRC-Y>L8w(E$36xVrM zk0I=XT9fOh@P*T*Ih<3b>wbJaDd3tYKCh@bKvv2)X_o0JQ0N0~!-ERky?%J;H z+LPbHfr2^Gu8$racmyDgZQAV@(WDNLMtc4xv=)Vj#EpeHNnzHhZUDJrN~)xyR>{7? zIynH^9K%@2G_E^a)pg|-O1kM0Q_>|>?(CiMa1Yk$j5TM}Va0UeCTIDZP%`R8rW9J? zpi(NxG4Ecv&)paAaDIQ};4o9jOaiBPYNQBOHPX8gI;eVFWS6F427p-AUiGM;SYeDu z6X5B*%n6#vQ>NTJfSZ>Qx#+8ZKpon_H40>Pj`?f@>DKS<&zmzu9@)D6?KU_Wf7izx z-G7#?@9exYSwkcM_0h@wb>acXJY{P;eioaTaqexSv%jP5Zz@V+iBJ&T12U@H*YD>! zkDO`OcJ0qkd;A-}`L5cWR|Odpxh~l|&7iPM!Z-<4vl-VJP;GStG`SJ(sdL6-W=?}P z@3KSO#2m;C$J(WXRp$jwmD>j+X95@B-=n_w99(!nUau%57#5@fYAqxQp6dXl{F)lT zsNY_7(9Qijqe1C1GJSlanz}TwG&J7~5JpiaJd2>mzv6PXy&}~kDO2b4M4ElXi-r>h zqp|=1AOJ~3K~!3B<*7X{rzqkPCbib)sCjQ&FO$O4$HLK#=imp2Xqq^8{TcGUpp9<;{qbFje&aD;3Nx)x%&{1+024Ya z!8}_u768Pal`YZ+2r8TB6TdHy@KJ(NqU&pdjfu8vKj!U+0jYZ1<6mzJ$&ylHstRe3 zd+9P0*O5ALZ8=b{CBAo28TTzO%W$UP=Iq`>Hldql+lzS?6+xzb|UM`NX?uZMR(_8zG4Y#MXcPvgc2`?Lg99+qGR|Q$Y3rX&<5IpQA{@ z256e*-&mS{6zK>zApln)HNjKESi&MaYmM}S(D?3{iA9^D!cfK2*L&eT`wla1WtK`P zZ$v%YO{h{?=aErCm=LW-k+WQJ{c|sH_2H6pdJY+tu}-X|pk$7Y;iLUbxpY!SjWv!!u60$Jc zt{q@SKdg8~oMSeQ<_OKl&4;-?YP$De<@PbMwS9QZKK;Ir_90?@EY;rAMDfbn8`p^I z=SR-b_hCNAeB8E)^Jov_O3BZ$0#=9&z9|6Uys`g}lM}ORyY{0u+4}u)O@R?*VpQc= zVHzuIAT9h|NSJfuj;6L0X+K^92_Pp^3vlkx3f&3J)nPF-$sO+SIt|pFBNJ=q>upe$MF^s!QnT}~ z&7rnBAP%6)maJ1dM`A&$x$~#Ad8v(Rj5J4Eb*C|&I6Ge~F@d)J(}2^2deOxyi9v;z zUO3O{3j#|eUq8pqV$Veh2NBn&RslK%Na#+M;67t$^xz)o(YlbgeZ}2=iV1USc{{Y1 zt)Bia^SI6sO`sFv`?Ue=99chiONI1(o1GGNhmU8|!7)FCMm#7z46e*;x1DAZ^>lrm z&l8A4{L=12k~Z&bu^{?0JLsEfs4>Q!u5plMBO68N#$eZeyjl-4{irs>pY=1<_IrM{ zliRs~BradLK-s&(`%wRIQ6L7xl+5% za$X7LHGlRoXqrl5;m;SmI^Rj7m(_w?8Z`+@L0II(u-c<61@;m}66q0Mzi#Q@3x83y@w&bRd{zmlX)}Z$syAfgBS}(6@Ho!c?Y`kYRG-p1{MU-MZY@5U! zZBeiRWzShMHRk$8cl{al&vT>IM#lqm0U@yfD)aa~!EFbU?%J+>;+qTRMFkt*7pH}Mte zh)^=hve{};PeW8yCb4R;OI4PbQ@Xf%ji3K7{!@PGM&{~h(Vb&~F@sj+cYpgnzjEho z?!J1R!}I4^=qbV}$(>0Xi9{8p>dX-y#OG!NNEay@Q8Tpkpm3}Nb@~DA!g4GvRR)jf z$&qqesnZ&*%QhaS{(E9_PTvn-ftN zYc!oQ%EZ|^F;*e(59A6Zq6T5p%L|7goY{!Jn8N_OeJz5hMpaiL&D#s=rN!((6ga$; zdF2;B!*}W-H~#LgpbuVy=Pok*=l?O~E1yGCM2d7B>Qb1iS}LX186eY$RD2{mZRVD4 zevwDZZ1^zn7&#oL@WM=*P+g!c62->Xj*lz}>xWUdgzg9_r;R61Bi-I3UQ|7OTx~H< zNmLc4h478Pb(KrsxXd`fZ@!iIf8Hx(@q#3SST;nZJ*%o7H5))_@X>Y8CQ|?B@ulf% z`<%M53UI@9T8lR7Q`CXZIkx%X%CSAlPX3A*@R%YM*1zi`U?TO=pOYZA7VOVjQnhE% z)QWDZs-8Nb@0R+!?9<}gSj4?_uTcP`ts`+ln-}vm?Z+52Qtt&#$pI zITL;h#PK*#ofzi%_i-#!$N2N zNYkOu(u&y^a@fWo#z}j_k>vtF+F7tV2dD;g&NViY?PIDwF-F=1} z?)6#!Kq4bx!-kTrKj(MbKxf+DEpoN9nY26o{8+VJzfp_z5wAU3zhT=wa@XFEuovQ* zw$Qy%MeGS}JCJnOcI^}2ww>V-lYR@|9ttCX&;jEt?f6C8cKc45m^mb8?ifq+8(6bM z$P`a$PzGim9zcb&5gy#TPkpdradAbJil#(K+4$51v_>j|AUUHcQK@7KNcA=D-k6*X zATy?lrQ4{5UDPGK|H=h^|LMfx2vlK`!k8-u$C;a_OSpMPek#Lo%vcj5%h};oyJGE( zv|23^vWfwfD#=qAtRM&2ih9vPQ7cen+&p=9=vvxgYK5(gyKO)gPa(^zR@uJ#v(W`m zKt}J^mIwFPIZz(+y>DyEd;6Gp{(U5IwElYY^MBO1*FR?aW6j);xrYs}aO=DNJexpp z7!fo1!)%ampTpdP!J@)MP%`Kq{k&?9^sc)7uKl@g+j=2>g7QL`tFb1M9Fx*ptcGi_ z_Z&ybT%BQQ??9<|)TS+4r93;=svbF6)5dkIxoi+DJ-LBK;keEmZ}z$=Md9`V;}IvfCRS;mvx?KiRIgYaGP>A(L>hl{7^BCoSDQ#Tpj=y2 zrGN}b%FX$2(JC?@OepYb6b-&E=Q|QNg+j zl*UizkyOk)tab_KO?05b^uBsJV(qdn1L$z)HBvssvO**xtRuy-0jv>0N8?O&x;PtV z2aO{Am$Wgn=DEFVKW0sMGy|ofN*{Af50w5{f~52HOe)R&4j51t=h%Ps)0{kikq^GO z;NIuqM3p-U14$Q9lW@8`fEJfV1HIkK1!wVqZId%iglX z?M^g;F?4=!LI!Eu3B>w@)TU=_0WEA+Pf4!QMQ^(t5XI^Tg!vt*<@h)%H7S!;GSzHK zu>h3RIwakg_jYYO3$sk2*A+i}Gff-p%=0&~I3=NL)l&U~Ec*#cb=tOhbJJrnH@kW9$l_M>8CnN`>Y_gu1p2;2 zKoCSW!yIwzr%_wL3QFyfO?NtVh_L8bDY z)yNMPnOqlWO-ypcIz8n2(Pf_hsdGG6pX1$U?{ZQfAhG~i(To<)xoI4v*h+Uzi6WU= zGc|dFk~&a|rTPcITH`DA73iqI8C*S4(KipakFNL7@dB`Lw2a z^YJV4;t^B{l?AYeSz!glKxuIU{?E>N*|lB!(`fy>(}zwfGlwIX9EPg*kosK?moKn? z?m13Z2_2Mafb1M{5x0^Ak~<0}-h`sVoUZK-qC_N%s}c+T2+l>JRjpP3EVj^7GJLeE zJj^2(*K4?c0JknN>>cp@!+|qNJWLaF)Q8NsDmdY2L~@9Or0O84P*Wi_N2XAz#*0dI zN8ck(=UcIR2r=5mbk<5H4mZ>AH{6~InuO%hoZ)C!kygkAmpzu*fKvp3)>zaT?8iJ@ zgp3N@IE42Pw9&n--+V~T6H7T@;VxCxN-e=38v3quYe4~AhJy?<80kQ=RJ(wvJx6if z-TcGO5%fq|I(h=TO`A(j!Nv?E_~+C<9y*q9FP&%au z{_OFt^F8&xpr@n@iCT@@N=-tkXD;hWR8OYrK%Q%gs2tWOHTPx)xP&(>;0j)FTaaT z=@j?gIib?;B^A}=3u`o|QBYEy)BTg{z~*39;~lM`Q`GcItH>>{#D^L%5q(y9w@EI|4A1vO5xd0{#^QBewo;O10Oa?Tdr z6aX+DXVwO+8pXhd%$5y+LI#U?ib$R6K#$EccPt&itkiZ~Q+FHBboPy{=#x|LBq2*g zso6bS6sYN~h&)vzSf?gWISpUA4?>bT`Ivc%w7WBZJOK91s8dN86Gdj%e(c(|of7tP z4_L*1@aW|GID741b?a>^_X*P6ca?|{c5r}7PDM_DiP`JC-cbs zN-`eis#LYe+3Fy1l0?-?ii`vwvyk5rA5cRN z^gPXkT-@BA2a6_E1hP=m4EzSYmK_`uOS{)DbeR&>7^BX`=Ihn{p%LvZeb+W!mj3TQ zu5E00rGye-=$hf_G#wX<9(C)AvjO(#kUXhv z2a@jEuI(DL@e`JONd9e*G@QSLMUoD%W%@J)i?GRA8WMF6IPd2@1CB5eUqMEKx8<4t zpS^d9wJk}`^S;Pj`<#33qu#G>cC*RuW{aXE%CZbYrU^l|Akl&i1BN}LG_VDDWY0YF z$bex3o*No^VnBec0Rh7n49I|O_$7iQM2Qd|pqlI^`&C`l)m8U-_Ffs`K}2Nc+GpQ- zu-Vnsw|1gV-M#l(D_5?}Tp1C6{t@x~9lrR*ukeR=F8SI&f0y>^W8}-9h27%9td5ns z8`CDi$P6QwR8_{mvs4n)U8qBlNGJp#;m+6)78bq7bv3?q_dPC6ft5uIt-7lM8oS(G z(zuZqv9&{qFlU!!ET70M=muhOH~aubO$v>ISn0jjqW`NHRvN{Em1AL$>SY*?idkbY zfE&r!{gah^rn%o_du(g&zfV2+Cr6*3rb!%wjpM z2mkQ@TOS1-1m8N90Lf>c{-S)gnO^JOJ`?_#(dux)M1F% z!Ql#GP`8yk+d6*On5vTX`gau^s1Ivum#y&Q7*51J{wf?tmSHo6;G;TG{n~a z$RS$L*sCrW$&awu)GpF!5d>+|QUTGiiDV+1B}pXkuuT5v@TqUU#Iw#0?wLR+!&-D1 zkncLVjvb>%NA=_}$(|fX6F^Ots!XS*emY0v?_+`6G2{D3ofF6B54jAnkwY@-2T+<1 zq$YzEFGPIm9E7MpJPOiNLXwDF1Z_I+GHv>&e-5|z4zh|x@<;Q{pIX90!DWzXqm+tP zakg==Vz=*^Or4vHX^v35lV$FkymlMfpv&jpoe5D+3;BmCQ~l8<3ms@%kGHei8U3}) zwPVzlI+XU^>`8`10%RMPjOwy}$>*&%pF`l&u=92XNzdh6&V>yS)OG1(AZDz}SS&kB z@fHI}f&qx8C7i6hGM$(H3xWf8?;$+FsJ)tNq8QH%I;I#`aHyWxoxRAUjL&?vfMo6rWOD|FfKLMGDsVZ_MHPJ0?aIV&ae z{E(yTX9HneH)f^vV-j^pzemDj~c zrYfjL+-UK5(EuXp?oTJ3&ab)H_KiQa%6yn(H;zOMO$jDbSnv6$Zd6$qXT`xi4bKF% zj7KUx2Af#`kc2>j?hf1cNB5ps!>y?r_F?D+>GeSxn1qd1Cu6q^cg6zLsG|y~AXTV~ zb>Pqqa{ByGiKyZ|mYc^koX1_dAsMS~EtHH^C(iIK-Pp}EjxqtMgnag}5heSR0Zvj2 zGX~;wcQC#j^ry4YBmhu%e-B`xNCz}?tV_fiRcz#vifK)}F9c|9=^iS{nspcZo;a%t z8RDl`B@y0r26@jS=@V9t7m+gk4mb6-Fds{DULG9$*!}`aOqYfW%|FIs3O;`(5L~hNGy_Xe-Owsf6te@!5*uf|qoZCO9a_pDgJ7scvcT|M zuqqxiy1zD4C?NC8t(5Nl0?zUmTs|NSVrUN?z-Z5LU(C~qEmS&=r4T*UpHC~3ZPfe0 zj*iU(z$B|tIgrG+7u2^(@TPOvl;fTMpi<`|jasSb_91W){Q4eW?WVI(8O>sdLJm3OWh zZ{1okEi6x-=Z;qHi}~)O1j|D#7#Cho$sJ1utHSzo+7LeTd6QfMH*zY4O5woDD%W5Q zGmU`Q?iQGFUfh*o66~RQ*#eqN???dV^o>$ks;*%%=UT%``3Xg*iyu~APL z5Sj{i7^P)8HXKxfN!A%+vsE0*-r)4&p(708GF(Fa_~?)KQ(DiK>bZQ<%T3b{=<&Uh zfYDjl7V)u4W5v_=S#55lNXitYSfzx^w`T0CFkW?Dr%BhnjzW1I!NTwDOCxJi;tgRh z@U2_MTNfS!PY#tw<%;^?MLzreOWu59eD{`vy4~7~wK|!O$!PQ}yrl!VA9l;>bPwJ< z$JdnOb#J;}(vAy5JLH%H2cGOtV^dFq0qMWFT+v99vSD`$Zp5k~)i}Xs84-c1I?=PV)h%J~ZtFBP@7!8q~%K+3j`n$V;v&IY7 z=f4AYpQ)Z+KzBaMPB!SNAkKV!hAhCSfog z*h`mcnDm|;nypNKN4-9+dEIQ;+()Kq5-=*bMR z?FkmLLqmSos9C0Yo$FlRHOt?!A7Tv*?*RJ0!S?URLl;qtuqH&_39l%B^V`N|n#GuI z7@S9a9czD&NjjS^20b3csom2LRi?^%=())b*^Ee@eyoj5+C-l({!X}a7*tyM{+?A=G?)r3FNY5_04~i@Y|f9 zza--^ek(gDLVfOnJ70Mfd#~~M|M&w`R(QU_U;aG2c-t5564#}T7Cw*pEJLAmp)8ia z#4{UV{AM5cHN}*L#zn+PGj`61A`*8TDJ&u~i7R(=$W#yM`q+{=N*#)yNyLmRn8q$? z^lzbt%As7@!tw_Xc<?GU6_iIpqKVAOJ~3K~&Mv zE|WCclk+pfUN_(9*}yzL9+F^t)W%AbX7e12ET1uLon$CNg3AT7>VRmeG^$^3LJK*g zn({FX)`FDCX`FIK1zPiCtHHj&zIyvqkfxY6XI({ttWJ%bf!8S>YtJ5>jL3t}sZxMi zXvG;~*(=?(69?NZmt+}zH4N(&I>0V|ubzEAyI5oHeqWbx+Sk>JKMI zI1KDy=%VpU;P8xD=%_5+ylJ>rEuqO{v7<( zpJaVWD0ku=FX{yKWRprmthrlvzJ`_z>k&bI0K^vhvuoUQZ%Bm7@a<|3XXVF_!6fL^ zfmmKL!JDY~JF2<)N5{oZjoPWT-bYf$g#|{;nF+AMrZx0^#`V-8$-8BJPdV=?WwbMw za@%&%3|QuG8_UB&3A;k-w&F*)SJn?pxE*ylCytL!c90#(mP)$KN#Ci}9zSRB4~L=EGu@^^hK=3g=mkSDX)I>!Ojx<#x?II3;vSO& z#v1NFVNg#Bh3~RU4_4qTC? zc>25ftbX@YiAOZPxm7mL<)j65mllgQUf|5?*01twu7Eo@L;9N2#>}yH0?)dVaV|fO zrCS!$-vCUzlbHoD1*rvD3S}3rkkaT(kE~0YyHAb<7c@a2wuYhrD4P`BCDxiw z4=fCSOqu1fSjjkhC0J7)ceHUqvl@vtq_anjh|gy_7&97w z5&xy2*c$S_6;IN1SlBgXr-JH%)efGBrGwMc8W#Yc^sMd)0$LcBI7li67sX?E??AgN zCEY+xck%%YPIF;{*QBAG`b8V<=_kd7CFjc)@agksX8w0WIoly)40}6-p4_ju(Yov( zMs&=_{Oc8Huu++Sl6;q}_opA9!W&G+{uT_?@x6oB`FG)c$#NDqpQtkHEcrd>;&w&Y zqAoKi@^Q5jQj5~qjF+C1z`bjD?}CT_%bQ>;l-pnxslw-80{J=NyH}NqTfzb3n#Q3< z7%GjJ(BgV`XYq^cYuGP_Ba*9@mY!DJ+!jg`9Vm8l6@zH^~_XA-@P zL+zh&`^9Y2^T+G=d>0FOki^H7MWbsc9;s}5JH=xz1@kN!cbjDN4aVUIm8qT429Zgp zpEjpFxmNy;%Z@U7U1F`Y+~|ZOIc^b-s=;MpSqtoi!y0`mxfaV<=Q8d~%Fe#dF?CF? z(*woMkUrjoSPN5zW9U&Z~7`)4y~*=Lf0Z$ILY*l=Y}H+mbo z*QSrUelY!Oa7N5+I#pk{ZLOY{VutM%eLTj4$kLhp4b$;jt=Q?YR4wKhMRZ zg~#`v@OZa_YlGt8WHomIRMtqk2DkfB<6xE!Da_*zpLFg)HH z1u3x;t_rfS|Lw1H{XhK<+`mK*Z=$?I`NB)o|KM+7ufBw}V0i{NDOpM-1ad=1%rO;Y z6_&M9-h9CRYsSO>XNUdYPoV9wCk-Cm#R1X`flx79!k%+i%N(CgteM{5vylBL$B$J* zd!OrPr8!Q>58 z_wn0XIHNR_yxzWz2Ew_V%O|tU?{&Tt8m~e_ZAGk5OGWD9_P}bM<(-1n67eQ0RxLtV zrc1p*k2NV>`4-E#Z^Jekpj7Dw>;QlY-J2mnKMNx&+uK1g!%Cyw68QWVxXr8Bt(URG z0*^gDS`R5x8**9TYN014=m`pjtNYe)7lek0hc&STfblRN7J$}}kS^z3=Hy!D|4)-y zI#3Yz4cTPo4zFfH4Ohdam6e6YGMJ=*n7bBQfu^f_zyrFL*rRL|nkN>tg0_Hu(;lqB zsKSk3)#&TVAnit05h&r(-@(VMh%s&^s0!7DqHZ_4deD44catuWF-_Bu?aUa)9O%H| z80&uDG&swAjf}aJo4K2MW}|m%dw(DDx9J`tr)|Z~Zkk@H4S+fI4@_abr5mt0<^vQU zX518_sFaCFJw2bqxa@#s?t>F;J(nLr$%XECLv^NgarFBsJ?n>E=5~w?Y7q(Ie}HTJ!S4uHV574 z+0!W=z6%fI(i6c&D^ngi=BUiNt4;T?=%=o;%7>dDgCbJ8b)-Fs>=Hm-jc_1BQxE;& z=TuOa6{_yxrD|j2O|*NMIM62n`dvT~$}Z;jO30IZ4`QRM1E4Nf#`+)2TOKbG@tDW+ zY6W(NEG0}%oz_3|s4s=+UyoU>HQ@3bn+>yfwsEF)v>%_2*(6Ik2x-%2#`?V3w3~}e ze>1Z@@59k=`91F&|8|gBxG^1iSb&s4vb{x$t`g^F{O@d4b^YR5FK3YST+ZcFU&2`E z3fKWQuw{u1x_E3Mdja7!usfuSw{;+N{>ue)a)a#m3Rc4gyi?%dN)S61y9Fu%*f#2| zf_?E0O$^;#BA3mBga@NzXNrh&u!Fmy*)9x9mu4QnsD*1=C}Y+?g`AL{ol#6ER6OK> zp|VosahEv;tWsT&L}H~P$cx6F!Pbsi;BQJ!R zYVRrq)I2t+Y2nr?ly4RIr;YMk4gF_(SPv0N;5NfT6NcNpO#OWXGW4;KqrX$il}!IW z4Fo;@9A7v0I0i81p+P+jh!L?O2J3xT72c#nTnf?n^#I4x*t$a7FHD=l5!O~OmTFq+4c3@}ilmmL4okPRaWo}q)K)LlzMCL!Y) zC;M`aE!WMn_&ps=eI0RGtKCDv|1~SY!g87Do*D{a*wO@=P*qvjQ>@aoqI*0EMr*#$ zxr1h&Ra&K>8JjfS+tUz^_Vg^cJ!V_{o4{&5lYt&$vl4LwRt{h*EFsG*&Yws$!;qT{ zSTQzWc^aQN0y9Xuxvq?PR&^M?U6k4g6)+pj$&B5InK7@oV#UVwk}_0OGe1f`7ooXaPq7<8|cS!bE`B91=)D9Wr0rK@|s2C2^^ z|Gj~|3%pBVhuV&}e`gQB`-ngH^RII6uYZy6?)Dxw%Ur{jVC|*1lOX;o7#%#N-$5vm z7r{eq)J^XsZj&BrWi#PNuoHih?i0bW`>@2jXF_;AWU-rSC39#DdTR^|fb=LQfOS6t zs#7H5&hrNT?B|v`r1o0U|1SL*v_GwE@AZ^&Jj47h;__P-3{NC008(h?@n_Wt0NZU7 ztRhxp8I}Rg3BkIJxov{jj)I`oK}%7g6hm9YXa?MSfZ>Hu>yZDk#&v*HB+LSvObf%R z!cMRynV9D0W{JL+Oys1|S1Fsq4(RrnZ13HZSHv27%AT6ze)o;DT&D{g9VhMA&8W

jaN%6rz@;2fH(QW|c3Vh0y$S^_vV zP-78?$FRojFMXcZ{_Yo%e*$0om3L?lE}&k3T+w7f>cOjMAXaECTv=3I_G-fp>V0hs ztj2N;^*cNEzYpuTK-zPdhBDEE*UeISc3n@wo4~>ep?uoHn~ojNlMh)o?3}0FC&#{? zI5vyra&*ot=s8h8)3r>;W&l4_Q^{TXoCkB=66X-dj_dQWGQ9)b1s2jJY(TNO>mP1q zlY{@W?yhn!Kh9;mN4H*kiO>DQ&r_}{#gvQt#vlFTZ*c#uCs1}^4}b$mVZ}4cYbg0{ z{J^o_U?xZ~2v@vdadelnxNrkl%}q1<4&KJ~dv1Sf`bODRF23{{w_dyA`o$g1pd2b% z7RTf$-E*Q)XcEZ}!f+{NtOI81EX{Nk#|^J}OC$|pmyww$$O1zQ7twrv)IBytXlb;| zcuY6ghjH!SE26<1mE8OZz*Y^7WP`qG2zGGSz0$xQtk~f|vjb%<*f-w6-g(Gc7v!4? z%ROj<7B^s3(f|(hyQW-8Loqkwf=MG92Jf`aCzZ7+x@Wjqf*ZrhChG2mllBQEwR7ME#iSM4bbBo`Jfo zW7|#|+h$|4v6C;hjmEZZw9yyaYHZuKy|d50);d4p#mwB#4E=_va_noU5rX2CjNNK1 zkI;wCsKt^5#wgIxS@KD=Zfx>kkDeziRAV%({ZMoGg?n^*!uX+=R7(9vzsx}gpOSL0 zwVUhkT}@Z-L50E2H^3{YDnQvtGd85hvozD&GUd?)OB862XlYZ)p`&1>lo1_KUK>V` zt4{)rK{a&b=r0p2ccKqED!n}uj`*k2oEODiCcKe21=KN?+_^PWap}>0t(5n$t+;s| zz1NRD-bMdrTq4@K@md1j9?{<5B%U<&r>V_rnC;FKT4U*Uoo<<4Dbxi7X3=6m0OA*V}5GVF%m*qzgc+3D~T9o1r>Me~DT7M}BWpI|?k$;^DkkPh3Soln}R z<@MtV?f*TDx;XH*fmts)y*6P=;LIHZn#}O(1|~o*TD0idg6VNtYjXKx;EcR!A-*5Z z5NJ{m)yDF97bfkfDHHkws!MNQpq=R zJw%Z%85r$)0rBV@H8%{^<)}rzJil(b zdNFPr?fKw}V1dw8b;v<`$eY1Nt=|*gobLc2GJ1%svaD6ipX!-}D)xJkSdnIzSeP2m zhWBYdJ@4-~d(8Xs+2E`&@dt3QcX9z#3cTIA@HMG3HGReJmZo+xL-au42dl=dT$nX~ zR2n@J6vD4Lx|OEw2Qsq&C44W4u)h|&M?V+5F+#kzG!wQyu#dCi3K;UY21bdEU@CCJ zmPu$5NP1Vwm7mTJ52R2&I?sM1%^khlNy;}^%4bckbzHVSs#)o2`rRU_#6UB_dt-8~ zMlm(u9hu)olA_TUGXE6^C;vv!RZ86=nC0|^syC+ZI7^?jufhxk-JoP2M>~RHdvR~0 z+P|lZh8Pywmy|d%|FlP1J$eUlAe;voA>%(nY$uKl^F3D$?Zhp`TX&(J`m(GpuQ2%1 zQ?{~xO(1f`5w~b@X7P}D^+nzZv(=2Cd-!g#}C@?1QiAl6kqEa`;-nwruYc#tH@>tlWEHtAw50 zoL^=iYd1k*UfLjA`4tAy?CVr{L->?xFK!A$bur9mz-a@~$TM``R7w;}zZ_H+FoND@ z$NB-RWg>OCb|gfb%r6R8D@~X zn=w-2Cr10=<@J3Qq7l*jAd@L+KXQM;A!Kg{9%&1FP52r=zoc$kxZSEsDpVr^*!_j{ z*Cd(l@onzY-+7jvk$FJwA_x&;UDxp4?})OlByXF>dZe3dSJ7PU7(Kh8hMg5qf4*kq zfh9Qozc^0t;lLvyXCo6{ypNE)svSh);9ut^=a-V8ZztzZcBauxn`pSIx0Jb(wK z7pM%))!`036rmu@KFpb4CSQ{uvFN#3!fKpAY?bS)&GPZwe+lHaJ z2tSHWeX;GR#OG;ZhV47=#4kbM`vqFEEvbT~kb>-d^Ooam^IHz?L!$QyurX-WPnpv@ zr;3T5?&cu5@XArY_bKnZ3w;{>?dHb)+2@zPHa%$L{5+oZ@R0p8v3#{1(fRv^HMeIE zHkk{ML$op_E<5bU*|X@vL=$+z%pxC&ug}`0Q%7soZ+WMWRy#J^BLz;aEWveM9d)~p zmRcwk)D%1}n<~Si{mTNe!tQwrHUyy!mAB`QLj(fuj*t$>xFwaB?i5Snh-f zn4)B^3R@%JOVJ(xz4!1-JtxG6{TUgYWpTB89u-LdR|5ODbw#Unq3520i1_ly;`@_! z4#QtZTReNJJ%17N%5sV5mR-5=@m>AI8+7opnB3@!?WO(D@}U;9VL2!pJ7Zobe-Xh4 z&mVwE)A9Kjd|2P}SC@_*q4Xg0qRVXmoQdM1T*2YEQv?uI887-|Zd)_m4ffZK`X5>q zteyiVNr?<5Nu!*#Gh*?iS=r`CxAe*A+v9PSgv=uP&-)m612tfp)&!Z3w(!j~x=I$c zx!7z|NoiNAy4H!-f44-baz^v`S4#RzJ-R)9iSvB!gyRh(vCK$NRr2m! z#}2Rd7=Oi-;gM$z*>des0nh&Q^RL#88l2w;vEukq1%@-AtG-w=sx(D#$0 zoG-;A4?3*iVQUY-SGAOhI>&WD$W^hSQ+0OOcO3YZO~Fb1OGm7zl|!~?OzK(sq)nQW zK8ADdw&yI||0fo{r80GVyDyd|I3YYGL5we$u6{j z9JN;#VsS_%MCgraW9PQ9Z%|?RYU^iOpL3pPh&@J2NTE7S7uUf{92b2jXds-ON3s00 zFD|FFcPV$D9uZ4p?RvTYT`RS<7hJLkAN%?1s%g6JZyFVR)!x<7*W=pyHzq9A$a+t> zWW6Cjcsu35965YT=5;1lVB#!UpXY&2vlF}_gGSVPv@G)!lWV?947mm+UFeKU0S7Xu zp_%4GmqX9owu8gEHeHjti~q@`Q=6p!9hc|z!!Z3j{gb{2E+2cQNK)VHGO?K0Kl)H4 zJeUoX3%NmvGh>3;#L>#L98fV`Y+HJwwCa)@>6YV)pEIa)ixM0P(J8=RrsJ?lwOH+g zL>Go{InUXbUp!oPsTeL|9$vyZEy(F^C78H~5>UxIZ=k7deGBx%>Up!qLTRe5{32fqD#Klgh3 zhtIeC{=FVkK#K?6P-pz%Czf6wSaqGY>xmoKU^#K5fcBy4OnIqstmg_txKW}>)km6p z2ti0yHGX+$e8f?@h`Ay;O+}>3QdFFqqR6%X-L>}G+~vOJKewS@xUuKG^I<+)DwF_A zj>uy+Lo^o)y=js#lo#uGlBIcLfwc*WhHpcQNQanm>SX5@cI6yV|*~l!^of|Mh#3#pZ2|#zEy(gwJI74{K=L1Q2RPs_qlLndE$`HrIcElo1<( zbiF6_fIsMMZ;d-QD=rWLl`~?&Mx6%|MF{YpU^~i2@Tu}Fl|>*Y9;18pAT79Dv^Ql&oQikDQ9#^>-{l>UB;Od37Raun6cP%)^JN# zi4oHczD;ff2}Op+P6{lMgxNB;&qsaB&8AL)j8+Us;`7idI9rJCBQIezW(91fQztxd{ zJ>BG#|f4|>Jbvkq_MYIlj1L0;_=d)k*o)7leC^j!4HoIQ#P{1QBpzu*COagd^}bw8VA zjRN)O$bJOKhGO>#YQ@=Yr)VdDS+|D{djlg=bV&H*Age;f&*cV_NVQt_l0tVHidcuk z&>?6p>+CrZl0Wl%ua7mLsIx|3(W99e$}#655T}CG93Rh4iJ<5QzZTbj@;{gA&`mP} z`;m-x7Wal8gkF7#-iO><-t4=E4)Q!9JFDlR&V;9}`y-WUk${=42o%OBqqQK8z#7$? z0VF~XdM;D>-+`R%8B}{J{FJSj#7yQZNHzZm?72c2_)k8(PN@IpIR(*!`|6VeUP61l z5q_JQqPjOFiA<|8BA&-A6Xj6NBG52fPPlpVRU-fPI_5N z3;JkrpJw9217DqE(vn`E{bG^^FgZ@XP41o=T^r^oom&+PWIhy@QMJp(4qvqzYQGW~ z=z3v%_{68D#0Y8}UL9xFv|(l);QeE_hFyzP$W6`ji+LzRA*5wR)K9lxT%Q+bnX7a6 z>yuK_xcKtZmdnZspJt_$xb*AriVHAfw`P^KrIMLly}1;EcD4;INs)8K(ZigMn*%N= z+fy0U%!8m1jK}Qk2E>GBYZt}p)fcOkvas?n*8UqjEOH7_Tb)=8X*9s!$eo%cJusxr zFOBP5)BOXT%|Et&Wl#GEZ_7QWF7~)!;`hEME1~zQ2Q%_|j6${J>AveW2A+LGgg^((p1U5#-F=uHI_MKYAxI`%3DW7WJXqVIM0!qqJS09ruQ%J#nor8d zYYImH%R7rd4d9g}%25tReUa0N3r>b;GPrx=y8djyzr78Pdrhe{esSE#uH5G|roy@W zMjsCbd)M2bbz;_0M%c~Nu3h#30pJF9&j21m1+ zgBvjn9RUlL;nf!9o<2=#A2?vMJy;qb>N`#xf4jn#*EB!)XBo*TTW9HUOV;$xt3+}P z%%@2jXHT*LruX~0FY$vN_QMp46>sG^R5QAJ_zz1aa3i zf^Z2$EX~RS_3IbB;%uN($g*{L7d9#qetLaPjLeSlyCCn0Z|>f=iMz+R=3XB>LaqJ> zi&+VCvy>kcC<47L#E{OlM%F=G--&nxX6O+N!Rf<@f>6e9x`y#ni4Eq|upM zWpeq++dUN=09$C64QFnC;Y@hC{_=K0?B=WJvjGXICPVsHD1EzQSfD5k`-AzCS?#+y z<#v1+G(6PFWVa~*U$x74& z!L;?=q1kEy<@V7NZg#|UOa$GZ|F8f^(kL-zFEEoBi+1^J2#@cbLS-6CG9IQwENW+BW#sFN ziFT!dnc3Hu?418(k^DRONGJOmi_FhnH9Cl2s=xir+I_hk)ReLl$h#}z=1bF{iMV?$!x9t6RNzg~sRID-_j#9_E*{FYcumnb!t)u1um(8|q*zO^ zyrvAAyNu%Y_ps@?cGZihv*orc$MQig%En^+&wB)1FN#lo2^(hZ7(tKEnKL$)QB!ey zEvh0-mNdH4TyhTFz6|I>Ax|`io=U@o3!6Yf}@@jkb~x zXM4}m?S})3!+A$E@waAdIL>={Dqn9H{=p5lhp+E*IGCll95AHyO({o5d|Y#UKF&LP z`ay!9|5bLSvj^>RNQtylWb6G7`SV|Tz}$TrVHIc@1}j4q5F71GUnVP1Mwa%dtMzF27Rri<4FNeGhrgwICzg;$dA0x-E!;oq1J@tS#7`*C`rXgEzkm_hmb%1c3 zKLa2LR()OkpPZ7~VrPMANb}aTyT_~G>bXzAbj>a@>iFM&-_ zNBBsb{bkn{HtkA+DqS%@p~qY{b3WB zbLDU^tf$FnUBv_{p(b)@(<6*3LIzg~>Q8nM(oGhhS7+5tZKp2{inhAr8VtiSogCdIJ6i%vp!ifR zYR$-T3%Ddd}76H$f41!N=20NcqwB27K zJ2xS~Oa1{_TM}%j8$C4v5xLbYqio9bc-Sr3hbg4Zh^?;neYS|dFh)hSKX6>Rb=Zd& zsAb}WS3wmVe-}y})3!27Zp_vB4+wr!aQL<9#wK!a5n7mEicscOY#&62HcQXB=|N&k zR31CyGsl66A10j_>5o8!`tnDmznr`OSnN4XLO>xP43!613*XqU@_d6HhwH~={ZuVlTL{?{HYMK!n#Va(~ z!Df4(SO2x=2AFg_HMp@5hnC+I=K<^dDx~Zw1To;K0BB{8nl6YkcW0@bZgfkpAYoz)dW7WKIQb3 znCFMm7^qZy#D_4&k0K#w7(u}0+J8Va=ZHiVH#A<=Xu4=VZVTR?X&%eDNB3pkHXBSn z#bs4g{T|Jq_TJ-)D?#*{t1J5*Rwl`(0tPr>KDe9QEVdEEYp$Nz3dQE znTbOL8 zD1h0f0oVked(bKQM`=HSof!Gt?mlZT_p@rB#)t?S?jT>#4 z%)~-{Ko=6z^)V4p8k%zkT%H1pz~SDpu1G=M5kH1Yr$iF#F4~0*2koeCx&v{W&fC^u z2GS6=#hCn7`^f`cLFvKLDVhGC>Z#&djI^?ttDDSx!BNagZt1X9G>eH^7`+t5#yAz* zwLa+k8OQddSg@BH6hggpvZ8dDZbkKKp|zLzm?YtcFE8Ya=hAt0B2+5|t4&+S;{+MoI&*-Ms1 zFoh$HRff_JDHq5&$xlyjtSL8k z-iH^kH6b_Af(mEHjCoSI&IWhckn^Hr3)4;F1^q2re}1h)t~>f%$`*erUqAhTCPk>2 z12P*}xF~Y;$S2p!qGaWxnC}v;A;kcrewj*^iDInR*AO=QhL_2PhojRf3>f1W`Y67cE zleb_W-$#QmQqhpe^u%v74*+%%g128F^Xfq#BZ zspCdiK>f!2U2c-u$B;BH3$-KIWEUOnN~;U@)We9<8RvMhgjuozSE2Mc)!TfT-~EW? zBmPI|jrF3h$b-6 zs#9nE>%-p3;|NYmP|^F=c{;bJIWNe*QWJA^19F@IV}Sw#Qnw%-Tu0U!TrwY82ECV6 zG#@2ZaUiu_{S@>x>&o%Vdg-4A-QuQ0Dowo2I!knc>I%*RVp9Fsc1(kr)ZNPyzYu2P z6FAeBx%NSrQZS!5CBxY#kMQilv7no30U=>h@oMxD5RG>+95TFREiGcIW)cH3@p13h z+(tL2L@fefq4E_W4G&JUymhcQ(+sj69ta`POO3&({K%c6*@}y|^Zf^nt~~(gJ}C-2 z_kVlZ_MWPJTgP9%fS(q1_#(?d+4)^^c!LJ`aA2}M=}|Q=qa-m23>8-X-pnoOo5=hj z%S#RY(P_`hJob{^C6OMaOv$j1_vu~tQ$AnK;A_c{nEp$yqK;h`eJ~Ekv z)mHS6)h$|W+B%HWs&=406pRDn10f!yO|Q)`E#Kphxwf0so-$B%8f_Z99;abdh)Spp z$|*g~N;eHp^dKl#%yC8!7udLJQo$y1wC^FQrhkEpq3V!Y77K<(fm-^RCff4SY$=UN{|AKn=&|dzD zB&~f{M=Bx%riV-dgZFH5QmWWCSjRBYk<|RIV?$$#-!v3r(Z(JkNf5u;_Z5)kRd<_T z^!}YN^hTkRD*QR)BBe-_4_z8XM2`Kon9{^l%r;Jwb2-4Nhuda`wL&jb@KV3BHw~-% zWo(jh;h8$z(kk+NkUR^3saQI~*394(n>V1ic6;P@8HM1yau<`mgR|Dl?{V|+VP`k{ zls0=ExhWeai2^q+SoWRVwgWzmaT9nYnrrk_oiUWpd?qU>eMhP6F%eTcn+d zh>6EEnlqdIH=+9jGjS$pIKaX@$qGvPh}CT_7V6BhX)2<3j3@WOrBG_L{dnxYJUiiT zc?<`CQI0n$j~%CB4eU~VBf;nbm1gu1z9V}2sN2|zplGCxbT24-cWA#)6=qt%TYw7bi zQ}SzY>uBc774br^*uc+}*$QIc!gQ)d6*e=>UVf@|&uFAH(amLTf5i+Ji{CKW3V5=hSYF z=dLABbz3Ok<}^KJNvkLwU*L;RKuIIIuUu-4ltwsF;>57Bq*sbMBT0XJ2=Shq+W!)R zjRwUGv`Haa&!>+jbmcTsLy`#z#yi?qULh^=8%^EC<6__Hz><{wvzYF5y)?2im8F1Z%=&^fvyrY9_X#gmG>ayvW+ z2$1c%lKNp|ga?apXq*H<+;9UtAIk=_ub|e~m}kO}bDkN#qs4uQKwMT_d+=wXExJf> z7S9^xpf!Pe=!rTG75!{km)y)Y`6gI~m%B>VD_w${gJXQ-KA&mT((rs3?~*TLUQZ%f z7Sp&KC%2$|uA&fJk2jQq&ki-l6Q@-Bk6b`E7Ep!(-rybH-r;D=BPC3zqN7=7Weh!2 z;{B^je_$=auy8_d<)R+>$y>;eOu_tki{dBWTq9Mr^a>fR1r2KHV84+~4>|5%wz<0L zEmC;%511sDILRe_GP@$_{vcZdzS*&ate3}hZxQZ0U1M8rahR!$IWB8KF=_dR0WW*B zT%2f}VlgL`r_obnOs<5OY|2GFgIV*B-a*|^p1lAR>(BYyCZ>KK1TuVjVXwSZV-$TwZ)jYzubbA6f zEuLTb?TpDwgUGE(QpeQ1TT?@Ku?4F>4N0=nXgS7qI^*g5p0^NQsbl|vU@afy@x&>s z4W|r~)kC=zNZ57JxkzYk-p=9JnTjEoL-1-~o|G5^;NvBG(8rS(FrKjpHbu5xo#(f@ z$1eOIId89F*Eyfp&z7Bp(KS*ko1_Q~^maxhRm?}zgZV6gjB*<-C(?*2nwh}N>x(pa zdwtc^?tA_z|10=&BzKSNML_QPj+G}->jzZW24rdbNF=IPW#chbLih{m<=-lmd=bmd zr%bzS+Uvuocz5ESM#C$t>aOmx&rN}@rz)nOYd=V<8%g|o-qcu!H*W--7C+hT>XD0dRox73?$TJ0Y;sFHKg?|k5^NN&Kq7~A7^yGqG`qtay_#j20`L$l2t0idN3~7 zy=PWXk3343TJ=z1!Sb^o=_d%5Qf{W)0lhm1&!l>ECAiR|r!U?T?gUqJ>L|+gYFprW z0MS!-?hL>BU+2f;;dvSZ5ea-5G6-eXJsLNSPkz^6Ix;`~>Un*+VQiHkB*VfNzZmEy zHeXRVMzh`MOYYT7r86`NbG-367*T}X^6LcZR%+_`@^BDtn{+w&`jvsX|1!U4M(?d| zAhRn$$%6d+OkM{@U^5&qe2Mc_YuE zU0$klXhu@hftS7mr6rqh9O@_YJ~#u4RwNloJAF-|O=&K*%F)a!r%#gmIE!VvkJd9B zuadb=s%lT}eRQ)H-Aj4mZ52L5Bz&{rdW5y{U4N|2l|IjX(gWyUZzfE9M}wE;{!NI= z^_#mOqkun2p-^)q2YBh8v8nwxQI$y#AQ?16>G@aNht7h!5d8VQ|gO@!8W$&etvM*~L{)TFk4#m*nv` z5S3TVr!Abiy5uZC0F)w1tW9j-;Qdvk&CEi3l4#3;P@>K9r{T!0<1z2k+vmW(U(rwJ zrLp^o!|#pDFKo^KA#$zzou|ux$z%Q6B_erB8hutcga9?RE62nh(D^m zMG|4k&Y`?_6{>uZ%Q5-E5Lj`o;}7xmArx{2|DHnlo@3BshuvLGdp_z>9UHF|9F(zm z(T}8snG|_JyNGwTih^|&yVx<63t}D6Ts_ly-GXTq?&J(w8SXyv;yBYZ<9pa=MA2leNWU`E&e;x_$S-2Uu@X9ZR;z-6|Jg01J2QPDF zY>ZbtR+f*tBEcKP-iw~GTsmMcx?4PoX5>u@^*6k|J9XLOj71tCC=J%=n`>_H%zuW) ze%RIChkvrgqy}zd*s`Vrwt{Za4@_XYfpb*2ijr=s-M%_(^#PNej5Lhj;O0z1jIIrG zIejNq&#;9c39Q6HtCC*((NR|HmSaHI@yyfmfF0dzz*F(%aliAEL1IauB7_CO<89WOroOj~aEIgN z?hO}L0`OO}F4g2@gnTWx5ZN#O^@B>8tQ{fMaLr6-H_1dZ=%)QgPV!G7b2wa*l`xtb z6){>jqj~RU>M%IPU{}474g-{tE;IxIKZ|-G=;#cOql{z7R;CwHxEgRQWJBDD0eJX8 ze#g35!pl^hM1R!=Irp)PJ25mXh&Tqt{T*e?xe_4u&3H;qxdWzWEB2nBjGD)PP&N^A zoKW7G2r>F@PF?vWXV}~#{P&-^e&4o5M;Ekxz&!$~r(Y9=sfShYBoMs#Qk@N_#IkZ# zwMK3zFz}*%G?9dOUHqB;Z;c0^2eb#oZM+q-ruyFXg>3whkvn4d6Hz6f%?8=nB%m5p zJ^0{&uH|oe(}+sX209g}g*HFD;Q&-UbJNCmF;vJ^mseK5?6jTeOGe)A>2*A`&^HZq z7TUOb`F;o&WRxzm?Y0ORpHZk@UK&p1K>oCvBCWT*wiR^6^=uU)^iIR=1G)&m+UB7W z1;&v0=`mX|E3BgNKwxokj_Ls16}6OSgMSWU2O{$xeOv)BraG*hFeVRMCJVfR@j@RE z{?2)_)-J&OZ25j`+Yj-cpL(1YOL9A!f63X*n_QZ_)19@ibGDJ!A>E^S>t1b+P7fy&esh zcISrp8wZ=EB}08ma-1iIerTvVrBC#A$B&ewGdDKYc9S_ixvT*St$)Nij%u0j#pFL3 zi~PO|D*I7%I96M0h>HH#dY57?i>nkQ4Q% z4r{S7L^p#bNx5w!4Zj4g(1McwFC@+B+n*CKVyAk8HAE)o7p%SIbUQM%O>Ck}Bfy>( ztD)(A5=6MltnGZwm{^$S)_U|Bfrhzdrp36LPmb#kGYtb)aKCi}MHRTej(VoFvcUU>j>6r|KYbVU+JY zE0YUu2(Pgcni0EGznJlyfe)Kj2}zoSr(KDjUmj&#FP=F2uKF+~1glF?*JVl75A*_c5l$K8AlB0}d`;hi+FbfE(=imp67ZU? z*wI~1In*=*Rd7o?dlnWPmCp%_hsrPWMBx2<=BtJk$R2tR9R>aGY;-jEA`xi;A)L`g z*NC!vQz~y8P>CQ^KJQPChipGzpS)K;j0<19c2m9L$1_zQGL);Uz%A~JrNq6U{A36A z^h2{HjaW#FCTF{Lqz%Ak5^U$r|35%!8yJFo23rq!q`ii_MsvVKV~$;kC5mborj(Co zM~85!Ac-yzkx_|rnKRx%G=&jv2>}`s{5~r1fjvK9HfH*Xh3#OkH}{z(6v}51RuOoC zHKpXE)KcDYedQl<*8PchrT=d+{*0nBjAK{z(Aa7SJbtt{PTL*vF7TV#%H%Y{^J2>p@l7c4y}`zkT&Z`<{o`b%%Fu@cV%$k}=&= z1rD>|I0WAzwf%`^84Z~G#y|XEIVD6$ym)fI7V)|I{>ffqUA_10A#Gi?wSighFw+Z+ zxfN2a|NM#$0ubb|{c#Wx8s6O-nmjH$Tp!QNeUw{#SVf9wG%YgJWHC31sE9AQ)ZFLT z233QD?mD<=K+tkr*EqU8Pa$@(p<>^c)I!MbB^330jeK44*4;vL0eH+;DWk%-DatFS~Rdx5V9(RlWyROEGU6QNyHFxe?8p zh|`zLIqW^6@Zd9jO19oe$R7TZ(xwGsb%vu1U^z^Q^Q>RO!rD!$|N~M zs@yoi@Hu_X5J`0P3JHSf6lqtcD~V^c0XkWIr#(W=x&>xVm!uSQukbho_FXE)n;)6U zZnoxd(dT#SjEUg>A$@3~Ll!*g@De?~wqkc^UN?i?=?unAO7jbp-UXNSVMo=TRXl8_ zBWG2oRSc*dwn_n3HN659x^3LoRY;yUFw?VH95!UD5p?^_zLtJbzu70nHS}}83`l-T z|0rULx`Qw*5RT2mANqPI9?U#rk}_P6#N-o4XC+xHCg0hFCg*r!H-c0` z8I}C3%iyg#loY$PZqQ!0K!!+qlue>t%87nuViPeak-df!{p8W6Y^U!*J>s+2>r>*N zSTL&7jd`b7*6>}go-)zM84hBSmr&7eaE7o>Qb@3|V*HP#rb23Hkf`k7sf4$jrlmZU za2a%KJS%Pb9&d#|J?GhG{`9rQ2&oGTR*M%^9fYQqXIZpyAW2TXvBNVhtUh^G2t4YTbNBk`duK?t8eUqE0$6B@rFwwGEZjQ+{Z72 zvk1nxRV&OmVIQ|xX zOfk_}4FZGd42>hytsC%(p=4RDVB~Zy{*`vz|L2=!4l1k$vmwy>Px{2a{))}ob#Yjve$GfQvgWN5SD%u}WKC@4>* zR3(#$_zLTQBWChHEWn9!24+WAHQ;3SUJ;tVa z_+;T{E-1s(^|?n|*5EDbzI1M&`p87zz%daaK;|djl_Ys)3r$MKSR%*5!BtyLNvU8) zDb$q7`CFwc4xKdlr+)R#3Q;hGlX;fxc<6*NH;HAh2yBytfh0m)XJ~sV_B!+8CKib< z5=HNr$Gd`V#OWd*yuH6xIoO*i_Ead9%B;x3Y(}+ZI(I()xn9V9Gv@@m>+eCc3`Pg; z9@h{x>Nuw5Dr_P&v6uyZsL}z=m+N3u!63ihMECq2DYs*g;5m}4p-kPfz4c0Sv*^QD zoxXf|a?-uV2Z6Ope>`_BfW%?vAtK#zRtRkMVW2+(+9ZH(#V<5qS$N`w=_=`tF=hmX zQT%9x<8(~NJ%=nLU;ape)d+yXcK9?m@MP0I`Ydqs<0`Sf^2H?eQ)J+&FGhGH`>qIQ zxC$ZZ=5Yr176Mk}=RhxJ)E*xyqq1EYmByb27~x_IbGL7QYP;~PTJU1nS++7_@{=G- z534QxUY;jniFOIPa3~&xa6C#rKOUdPjh7SicXGXE7y@zIUsoRw!A%3t+8a2kp9}4? zqJ9BuNTe(EK?k{GnZ~tZp}Lt@Gu~9IO)oCmUpPxhIlh4vxO6rRWlQ*V-9avn3Jt`S z^)@+%mEjnQb}5XfkTMhU>X16VzE%|F?VLlEY&UybAZ2E~Z*9*v|4mWF~OCE^J96rX_2vn|QqHdu{{{Un39)vcZcm zZ@N(0WOkFmvJef6#<(+v-2R0p*Es8#WpJ828~O~FK(d-l*6aSCmTeV-J?KMv2J;MY zz;1CeEvb-zEvBTiQ#fW{N->3}2Gty3dk9&>E&o0|TuR@Oo!@=p_@*7c&x#=5zs@`5 zqfJ-Tu3mJ!xA0Ljw6wH7ds?W|^#b?pZe4_cmAb`c>)~&28lK&0C#}H9$|j`%VPM;=Psis=^Gb zHi_h-i7N!Vb%>kxxAsg_3?I)3*oQJ&RqZCRQtKH;>5TY)JD~p-7UkhI`Zb}%pW%R64A5VG)7iLqI)aAddt#y9 z17$2{9=1^nlPj@RJRYOXnqD7d(ZdW@U)46$E zOnI@SN?(acBxBYL{2QvX5@Owizn0vK`}2$qLT;AA6e!1+ z*{n0=evA`}G-KCczua@S8;-1|$?3r8&=hb0fo1wHRL{Qp5#m&OVq>Ab?ap(46H&OL zg%02-iyUQt9oSYGw0!Ark9bq8hvrx^7%QS<-$3TLYWrb{e}rnhq!zsir9wTt;2Dns zZ7SHz5KZjHkbLLLuX80?8F!wvVBJBzDDDhit3(;Xj8fi&o5VhUyo`eBhgJBil8Jb8 z8gS%AHAOuj+8xe}xwfrim#&#(Y7#wXi4pG;D%wgV+hP(VKhN`P@voRXW9!pkrmEHl zp@Ou;3Y!}YC37l!{tRAF?+H$JL|p@6(bdmjai~<*o|p_={>>-CoE_f4=YZ&u8^^4| ziN3P*4s&QthW(pz(E-GSH`X+?@au45ybpNM#PWXROcK9LP8z8Jw#GKK&~B<|OEZtg zYgty|;_rneUL`gXq>Nd<&D`a&@Mbd8#j&H#+HP7}CId3EBPL;*PU1=DBIv|&iST@= zzYGbrr7~K&mc8+ve-+w?TtFom$j4i$<+&P4Z8(7fXl~|+H#Sc;?*hA*U$Zv383i8m zOEIqnN31sVC3LiW$KbXiXO}C>n55 z|GX_9F)tb)YL<6TG-eLnuEtYN_7AcMItJDJy^oYCO|os`-eq(at7?rAt%iFkqv-xq zf$js_H0pCX<;0vwG+NMc9>uyr^r1QhR{z8DAHsfNfq=QXce;d5 zOdjPX+!il9y7AUn3fJ3=Sx%Zi%3ZUg!L-chQSl4*W2xJa{~D4tzQe6K(K97gAKk0IF;dgZP{lo?+osOYPgrhI+zJ*VuywkX5`o<*VC`BM>vl%3`qCxPP zDjFq9^kb<1Qb^ehK4fG+?NVM1<&xD~aShRuLy=F`Zp!1&;9^(8RX=}OBt`KWV|0^b zOBbAmWszGM|A^h41eQay(#gdBQceCbQzt1TeJd;0njF&tzod(`-8@(JB z0F)B7Ad!q|4%g)0gCj)7LcR4Ne3SwsrijOk(5#{OS&0c*v0R|zaTNt}WVTruN2P*! z4Bl4QsUspNL@vT$rX%>h@ybVr(}@jO`e*WEh_T)EaAnQG?U4V}Vivf$;{sh)wwPMm zNG^Y*!6yvCt_`RE-lj$#YV-lo%1!A zzseh0MO|+vx*g0+Sh;dQjis?j7clf6As+2i!CF*yuSkp6?+_S^;weZ8gZyMuf67fu zNHrfYKFMR_Hg#Ba%Wh&r;pkVzz)3sP^MV)d$zpRaAzBO(=ke z%a%1ay!D^2r^g?TB5an!E5~Jc;1QH{~?q47sMK!NYHe!*{4Oq zCt-aDf-nLFw4%6$E@Rj3NTJsmZ{9p6nA=H%VM#a;lpLX0kPlCQwn3f>l-28k;0Mw= zUbHx&DK9;J3jHB2b1E^ITskl$7f2TMTuCF1 zw(PH4BnBU*9_~p+K|UNw9``q5hIjwBIBL{<-WfKcbt{VrwdZUgR8N~?C|mGW>cNt1 zF0{21LB@@>Z5jWIpOEb^cL%o23tZu+V!FgE89q3qz9V?&3tSxUH3a`Hjz*2%(RsbY zE3#yM)IzPza&#>JE&b6NThy>iwSymiD*9`8PVM^=gU{iQ=d7^pL!N&u7NWygL|+P- zM4-&eZRrGr6?=Mmgl8>_TT5WJh?e%@+m;eJqIhUJ)IGmY#@)(A2OGNTCu^-u#KTn? z>=>n3BqT6dMR!uw@=4kDO4{LQ;p`N{LCz>mE(iTc5#s0MDrbh-BS+7jk#~9q=gi6% zwJXQ;+i88#S-=TbFrDI-5%9PdQi8wR0soz#R7ICz@@m#Bj~Sl z)Gb0mZ5;2_FIgH0mfD86*;y3c8L65cPe!NfNODJNI+Y!AXNAKa;Rr@0wTzyD(d@bV6r3mGTqG<>qlY&>xR*y3*Z;S0hPV(GB& zMbT)l6D#kb*pfjJ5HfRyB8dF1TJc*0dIwf#2=IAylYhv9mlTyX1leU@*bR;t{zD|n z4fQNFGuLEEP@o}uiG=Btjct7;1yZJ0_+2KO0hYB3ZfFPl1*790#ahC(RcP$Hp(J5P z388|fQ7Ou3bc4Z-R>jb0R(0tURVApPVPqS{tFE6zXG`@n!yuaSig6;)8Zn3e)afu7*!M-gKNKd9_D9O4Z$~aejEbE@EA=fEw_hS{@t;-?xCtJ5lRS3R z-279?1N`uV2_T(7%w0AL3a2`7=20sWsM1PL{`vF^u|O~ulVNJ!h4e-HZi?{-t0~~0 z$DplXUZ{cX2$*_d?o)S&WJ>1zsyY{n*rH$BLacs@A)R&exs&}n%3sl}ZrN*Egk{vG zT1w~K{+_JKhXB>_Ln~us`lh=nKSHNFJk5J?gzIsGr0_ps&aG zzc?UHTl?&o+cXt+l0q-%ZzbKPIvwH6{1!{oXS87ngy%N%asR6AcBKeWp zHf*n$9P$mE#;fAe$|;@1nLdjBuTefux0>i2e<#&)PN)N?!LTn~t@XT0ZI_nEGHul*+G(BQ=lgKBV)_Bc6YhyTLjMt@LU;RIatmGT+fWfM2i0(TrEu&`N)7I#fnp z#)SCj#9PY#kMLAe==ch01@PHjS@pz9I>$Vkr-vRUTg!{ zp}aVy61n>MZiLEu@7+k`-|VtSi^Ytj4_tYKH-F#%#8a=k#$#7bcybZOvuAb?)OK*? zgyW+Vq&Jo(jINg1T(MYV9{xhb+%%0`SpQ<*Owv{Pf;tdgr_m8tbrm}>31NNIu_nn& z%KQn@6kJpyv(`Qv00mDMTefK|;Fzr8h>Q-|C9a zP&l{4IJ6sY$<*%dQK3gn_)c@rjiaR)_& zWekP}lGI}nN*KZg3;Qx?ZWy*{4td3R;1X`3vGxR{4fh-vZqO;?rxE)w)^s$^kLN;^ z@^?jIsu`2pc+~5=Ek3i=6I+S~{ zR6g;1pL?-*!@gjjRC`{}jQ0NBvyVrpEJIkkVGt*SV>mgo{iuGUy5OcwkTHlDkwXnx z8FE>ZC7qrmJeAZ?ivl!ydKHOcd!u+Xi5rpBpRcT8)P9B`Q|!Ch8Lds?9ujh4gL!OA z6{dUhl;6Xp-;(o%F?estlOO2haeMr&8q_YXhFa%kYsKl=P&H&py^+uv z%-IZB;d&=ddrQo?%LKR-R!l))jES0wG9djopGyc#!#mPKbGzHtJl-wEv)+BIn3 z0dflq5PpK8M>oI`jBB9R>>9_2o}e578+dlW(*v$vgKMuuKm8PUz+hqF@*_2#sGlC24b=o9afFX8WjE|NdeuhUvAAx4Fc6mqFlbX{K+DOr zE48g{*y=Twc9n$64m4J8>;)KL*VRe4S$ z>0W(;)iJ^lx-oclDv#H!jYt%FQ!t)nB2#ry;!UbG|M zs>Ykbl{KR41Y#}iBW^S``-FcMwdEMew|wp*mSD_5Zlf-4#5wSrd#}9EIe97OGNhe7 zewLw8Og}Io4JVIoM2!FWzG{zN-lN@3=DZyTm^kLg&xb~#RmDIxu|Li}8fRUqxPJb=rIVN4{9 zh+4+Aj(4rN@TGbQE_h6@pLd?VcY~JaY$SFQF)MpFFvo3QJPG@+s2PpNiVmwEA88&A zF%)HCY0cdHUA7m((LhpOx5k;Quqf=D9!ggd@#`p2i?0>iFy5UgR^*v-;B~Qt`^ufm{%l7zMHQRN>e6Po?B(lh-$Twj`}Hbd-GOS5Q$Xy+_XeJ|Q?`}hH}SRLa8maDKkv6yiT6gx2$4}iaLgtEiZ z{wzLp#b-3f^=^b?7iPk+o&JHPim7={BSH}bGsatvlT7_PkvpN74MR~?*9M{F@MGD1?TxSlzLV zh6~V*bn(|vzC-9}=JKCthD0hfQ?B&{+7$*{B56x%y>};d9m=7+h^5jOcSF;`t?>l^ z?Q37+blGzH#AEQxIehLhcwz^e6R!L({}Fl1HJ)0|IH$p8L&O=~snWGM-%xjd+e0>Z z5)OQy>IfNJGD^o7u0U%Ty-dhg5sy7LF7#ogOnki(A;R|WPn2p)I+Tgt@(nVLl?u}X zV4q$W1*-nEG%_e=5U5lV8>=Khql0dZHzyqp17RS5iXt0u`kDnk+(Xk$;IDM|ayDY| zSR3xrZHGq|Q_kaM4iBZ!=J8$FyLGrhubZ)OCQnkgwhAg8Z5^7JO~t(gq~kG1Jx*&l zD0tm7dSh4zWHrwb?^=C5Bs~sx7pxJPMuR+*wU-z_oSLY*dx1L767Q@^7+Q>frOU4K z?1_Z)#8kmIhx*}NOQ5oLGkU5&vb zVwoNWdPyCWI?DL&@wXJC_uC=$u8T%FljWV>$}(+(Qv0~4SFO;8wVy5nr`MV3h|Nx` z=;7U^Qc$OhzuRQ-uF#~deF-JFl<|_KS$LmB1GA>@8J9K=xhT9-A`qA2!hITN)zPx1 z5{{J~vr>`2Udf@*DIQ39b*f~s8Op%`vZ`O0s!|>4_)VGJx>St_yFN_y@0+A%Pn+t7if!+BH zJTRTN=M2OJHIMgN-IRt4Vw7uE8fIt>@#`{HSwHXpt%~pUbu1ILVsiY^kNLW7~Ts`VarO{k5hfaYqjH;t~ANJ5>`yRHl zO>@mRk`-og+-MoQ)^VF;m_Tto4HpHX@&fUCCBKD zHdjdnJD6~T)(E#}j3(Lh!%0K)!?KI*zmr0Dp~QjQxWld4C;zt!l@Yv1%p#Qr$)HD< zG$}5xqN;>?*yfE2W<4zQ+|e%*2SHJh1%$igeS0*`Ir;F0G@1FMZCqPgG_-jZYEecT zen3PfJOQ!|OYn$hv~NW7LqiK>P4;UJbnyKg@-!Bg&--JzFKSc*zZ!SRbvU(FDRUc0 zxG+c*4c9-Wmw?*AT*HxV^<4q84W8v=qro5j{p!X}GuEWai@I@JQ6g@(CgQlZU$YMy zMwDW$(QI>Rd)ptdLphY^Tjtt}5KgO~+#r^p%Z3z}`viAUmqF8oh9%U&jc0a{3_2PX zn|C0(q!BgHrDp8(<7gd5j|PqiH6q@0XS*y;y*)WnBaE_|d$5v=K#z(O=Fo+t{3^xJ z2_7nHHC9DG3Etoa$3QYBpcGw=?5d6&!)5OpD?6U<{WkA~l@8$7gW4K>9!~ppf-Tytk7; z)@$;{72S84Ar60|etS;P;il?XyW<7W%wTxF7rZBB*mTyP+T%qDWu*e$sZ@364!>uU zsP$Do^8EW~Ple~<{moMjM$$t$ltbAomTgnmkui0Wm>T5{B%QhfBU&kX6(*|Wp@_EW z+OX$-7SB#4qh4e0x=R<{oW|?{PX@2Xf7B zO)Tjvk;VXC;;mD&AqU4@2~$3XX4_ri==?S8 zo_>(s*Io%<9`NPYz*nDTTtDIZ(>K^H@YqRb5vBkw;cT}sBusIGOrGZ&p2%9+YT=sa z^g|=A+0-n-Yawei~n6?9}O~83#u_1PTL3!%?3L zqgg_s!7ksoV}k^zlsHh6$wu}Ou^zkB`YJ9r;K(l<|E2>`GmJ$3?6%r=dt<3{2t_c2 zX7B`uQcjLXD$;?jH3fO{HbR+=^&{YcTIcUR+M|4)YbL%I`9++k5PWM|Hb#Z|E=GE^B%iG-ok6TYI28l}@Lz_;Ode zn&jM^9;mN%i%)Iz-i)ck$wnA6E%t8L;bE7|04JdzI4ZJqlw#4Hfr+14l{EnNCTWsyBy+jfTsQ$^-1Ad&xdACewS-mY>;&IyD;6= z)Q54tC!Ig`$bGH`zkV4@e9rc*R_Yzr)m_wLK%qct-@oNxBt4WvITSBWFrA4>w)O@9 z03ZNKL_t(23yYrnp;tubG3BXkg3w3IpmGu$JWILgP9N7?2&%sukCO6yMRfSXRjG}{ z6;K%2WSpsg(3x?&7U!*@tb@AgGM-LmC6aATcOdZ$!Z}>BVs3G|-UtL$Ab>pXm`(;a zWnB>>UestFKh(3^;(uZhw@UCy144KJC%BXQTJ&5d@s)bS}|*muIpEnSHA9;^9Qz!8yl`X1KaOC zLT)XzE1m5dw>;T}Ws}5UPmyWG&>6@c$yW;Tn9+69d!`a(aTU9vNh5iLD?g^7iF*vl zB$dG@f}X7qC50F_H9A$$c*(@VRUFJ+Ap6F88iO_n6HRr;vOn*kyw+>+xwMHGq^P3w zEjpYZW%g;G@=Lhp8=taY8`6_d+B=Q}-8I^Mqe@d|Sz*WoVdV&M@| zo2t(sQ>G_Te zC%7JN->xT^?jGoxERxgDYZ`?p{`dbl8K3Co&FZFdqiT)$a~BP zEjcd3jeD|cOAOYY=R|E@JSVX65G0X2FTzWSC^810_OXh<|H;H-za_)BQf64B-+#&rmhnIfAF{Pebzj!jM;!uIT|_iLj>5wHixl zkg-^;l6{FFjL4Zci+S8RDu2pG?CTSktl10lMg4c#J^LM8563+vwtkDs!AN>2hjJ)h zT#1rEJ~|RoKw5WY0Sg?n4I1s@#7e<4g;Qx44x@!2&68L*ge z69A&f9y?D^CnHpf3r1lah6bIE@9C}Wrkz$FxJ%ltz7WwJ8 zb)%p~1?Y>lUBg%#NE`3mGWOg)YHXo_Ax*=OdXdp7oh48F>OY}LGh6ItSk~Yos%g5k z+bOlkjLQ^(_Cv4@0Zqln!3B`W7-$zqQ_It*u;S>^;IF zYVV7QR1?_EEi{bQBi(qTUiH{+$@JUo+sa7Vd@W|i(ojm{J|7u1L{wvkD4gjr$2VTf zgV#?v{mQ>``pg--WW9m(dKpL?-}WUeJ6gU^L&wFv*ZrR>j=4wg9AE6-C}EKqNzp_G za`jpC4d*NmFUT+i4|-%?-W~o;;bvPb0es&x@c6c#u55wYB-zdoLmP#`P}LH5s0fW= znQa5z8T7`L+abcDS`+Wim-ebKRON0&qr8Y+ivyCNMb&3KPg9sQBB~8TnJz>Qk>@|P zg?Ft!Q`+F`E@>1#W{^lpyd8PJ&i=)L;OKt#qYi#=>ncUyNLhAv`XnOs^N#Km-3eo% z@Nee}kw_?Q;LamN&A_|?whiN1ploO~OWq}Fta77_Zilp7rmSWOgKu-*B2%2(?`@1f-)MqD7_iaXu9*mkwzp;RT+-*++ms0 zg-F~aE{|_$zy?}FM$iT8qw$r&P6s26UGx9A@iCC3ux1A_UW1M61DDAOCZEHkUl-*F zcMs>X{cHCuG#2d%C|DCKH%1b1R%=w(>6X3|_q7u)kh=M<{a7?*RXC8wjG2=3bMZA{ z-XIGLiyJ=u+{Wp*;Tal7Y$i=jxdGR*1`FqA%#B_IYjb+nu=;2gH@l1VZv_7)P`A$F zB@E4BG!=FtKIe0+@_~@;($l1jki>YK%w&e!IvtZBPk&2T&AA#%T695lvCmVR^uKB$ zi&nbeUa9)aO5Ut<82_q_ROh0Xmvzxm~0Bt4WvITThzQWfMB^fBNn@F2=H zrebD-il!SSg%DSQysQ)!ubh>UKrSK9@kj{v8B<0vw>T-b32RRf?KQ($3ZpOrzw&@| zBbNm7qxq??qi<#`v3h@D5@B@9me(;D&cF(XlsJJO&ZnffcgKii$L#t_I9dx=b1cvO z-$mhQ8bsZ_HBqW29FEZWV_sL!djH+nnC|EZ8b;edeWijn`#oLZ`&0c zMNffKZfzEx?2GNA<^r_ShZQ6{_cF`_3idp+CLIV`Z?`X#<`1XE0D%H=t69eN4OF>~ zboHA?rr4W0&mv^jG5Jck$CthA?~M3mcHKh+1VU5G{Xy$Ob8F@IZ$=4MY*ickXh$pK z8-1$ZD}*rmt8JQJ9ZhS8R4r!R>8-8NMeKdr)r<)%Pr>=Vf=DQd9FcCdA|lhhyzt|bZqEp z;aM=}IqHz9(ur$His=LHWswPA@%Wq0UsM%ZFCGEWiU9wJkJl(*BG-;nT*c_`=^0VgFXrJW@uX{jBOI$!ZfT3ck7P$TbC(_NtmS&-~DFD ztanAo%QZaeXA9iue)#M7Tuun{@>FuAwKd==ls+nBiMCzxdDTU|H7Ka0;B2cGvd!N%`u#GF|Y^sbkgFWI1zF9-YQ8Tp-hC!q zh0VS3tFEnijlAEYCdIs#8giJ*{fPqQ&h>^tqh3$r?#1S`!bR?zO9P_Tk2W9ecv~nQa;B4g|aq`E||e|hwa-@>b+Nr8+`y1$<58J zw?=DXMzbir!)}ik#6d{xjX;l544`=rP>_1*D7Ye#5kEQhl_tH8cxEGFm{fY2T`6-U zVYpWF&xX?WXhhLus(z64u&w)Bhpm3NjE;OGC5>g#n7wug>%X$D6Bmx+Wad6^cKtMr{Mex^uFWD>3`xHk8(wyM)Vfl z<)VhiuE%4y3rI7xr-I4nSi--xTx{(L^tL)!K~&9-TIDaNHA&L(?IB9@+za-W+*TzN zlhCynUNAXgY=2d?gN~K43^Mtv>=;W+zI9PfsItOkrOFR65B~IscLnwd#0o|GRfFD>T+TUILRfL6ZX8DMN z>%7KS8XEH%da^gNc|9i2L;~T;JN-S28G=QdrGt>!#x%~O3`gaPmgkF(nF#9KJmnqJ z&4D$@N%B?3WbS}gEn|E?mv1SObXgXbW#RPnlqa5ef-ijG3w+`epWwqE{xH3Fe)xxf zn0LSX-Ms$wum4syyLDTjb@kIBP$fVz>99HDh*rY(5k9LLmWMNIGwrW&F^x(bRjzIl}x&{GpLKk-GLif@TRy^J>5bAHX5%f8WcVPQZwYVO1$*2YoVl>N&#`g*PF*9R}-daKTO+;g+~ZQ{-&_a=Qg zly8?(WIrH`X}+S##is&tMr$__o`kXE3!nNdH~-IP(Enk>(HkG&te?`m$v}!H>T&rn zP^HowX{w5}rMzBJ#tZG?iMXA<&m2i;8QGWFXPwQM zM8n+5N zT+*j34o)>kB8IN0G&a|`0XDti%7jXUaMLwklsOlQuoLS?(cYNhC&UfHZSVK_4%Lpz zV&TqKdaX`FJ|+`Q+;h}p{JF6(1IEn*19EKD!?EuhNuvbQ?Q>z5HI;m3&+|?+(Az!J z72nV0C3Cl5mW99itH0u}|N5`_u^;;}-uvG7vfXZ9s^)xKmCtdib3J;~3sbvY`ed0le3;+95IVb7gn?{}5y z{a6j0#kkg-lU5ArWM$ozYFC;<0bIES`4cOb{b?98myDkJT^BsN^+%BDU_y+5k{7ZLW|Gmm+d_S0dHvp6x3e`8aS11upjHP)pVj zVLQTEGib-;A^vyOZJ9K(&mZ=YA=8~bewPbwb}vpThKN8FCL-jy*H6T&%P=TmEN0Ts zRF<4>A&u4>T?K9r#t9M1Tjp!6JcDqI3@dR1PV<(R^{@7h%?*)u)^=YdiZoGmpjK;zCp&ZH!EhBPOGPZj6p;?E?kzY93E9#;Z0+$N*C= zkLPT7FoZ=SVyC2 z=p+}9BEaJ14nIg%kvgNyxVuWoF{{<%ymcz``?beS)f>v+AU5ZN&bFO#zenwS$$O`& z{K=pE37`7Zr}&j$`4t{~@WGe5N%w4d>Zzyrz2Eyi{`}AX9988_Z+g>9-K0aguZm#g z?*#NAL?5BGSD~^qPx{sqL8^jhJr1SFh^PtoO1h3+VgpJU9@g>#mt1q^suzBAcl%_% z#Vio?ym?y)G-lD{LN6x7n12DT5g^sTB3T zNxr$d>YkIvQrXQnrTaJYyQ&F^@qB<{G;(sfd$>d<>o6RaDX8-ybLc|v8hd?Dr7jS& zshQ3b|4;y9bix=J0#$uS2%UkJnL-N|e@>O=0>^B(CEt=97Z)6|-C-b@>sJGHP=pR^ zleZC=NuLCK%!d1HYKpAh0>5>~;PyG}c1OT5%Iz|shjQ;1#pcZuywOmOnDKotQ*dIx z%HBUN`5y0BD`GFKRLZk|?QZMcf8J3aX_RwgQEM0XL=!juVEahH40drw#{QIyD^_V!8q-!oQ3!avpxiKNc^H5T+DDbuNzIE^>e?~x zF)!WayhcAnec768Vkl#wcpK!>(C~{iH|QB|rSe-FD@i?Xl2yB}H_#@YXd{vymYWqn zB(zuRFdA)1!Nd;Qlo^lhO z?$tdQrYtgrg-8&hzTOLd)%cM8FO~c?C_Ote6W0q!YrcHd`IH++;<+Mkg)umcsfThX z-&mO&L_!A7>%xrdK3H~V(2jsDdg~hJUwbo0H($%q?kcyh47S|jDvHQL9LN(f=uJTN zEntacW9KEENAjh9e*!5 zq!QeH+xcCdm99?iNE&>(M~TzP{e(uXFb!zsbQg&F%O+;d}qaZuaIHV_NF?_ zpTYYi!j%=L{g8J}<#U>pWM1>Iv#TO9$_z?QH==a+8qhSHy6buva&=hvf+om_7`0lM ze7L!Lo`GuI^U2lbp#{`wZW(TChR~4JVP1+1PRE;@->bWQm}v*LTy|=S!_YY&ekA64 zLPv89>qyFMgUeg{zDluL7TiNm**mlgPl~zT%c}526FT9T!xZZ^zsK5>e6s=_3nS4y z0ptB#Ua*n$$AA3CxpCvh9e*EVu-ol8J3Hg4r=H?#U;7&W@-P3w&6_tbz5jEc`yB6o z|NHs%U;lNkU%&oBn{{88_r33ZeDRB4e5sppDEDYF=P%1e^+Wsx7W`tQ3t@g7yS}G~xzRa4jTV z4@y(xUcay}6Rq35?q@PyVnGkH!SuXac-41md$!uqC^a>Zc1wGl2gb#F+jx#0qnK zbI3d}f(sWmu2ZabQ8338SHiQM8Rw_jc>7prj9)0WZu~bx&&&oL2q$$T> zwrr1XaQ()sIXgY$+1qDjQ0oS{C~zOjOI-wE>uOn4Ap6+c8NG%I*V65=|>R^Lp3;k3EAN|$=<9Jerhd1SUU&}sSq z9P3cnf+{`V-F|WYCeGw8p4C>A;Xx#{Ba8u+{<45)=pEW=O^~hkxEX?X>_8XuAZamf zX{EMtlWxY`g-+W5T^X*ZcMi%fnYk^Zil6&>YI4Jiiia$BbjPidvyPb?=2dw}sJ=ExhTC5Ay2oeKp_l z@DY!x?Q4}CI(8_F*SNGO06?1P-`vKMvVUdbD^jVWhlZG@$SnlCS1Jw!cPQPwva=t)*N;tKXzZGpN7GN#hfLnwb}RZGYqWWNkvMEsLhO%tqiq^6mH17Z zT?)+>tzJOukg5P_evy>NXBz?y_-oc}fKKi_$`{#fDXFl|y5Am0O`Ijju zM)~3wzsLtZ@Bx1HSAUh>`yFa{`Ighu)0eslhjL#RSB~Wv5lb#JWTE#XQ*=7?ZBbgC z0f%kT+yjEfIs5^pb=V9286d*z<40Pp4#nKh!z0hqb z07*0Vlo}sO?EWTmF13tNx)ZkfdEebWWfPfeK^KMQMpMC*`xtA%Pj_8xY7UMTn@w{m z7JsLo4rf2C{t{Qv(bZ={H(3UTrT-r%e)qtl$fDQOR2)pQWz~3Gk~tqOA%JU2Sta^qh}W0Hjb_d za<0g^jm7OV^>1P3d9crOxK381A^u$=&S_cxiOeJpx5|*GOa4?y8#tjue;#}{JyT)< ztMjU<SXaUISk_8f^NGraMECqJE$qdrh+nGiZ*9KGZNq7IUc|I7sgO zTHkDXJ$TE{v2i2rvDX}7Uktry>75KL?k?x~JY>x}J%^$uRWq;-N_@)tJZ&;68F$#D zMxbQ%-27s@{oT8m+WAo{Em}uqXk` zz3(z`qp!DXj<%1n(k0@-l5{(aoGUi9`WC2Xa;_SwdSKz@2=eaNTfTpW!ZAixMuN3$ zS3h5ZU{1ajm)CM);K*MNn#zmrZvXn%zn)+Cg5~s z3&_$>e)5xi@Pi-ZJ@0wXi`}$CIh2=q5#S0dKIIXOyOhF2j*40DeNOZnKac22PzeROeJ- z++_&M&aUUrDF?dvSG_iHqh4Dp$YJmd7BhjYE;!WwW5Pi%Y-<#u211CLh?6cIHqA0* zE(0CstdX2iQ?&rpIo*IpCT_o7Eg^;(1_EWM_Lq0$~~w@D8&y z#cySgCow7Sms)=qS67r}URxPnEA6Os#p<=)xue3xfvO=7B@J-BkSR?C&y>iCGf{7AYlb?^Z0G{RLtGa9x*WPqG-w{Qgxg+4 z;^A!#@+NrvRGhDQ4B9}tH=#K)Qo=P*ZL9>4Ve!aT2|6^|LcXu{mSbHL0A->+DMp8V z-A3I!5p8t77DFy|Da5z{VN@M7b^@a&JJB!{#EZZ+!E}EW{19v-$kq(v#{)Ktuo;8f zH*cZKIkG%!%lSKB$>#crtsxOp8aH;(iug+3!ft~dYNc1H(abJJw+Bnc&5Q9$b9sqf zlZc)ev&lAc8^&Q~{5};;zppdLlHhf25-M9yT}yYCXzQ|*G1*lIIsz$8y424V?`t?^ zg0c>kjK668_qMh9{_&xr)1 z=2_4!e1{kmxze8GSk67OxzWuqKvr;f*Kom9 zmKD8^IMTu}y&?@|Wj8zVTBIT22ETfR8Op*dsvI@uC*#1@wu*T5*AW1M>Qol=FYZ(g zBkOEa@Fx7P{nSkUUX6Nf(O8W?5C*+IO(H~R8 zWC|Ig^rCnqqgImfNO>|8l_fh8ioCZW7?lq~x}P`{O0_w%agI|2jL+7Ej1-*-5H05-n5hF482KcevY* zj5lQWX>0jTb%RA<$;6dnMbV~iC=5x^OLKT?xQ$FJX})&~0ESwSjg6n;Mp{u96ul`8 zdd(`?#D$7s2LV1l8Bb2;>8$!#4MxVwn`;3qL5Lvko*Bxv0?&wWE*p-oq})1;bl+D&>iS8tAuR2U`f~pwy)3anmtgS^><01pD9Mx zxIGa8frN-e773S|1bUTeb+6z3g!3;y#uNX?@4z*IlLz3HSK)tqH@xw`gCUIWYdJK6 z$YSpF$X@A(7zm=C8`TN8xk3i*jdlVu7}{tf6bz$wM&jcTN(vux>gS|n8Z0&4vRAQ? zfru6shQT}(YJweUg~7}Fh$dZ9V>FJukAor*AI}-D)jcqp#aGP{mOz(yOgA@@hLSCX zHiVwt=s8_^_~^@``MpWCeA#74giz=u4EH|I8p^e=VMhfA^2X1`5~06o!UHFRs{(rS zoTvZ(v+TZh6F&VZ&@-<6-2ckpiYc4e-=k|Tq;IzR`vIXGd*TmGx#c8c2E_5!} znyboI&qU(-ILPdVh>v+}51BD*^9IowZr#Up_+aWhHBAvFR*tH|Xcjs^cYE<*)Y|ED zYaxmpkt|+!v^xZw*6a{k22DLhoaW1nlLso++hK-bXrYORd?94mz^Pj?wAR9R z_`%eedO{p%gtvg*-_zEZzB%G9=`(RnRAGZD;d+yiB+3X6Em z7-!faf>ox_HGFJHbzDNL+5HUW8IVOQl6Pu?Juc!(W8Uk3ADkb`*IWHsONB*0H zMRZJKVZ1t!zK#UN-C+hJgQ3rp={SwYkg1zsvdy2VZ7F?>;P7GT@ZVNKmGg|@(d7SoW2hq#S-t%k}cF#*nB}D~|5g8l!Y)5XnH5>N%Me{6g{lBImg3Ae+Oq*w>-OCV<8T-Y6oL2mzIjv zANxpSpNqA_^k7NkOYWN7LqT6%ff3BkhYdmUA>WTW2D_a)Le++Jl;G0U^(_y3@G*$* zP3Wy#Tir!|jFD}i)DUyA>EZ}{r#qo2`N%Bdl&mU^Vq-mm21>ZFN*=l;-4?^4%*@Jj zxYft2jp>qV#sadR!)vCuY_?lx$&*bKTE`CR+$cE&7H<6Jli?G z`WiONEw1zpPj2C~XIFhm7>yfESPFYedBG2jg728+qvhPFTf>{9bi(y-7*|>G>lok* zdR%D-f_p*up_W>L5lsZ}#m$#%#$^%hExlJ%eb=}*fm`Z*otnEa8mLeE-3}$iJZgOX z8Ozt)JQm;8cutFbQ97$-9Y}};{KcJ2;k!I1C!*vZkFx2|5gX5Fwdz{SOa*g! zjBIn3mHnrD(V&B7Avt4^6VDJOu}dJ4tua>aHK!V0E zOToy!xnxd7&~8eGEUsuedoj7f6xd9t;q?!Hr>ZGX!97=Egv_=j*lFsl*^Mx8)&sT? zb~`32DH2MIbWwMs0_16fGQY7rA>s54)Lyv8-R`JD~_gW>L{0DBq>IODj-&g zH|`H1Ld!&HMV3bMo4N1=#5d*g5d?EZwn#2$7+ zRZ*lmu)v=d*X?3E;=Mc29hvw+VY+Jjeo`S}+o>dm5mv}pXn7*DQmgFWP)@kP>%QYH zoILa<{=-{e$G?5|mVbDK@B}*xQ6baCD+y~8(tztt$)p4k`#JVb#F&ijUHE~5yLT2E zC#B2LO?%L3JQ*VzNO#L1$3Y>37X0&l)ibo9gg8xJGTjYzl5TWr zb#+eN*bs+PImi22tTQO}u}cIEB=1u(gQ2u(tj#)tZgx#*l7K@F3oUD=Wd<)5r)il< zUf~p2RC(aWhS&e_8+q+*<@G=EW=_tPPrqu*|0BZgDmHH#!=_0~hqJQEgPV_c&{t`l z#%3CU!@ZO+P$zT*Rm{brI>PAL)*&lguT(EzE=uBEWjk5dl=`@i} z*uaXO?z8M@yBNJP^tbbn@IK2E5QxOG!w*zM)>Vds^dJ%<;h~|J@@*2|eT?X&14?6& zBZhX%?$nF z`4KYI>a9N4p;P4>>gs2J_3OOh4R7GlM<1oN7l(K}pQ5UK_OqYm-~avJdHnIm z+3j{*yLOF-AAXoOzxmA^A0NNeO+1uuc~RgDLy58xzgDjZOzyxL5y`8 z2uB!_oQWeypQsF&3T;U9DvES7u%)oGIB3O{vj7G``Mx+Ui|5jHTUZGw3W>1ME;DgQ z?WLnQEP0dH*Xr+>T``0Liqh-KOmoR$i~-9qfewY%Xw3{C)=x?0JL0E~O!{MeH)Eu; zNatmCkge!2giGJ3;bg>;y^OJ;MmCKTNny>531(c3i3SJ|r1g0cD9vrIEwd5pqO}@i z(_J}pq=1;gQXL{}NkT)=m3cVs$gUx7fKcn8bWh~sLV-WHnup9H3=Fy%KO;sdq_7>D zr=hI8o*0VWeOSWQfLVU)QqS$)J3zef|9xsSCmA<`r=f9v2@P$ z6^!=ZbKZ|xmRqPi27DFt8SlrwQS4CejUtzPzLW5I**|ctlIda>$j;(k9#v#QwmU@> z448ydzUhAmvXu1)A|2%j3)&pW)gXRlpRf8A7wx`tZtzukgw4@|TzmBikH2!mt}m87 zSQ;Xo;fZ#}{^^rw9z;}{X#YYJ^*%}IbKTn;JpSCs?LD#lw#STK3z0Egy5zk8O~qro zNz!sl;AaOoW2n(RZ`;6>U>nzA7PoDovoiVCObF=6bPXPuoNyxcTa2xDFpQ>B<|F1t z#8ID9QL=!nMMas+&=n>};|70h=Bh10kNpmdi_;P*J2M;&Lw0qGt+^nKoucPff7?ui z>rQu;i0M_G-LCWG*l?uqp?O<`2Tw9u&ZBkL_1G>u#&Sns=c0Z#;50eiBfYXf!MU*_)^8$woA%G!*Y9N`%tT;EBb}GTRhg+}piFH)x9x9*1%$&$q;iD!fQ-b>+Us z4wr{oRzF!RhWB!Mgr0ZCa?aS?qRXk(qo=4Wc!YRRlV>BOkwoaCX$qRHk+`-8fbgcy z7{>N*Wqy=GOD-v4#1u7S*=T-vo+lBLD&&E`f6hAcgYEf1wT8DuDmv+h9fzgsI*d+t z7CJ+=tc|G?WvIxE|0?^V^}>q}g~_hC7lh8{uWxE5U*s6A`}3_T`-ZwjQpHG{`d!zf znubXYnX2|7mB9!=z19KJNQ#3bq&$*U#9ci<+4XY3C$_UjvaHFsVz@KEFvcP;(;7k* zsXXDEQTCQ}#-ANrvm;$8207Y{x3&|TO6hky8o{QmF%etv(`o8H9x-~WC9Zr;4fAN;`| z@Uf45Y-RAR<;IO0y#4KO=Uwl57Y{!8;MaZE-~HX+@teQ-n|J*EGoSekKl`&kySnzC z_q>On{K=oZ+wSnxQ%~_nfAmNE^f^S0D^~ ziYrj5{Y(Y6cnc;9X~YYJKoeEv5lF>jpfg9vo?;Qgh8f(3Cy1E8Yq;iRHiec-w1EO0 z$(ra-B@JZ~?iS(7?h2X@3yK|7swLSFvFz!iEg9Z0VzNnLR~A)Iyv6a^nDNZw8O+v% zz{#S;?KaJnR9B`eL`4%BM!JJc3Bd2$L&ON0Xws>iPAB`gFX{>LGv-1BPvqe)w0T6E zFEAu*NJFA5LXI!Z5-DjY=^@|8So_2`2BWpSKAOc8H5;c`+&S@<<&gV&54T}T|9nj+ zhC$8UYapDBElYnGJ$evXo(BCqx;zCu6|0Lwxz|e-p0#{`uDRQ{lC*g}>ZwMYefPlC zy918zF-s%fC_yKkSTx0w-bL~@#gM1Ve0KGYy}r2NZnu4aXC8bl^3V~Ve@J=y+TiwP zphL}dvKxXiTqTQEYPCuzz|nt5i&Vr^4Ei*r3{B8)W$03rGD`pISgzk|f2KhT?3o}T zcx>UC&3xbZl*7{E{=!e%($g+-dTe)_aX9F{qIf2OZc?sEsrYwCL7FSuK z6=2LZXgL_0m8|A#wL7%%l9)EXLpNKK6I63q=kV&BE?YXWNXC3sv{jTv6_F*;y!+^+ zeafTduk~l+NYX<&lowip09O8F*BgOZo2H(tH%@3r$83+U&`++h(^FbIWvjRSVEi1F zUAojydCcm`Se}>i)cw_dkzQ;5UlFEWvVL|SdpX6~=;DHh3X3im(vfUP)-9O(&JQV^ zg{^+5%FKn>=JCl8nS+gi1XlNiSA+5QAtMc@mvFBaR6@L0@53n9@{XLhhQWvH+rL>Y zd5$(RW&4<~RCS(569O?DvdV>#%nCP?PhXG)?V6ypq9@7f_b{c-^%w@zd4xGEltNbT zHB8aM0l%{*cDo&a`?r6~$3OmY-ucdV z@-sj4GxsDK_E5f&5`=xwI7j&Z*?ad`Td%5o_!;wEYwvy9bLr*uf|N_SwA>X$TEGut z@-=(}#76({_amY)sQH2sqY@=CA<=&f67dp}&ye6HVoZnzydY@&B3RIqE`?S#0vSxF-*Lv4{=Y5XLGshV7epGw~6{jKcQ~-yd zIzn`21l*ZOJ625bio}F{10$2Q5>0NX5V`9L8GV2Q4z>{#6IV2|5^Pl`Wt9MGmw{i{ zMoKsKy}BkDF8q<3iio$JMot|saRFs0z-;jD57AXba}^Qzl9okM5>Vh{h17uf>#p$5 zG8vMI64_ahGzx04e0SRAjU>A5&)c(N51NSI?59 zJ)>Yli_<15a2&(({)Pd+NG^LG~mMoCP~tU=ZQXL zr6I5Xw$5o?Iu^mhL&3&na~wW=1RKLaoVxo#Joq)g;d~`1wod0?%9>PjGi-};0$4`M z-)YgwvMQRZeZ(VKQD0uiS;_J;86cWk9GeESLhl9pX<1Wvh2YT+F1YdpuKwQ_;NdGT z#KRW|7F)n@WPr?ubbjTBFU1cjoOmktRR^AW`y@4mykJQ=0lGt*+|JP21mO#~N^b!V z^Nen4MyedhLUB!S3X*1RG5hgR0|H=H>t6L@oQbw&MEJc$gk$6Ay{C8mC zfU;3A@Frgo)Ul$DZSKvz-L0+29&2@l-Rs{NAhUw`Trjg+5K)~^jAf3+FpF4!1%lZK zV4)ay1dHuz7;Ci~trda=)B#NLv=I?kntd1whWUWmTrg}1#@T?82Wuh`B7o$Yig`?> zwCSgn3`5|Ug{)X8Rd09otq~Zr=Bf1+D`?>3^2*yaaeG-i6`J{(0<}sUCK{V*5C=e3 zV|&B^PwxAaAzWu_3IpQ>26EG~@0J9B40?tf>$FaLN!{v&$(puqD;6lK7(}55kK_OP z)z{*x>#xB>r%q#d%7DA)cLU`(W-?+>J9w_DkkX7TptL%788kp61mL4>M`0QGY`efX z5WTD#&F=lJ{JXZjq)xYaK^m3RNfYw#BTv!F>iwW|N=Z4$w}o=Zw;vlw!D&Kr+V2>cyicBx41bm~3Yrz^ zbk3UBqX@$xZc{#YshJ%%C$kgHI~8GyO# zqRxig%Fmc(?J0D22MiDlNwUb_71=e}xInTfWOk?Xs$y0xove{HhRj8lI++yS(E+T) zR0(Qzz-v}m{ksf}&lDK_s&E&^;7|zgjekr2t|`w{`f^LxVtIsMofNbim(hgCEL{2j zP2iKpF{54Zn647mQ6{H(-ePQAb42_M5M*#8o=wI&E|a*F*G;V=k=?K&yjo<-!s{13i7sGfrWO3m5AuKvI{oxmVQU zDxNG0EM^tMAvG)6)7wDVvGu$LNgpRE3zk_;nm+fn6Yj#&vi&5F0E z-v&*V?3S-}^w2iWUv*GmULczVv${b&tHFKpl`>r*%5l#Fbw#z%FwG7z(L^9%ZwlSX}S`PJH(<-1C3jjR$rfz-eq_ zTXvwLm_txxhEXa66{2Q&Ujkr)lm3b-1B$zmx3fsIqBfR5%%JgMBm1_$#i1sKx&lHf zb}`g8=h6i{ie&7f2tY^zGP|ok&k=? zhYlUWjW^!7RQ6?;UDjEe{>#7oOV`gshYsO;zxR8)cdowr>a(`_=9_QEXFl_p?%AP3 zhw%L8KOaYr9t8m0ci(-u`R1GP;DZk?z5lU~eGD&o$xHCkm%j9@b*8J;bJ#04Wu^Aeyl$D4If zP@!~@+Q{~1Gb3K?)B&;nz2v#${Aa0=3M|m?h1RaB1*fHAHjbF-j_otLDoLBobvmC@ zhHkLSUterlf>ofIrccYs?|8mOG_h>4%Fjc}R}hyyNd?p{cG9pQ<@%aht9BY(D_;Qd zn4Kdkj#b4&sLj1wjmi`;pvYoXn>FrxEA_%@w2`dZy`HyzGp4~YOpkyyoKn5^0AV<9LQym+&+s?|V1 zV;2H(D^b}5%BEtrA=sD~)DsmC-+3Hb6kA6RV%QkMXrL-0e2c(iR0hdvciocKNg9R* z($n?NV(e8YvJ#BxsR)WuI!4z!j96 z5}R4^EOYneF?CNdAP&+cX38c^cU)eo-R`o2_+OH22XVn$QrrYtTqI#Gd0 zajk>$2pJ>giqe%3v=Zj0*vm9~Z|m9m!4y)r^yA-L*{K(0hE6@hbM9(M>P#k#J@{@f z>oY8uEa{(K5Biw8Z3H!bw;fiN+Tr*=YIQpyLAs36`dM9mB=|1D6uS{Zn>XOmnu{k| zI&VNy0C>`qp0os#-gD1AyXHS};sk#Cw|{#HAbtANpN==b`OSFdGoQKgy&wPaAICrc z^FQNH{^U<^?AWn*{*|wM1%LR5f4DCz$$Rg;xBGtMjW^;)e&k2G5CKB@8r@F$<9BUBV3wRZS&eHzdygTm zjXW0JyT1MdkoEFoY^0UXmsDYZ=zyUbpddV%mJyJ>dnByWW0kn^`FRR#@cY!VBGUy0 zFrwWqFYsW*_BXVbDFI4rDTqh{Jc$;m0$4y~Ct2H!uy~|9shmu}YWpq&hFQT(0bm1| zA3)LK2UVjh0e%@%ao6agz%ZH%Wf2VGSE7l>Y8D5A>^2LphX7pyPF2&HjMI3JD{0$W zytPIv8laU9>l}~@g_(Pg!%EkBS2B%Pc#O>KO;Bqq4<(dP#3URINazq0NOoa+vng6jH0Hn~e z$kiwO9S?I-MKRM6MHhDdCIza3 z9kDoj(80uq0#q5HIy!%skPS#)3tCLkcK9ZNt!twB;@d`C7Etab=R>@hgE2p2?0o;w z^?tX+F*Ql4LUe&5)maZi1SK~|wRnMckCV8UOtU1id8wX%S!Qv`$hWqEu6s?wKIynD z$E?#j?JIGmE}UZw00!F)ERMmd0j0o8%g;&jO5po*f!9e0`=ysBB! z8I37m1b(;EhG0ac*bG|r8Q-E9CsLh!5g@g;=h%;SAye@KD5T#Tcb{p;hTz2qEe+%Q z$w*B({gi{lTU*@@*T${SXaKScr0(M$F^=IpM*wJbYjJ6XpCz?6_#qr$6?E+gdZY!j zkWX?6(^9D?r1|8y3NX55W!Y;(_mL=ZtsZanfN%qQ|Pp#AA zA@%Hh#OS2iVxr70m}B#zEd%K0K%M(3Te7&387-!=a*;^40`9jLTv=5k?hg{v=y*Z~ ztEQkB-&DG2dz&cXWHX?yISCMB*;8H^F5tjwjl|nhS?4P4WBMMoSLXNj<@y!P9UKyZ zk$U)n1{k+c`B`D>*`>64RAPQuZ3QiQ*@xOOR#-I%U&dMKi&r1J2)Q8X5IM~y$B5c_ zxQU_(x61lcSzSLUspf!48b2=q)%iJG)27c%VWSjsf*F?0RQYGg$ z&oNrQZk<(B5iA@mRTHJS;QW#dLPDszv{s-Egi=wkIJGIbobs%oAPpUz- zfEH6Yv-4PMSN@0gegL!;N1t>Rp7qif;K73x|MQGZoZ8xgj$`aq@iwSik=g|~6u4sCD9jxO)OMzf;kd(7i9ene!o?%(acw~dxVWEm*sDe!%{%r_$<^_u)IHkbG zX2FF|z7RXJ4UDsb5d_R&F)s-bNcA{=?eIq&7>si^(wqc5w0_bq5mBc4OSA|z@EHbf zL)-WV3pNjub`g@7B~$@zwzQ6@vOvWG3mps?4eJ<<^$<2Q-cOb4V6`iGwD3tXfZvm7 zb!RZx2f_ZdHO?>tHhHA;=;*Xm@rwdi?_4HpqnHc5xWyW5Pn2}nDT(KYx|@Mn&PY2c zUI}#Mw#4#1L;Lc3iHok&Iz7T=fhMY;1$`2t>8D1m{iOqeVR{a_m&Pt+(iDe184cCdl z>3dEx`MW%dUYpus63_SZ3qsknYUm+awb@wsK_G9om+*i(dtyJu=_u)YzBOIE4r?3d zIWw8vd)C$plDuCbI%_odQKCvy31+ua8$g*4R(G4Z-P*UhbbHFniZiI+eoZ3+VA(gw zw2&N5fvxUSJLE)kxSMqWRDExX%SAE`A7JhE&9iI2zSGlr1(I%VZZ17ri#M|HgcGTL=#Xt0+58+pSo8SCq z+1)0pm!_qKm+fB-7ZCVL~z9(&<`kxz=R`x_O+`MQKmknDDZS=Bkv(o9*&;7C@49sX)wC zb!9&g>!KT@lIqXx%c(g z(ql|D_0a{v29`>j&#8c=eBAe>IZj=)jguP#FfPpU z9HS{zrJ%~-w80NNQ2Y?UL$?%#xqZ3fAmT3jwsB-IrMbA3Oe0z3Lu3JNIq2b5P&6W5 z#BH#?Z)wRv*KD2vsnbOf^|;I>$Yf!glD9z(;7Z%pPrvJ;23W|xWvI|-tfK=JFsniU zGC&I~6hT!CTZ+xi8Klf`T1K-c@%Q?bfG5a0 z6{EIs2@78S9%@|s&N-rDFYZb^C{VOOWfKeCgos%U7no~3pqTsmv{-6@%7}^)&;pg> zU`7iYVC@G~tJ#@F`yAxZ73wJ;q>p43ytqXpG{LI9i(sh*u(jc9!QdMQTtKT_33XT8 z%Cx#AT@4QxSB6EPl~$!^wqnhz;B2WW-^&(B>$Fb$Pqv!4;x%HEGMP((?5JN+z%WPt zUhpL=#l%YuTAf92by-iHt}1zh5vVu>VQ8*K?-2CA9b&f~-?%5~VcV(E%OskvV((Kf zzL)))lcrB>2l?D`#v~(<|FN}##Cx2M?WY~eGM2^F)|Montg<3a1_15Y$KLD4iSzg^ zAVW#xIiu9oKCkG<()0a{WnLtTOu=PRJE?v%Zpm z8<$;n*`CTcaNxkcE??T%*uane=#S!efA@F0=QrJS)3*&Ief{fSk3)wJ?K%JT*I&N` zl1@V-tkdH;k-cQFsRFWtDyMM@JE&#Ah=NK*II^k>{l$%%Xu(6p(v?*J^b-gIpP73m z;vqHob1CjRX#`yvlqHlw2mFd#?a-C7X?X_f@lqv%3N--|Q8(-5^VHWEt_*0bU}UR! zuuk5gGFIqD>H=jIck%T1{c2tnv3PD`&)RLd252lZc5QzcKh%}UG6;qO41-$Sv|)e_ zHC*k(-H`8Ug)X$sYaOGkW=WdI(G>h)uvk(x+L^{2fD8_H!1`qI0Nq8oC<1ipEK&0s zO?7&?QVMj2upA<&qEL6GZ-O*9yl|^G@elzab+{U>+FPqiL38JVughYw{o3LVfxcM| z({0kgtC=OWs9n@hl1mSgZ~9!C>2qGjs+tvphb*t_#QIw(o}+>_}*08W44`* zCa4y>Xdo2u>gQle@{TeH%3#WJF{$5xM74c476oK%%BJLf=OE%_Oh+om+UhE$G{sXD zRcrbTR05ZLHlvGwg?iWwf_7n%q<|K4trRGV45&hH0L3W40*W$>=KfyMfIFvS2!09( zEx6nlJ*+#?EIT<6aULXQQKJ4JUzExa0o8d^R=A6gO@W|DvGY0yiNzITO}wqWYk+lg z?ojM_oJH+~4Cr@W9!xDVX2jPXaCWhv#2 zmS3Eo`iNn5YCPLOn;I_u>T-%mR%}aCQ{77-@B{}@189fKHasw1TB+xj8XHp&>GCKP zx=!DrDeDM~cj#+X3RDuDQ0CA|Dn+=*tUimo$E$~+uw1pPg@0*XX=0S^{3Y%g1fl;+ z(S5g`bY)E8HJSc?<}&0gd3P^Ex_6h#-~*j}=FieXkepM}n8GHmP8&j5Vg=xw8e+vI zezK~lDDK=^yK7n@8SR=+mS$`Za@M|EbEZ0WU3K2N?DeyUHtfo-&R&1NdDdxFIpz8U$HKRt|53mLkyV^Fwg7 z$FZxQ;<)0`78+Hq6H!a1qGGy zpHYow%N&9cwT^(Mc*CIxdmP1CG2l`FnHQ*EJXcPhM*YMmQSZ7NICuf%Ro@3Z^T~jW zkO4-gWPqxmh+PoGIGHs8bXKq_1|tx(U%3|vL=6M9G)s%1L+oo&gw=Ow%49sv)v|dk zz(A>yTDa}?(cR<2ddAxZG0Q;@R1zSY4(b4#!s1Fw{2qMFfiEqJ5etkMQLzasMN)uK zM{HvUzzia@2C+E+t#H~X3SflRYF3E>P_pY9{THXLMbzBmrG{66g<_?JmenzkCyOb% zc2S2o_-DWdZ?>*Z&s%632UW!{hElImD?bOQ z0c*G<18wnOYm6I3j%M-3_`m{#hiu)oHUX?-S*$qsB#&lc>+~I&G75?KtWF~-s}>!A zVGAfj9GdVTA;=*ut@FJFT|GT$69??bZpe?UC%g6Tk(BxE-eLJLZ@)lkh_gO*Drg~0 zI#8AbmpTc5kfk=P0!hz*_^qG0sZ{lCpVRZ8gmr4^yaGvAS&go`Y5t*y9>O=i@r~}; zGoJB`b3RRZ#xtI=^z4gY{NkQL(wDvLW&5sk7zRA&InTkr|NFnkv-|G558wReH*xvp zm+!m0{iMT(563O`drhm{@^`cHU8l!eq7unVMtmQs0aB$DQ;rGjp}E#Ge|IT_pM}A# zN*m*Z=cmTSsZwoa7+%^fqhSrl4RjIty|=xk#T4Kb&!-6yqfxJ$}YkXxH)yO6)wz5fw(m$=Y6cR=Eg`XBJsJ&cm$f<%Sd_z zJuwW;Rv$77+iiNJ2p}^@ARQzvuKcnLx7v!n%jn81P-_Dz8KM9YE6eQ{c;YH; z4B$XPv;hK?3Po{19swR$d+o2e$lAp!4GgD3VErArhlXksc;P{mqfbG-=QKpV;fnJ* zo!{xP5JaczLMERx=m3wUsKw2NL>k0JpebTa ziUEwgT!Ii6X%4L}ogmr2G9gLYno;gmH2|v z^`7kzjA7ZB=)c-EC1yiez3By7-DrXt9%C;sJiHHT!zdDOUUC;xxHi5gGqm8PTVy_Bi(mtg=N@zJ(U z{;vE@yWhp12_$I6UZuy-*FrCAI$GZj3BAf_R_{(u@SA#u#LJ|>*{QGTd}kf!M43tQcVFEDK(^91~lB2O`#};q8a{GB-|V` zqosvKt%^Fja^bW^v0t(|aV8l2Qb-8NxD9%op^GJWpJSv@%m)1Rlo? zA^gQ?hJxdQi@Ui|j~@mHE4{cyy9_egIixswQe6qFK&c8H3JgQdS7FHi60K zvz0L^YibFI{9PyS>{3Q92W%eQcs*{Ma-9Q0M{_@^Xv!|ZyaHgr19#qu#s7N~PFzud zrwH(>X8{*(V0QRY96dSUuDg%o#GN}BP9MRu9=ZUhcNDkIfm338sno$PE)su6*lE~gORb{f`#T1zN;I&%L9H}SY!bZz#0wK^thx6WH` zxA7ab0b~9yX#t$>20*KTSz}7KLdM02aa>qf6^2oPKy-wl@vtg(^R9VhoF>KaIg;Q( zsufii;Nc5k<5_~nQ^oW5f=7g^3Lach;jL1ji$xp&8rv$)KN~L*71Zrh7MJ$U|3UeW z|A3r4+2W&aY+&)~R|8jE3Dg~+RMaY{x&i0_EM~a)gy6|rPs8xM3$cw6r>;1R`%hnj z2ew9>8b_#{wzevaj-vWx0&#P4JE6lU1Z)z&4)lDqwLA>ghYE;5&&3M2xHP9Y<2= z6iAul;MN9SbHno>PyasDCtre-3{^sXA!H$e-B6#7=Xp?2>6$MHaZL%#8BGFsh)q)n zO!#Q}JmIVAd963DW8`uICToe(VU#2SsCx~FKy;PVHs#ZkHdw*UV8IU$dt^@9`!xB4 zru{7`XET7p;8Ly(m2)d0rbJ50&+&eYIzBv;~1 z4Z7V+^k`gf8Axq?sgZZN^wo`Pr2`5-%$r!>+S()Ftli3pwxb>L)fFw^@}9oi=bKP_ z>M6=Klw^bkVXsb^Nm6%7`50zWL2>o>N)-N&5{Auuk7OiRv*wk6IkGGa4<01Xrr zkCDbOmH9HK(A(gi->wJQDYFS&;_l-F>lph@oT(1l-f8@m0+o7vNmD?EY(eTEpCq1T zn4l}@SpXs+>I|-g0+tx0mq)2Yf)V2!K%H0yI>fjJvSH_7+6kO}ly00ED>p zu&U)>z}(-FfKHA#0RWdW%}c$pUKs>369X=W0vW_(lG-zr;)0Vpv-c{7HUx&d_029!3up`_uofi?@^0OE_FFs3NytZ)s5ov?!@9CTQmQ>8@@+aghh4DF&1 zSxP`j4J`_$VB|p%TNF0|?H_j7_zgsv@E{v)ILos!KtdPwahJ%}s zlZTi_e%z&-Z>GXchJ;NSrq zxaxV>x#YXB*cr_i-aS&F0xT3btvGbqMY!ami*Q zDA$v(6=NL1V}tIGV@NAX@RaL>Wzh;b>Pve#t;gW!)z=iN9XVv#NUK|~`YLjsNH9UU zVi#6?6{@uovP^@(_m&!{O6zO?>mdi8`0DIBed|)@3xqjsB* zcLhFs=oUO&zh*L=Tc?9Ofcr?b*-|*5DnaKd_tQYZd6cwGIyh(-vbq1&EHsi%`ge+( z0t*XLB0nWQmd{?wWH0&{@ExtDYfScQ?D2TNwJ9V6HJQ+KfM(>-m*R(2PDkj?rF=ic zf3G9cy**4T^_9Zmo6=k!=r}VrH6u4N5o{Wu$duYRUsOeL0?1LA_M;=e-B_NDhLKCR zB@&=#yl-PP=h(E zSAZ0-3!kRx9D$B;>x{Ni%A@J3lI`)0*@4eQC1*t!ll5XgU3eoJW_aDGVh%w zLpG;I8j=zS;}FEn@oKTuL?|TWae`Sk2G}-XKEdIV;1EKA#ux%(VFL#5hnGW~q!xQV z3~)EY*7k9`LPtRz6=SWPk`&-96p#_KK|S^>EcWM6fcap`?OY+V5hx40+hr!G1sDe^ z&@Om1Nh7{zFtk~9HbGhk3Sq8TB4lHf!GY4S&VhrjwCu8nfgORdZ>|6IU95f!v-(<* zGVk1f0s*D)JxI(a0d)%EMd%Vq7bdzwTFU;fS)dFjAj1w&&MUUOP5^A-Y@$(-ENHGma?pP3^~OI0fKggq2 zG+ElU@pS6yZtSc}lk=Z`2hMvLycT@b>5PR1^8NNsSKrbW~ z@dNHBx;DE`-@-(`V=}v9ghh}xZ$gzh6bn3faKztUaT@c>9)jW+X1c&!0mbNHrWB|q zk1tUDB0KnMH(C(~3sNoQ3P^{Wg`HW!8?a-C){GNP9^yPD^oYiMqYMBu6^!1ec7(^R z-4643C>NHAO0kl=s*jwCtHB70;Kcd ztLvGf@t)NTkGtI;Jh!o=Y|&)?<&jK0u`9#pk}GGGTowcFMnGnQ<6UjEe}JOGVuY6! z{4Z3dGflJWEhS!%Zr)m%!&3Pj{}Z?@+A1tCd-Bp9%s(;Hd83WpefQlf!Oy2Y^{GqG zz8xUxVzJm$zOAjTbFO1myw$zdyH4x$=p_<&Q}*nd1Oi{9ofeBdRcH8Q?qT^z>l6n( z&BBI2s56jCVMr4rHwDEmyzq-Uz)PK);88sfP|#wzB^Mb%`wVkoEJ?@cbq$LxS$R6T z^t;O>S+$_D%;6FTcdN(rE1LNw+LsJ$kg4vLr2i|Sp4pqU>SS!blE6@xX0)r{`f6>p zNSKwvPMKrjG3YGTCc%~wD&iLy6`D}myb!dAy2OBDwOf$~A;Wiu+*;tn*9#>9H2D7% zFe^@98)_lw0?4l7as2!yV(QV1L93-Yh+M*oH)8eq&=U~v#2Nw*DkcOi&_d80K$7z)nXdDG^!9Rq+(G<%*vt(R_k=0B?m_UoZZrwss))nb#@B(K71(-9sWOY!If8Fwh7D*UTBvAdE8*b{?snei;;25HYyQP zA=SMHq8(^D2&8FoB8`{?n27ccX(7#X#1)~ch>P*6Son^b=(4-z8&Q%}q+9L#c=2F{ z%5v3;c3DLNX;qzQX#*K$Xzli91(@p=r9sDw_?$UF7!6{d(;Vd`rhvIS27v=XLFIZW zZi=6$nQh>@BC#~r5rkFd$b2(wlo_tR>dAP?k6eWV-mJv{9Ge6GdJ!Po3Yl#{D?>81 zcAuV&I6dRD5pgkJY@1nY!zzuLNwx7Pt`l}j;UNH$g*Dd&_gC@1&i8snF%6EY3q!Q* z^>xVnbWxQFsGXY~YsC0z>y7vYiPfbNt`|Q9*dy3sReAmx3i7Bpy4!PE>$Fa*lhZ;} zj7y;}Ml3duqKftqm#wrV{TLYR1n|PzY&+t@<3pDEC{_GVc z>dPX!U1Dp-80}!A?bCSXI!CiYN7QGKAB{QSA!YVHofOS^PBdUz2ica8%d_Vstj!@KUNm_pHr_LVZrf=A8$O zowi^rp$2r>S{I+S$u>(MX*#gALs08zHo;-;63-@dJ5S86B%OSSJRNx;m-DVlF@;$M zNpDbudV;f+^9CgS{O3Qv^z5RGE?OC%b5(rIpZ(dN#VcR=%5O>A&Xjg`cFy_TRaT>q z1aw`ebvn1yvmte71O)~4f;za{rYPuQ*en(rvnK4wcqPXC95^eD83 zz=~`X7I~|2_4d@_3L+K#V7~c#o8jt~OV!)1QcxY#1jH3~A1^IE(_o#>pOiP~ z*`z{><4r7IT~43BSG#2tH>afa943xl7A-INoA>ph4d7E3DZYMzt&r-6ciTm9 z=ceNRK~V<*4^6F{WEIL_c-_QJ=RNPUGwiv%?zz;%#bLs?I2K{SMLsTV+?Vz`$270e zNt3b&ku6%|M}`1MV>yultXa(-sj9A|9=oOBRenIw{<7M$(XDk_r`=NCM}mS42sWXp zcA;ApKo=Mm$8d4I6Eoeyrk;Sv7^IMLlsHXnmW6RNKxq_!pw9d01dYGY`EJ?`~H_JTBZGabUc0m$?q43L?FYC45s)#@x(e7s}U zEPM+j4P(ngqn2R5is`JO>0v$0*@gA;OMBq}G($FIaiF&?Mzo!7^3DczmGY~m7eLfDI3EX^6vJs*xKxPGbkyJD0t%EOLN|Ur2qDB z|F-n(1uuBP%Dk&w-0!{j-bcMndr2owoOo2UHicLYvIm7*j+UlGn*Qg6 zUEo%I)C)@jdjN7@4ObD?BTac_{ty7fX|aIrE5X5QL3Vo&EH7J6WlIug=2mYz-wnRb zc1ijUpfLt{jK7s`eN3TD1HlYDGk`mWl8D!+axO&AB1bAHKhqAE;wXR zR|HiC6B0w%lvV~^Qab<=0nW1x6huW^d!<$3x^Myngv-W0*V5ur1rQ4gg1%;?AKPqU z+Adb{chyeyP2l5i1M+1tW<6wMTIoV11&|reBeuLwk+SNbXUdp<&micu99i*O&QsIp zVNzBWtbs;^ry@TWx^IGjTnLOV&|K`1-j(>*9MdYK4#24m02>g@fkRi~(&t@_+2uzt z8;)bVykL97nmdYe`ywu>OG>DSskcFrxR25ArJiT_=80)wpC>~f2R?j2o@CES!}&eR z4ogoeI?_Jp-+8+QKX)Ld&r`|sn`j=qeFP|j4v8D~YNM-5U>oyl8zW8mxfWKXpF2~pk+oQ%@!ZbAP!Eoo#ZT9sL-WCFjn^V!viMDppVop+7{N6+oiNCwf z=ZeIA)Q9HCWt@#}tJj7IHV6?kS&OuLXp8)kR+O5`%~PKE?mxi z^V?TRAR2jJ;!_UZ6rmkuvloqW0>;WF4lR$sT%N-cG6X;Cp;c!t#THsA$&m4f^f~in ziBW=Ef=W?8FiSGNuuOy9O4dEtQ}=?9>Z6_Ck2X2|Nd4YB5lvh_>n!$Fb$NLgSvsFV?Us+0iNsQ+OoZW!V5-P~d`++2zPb!exuq_ax!G@V0~WnGkn)3$Bf zwr$&}thAk#th8<0wr$(0w5@)B_v+ajyme>yp4ewcd@=60^2mSDY4*EW1`3!b&53qH zEVw9@y~iRUt-BBgdt0D+F}lnw0-9k^%|isMXRTNOj33>#D*Ub<^}F@gR=F2)THpleOO)g`&;BP6IJIrkX?y!wJjHe&u7n1sP7WR645H1AH#cnz_*7h7o_X z96B;_-Zw@pCJik(Ax3XH3(w-T{(uF*{d0occMd%xdY6w0G3~wF?&RZNhP&*Qg;Ue6 zG9dT3o$+G_eP}p5a;1rv65ArGE>lQqDkj=f%KW5K6E2>;2|~dDP{#E@29DdgkiIWW z5Lbqlond$i6x);o23wVbIib%1GW_frDU>c=8yPl>e&c^tjO(`6U|ISk)sS;`o~Jk1 zk8+}XUsLxFuM0!`9wOE*A{t4mMi__Y3)gUPkfM*=P$TGBjL2=Di(-dUVWDOzw7dBS zDLt?Y0KJEp+5|Jgk|9fy&J@o6QHyOQ=iHxE&BY43Rq3?)r)Y;m2jIt&gNb?w-Pj?; zQVp;e7i_9e!#ki)l@0|ulI;wjI0UmI`eMN#i0j`LmDS<(#)nlhG1_dZHCyKT&#cRR z?5d{BT)=Zfr8MON8^H|*4tWm3dT9jQ8cYC$oaj9r*Vo7LXV|~xFXl3$j*bvRq!{P{U2VX+u%hQob6Fd$>P(3*8H7cabKMw6*VOZR8(_sO{X2b;& z2%9qLNPv@DN$-LA`~*6|Hz3x&l3a}FikyYmm`mbXc^i1hJ9i6Lnb-4oulf^8iz<(R zsQB6BK|H&JN)vUIG)&#$;(#tz+={5zLz$uhS9sy~cz*k7tgDX60#p+ZJ*`Y=Lkrp0 za}lE7ZIIFx<>^>F>Ff2)_jU4H?sHQqJ^#l5W{<%Vx(7Nnk18G4%(7W%kNhe6ay_39MP%b-s{gV~IQOKzV+dvh=;B>+PZ<80yqJ z!4LY`nrs66KZ+~4N+yPQF@ii}(0z+|=nhSbl#m7y&9R6owvpZD6=+F{Q1F-H9sf!7}(m40;7m^8p$?nj0PF%zDjG z2RQCZ?JjONzDifNtgwB?%cuF-fXABN;bAGG{iCiR>jg9kZ6;GeSUe1b9a||4 z4MiN+0_G1&x6W^L+o96QKd#cqU791+VFvJ12Gn&Ym*H!gHeusStr`<7eCz6C=fE#p zWqn#k_{{G-6q;yMRM$6N%F|NH zE&K!tmlP0fA+86BmXC^H+#$VWMF`lYYylVZa$QN(kaFe^`{GpzJ7a@AM7-_k88 zt)Md+!Q^a^@{aSbnxp-AN}uEtYhJT&6er=1Em(SuEoQk5e(f!cmhoEk3^%0gO&8w< zDp+T^)!az(j`7I$K2*XaqVj+zc8#to0c9le2!lR0igb@ zRKNT`x_5gzF=N%{&O1DI&8$J5*?4xUnx5-T@K(+o6DVvxtE?GqEQbBIRB@rQ>5Z5h z`Fnan0=Xj))|8Awk<~FE{z|wOdYjJEEO;ROsq$e?_?tHtfNe!u0sjxA8$quCW{{W@(_v-*C-VG7pp{wWJAZU&i!>q!OMFwq?q0Xabigo3{BmK2JY_!C zSD*WY@A3#Z8R9QpIO3htCV9)~vbbrumL)cf?T=wQ>bO1Dsn@R*Tn+w>`;v~?-Xea+ zWRHk8$s_0-0_V6#S;Kb}f$zImM*iOYP+Yg>8K3*a+$exU;c%_q^zQNxBtaj2>sH_? zz|ZhuHwd^@q3-(Fz8L|e^ z@7e9Fqs)!E@(WWBOlXYTpQPAHI2@#v>P=w-lIJ#9Gc3^;X=uc7wrRr zOe{)Z0;pWNJX`v@7*_Yw}7@Xr9MGffp7=*@93Qva^+*5N-adWF~^BFBE|J1>!j z`q^ZLn6WRBT2(YQIdZ+dL>2g=G?k4Bk_{Xcm0#Y#adcoC)f-mH#j2N7v8FUpgJfD( z{SJ>Rdbjr%4o73YTBQ%nXGe^6bkml{zZr?jYdi!`1t+Hq<*Rk)bGCMVOUoQ^2S!|D zhqx4jmwRA?R-`uH>W;TU!aD)?G5!@Tm;`sMtS0nh!>O>fKVc@xHZg2^?sYVc?-@ms z(HjoJmO;fHM>St^WO)e|Hpv zaBYAcNN@@&0KnK&DIm9SfCL*MVWiN<;HnN1=oY>d(ZEQzm$)`;3h=5Dm*2>Km-IkL zwHCfMwTh7>{Q+^a)()VphF=bRDnPrNHF=Tu*|G9Ol_a;C$RZKZ9kU#(m_;mlh6u}gcj8Ry)6Ix0BCB%9@qe+qQ_G0QYZ!)unGxO z%+8>XO68|VeYwXYZV;iXiUb*E%rv);{Mn&H)P+B9;?o;ho?L!CzZn#mmvM&iaE&Td ztV+D&#P*`zBxWhSH_|V{#%YuYNU8Jq}YuYJ3g`_w4MHx*fS!t zw$!c&G!;($pfVl6IeZWc9yfQGGG|G7{>G|`uvHabB-J-iGD1n93tKLj4+%!E{+NID zng|?F+bO7GDbOF_S&!6~yzjnB=34&4&i|5QcjJnF4c^b1{!f~xUq&3FzQa-u1^SXnzr!n__)jIn*hXRlK!56s`*!Olfz1pGk_OglbtC z3fX3$j=1l)ka&m;v?k`%=Pu9~5miw0EQ2P4-L{DcAnFmaSI~x}3(6*U$mmJ$V6e#Z zm&-okUN!#k9op7oy*Z)pdVE?bX1B_CE4idaPW3;>SHB1sF_idxMhd%hsIZZZ->tjth)tn6;~Ao`N!yek~p#ER8=CopO_A z7t%JVHu~E*;2F!k{wEz{gE^iws{5w6VNl*`~(@) zmj$b!LhV4Ve#8>gY31$xkt=mkbl31`c8ezVn;EWJDxXy1!`vy8QaVVf1oIBUQ}`JW zVA#KGN0|#((?9n3@4Kz$^oJ9QIe%~_RtAK`xsL`>wV9o`eILHyt@Ct~j&9Vd@3vaX zS8KqcYz-f-{5bgFu*X;Zv_N*pkEUSbu6aLYWkQg+-y_#Z>JOMP@y{zar}dwASOi`$!y)GgXPMH$k(Yof(t?r79Llz zW6a*{kE!@VsUP@S8pTitb6$7@O8G2^&Zaqcqh7jB`8{s?AyfT6{_9G^16awUZh8SP zoIZ%O;6wWC9%}9@*nh=^{wec?=y`AL{0d0UCQ9wc4 zerlknwUHK8X*o<`ZMtbeW8I;92PtG(IyyU9&!L?3{`KOwT%yyYkI*MWgi{)308 z>0yu0E?WKh3Mu=6ZA0aP-Ucs3ZknN#a5J?9=qJCwbfX9ZmJ*XkdNGs>5Jt^jDmD`# zz}%$6NHPbLwZj2ylLpL!ON5KAA~6arfeHpg#2PXMj%88Cs*u_S=udqc!@9O50Rdij zu=$f$qLl%|fC#hDA~4mK0%D#y0~0PgfD;hE3I+}v)5?b3EG5{YEeUnJN{A+Gc|XE8 z@WlT5626CWvA&5URKDQ@VA=azv&3!uY5iV5bXos4*}+ze+&<}0I5pmQ?6qUZcjPba z6aQ9lVA-4-C!0+Nn+~^e*IhcZuVq;;Es1LBLhpkHatCQ6j5`d-f~bo=m{>Xce=mRl zgT}YzRZ}IcMOoQe+W`UJ>6I?m^8xMMGA*o|+Mfa>e0nz=>5Pm(oVNVd^1Qr?&R?>X z9J$27G6SHr)hmAYC0xJ9qlP$HUa;tQ2T{UY!uZG^n!@jE7x|8aJ@rb;Nhz!iC>BMt z50P!1<(nK_T|2v5nm(VCOMLB{^qSMEnX0dV)0Q3JopyR{5N$g$z_r;}ch-w(E22}J z5kw)7%>)*o2z$it|LEnc;~c^4b4p-Jyj64urVBCLX1i-P#@Qi#V4)Y!@qJ(f_O`pFL* zKcgD~6|r!lM&U9+YE5H}HEC@+{jb2dDDK=yps|{8u5}?yT;5!}%*3mg-`g}*78*=+ zw6u`WM|SD>q2ts#nnmP<<6SjD8QNMsQOsn7Bo?Dc=^(Iei^*#O+1O@SGSp^(8c&^w zjb*F$o1;*QG-FhR8SIvTgr_K8<^H}{jT9}oBCo?>oag@Bns|T>c&fZ#xU)2D>oY!j zob3%68Z6dHhdi@I^zGoYqMVjuYHiiYjeHhq5`q|ts zh65_8UJ7c8X8umG1ZbJm@-Kp#%{MY;>gM=fg`9_avCrHB^3V~xkQ%H?YIz6-jIlVy zwLgw__*Bk9kiz&QL$`+v^7g{avUTY$GFhhmc_3CEWgOU~8>XJHiXDk|G-XPuc~dm( z(D@5sOvtSR(Qlw$t6ngh*86p!`yB~6$Hp1cX4UyTrtv5xG-X^N3t%BXA(Mjb zsDDstr;~I8Fh76~EOF0AU~s_1L@+gP2a59qUCd3h*!~hGv^!zQBQ?DaE;F7#d}aSx zSi3Q>wl`QDp*+x380DcAqFoV%Fvxsv|3TZ!YdXn+me1IYfgX*2$X=m8qo=ru(?ko+A>N+(B!8OTjR$k$fUURI z#Sx6OOu{!~lMzDFqH@&oC5b3V7>cm={){u)XxR$<^--C0fJvDk@=7qWQFd^bu5p*b zI`0F*n&?10W^*RjWyxskFfjNX=7w$;{1p==*=-U5L2J zUEF$gu5nkc*x48c6rm;Si^Vk3+g@FMM~p_vYrH}DJaAS@E}e*VrzT_cSB8!Pdz!}j zNs2nf7J4CZ(CKYjSN%2s@48HR==Flrnf%z{ACV3a2u8y3m(%v5U8A()v5b5CFQ7aF zL&kss`=0_u6nG`N?zmvsa@(|(1qdWSj>P#+Rq#pG+ivi`c;x4K?Kh1=78mlYLasox zd-sKY+uaE69RR{akeQh&ds9v$a2Kw)_g{W1WyASy81pd9?_b#S7DUO_m2KBU_RSFB ztd-bu7=))NlUw+2w)_v`)b=pL+j*L*=LG#<>+oxpDQ!58_HQ# zWuLubZ67XzxNZ}Puc;4}K%R37q9HGcbUQAlktif_LOqq6>_}4?-rtxt;}s?YKenBj ziI2XsrKFRn5)RYOL@lY$OYt?em0nsnk0#%1^TP?7hn#AWk)q{avAf;GuD>=_g8_V^ zwxI7^8G$1@{f@>%+b5?C3DLsIqr9(C&MIUHgTFByomD^qtL(Y_yv{!2F&Z+470MT9 zp!Ae?u3_e8=4dRPfI?NyM7?9A*+GjJd?F}AA70NYV52cJ2p&4yoE)#PkV$Y}Vhily zoheh{1rwtJO^g(orMO|A*U3DJ5}+ZNzmpjNuzFmpQRFVZUz}7`S6aN~(N3f-G)uC| zXV0%m#O~6P4lD>KgjkevJ$&rJ07?;1T#@+nB(jtu6)jTuEYxvRostf87Z`U?E5gBx z6Jpk0Do`|*ff9z5aZ@bNFHFm=9!2)q2AuzPh@80yhOwTFId~DUSr$Jx@yWMmQE{px z8FTyv;n{}9sgEpZNiC`=*H-$)_TG95qBD4m+*C*#nJZ0M`axWbMG=!sM{DW{ee$A# z!5dDPY3+!&agvG>q)NoV42Lvu=0ZQ>Tww@wAY?%wIPzP!cApv zW2?YGzAbNnYV^L1XBSG^r~_)dLS9?MmE-7oXczeIFelAg#-#+;Sp8eQE5!d{V?9=y zch%_L2no2Zk4aO{Wt|xBwMMp%IT!e_Jnto?`YPOwAU_}`ueqdIVj~?hn~Py3J+geB>(wZ{8s$_oj`1`@w27 zuBhs0G(D`d}Ujar*&5kX$Ypweh1PygM@+xM{d`>9bQO~6R^urq7$VR7e)dpF>+ zKihC?h@-^1*>tz*%?{G58&QK9d(tL*@! z?1k=b2bjb)`_<*;UhL0n?A<=1Kh~oQ|GRy zYWrb;|9)2I`#9Aw1^{FN-0S>7^a1jJ;Pek7m5kW~nC;pCUyNH+!8_E`rEk}F1$nXn zG=3Q-h67vuHYS6aLKk~5l4}znbvn-Fc>hW!a!$7WDzOM!Ds7pG2#`78*rR*kK;Y?V z^|()=g!`loOFTbMDH1`!(&rF$ql=dI4(C29Pjefo^=w2HzdZY2THGXSc0%-^Oq(=+ zR;ML|AlhKNm`~vmHI+VlQf%SMNGmau3aG%TfBm9FpWJ$Ru`p}0(4DCR&pFg^?nBTkR4l2KG646yQQ*rHl|6kNXd={Ul1m9 zUxGqYkL}K#OBx9DdW|3i8nrNg5g!xGX?s7`;2X6>n>TRKk^feqjIN&5D|+(3ZcM5; zr_P=@G?Sm9ZFxMNcIxvAZD<-D>_E`1h&qDX1`Jb8gDH02L;$M~=^@m^BlicKGd!V_ z&x_}OIM`xx-#MTIIvLDm%zh;A ziF@%o-pTpYSg_f4NrbSP+|-T+**^ms%DE9~zGN?^37omRF__$#Zg_~N;oIgQ@=am; zZm$`_m7TrmXvr#<*CzmGRQ|2;*#H76b0JDW7fST@h$Ihk?dT`f!>Hej{&%-ykX`1mzK%yFoG8HbJzaI?^2IIPS_~*&po|7J8e=9q;<5rnIlP0GloMg zl!uLv^N(F#xoX-t zCe_zwQKE5Fyp(Yc>q?=r6zgSO`wW|lIAK#ATT6O8Q&~&d8gzi zXsh0i;p^{}jYDSslh#dpTig8+T>Bx!?>$6@T$oGZ?jv%>{>`0d4!}5i(?6a_*|`hY zM8ss;bwK|YW7eKr-`W~t{2XB1+pwwKcE>e%=~&&j2W;bm#TiETTLqiIC}JKAB6~22=Q`RLM;N2W3Us4&<*h~>DY2Iab5x@B% zn%c5}K&v#7m%!7jLBy3H1ml-FXn`z_H@#hx{u*0s*I?PG{0=f^wu>=pF|Yqi1y@(8 z9-tfmKF3F^PRt4n(fo|jsE~YMM=c=l3*_#uD$US99GvE60hFs^^l$@ijBRlzgngQ% zn#YVe@n@`uU#&^MEXuVwAf|+A!Q2t+lB7Ya1sqCK+4>OAhALSR zRzttZ6%z$-)e;;KtwzB>BO!m)t%kqdzsHpk#s*^rDt(+D{H1WvqKzA{1Yie z5tZ78CsZiHh=|Z}vimP+sGTb%QL(w=Moz+OQu~1V>$r+4*xD}8m63N>N(~d~ zzQPUfEVwPo0}}B8 zmauM}GqHw(9=9=YB)0Ib&Jp*OnquG6#Vut9C#B{;tX7a9HCVcI%G%os>7U1z9J_B7 zuV!reR_I@8IyH@zO)R2L@GEwdwTp+$!!ftB;VCyA%q6f4wLsZE0;$ihoy)-GL6l5A zR;cfI{b$jreM|)y?1jMg0{hgg88t#1suG2OhbK(0k<$Kx{D-nFe)4FTQ3~?XmlPMA zyl3|M9=|xgxIJQ*E+ubCq>49FDngOZrvf8zcBL5hqT0DevQVIV?OX`isggGVqol|d zFA_4h+a*n{r3dw8uLx}8u%l23K$ zRy5KU4HA3>{ja%q>*ZtC@44}AQSfWA?YyFLru;j#_w)EaAkQ6OM8rfC{JhP% z@R`)z38bxQGnswTbKiFLn2$6F{!h(zp0op2g3o$8Jk^QCQ??t@dBYx#``t+=+KS@D zZM{k~FE`JEIw;LaRU(j)k=DnUR@De4;SZP*ALF|t$!0Vp7363U73bQMMe>~uoO2zZ zsQYA{S!FW!MY%9C8~20Bd{7fnz$@};O6;=2$S2y_uRUmvbP9THVp!%7ZDsPK9E!rI zSrs@`%5X2R$L?15=mQfIAwxPwr9(|M(q5LZdkoVT1DnXHi{83pGO%PoM=E8P8I$?) z(x^ft5}7nI$Y_DgcIr5`f!a-XONLC^&dgk%*IkI_OnUmpc0#yJLTjU)+B|8fi4Z)~ z{dIF-81rL{8YDH*@a z7OrRR3`(VlY4SPzULeiN_izL6;;LI!4WLHxA|-Q9f-jTG{VYJPKulo_EyRV}bbMCg z^B~LpQo%8Pp~I8-QyX~@u2x;c&ymqV?;(oC5yQvumDnGI)*C=aAH6^07Z@m4naON_ieYFg-k6N1A;TfZm* zBq3Y|&KJ!PTz~dFLiHrRy-yrjefm#J5>eNb1$2GqXsq>{JbXW_2YIr4sTZ;Cb1$uv zRUui6Z~6*b5%d-oxzWH&Ic`SiF~5E;yY*{}*BuF-m%LuiuHO!nN~l!G(8Z%JgCmH@ zfU}9}Zle021F_P1}NsFl%9yxF=`p$IH zU_SAwH}7;SzHqb3SCm?69zO1Td}&p#X!=%H==g*A+~Vb~#WIcPPc8JbgXX9x8at+q zQ=o@^jY9)nyr(i(wFaxG4^fT>tioyEohM|OC*PpP!cg(_>=v&-z1(5@qDNQSjPO)d z50but@bTY=9vwUfux^YiQA3l};aorwqABXUSl#rboDY5C&4v&@msPoK2B-2$JYY4O zVq;ERZ6q~-2lMG|XEbhQ`peU*l*(Aqk-KYceyR4Rp{2;aa>-6w#e!bzvnlNj)DJoZ zsn4(*ifvp}C(fSwHNBB%2HGQk>NVHfZr;xD-t4V6TD}4(1QGWBADgc;?ma;_zBk^l z0KWf+&c!>RmLS^yd-jJLFgkui{k$9g*nI92eiI9PzaDz$5}NL{0$Aa9h~NE!egCn# zTAV-D_W(RSf$!(t@6A`upL4_g|IXo=E}cI}O@0@xey~5cgx{h*KY%~UJ$*L%KhNHN z03zA1oIfYKM!U0$m7jnuOdz0(_@6UwPVKFE;7o~-Yhr!|N1ZL`AsZ9FlO_&2D(R{d zlVFrqdRQx-p0~Rc1WkwqE-q@xqNx+yly$m2m6OfW*ZxdX*^y}xv)#j5vs-&E9dG)l z@1FVz!qmN9`xr+lt7Xo6`Fj;EYH?hMvby&Pnk6~CKp)hB-5Q5tzXOSa%FtiXC33E# z{23Le?h)gR{??R)*$jC_5y+5iIDBI;yVVChvv_J6#wWC}f5qvTf;Gk28!U1&y}7qjcH zcKBL$Gd9ab7SNj2LatI7?obZhm6WSNbTW(fu~KtBKg2nq>{K!nvNH7TUn}h8;{7gR{{4leo2ins*liyM-_q7| zqM1TmEqUCoo}P!fi5ob_cc-Q4fS&mQn2sg zboTD?Ow|X_Q1rUe+7kjW+_`(68h%guzqOx(1^kBye*FSe5zXq)pzi=GS-d_Kgtvmu zerJXeFZ3}T)Z}|K{=tdn=QT5%-Y(-48e|$Nf8-6_vu}d4Q;FBF@EeRC;deGgxl!Q> z5>CErfV^qrjn*N6kkG=}M~hz_uC@cZYS7x<)=L*%;tfrDuwXM6RJPUSpxL|_?^+D# zi^s|gAx*tCUh;(DI0VmCF-VMk}0G)jB-d&VlO5T?H3drA$`zH{j=B)AZK)IrJT4j7v!@N$N=aYIe-x4)g~DEN$7Sj;HEEo zKXdmR=lkR5?dD+C&t@;S_Zj{3HwjJ!k*oo-S; z)t}z)8bAKZjfeXCQ2fb}hOc0Ph>#ik3nE@q{qi98y56locFdOuiW0X#o)5?QIT4>E zIxyh~+Uv%PvkI<;gGnFmj>~{W15}{shs=orG_!pX9Zb^Qe7!~C_^j;b8Ddrz&u zq~Y=raul1>s0mh;s5Lwf^R|aWeDkxI_PxX26C~2ZkVhax^8zGH7~SxnTObORcy-`^7C4L(k3q>gWqrR-c#7UEeE$O2j{u ziaC4#)pz*SxcUH=qq*z2PcWKXVR0yMJf!L%GgC?)8{~g~9 zHk7}VvKGy$lQ%a1KnqVcuwsa1edfQqP3RqIftmD1Z7C~ZsOX=fOm7{VxFr&WrQ|~g zqC2BlJWL5R@rhgl3K}7-4q_q`mrPSAy+baC;9_iDTuywP1{FPi=|W2Ak&4uzZC+m* zKH6#<-*Ost>M*NZf7iZE#{SzL>IiZR=jgG>3*-m4m*~@yjXi~OaAf?7AAq^m^8`Zp ziMTry`;+K?d+-&`+Z*zxKM!#TbLc||+MaH1+EDC`HA>V$lRBb3f%8#kWu~{OT!~i1 z$e+clI%GyDn3u}&bVqa*Ii0X?4y0)Yu<2UZZdwfUlPj=ztX#pUer2erJ<)2cErD5eZD76)o)kGb~1t&=<>NXw-( zc0PR9ZS#CP-?Ix`hN2Je42;70e?iL6IUAc_2cY@AIfBPtF*a3hn21I%%lA%vfso;) z@@hHDZQN}!Euxz{5*{|uMVf5`=melBOd{oua&S{hSkw;k&Qrn`Rn>~Y`&J7EM%7LB=Ghf;>z7fOGz<}_h&Sy0BeHVcmtjUs* zaWPSjvLkdSRFAULcEkF-&rE|xj{mC>H8pWsJHetfU96Q@;6#M$3#W-~P{LvGK2ORZ zXYRgsU|?iZ$;rX3n^M>_&QDCuv$BmV2Ofnsj!-68A_Vn7Sc6TwF`{D@bKhg#@2i$Ks^d8G z?@&kN7KBm$4&$1dBgB|2#~S9!Qc>gVyHcfTgFNYSTV;CRg*%;Fut|BgeZobeE;&v) zJEjRCrDM6sC3;@Vq^Pp&1~Fa=GmI+~{omt!DWQ7%(;(VL0r&5Mrwq2>_}8vn_vxd1 zKqaYIYqw~9oqb({Er>(FX}AypiT2~5Nf4xG<=mXH%{xQbk%H&5I=rzj`|)3154SYg zWE2sf>1k(c6Qp>b_>6xk z84gqCmFl4v)NxLKC~%H(J+0e;idfJ2Nv|sg>CYgjBws8$3ZYXJix~E+a~|YndT*cf z+}y`Mt5jo$rW{Lz*K`zLR`3cM#8MmibMAei4$jj>f8meQX)R*AX;hO)G!|2w<_Q!k z^Q{eEyyu5G6?2RdtopkdyDsjFbn$(3;r{Bj8LgsXSJxQZfG+h-7VF|v#9TO&TPkqY+jy4ZXLAXjX;G@cSb|5Fi z$y3>{%cKK?xx#vkV=IL;x(8vFz{$pAI`L!Gx76PcF`1ggFg|VXw87xkN@gZfeujz9 zSK*g{@^zgxXiOedftw>_ zTjhSx^hpmpY1JBsqC2Wf`&X(wqckFRVC1ce27>q$Tam`d5;laR*K`MWma+M}>R>8nH5pcKCH`atMWzS=@FlfF^Ve-_w^{+?yxu2A%_1b_=TY)Xmb9K&I zv;q#M#mFUM(u08E@m>aUU6_eUS|okg4&jV=4Am~QUT@-3c{~p*Q$7o~I)8qSPP+Rr zK@RqFS>x>M(_YtgQbIPN1ilq=BR7v;>Q&T{AO$nBHDiGl;@+j!NdWvAG7EPg2^oWv znh0h4N=mU#)N@5J*0$*MjH!>JTWDDzTaOh#lpn=(>_KbRqoIF_JFVR4{ck#`UeIXa zP+;bkW92@Kq264XfCb)-?(*pH6Bb@XX%U!Z3>VZb#x1_FQ1VORNf%#5eCbZ9q%{w3 zl24b6^nGqjDx5H5mL;JTs)@WISj{%}43yImP=uhznCV%-&YM&Ns(2Ird$JE50u%`U z{Hnn+ad5o*4mLgU4q9)tZ4BD-&V(lMuqZ>cm{%z+j=U4Ij0m!1W;DA7HVZ|AJlD&@ zWiERu7oyZAK-L8IQu^z@!`d8kPY`QUlT;6VF_4b_SO=$EJ7w*xQ%4T87|5D*w}^iF zJq<8u>s1LodRvE=Fm|g`W_ih0Ds1;LbJg&)z+IC@cU}j?hPz#A|Anssb!UG;I9?}U zA-@#Kg^XI^gjaXe6zk{;7w$Q|rK3@yonq&?qYtT!e}vI&1L*+5kP&6lbsiO7M4@$1XxV? zD>DpBr)$nl2$`;6rMk(QQ?S?0AQ@zu`xVw9PYgPn$6}Mf3~mVz%Vw#afWTN}8vj-~ z$1@GB*AB%%%|XN2A_2ohsTiR$PI9{Dv-*w1Rm?4 zfq&}NWj0xl07}$P5e(^Uv@`rlC7JlHB=cz2v$gMdn{wH<KxYR2=$tKg~4z1~dWnb|K=`Ri}46xhh2CC z*8H^b3}E!#`jdCN&Y^}ZqBhBGUFZ=mx=cT?N)W*!?++)V6#n|G9P}@{y(n3^ z6QSQUTJZ4u@rjU{Tfvt@rnL>uv!25kvPq$i+c4ZP&t9lXWMX1@AVlTv&-g|B;l;8u zPOs!a(7ZCfbghVOwE{xxhP>A<9jz#`mlVeeiD&UJf0wl>6mUf@jx+8}AJmtil;Gfw z%U@T}S%Z@l#*NuNPGW`k+%wWm>reT2_baGN!CI2(-Nlq`;IX(U=@* zoM8U_nJHulkdu^@@_Hf2i(r5cMRu-rmh;cNJC{t-v+sYv?r&Az*{3zdaBIAOv1V82kO+E?)oH z7>-^685wKcM^8khb*l>uA4JB?oDP(g>$eb%U{^0#xBsgFP53C|trK8U5y+l6&(&G$!26=<%p zN=|aIYJkeQw1H0}JCHWu79#*yfK+T!SC{-UZc(zWTV1onk`X>Fk+=4i6?a$}$U1xe zJYp+cv__M(3+Y*!I20rrK1g`y4{23JgBW#^WTIi>FQ5+~J6(lk+Ae9MtDBx(5Xq25 z_lPCvX=rpiM76f=d?)_f?B%PE<2W2}BGKRAyb59j3$Z{SP`A0jev_xgN(y~;K!V1E zl%KEZhr9gFpX+C;QFkDHLuv7@9XuwGkwivbmOf#nU4& zJdWqE+P?gCcw)yz*>J?VK_%8w9G(%eA`{292@O3j~5t*)E{>wB2?b z2aYDWYh__1E}nupK)&#DHA-Y|8wHlGnR?v8>uKr1SBO z3IEDr0Fzjsj3zj75-}n_Vako~07ok?Eo{Kk#z{{IO0QKw8lrr|!L%(EkZ|u^B2FtQ zcQ5}3V)lr7<9WOG_c=Vq^{pUO#=-i7iA=X+IPOMY;PO`GshW@t#Kl5u8%})Ai%fjG zb}(kBHXHzEIqcuVHeKlj&!X<2(8f6 zz#YL- zHXhb>%`G00C_Z`z_b{AxpHtd=9&sG_vlJ{BqIp5K<9*X3dlw|uhB%v0=loe7_rD@9 zt2$~&vE5j02xSK1d9HCt^{2MI4RY^4MU za6@a$pqC*BXI|!wBcSJ{PLF_*y2tlN>{sfiK$OW3I)9$-3umUHIS(VvJZuDg76&3e zrP6`MDpyv17^~lQR!3Y#s&i3pW^HycX>g^!NL)sP){PMj5M=2?$z18$kXhU#6tl}| zy&p|=0Wu9Lpxy64plj0(?m@IZ`F)7FLgBfEUuPXF|3Z=aV@PUp&WsJ|XD)=P;x)`7 z5^kqBf52i0L0^&g1Y;b$VTROGqdI4eJY*0j@C5{h@pDY4;1$0hU}_QV`9eT-&%I$< zOW9%5Cy$hs9_gZrw!Ie-X2*#5fwt&|UNmzv3?0nujED_W0Ix2uwUm&;-$f@YC(~nOne<`>fKS z!uWFwo2xrHhaZ?he^9!z=FwDfi;K(Liwz5c7CK6+DPc2?1JTl0M7+9-@$?K%rD zJF4~5a@YER`N2a zrA6)9&RhJ3*O8c6tF*IB`HtH!_~Yz`)q|HMI+^O>BDRNL7$9%Ij^2Fz@J?<#eXllz z*}K+?LvP(Q7`B7Ya|wE_4Z+? zKzs&1c3)ki5PM@31wLtV4z)v*W~Dj;sm&MQjB=XS`J{*4(4bIbS>SRbgvsnIwf-zl z_tM&z%wgZDl>*ZxZCNM(s6b3v7X~v+@-gzoPOZZ^$06IHKbLOi^)&UPj2aExzp~Ml zj_*t&Wtuej;A|(xtRk8g#34TWCU?4MgOY&2@oCfr?t+(by5dMNgUW#Ne4Lfg&-zBpfdHstO zyKjjbK*`iAjK{@VzfMo_Y?TZN@7@UyO8sCsJd$Rmgzb_7ADzl(svljT4_b%)NZM@^ zYcJikdMZ3_1C!9~jh}sM2KlD8M7^<7rp1@}wo3qYt_epbLJ4dEN$<+~$Zi$%19|+VWrN0paNt z6OPB>Z8R^H?Ua*4L^75!km7*dt9%V2jx_K|6lpFD;u5ddw*LMkaIB6JB3*6r8ShA9 zsmBX#Zn1YqBbV%#s;dkR!ur5kZ~#w6*!FGc$j&nvt}h>V&YHX@6`TpXtBwf@@Csl;gkysD&GA)D?|nwKo}8O*+c zsyfz9*i0vnxt9!K2zS+%b6F1h;x)DlN5nlgT{jQW%hi9sIHFLdl@Dydu>PlLW^ z3GaS*_iEVPaKoqFTDu)b9x;;BSKq;86gIow*y;ial*jH`Dc56J1SzAQOfS(qhrw`yZap zfxXVC+uBKE?bvRN#*OX9Xl&cIcg)6i8YhjhW81cE^UHhQbH3lOu4m2lj4|f8Go@WZ zPR9gE+Is|BBG@Y=2G*ay>3`kTldI5UrE{@Ju4Z3j8&4JqF+3F}7XKc?f9?1J&J0l! zd5K5sdg7uMjqR=-QU&=^H4|sY63lfl^AsGXUaOFK*7`RVI2@1h5IW*BQ;-sLS=<$# z%NSRHk38}w8i>v>F&dpOE~z6|aHAUan1w0HM^U$NfZyg>aUL^{Nf;TL_$Sde(i$Yv z__($C77$%ut?CUJ*wFdW_8WEd6fBk|(8#LC*fcP>B%nTYmH4z(Foy^+pIU3~gomKX z{~e_Z8O7jn;Y3AeE3h5>3{DQ+orNlUVpwF_bqxH>HB{>rqpNFpqq|1AaiTOaW_UcN zJ7`Rt#`@S~jC)A z08ERA26Xq^^Y*kzdS;Y=I+;yIiQ-|wSOzPMF}QD1MXP~^Tj;zhz_klbUuI-@|T^NGV*8cI?lBX;D&2FmIwxx~_@NDZ#{S4w=u3IC3t)<5wRG;Oa zoNu&GqmW_UhvpOK9ye+n6g zbJKYl;O6y@K`?kdL-I>7jZ<%1eznYM6uhpYp4NSa-hBpGVKT4Wvzd7>lJa9P1##|2 zUwp|NJFtjD*ICWoWm{4zlJBGS%bB}mz26Oc>tQxL7-QJ@*kb_CNMO{o=eg!=yquee zM;@73`;l0^Cz^w#6fZ88)jkWykHVwU4N4sk2SK2y((+7eCqKb|dNv8fsK;nCs4Ae{ zrMTzHjPBH7!mB0OUdHd*^R@q(7*Iw#1vXy=@lGwO#+m<`E(IM{;g(#(uI_fg#MwC- zVsQi8qfG@1QVcA>cxG}>h)|C+Dh*Wsb zFPVDtzzE=H9)X9nd0S`ddOjKc!XYdmU3C6HGhAx{SheEqlP^kg@Pc)M(j)&l0c&TI zoFZ|}ITz$3S8Id)8`GK`eCEBq3@NZ_+Ok4tdLSd7xPG%@q@&?fGa$ zP<>k>3_Yc?6^`!3;v`_f1D3blmOn^1y`|U-ebPA>AzkBpU{azV^iVbzU=f1kmtim0 z>Yd=y-#pq){X~=DKSaS$NyY_;dFHS1diw{A74a8?lTejqyAjBV76j8P=C_IJ2VNOu zh$0^EnWi}T^2Rk&KP98Q_>`aFtC3z{J11DK(?`!tq&eBwE-rTp+N!tSSKT~1NXDbB zl?vU37#>Jp%I(cgZ<~#N5S0}Ot29x>GCkh-qvzD3HR(rtQtgJhg}Pk)uzPX$G}4I& z%nb4La{zc3!3e*pxR(=N%WPqYj^IrbL`|&XY_n<6q-;g?9X9loZeX*=$mH}h-5GUE zqg|?TI|^VOdNW&4*Kjj|g_<#D1ZLgIqYt)zzy<;0&VP*O!{L6*7LLfOOB@r6sC&E| zHu={WG$N7fn%!JdV9hc>G*Y(wyK`}n_S5D`2~mBvJFwANfK5{1iYDQ}{q6+Y*J z66ErbR?{T?PQ))Emmkgd(ajIL^R=z>l_Popv+62ci2M?(WY%d3iFG?Vz{jb} zO`n>;S_EkBStFi7#wChd-p;HWBKHmV&=eKx0PLVX*=p9j&oW_xWHz9OD`4&$x%(46 zK$hzQhaZLnDun4|BZV5Y|S4?f)*zgz=^q2@ljzZFWyOwh*-o>=@vE1uB*6t+;>l!S@DI;a7X4|E&?A$fG~sRagAJTw1HdU(t~f z6Cl*a3Uw8Jm!96(%jZZrg1NWfLSS>;$3KugDX7jOMGz+<@HEe2+H;KWC3M))q_C{X@rm#IKNR9k~UYM#bZ;dPLW z4?iaxR7g?RCsiA2pndiB-k!V7p?&1v&oL3Lh1S50SFmCNDZ?$5Q4@u1wc(=m5?XU(F9O^=aN|A~y9%W~rO z(9e_04_e=sJ&3jUftc$F`5L3aXyhk=e<&*)=&H~ShdosyO70+=+^>9jO--xB$Wb1) z1flNBgQT)<5xDP{XOW78&EoyuU(DX|>>b?`ybF!aVej}=rzb`+7QOwHuzZ@` z)(vDQv_dC`&o%D4gLG02R$<(%V_a~MZ(&xcKwf4)(EZDBAeHF8?%DXAd_x8h`x8 zx3sxyoC}i$YogX+twN5uN$K`~GBMx%kM5)vsD9Dsx)MOuwB!v&=IGO^Er1xNZVXgC zVfjfI@-O%y$Pi5F2Gj5Wuu0|Wrp|HkYnz9GW)Gw`+s<$1( z)nP8apIoWz>V8EGyh)FTWtM^9?vTN!>918IH;){P?usr_1`PDsnW%F+A7X-~$YZ_D zMm%#&C2vEMw!7+^CN9p13m*KB-R1Ik4N9mt*60?Wl|Y5JV^IBAXfBjGPuOk(iIWBI zk^l>*aXNH#e9wNblP7N50fnV04g>P6d2BFB`Y$q!%?e(`fiT|o6os}P{BPI?#=eY2 z)+*?UJHqu9nrzDJy1Wys+q{3&U3GkBRF@G{ z`v!<+n$tHn4o9YH!l5#Re6qT|hT20E9EArv1J767frlr#LS%46S6s6Y{|@F_^2lHD zemBQR?M>pdi4oobnThBz>K_bBXt5{d6a|m%&+^9ML`NXEN6#PyickQYo^m~tvnJ0B zCf{!r9LJ;ROFW>bFVg5c>V}F$XHt0iTIUDv4Zf6im2lF ziE!@qEfaQy__KmUhL{zz3c-kpSDXrQk(SGuOnt3#E4$Kma=uQ*6jVz^lIA}hNYGCR`Th(HJ>Bu)2zwTeaFW?QM{F&S6m-3Bb*O)`ywOO>F{Xk#MH#s^)_c7j8r^`fErRv!i z@FUAgM3(MZ+xgueF8bTaEbWVfi*d(Ev3_>>gUq2rK#Xdu+T>-YBz2a8Q~2&D4!=~8 zG{Jm)EL83|ZdJt9n zFobJ@co|_WA{)oK8l!CP3L4%dBr)Z zp;!^6ichulOO=wSso~SI7%^Abbal5s$?BIu3&>fJ9`99D{f|Gs%0sL4Ntuy_C*WeY zMtx)pldrGdAjgi3j-|=;kjVQ-G5}?wbWbl09_J5^Wt#v+;f2@Bc5RVDeOQsY{)K;P zZFO0|8JCyT(&1v4#qF5Vk3H}ir3$!^V7w+orI9+*CSY^_(EJe@PbU~bQ2V?xV})SQ-3$) zIOdLj1DV2_{%s?=UAk-D3&ATzlM!P)|GX>w1=Km^xg`;M%}OBXT*w4HNg<$eVHJq{ zJ^@3k=FR_73RC#P9_?4M@1h#G^aAzWz5834X%SiMpI}LK&3lj<#U4Vrh-l|^wy_c5 zfAYZgn-QhIbG6xjCb)sCn?BB%-%(#iGK5_ao?7BX5?3+$y=V6sPOB?;mAB^$xn{jm zv;7%S4%&IZ2@7JAF=Sf|gy^MYce571B(A~_372hDj)&!58v?werxKgDTxF4Tmhu02 zj8Wb`H!f-23`z<6%rt@WK)PG+n)MKasgztd8ZF_NMgydZg|$4yz3Tc-%WFlAc9Jmt z!?7)1;azyA)wW!3;jxxUl_lD`nc4#{QrGm=ioSeaESexwyr!QH|C3@_@+hJ5VKh+799ImfkxWu^alCHpR66}^YJsmIl z`p4RS{IG589Ow!*h~?tLlp+?DqCiYZ!J8?s9b7h#k>=GCySQLhFEy{Q$=-h{B(UD= zK0MXZKIvIulF#hPu+5&fB4j(#e@P@7&$GM0++spvZ{L7>+!~X1B=sQHDdEfw!3kL~h5Vp|Nzm`+oz3O%@p&FjGkP+ev%zR^E%GGxqGm z6+7TP-F-aGG_5+jz&w|W#pfNc$oO|(W|A$sj@_lCP(+eY+d5bIEMIRMRo0Ezh6_Ai z*o7QW`L%6CeI(lKsEvy82Q&AF?HRR!tii>Qh^fqvC8#drtEr<-h(j4ArlN2MVCLlW z%`s~h;}3|Qo1}93gv%;`!LU2bFkZ!ZVhC5fc_Udi(z5XI722%Nh{Fx~v zVbz$AwP8Mo)j4{)xNHoAl|4IG&g_UK#!62{IC^!!E_3Woo0XH zv9sK)SZGj{bu?O~iEyP$Y}bg7cP>Xw{>)(R2LlO$lp-LxrKIajkD{8?^xQ&cDnwg; z?vSc|lfqF-W(gl388Kp!Yn)c8@|JM_bWO6(LU`fL(Nn>Ct%=8z5F;FDr&-BxA~SK$ zG8RCaynVKj<<7#xyPKpd0k%~P2JNu!IEd%a{mj=*sC zqs02+QFK&H)>MQ^aY>L3+)$raf{qnBy-rWvzw`YY$B7b9^C(EVZ|t3y^bDcX2B)!~ z40tXP0Q-1@8n}Fe9thp+%93wJqD(=*KDqLH3L;E<um{b%2_1c7uj{)Xy9u_4%hgxnvZx#VTd6x8CAC z>gTKYqx2%>+cb)BV|9Q!i<1E83uH(GtG^ilp z_oJKk9TC(?`c0avXL>f>y5x#QTF0#}9e2+PJqWen2MmQIJW@mq&JPFXoP8=OMhoga zE`G6NXvA593x}i4tAJ?In1g)aHeIdA#usp$IP8(BGbp3v{_t;ez5h{_d70QRA}qYw z7dhYpxnVUzAV8DHc+WwTK*)HsqJxp4XvD3UyaEVfQjEBiDhZ57Z*_LwYzWDTQ*1C^Md-(3J=IiCrV`0F8InJkN*lTg*`t6r zlRNk*}H?Thpp!USZe8Hm# z6_US{he=+mX))NqsA7n9DXtFqRbc2*;SPQ9CPpo}8~qWN~e*n4I|pA_e(%?6r~6MV&+1L>yZR#SOQJu=A%68&hf^;{RP zPI1>QS?}em#;+gwuI*63Y~e}Jz&wtlifd)9u(XK+oVnSGVK*_Q_eA=oQU0)2N6B!F zQvNX_J?p_4LgwW8l1G9cW|Y?E=oHI-4}10S1E8&7+cGhAb_Lw-Xyuy?2ur!qxOCc2 z2))?^tKcT_cXHkEdNojZM>jK;;2|5_3bBSmrY?JA2I>vdDV zu=fngQ~$%b6j!pe0ht1LO{#2=KMp29C@Go7Ky(#3y%yU zrt=l%QY`l^w~hO28NN5;bmQw{gXkKVx|4I`ybw|KfkIqfnQ4o1>TFr0F<n-ojJ!Rv2msEJG`RATcF^Pw^1ALy4avZ` zkbU1=Tgl}lpm?ko0P|{anUQz$*i?!uHIC*r!H$Mv{6+cH&e1Gy0?R%HwyRsi*IGI46g?olBv-By)sVBdHeWX~3%?QpIw&f+e{K|Uu4Y26U5~8YaA%%e%L} z%`sG*b&b2wBPzeXN0ory-+~pqJH7*hY_Ly~cF_Gxi)zL5<+&FJo%Y2%0^jti)3yh$ zUd1HOL<_}`*p9}I8^2Y(hRqd5gR%JtQafF{!BuL5XQp1YwoeW^b#IA5l*u<;r(_=2!JCQTd50j<2yZ}#16V+VRzZO2G5oc>IgwNcR6k^^t)C$&j1IS$2Fmr*Zn4*(6NbQykVO21K7!>Jx}1NI2@} zu@~GW#}%X7_HPNY#5FOJaQZcGQc@R@jhprK|Nry-?HJ1USm2c+>hgn|-*?i!Z5(U* z_>R+=epqQOK3ggeip*^!!5sU#*o%^hql*#>`v42#uX~REh|b_Ef0{H#wnxOsenK-f z1z32yv^0|u;q}^D#U7|M6|$Gz96G)x>A4Bt==z}6a722~?4@2k?JS%xfp7VW&ym67 z!!S2GQt680Ivu4t3y~yiSy#Xe4PPlmnXhg z1=_6Q#pz_t+n9tI8Dbn4MN$Ur-s&AJSQ-y#yMEj<>erY(V+YRVwZ`Lt_gM&xBD@`> z**dV>muUUemPsc7cV?&Kh+(<8;o3BbTGFW^^j24j(IbQd5)opOlUJzZU`j6VpgZh} zKWpg}C4Nhf!_<+_CX2-0M>aMQ&jW8`di8fMe7kRkLF&;L+v*muWd!C2z7_hlo%gpr zM-ik1cNUh!zWoGQBfs?;vzj9&S2nBsl^|=<;=K3^NrqUoab-YV%aUR{mc+~3^I&A5 zI;38~RRo5+%oYtUVUNa&gx z+GtCd)%(nEPJ|R6iu&i?gt`1yfxIpC?0!&vy{CaAi0NE(u%}E1Tdjs2XHCB&3o5_I zD&`S)`n8^^F&CHUIe;t>GM;WmZfT-Dz3R%eYob#P*Tvsu{;eIRuDVrowtJP`nkjP& z2i;$GEt)44pFIQ(*)xfIpQtF2WYQTwl`oTjkqv#>U5qU(JEd02fe=+rK+`xb=n@Pk zHT4HYXuDbv+cXMKLzNfd%2Z^dtW9Rg&;f#-bW7 z_+CZI^!Hdy*xB3kR7HA2VCjwnH^ymOh!P#fMa|8|!DJM4^g$C1<(`9z45T zx-KM~d+J}$o9i+EB!F9zoxWPedl<|n&3w1l(Vm*^buZ$N=YF&S5u^pTI{TR)dhiRRdZ8daAha5QJde}6ni=Uq%H#>DK5g|FgMj-%0K*Xz4nd)KMaamg zr2qyfu)lBVX}lxE@SJoFY6BbQ&cC2`O7V{i8f|>g=GR$?ub&S-Y27%9-~L(sE6n3H zB$g2`b)0F1PJ5$~6Qc*bi&iDj@kEs%TS`z7Zl<-Ht1lY3M4h{Mm?e^YJC8%5=rKd4 z8KLLiMTVRP4zp`Xv?^D zi^ZMW>mA21)<@+8GU$rdZM04Mv{Wyjr6m_Y&L3u4`(MH})>bupsLKea0gms-RgtT6i#Nw7bAyomPDn+|d)sJR|G~4t~dw*(Xc1 z#+%lH3jQ1hX-O9iui#(+UNBPXixPt1I~r@2;0pL6ybtUT>XPd>6Aum*ZH`ACikcdG z%_L@?ek`oS8Lr_^6Y*UX+~YN<0`2<5z01-#si};|ZRqdk{2j^dez}eHHm%$APJyeb zxd#cJ7TUS4KN2X=xz(QvR10Au;TO)Met23+-lfZcG#LWcljfTD$ zAinQmeo({Abolp9b~JP97Ly|B9n4{wTLhFe0W)6GYi}>cF zE^dlRX!02dw9anb82lz!jE8VJXmonF9_aVtuW?w1x@?}tFd8ZMupvdXd@$#jv55W){mY!w`M;Ch8IA|GS=m!jIm3@;>0N!qSIs!;^mOpI$l zhJCnvhNq~69Nt1TwC5Q!sgxV~zL+tn%<;clNrFnhGTZ~gv*67%JcfFXYbDE8H|86X zZxwlkpRsQV*HaP(1@PmjlwkqU?;!(v@c%YWtI~S6=ds^tr};HCg2vJCr@}4DU-` zrdNI7e&57txst`cwpK=MOkw0Jogu!3MkV_Y8I*G9+iiN4)bZlt)J3u-gBU>_5PyYu zP3x@QB?EZw(e^9n*Jf{vp9g$Tdwf0?+`ph->PixOnO|Z&6gvM0pLaV_9@{AGu z6Bc-QJUPwB^Q|x;xO=vCw;p%H;{{Rx0C1K`(b z=dF8=w?(8ffHFplziH72IhE5>iW12;5)wHPgA`GKSK{4;kDwJtWC2Zxi>As z(fL-@9}Y@nMjPw|7}UA#b6L<~WW}L}jJe4J68EtJ9UzxfHR>A|hMdHM339Pjy@-W= zE1*6yA4JH3hEArU0GTk+ES43>FJ|{z^HT>HbHyC}x$o7QSkG`+R$Js7HXhS<(El6W z0s3~OW6MfbRZ@U$u^7(Lw(qk^t?@=Y@L;ZdLGn-9#KGPq0$VSY=}0vC0oZfcCwwr@cF4i;OGc6=f}br$snOKRjgf zsOx_aBnnP(-YmDmP8Tf8#~=jew?hAooedk5Y;vDSSQN{^2tXmiaz&st$Ym0zj=xc9q>| zLEtMAk)3AK``y+~4>IOtGa;893K!c6$T#lW`mVFv@l3bJh$G=|@ zb6lVLIPlC|7+Q<+r^djh>OhhNBBCcH$SU8aakQBy>e;s>bek(@Nx^Z6FqDLy=B;MI zGN|}5_@#e}UzixeEB-@l}X&0Axl~_W0e}v54esxR!sEK$Z{1oy|TO}bWKpya$2h>D7KT!~4 z5^9C6xT%r-i}_bjJF#@S6_g2e8>vX!^onLCPc#K7=S&yLfo0{{#NF%FCp+g6ONKE7&|l ziv#HCC2sQQX^&Ij&|dx62y8MDs5(7^w*$!Nzv=n=5ZX@afAG_;rX7Gw;auE4SXZr> zvD=1m-c!DxQ(+CI}Zq9Dy;j>%7qZ_^TH`eM(+FkLy@t zE;<7SlPblhjRK|>@pf$LtxO_Kd@X1!`xvP@xN)L^xlZ3Dw+TtrWp+s|1<7~Ta6xu9 zY(1sz?%UKdnqW3ffCFxcn$XKRr$Q)q&ClVwq1(guu21-hCxzbGLl)3V-J1Xh+&APj zDSqilT^}1l8dqY62y25F+#7X(7m<^s* zfh~7HQnuQJ6obXZoZ>tH~K?|)b#8)WJWfX&=bR- z!!Vc(ps>yUb`w$V^zW=_a&MHI=Q;Vs<+aWU;NmjRao~tuAo2{VVmcI(+I$rh3=`6nL5g%z zF{-3^$2OC$;n`!6ITldrIKzX(B@jvzB;OoFV=Vz~KQ5A$UmAx_e7EBuickG!fAc+B zC1|^k?MY!ocoTIpOVfX&Rth}V)O|e7TW{AaUQTFxv6D&c2p$>YD+Ug>A+oo-2HpnV zm|U>f_HFyG7%<=GMsQ&*E1uD2Ei*0y$tfrYr>Dc>7QzD2#k0GahY1?`7Lw<1RexfV z%T1;e;$RSrANtMAo;P$GfI6jP<)z~I@_BbtuhnG>zSeyfa}Kj7Qi4{0j8QaW&L+H` zNM*KYZx}vYMu*G|g?kGJk>r0dZ4Yj}-t;Zh7?DPzz$2`pNc|K#zDyzrzIK$;RpsU> zeFblm(3YnaEql^2b6jkeG3g2IjavgJ(yZ$oeQTK0U@JIWJ{48Tf)r4XAiHMc*Twx~x9!ln z(M9aq_Psh~1Oaus7S7nbi;E8%{mYG;VYYQPBidOT;xUw-bkI`XDTJTG_dq$VHy!1) zJd9;WJ1u0Sv3ocabv$q1RJ+>Gu-{scNp3$-y~rGOAez~H?t&`NqLtC@Q?Mw$lX=;b z)UA3nAtJ_?iat|eIM*yh?VwH*aZYWn$6XL|p@ZtX8Lq*!BD9nKl)QxX+$cCp)|Kfs z?Zn^rh(wHdJp3Y1^juSL{1tjzVEyS|G_i~HNG8vvSAFl}qYAfwUGslg0952074N6- z-T&i|c++h0W1e3jCPf)+gUF7_i08F8&vL}ZlO7ni)&m|{>Qbb`aDh*X+kja<|>EYgj>bkqJ@9m0bA%@0#IjA-^W07 zEQhp~p1xpf+AkOvIX#0v#x9SJaY*e3dM~2z$(avbNHAn;*%i|!J$3rJ5tEda;4S?` z-8E-p=%t6hAKABYZXdfSFb}^ufk5g@i)INQAygh~(+uXJllwp2i+<~Gm@Tz@OW8=Iw>{A2&IZniMPAQ^oy6AsIV4(FoCq1W`voS!qTVhE$U&h*_Te2yAEJD#Ea0o!Rb_#J>jqP4d#7mmpn9E>X>wQC9I(jFCxU z(-bT0H^b+u5Te)cZb`EHYem|GTpSeRxQBqU4+-`6yk~TM1;Ao=&xTuf?^O#rc&6nu zJN{uIt%G&WmOD`Q3iH5i9K$fVMwZZDFnZK95nHBKI?oNhNG3mgVY>f#+GnR&2JCRAtQ8XZP-LP}b$5 zVqibP`?t%CtFdQWPUdllR}ll&o@qugPgvrj?{&JIqj*f4S2F-_gsuNcOKo^I(?3;g z;@|z?rX%f586D1neyFwt1#ZyhnqX_cT=)a3q$YbNL}D*-r+%L3`d;3mQE6uU zghq2rMR!_lhPdEm-f;C7$9_x$*x-fp;T8?V3{#uA>eCgem znY+CC)(~Og;*r3ux%xz8D6_Aj74=T-NG&PB(?zhmt*CY&JZFqztE#-bA6jrI9<%5l zrBKi#!Bul2VZ^(`b0?ArFqVr<^)Rw)i=De#5`qI<7NwNC$O-ok6YH8Fa8JlIOV5IIn4&Ta7s)IYnpV ze#~KGH2Ua+&QBlv1DD;GwwWH>++ zuZ-1{h(oq;BaTg8uh7298k(<=R@B6)hJ!D~JG@H}-h8uk-42AnW`W1Z%E2Pa>?OQK z6`z@`UUbP}9`wAD%ZcK|1|=I3wCq~?bi8b5^=@TVl4?JJRJ~2;)ZDr5hT$s?O87Wt za(G?5zg$`Vca^OYd0(K`Cl0%vLCMk@Zsz2l`n+!m>42IuZ}-X|n2DLf%f$57LEV2s z?)jaz>VykaynCXA5h+asG0I=PUh(@8X!5puHr+v;;8U-9j3Z|*dg`x5n<+i{)4ok} z0;8-h;|%S@N>zmcH)}c`bb|wvAj()5!3lbIg82HyuI2;PCQ|l z=>S6*hV@ZCs>O6Lir2-1$B+&|Z-sS(mp5GZ16GsUOl zB_y^H2aQH!QSl_!Hg*3iN;eU4_j1Bdy~yRJm@SE);(F{PKI)N`MK=Q9(1l~E94=&n z#ukb`2l!GRqem3^oRQ#PRiXZv;KazEjFSDJxD!l>BNFyfEfSrVEj7e2aw ze5&DFM4_-b(}S?T6opP@1WC2ZCQd*L5nJ5c?v0Jj@bkw>`i~aviK4ALQGt#WDw@=G z{+lasKo0j>xohXBptVBB=H72IY5Gt^2@DIeU68kmwcrBuwz~+aX zj|V^h&x_9Y$?FZjr=M^AJXFn}7&Tg5J(29}OnX_T4wiJQ+8R>L?9sZ-PBX9-4bbL% zT+Zv*y|i$cinnK>u5RN79_@#@J^Fik+U+69Y~rh{n>sN1vL4k$wEZ-0kF8@ru)n@{4p(koKN zn)mmLA5vVh-h;PKmLQb5Gk$;=Xm?XS7; zyhEA@7*P2YZxl0zjC#*!dAx5X^tS%Yenuk+3@BF$us#)z{f*{V{tk;d`NL+`nxfOn z(Z+is^ZDI!+-`E2KjtPaWULDPNMe`fv~gWdgzDKuOQIWeA^e3sGy41sPyl9y&UhhN zHqlKpku?VfjeNG>lG)jv3`>sA?oV1)zqqkwJ6YsyN`&G%B(02q&se&V-xNKCGp5OD zHu>hbNQ+P7V)PwOTR&XEH3Z0rv_JksoY1{VYv8#5=>kQtQC+(=tsZl7*?&}?h8{0o zw4gyJ@r3lGgdic(n%&O|G1Jl-ym&{{(Khu~JnJcY(#Ko?nIyc0!au8qLjf9Ss@Fa8 zzD@qGQQ3aKh0WgK z;;OSxj^QY!O?*fB6C#O8`UmH8rB=sojMNqbUto@>?wCoTgFlcBPIBA}ZK56mBf)tj z4?U}~+tYzn(PGsYgUB?xlJG$k`CoLwl`Ae1;gB|;(!|rxoA2NTVRV=(1r_L=CPPuS zR~RzqTR&;HlR$(--yp`uhZiLhYyXCt-cdumghz0W!89wOn4c{-HR?{ziXvGIxoo<3 z3iCs3-k3%^G}(ulq=#m*4%B$lwj{roxsg%X5qVOyKQpuUF0mownohRs{IMcO0?FlA zSe?R71Wj7W(A9;Ev{}~KVc`_}`Dfh@z5{9wa9$FKyTC1F5UX9*gIkJmV1QX{@BPp(hCPd^8lwJrvQnOl zp<*)x^}Ytkj`uZxG*e{$a|e+GGeIO_qdMspa|$}wPGa09*(kN;uj$+?-SyWZer3BW z2~A*MCz=8R*8@fbDj1vbk1i5j20)kVTKv!1Ewd2FN2R{1T$R{MRkbxZz4yje^L4d} z=gdLgA&jI1_d$(P)(9SU$VTftC5P^xcc0r6AAH$6CGP*$yX`}n-BLrXLHotdNyNZ{ z@BnZVor{6=3#v_OnF1%4FF>sWVXDE^+=Yx^kZDc*&l;`{PUO=2!k|MEji2_~i;f&b z;fKdwm&!%t1%T~!x*ATqW7Hxu49p`R=6^9aCX4S0%Zy3WUQI8;nM{9|S~$)|N@7j^ z_6J1%9jB0@JdaMmMN_dH1a^w6;%Z<{>mMx;Se7A!eOY^iAA9%>r}^>I37h9QWjRo|JJ?50-{=8cKM_x1>A-WBYl- zSLSq$K`k6QSvf*2(~}b-HR1%xVzJ{E{^Pj1h15a&&hiC~yeoU#R(%4|+|Y=g>aASG zlcrBmEH2c_g{_8C9v-jh%sGFdMTBen;a2T;20b_^fsP-)V!nc0as{DhrWDq%GK?IE zjnSdJ_X=1L{<1`9w13_uNA1QiA4E6;Q;iBkkHr=%=-!Ze$9agiV)9#i14^JbZCl`K zx*G#Z;~p~A{IOO!akKfskAJ(bowXTloTZjvH?KlJI2cwLUG9<3A?Ik*L98P7ZmwV5 zWyW&Bh~fxqAmKo=a@H z7KYes`HN2J4(8AFE}U|dUAFHPg>YZIOKcQ$;H>)sLv*29R5DAanp8f-+&mMK!< z6RB&;6n4Vw!KZ(Zl8}SM@V4Q=FPU7!O3^wVT^k?OD%Gmqd>6+iHj7^EDM4rvo!e#m zAaPo|=JHA3FQ$6)9cA@c0_Oovf70LBCsWNycUq14!8A^ z8`UtnZZHR)PWt)B6OgOKTUlSg-YE-4$Ip>obdgCWrkT^KS~3;p?^rOrr$m`O!IS*`Z7 zmEtWX0*s>*wQ`QZKFxYL)@W11U0AR&4>ye{@vN?0xd?5-bZO7=-?}KvdQuLR>A~ES z_zLFLgNE#r^H%D89{tqX`got=P> zxy6vrs>jHGm4VW(RpONra87Xko*`2}))Zmraj^YGTn&JY4$bM3)K6mKA8n_)cHC=a zKSih_O_akmr@VoDNNz%c3BLe|N?}OqE&00fLjf+q46J5l%;hxYq8s4{WLHgOMn}7v znru}=)rb{L{~7`r?xM5UlB}C&co|aiQ(JWFfJ3Qb3Z$Y-pV7w3&a?HJ8_ome z97&S3pv62l#DnpWfpOH{&9OoHMzUMES$Y7M4ur(vHfJult7(_OIFD1|Bc{IWO`Kp? zFl4U7}r9_&eh*rR^dteuCF zV?~;@`D>>Fc)sk#xeTp8*az_1=_=k0Ym~HLHluazr5q6dJiha^jhJliHoY`hA#??6 zYBbU$teN54uh%URdx1k^<6IOuSbzUq_R1iVt|Q|+3wO6ORk^2HUf-(;E#%6qr5?sI z6Gvehu(rm<@dNut--WX(UHJ}!$av;w)O9t2P>qQ5AQgz+NQ#hbU{M%vHg-%JD*LZ3 zQb#4tV-sChlo!=u!>jJZ^bc!RQhR8{#F*FSqjydi6+bef$8OUZcnkCu7i5lzJ<>rd zJ&KGwy%5)%b!Ft%pFuD0yMvOa<$Y!PNPRQ-Ivp^30p{;y3{dtfbnI`B7$oE|h55Fo zIg>g`6Dd!>++Ru#LruqFAYDZGr*mMH>VXo9Bk{kWy>y!HFWrwZM8OVou!J0cnd$1L zo4-f6?qhCt<`bk9w56~Mpenh0xdA$J&+3=?QO9<~nvr2+>%OZap!^%}s zKGdY)8?F13_G8PR1oVIU08&u+rK>lXzRJ6WUuK>vzfAj;RVhppLY2#u~c&76<%eLgC5Q>LJlZRoc)sEc5o8 z9lzs-QiZPge*m#SPQT|f-hUy{&t#33LrYbVIYwq5y9$v!E;;cO!O*)BSab{BK`c!C z+2}%(K?-#WDsO4MEtzsaKn^45-1E>Et~Qj(ewwuUrjB#v|sj zD;Kjh&TU>kcLz#n5zP^b#oj+3z2+=zTCKSZd|{BdG&2;peKf7Q$ysY>jBdsCjYR^T~`w-)5#tBBf z)y#*iDT-ksSGN^WL|)fl0iJSJlAg=CJos`O_yH<8`wqYxfIWuTg?}#%;B-MUKZn=b zp8-JSrb+knu=HRw#7&Xr8En)LA*RvKWK7M!qct~z`5BymGt}JZ#e--A;uli{Q@_pk z#=w3N${-nvL9!dChBg{dmQf*uk^Jmru{$I;ga33d6$>CFHP;P@F$^#Vlp4cL{!{J= z5eJeXVKH05fts#a!)t;pm77yKf(AxYk1m!W^QmwSK$EVxCZRwK&>Erl{@jRA`e5N~ zE9#q#q1>bF2f3WfZ+d>O^TwE>_3g2n?k05JT@d=HO-u@mSL!j^cr_*hfF0vUpx?%?~`^WF;S zW_q+!0V?S+v%;{K5Y7fSeWL@kT$lm!6u?I?`~`rY!*ByvEj>!%szKruhuom#xkjDD zgr`iVTyeqK^Fex3#+(s6XVE3ix@kC@0sn0!f+s^n3L0Z0&nz$t2D2zwb!<=5!Y=X! z4nX79wTVTXOs&CiN})nQNqX+ldH#jF!pR9mJgo7P)2lEbl#BCDIIWgg)i^8eb>lqt zF1k|kCVFsYAjPSJfGbH|sP*1we$bPrqj-;naXO8f@qIlSjHO2!G&a7CSd|=P@T&W? z56|VEmMvW_zCy)~M+HSB7k?%n;a)7vLoY|$)JRNdvX&S^4rBsEYA5DD^mm;XFcrMo zieVZzc{4>z5f%Dw^NvV(2AAA3;@u=?NfVtyOv^MxBh81CX~8 zr}w9I>9IZ|Gm-%9!G}E87*1UKQi!L$)+7K-GW zs~9RAE@&Yl#f1SOq19ey*)71{y?cPq0elX_6%YcDV22cvKrd2;h84YL{$15Ij&X!o zV}*O!yEl+VF1R@gFV3<6h@8~z;JtdvLGcbSC{!XfKvT+*)G#1(s}vPJ#OVjhtG9gz zSa}_FI(n**2P66L{-$Tf$prs3DV#9B@%kYA`@|ZUnNCobGXbZ}cI$%}Y=nA1ExdoXx&?6JW}ElcHQMu?%fjV9iU`Zi(a{Y+UNraD~Kab?i%irQ+* zK@u1o@&!hu`4M9@Q0GfFRnYNrejCQZbQHi=nP$No;|-a;RmmSDu%f31EB;ucEH21Y z1MX!TXPtSqsZ=K@D|AqU%*_xCotFCq7~+b4T>zOcYw_>l`D+6g zpzXT^Y0Lo`dv5|_f&%p&gK>QPjGMDdv(o0{e7pVqD?wY*a~TTLQ2J;1UkEui8rf^1 zXSx1CTvQ;kgNT(NWkR0;Z*LV0g==yw4tBc50R0d#WC{?-vOq8}egcsfY4JpEgZx)#!EIgywD7>nrx|P=DMFEhFCOY^EcR&A zhLVRizAmHow{JcA{EP>)3(tk+4x9a?I*$F`6fabETB+Owh>+&si-Pb3bR+Ws@l(qw z8o1Lh&>W#0Jl3c5@kXcWM7;x%?^Ei!vaW_a96@h^7;?do?X_!C&jgRuDZ{Gdw^Tfi z_FlC~m0L+A)ps7_h)|(YFO^#DZ7b|shWGN0OwUQv^os~UpZ(}c((Qcm@}EN|i5O=* z>R#@Q9%!;c0{#~Col|i-|1_W+F%FEWR-dI~$fo`SBWw}kfbJL>&FA|^QDg31w$0CN zfBR0@ekU}-Qhv4dB!-Y}2E8YKqAcELOGwv4DAb7P;WIup+;c$Bg?p^uO@#6H+XHnO zXPF?yCF!|5&|;X$*(qg9nD0y3vi(y^AIqezK>?2y0HCT^mN&5I2XRTz zr3=TT+G!QD^q6DVcUlog#1;xrIq@1Zr56OrureH?1Cou9LIngELPLdwlqV{XKaoJ9 z4P7_$CpZ*@ay$SvvDW+kr7!{_6Q9TQV$~4pM8fmQK&64iTBJB6p-c|opz-?{24T+3 zz^cy&#HCvATi90l`v?g`ZP%>9J;=?aTM@) zF&V0HG|x)Xdso7%a}9v*{%heqANiS_iZoSSgwp2*=_tH;Z?7RJE>Nf_unyR2e)kdp z9nWFwXRu2FF5d+7F;c?>05&512tbV!y?16|McW5uz@qPV`U>z2$DZ|LzlI&7#KIwK zjnx!AU5e4uA<4uF0`0q$S-=cVFlG;tw1X(pF4t*1=S7ScE?5dM^$__BimuKR_>w+` zn3aMEDn#^{l=a${jzbLYNqXqjb80nWn{azOb*9K04W_PWk>F`}L2vA~T0j$k_dcFH z5DJd&&C0Ibp%>&2$uIe_^a$jrGYloNc|RtP7+~1;LJ;%wcNaI?bGgTb=Wo8y=!?rd z+rMq|GgN>LPZq541LM~QX#E|}s~Co9(reO56OSyg$YDM2&7!60jXwd#ptykJ5nfT$IS?-*{hpGQ9$&JY>BGq%$4I84l7}7z5duB%q9YrTX>!m!pN4XUh6$ zgGy(Al{}_7bF}qx@>BGgkvZAK&rwB1-9bqMQlY$IJx=vyV%sAtH0b?Ln~ zBbVRyvo*xEFga3(qch&WE;fI!^wfl84(Z;{Y^{kGDHj}R>%c=9-e_L@1UiSj+BiH- zWnj$8#ZEjIigeC_SlG-rhU4~|P|l8{d>gCYvX!b;z*(&}1g<|=UoooJznqn%=kh>H z*H+y1z57;V^YgCnb*Rt--JHbhvS3-BV5jdv7K6zy_z(rYsKbJh0WZo*t7?56Te>oxQHV-0PHdLYXW@&@)AFto=b$@51y?_ zn6qYF@bJr2P~K^88>zkDoE!>Z9uXcJdMqUwm}&sT%ng7e>eza4u`^i1@`h8X` zQZPJJ&%H6zuoPNPFJxg7toF{ACZ*I$C5rzmh05vuVEgH)i4*$}Sje~dfWHuZ);YiHxz11Je5Hovz#wbSN!S&_{%+uyA{ zCs>EUY%SgpSd06Sd)K|9Sp&UB<1$u+Q96~6aT(C0*0BsBb|qjBqOWmFDD*Nqp!Ixv zkK?{@_o2dz=)Ay%Xe(J52_iI7d#0sfQr){%26|~XNG=Mde&-` z0+c7*U}5}UQ>olXQR-i7fA>Nf>U@4=b{{XUaFpPgRJYcYHAYOs;IwyMUTTdv8h*A- z4bs=>FsFIWMR?+xRoZ}xM5KZ=Li;y+Cg)jN>Ym1zZre{&FT+^3jD}ZGb-Z#e3^C6! zQeHNzHHK1>8*aPg)lgyk#9~5k;a3o;tl1eO;KxI{T z3IR%CAS7KwS(*7=_sW_)9|?_syx1TvQ1Q>C6s%j1isYuFp^-l2#hBVlIBiW{vZwOn zBi~0-c$eM+wWMcl@1M_w3+a~DetMIMMtFOUYlKzb!Kr)XhSE|7@+QRI{X~DGKxOyD z605!v+;F|pBR781HHL^l;_r@XbE8RnhILtvIlp6wGs5%J02Rq@K^(Xs08*LpV=R3i z=0@LadbEB{$El&HK4*Cj`WWJOy0-E&w#z@yvg|!9;?dZ#e^VJ4bTBV1=<7(~Ln_dX zTXKXz;vSY>hv@)9`6;4UcEE)Ib(=3#~amh8jzFi*}gJ zi#t@dzCH!I``-ujasZ|V9TFZnuIxmcPadNs7G%0aL(DH}fGcVJA5xgw9<{3VkgoF+ zdWV#_iwLhH-Ev`#DHKMuJwh?SlnBQPN#$R5vFI~XTykAB*N9`ZO(?2W?pl;Gq?5@` z?t6oDv^5|-S{BUyaN1wEmA@8G8OCsOE#0re0 zwQszOZ+`FV_~!3^125ii-XL*t8W4&^aj!{fxW{|o&(KE@$ulJOZT0h*@95Fq1sPbZ zhqP1O<_aMf84fXcHYa{(JLh%s5gisei_5zc@hzWHczOYqYPTo^RZNyE!JODWFMjq( z`$pW;-_LSK8z6{XNad&V#_=*dt%B-sAUD4PMl z#bV^TXv|BYh`G4;dpK=aH}O!hE->ri-7yD2KRul|X`kFWR{BE*_sZWGQP$^)eJ(EF z&)gwzs{I=KA{*mJkUaqmsb&l&WaD2>HR33F}!R%z5f(FNNiaHNvYre4hY6N zaJBvfhJS`}c>(O+gIxk+^)NCht#e3aXz3?|t3-%mlGDuZ*5=Xx8=>%{;6)mo-?c<1j*%dIHx8^+H7|FwjsP6@6`8JsPT=DW0k7hSy_}(;!v8EcHp4lB* zaQT_EcR9~elIFy=`E1KEmEOi}oMuzBIs5P97F5#HXh+rmQP?ztjgd-xi}|(gE+nm= zT|qjndGB-WcXl=5NqGGDFf>yVF!wFDdezC_tBHg8ym$2HTzn4=j3qAp;^isb^Uz{% z(+H!klB2>2;LeXvWCv>MoMr%f8<0gHPvS0H5g6XaBEJdKYwYm|Wj%=YW5LYj*QbNTF%h1Se;2NoAknl~5zudw( z*PwH}^NTZ5*~g-<5p7WKQ@Md0LEXSxr0uA&G(JxuROpEX@S={{FNHMP=80kNxF6DM zx)d+~bIy&hYaM#LbkdvQm8VW*V~Z9Qu|7dg>Vz(<=k<4`ii@$B^LojgLBw$hl3ES5 zM}^AbR2r8-Lcu!kGQe}Wf2C85tv6lYS)HP6OJGzUE%aT~>nSt{7#8vSKK=JL#( zq2vmsAa(jwR(NY|_*^*e923p={+LA`OX;;YS}rus2-0Z;sS0+!1*!Yug~mIoI!j?! z7eH-g5YpC$8`0iZ!x-?8ef6I?Iw4+_;K4R2q;s@pq43u12OA^JcWF?am)%N8EZ44P z*d}$U0a!Q7ZSX50otF=cq={T3&KoD7;fS0!@|F0#dG!}>inWyPA(^wDyhFt=e>z~w z{d}auMyxt)9GvCk zPwjX}a+!zEP|ixyb9tb}+P_ylcirh$X@UuVDBg zu)KkFcZ2-`n5;0Y#c4z1V^~sDGFyB1_N(F?iQ#R&#r_EvA8Ux zDH1IdonrKUVXmWKmPQ7m@LVZf2^UHNGo<1)6dVnDRbP@hO6w;Rcm`vnk`e81f+dEZ zPJkr(y5&s?T(${g;&)}3IhDGtkCWqPiNHBtt{sperk>YSkY2fcKT#s4f;5%LH8y`d zfSj@e5ehhY(s8ah6!v8_uilZ$PuDkE0t%cpeA^r@y0G_dL|k z?+QSk0_zU|`!PJMo>vKlSBNRhc2IS%RnHFxT)cgW7r!C+|33T_AIVQ~1K^2?-@|9l z6J}sci^hsA&~|JcB5tHs=>l&()$5ss|IYE&_}>4X!xo(!ne!d1H=TWq2%*!s;AtD+ zi4r<<32!WE&DKgg;s5eRWQN5u^b&iNms#7r>_Z>x zNo3dZC)cgKIA!AR{X}e$Sw11{d!bj8ZJrKZnK@vqE8I`zwN^?4r%29oRZbe*x!mj0 z4AtBH0bskk=F<0)K|=}1ec}7qJpd8j`kt>>F|a}(@9_CIF7T({`~;64{|MiZ&+wKx zZ*f{D5k9_#lD|6@&}bDjQv`+`-2cBotoN{XFGJb8_oRCqN`v7c7fhVRoiU6lo#LC~ zJE$5XRfXm=4bww{vvms2w*kcMhm$)(B%{l zxA!zt8X?f$#>hG6GYVc1g{jW)yltbM_;~WVC3)XrDK0&KTEx|9t;T++ewx;kSi4PldV%7p5XO{!BdE&w)=95OQO@!V{ zN@5T53z=qTn~~!cAmn52>zWtlTQ%Mf()nH%+5D>s>3`|`Rm_m@HT@Mx;c`}zp34I* zMKoXkvZYdeZ2j|2%=sO~nP56b*gR5bR(*^oPu_(tZ{g~#M_6_j*c&iOd8|()!wMzM zUKCU`FeGPF*$InkQ;^pd1P5us~odn6T> z{U?`oj1!Hd20>pByq?X}8mLRb1^IoB5sY>U3!1tQv^R=$VnnD z6zFa42W-E>Q;puZtA;MX*!g+F9*{l!&@80N3B(DbulFl{^4TZ&?42J&-V!Ww0f=J6 zIm&S9&D=1dg}^XWFtN?#tEUi7(AgNCh(Ij-+M zqGOG4KlHHTqnj?jBL+~I_boT6M9$H=u!}9cvP&;5y^r+0walt=TQ;BkzSV*pfyTaM z-Rz9i&lJcFnHEPvIUHjY1P>+|LZzWNbCuV*q%@sht(C?&xi z5q?|_24;I;ynxCLM1!6RGp)Ba&f|PsKn15^mJwz;IOFEtPT>v86-b_rROI%c z?wMk>u(?hXj}q*|^RPh#$EGRUsf(X_4>&HXmu~Gw$7Xjc6IPJmwVd~Z(QLnKqYOM_ zfqnF#lN?X~{1DINncB>g!uh^-pz}b>SxI^>=W_2$XGZ+He@8;coKrI~q#~zsp;1_K zpPJnw_|A8K3vYk*JNT0)1E0P9PU>_-G$a3gfr|yfoRFtGfyfS0A)B~ zc!1J7nBhzS!V@$g=j35zwbqVo$*nQQaI2=cr&xNK3C~094W6N{m*JXaY&;?a+8Tb8 zycu%>N2qmZ8sl7I<-QL`KkA~X@JjGX4EewT$Lm`JJ6W)V$XG;e<7G{n(+m;P3^TsG zk#YnPwk%=nAs~&Pe*13!FzVgW+Qf4`fEU-mXP*H#A<&K+Km@v60>d!Ijem|6yg`;q z!?iXgo<6_EM}PhqK6&fs*uC{GRF`a5f)<{>MZJ$A282|~J)n0~nEi~)QD;4ciq@s3!*UupJS@_6 z4aY+s?_OReD8BqP6F@YS-nXtvl=g8t{+pEg!m1~)E`5zdfsh7*PFS}!-cq|E_zrT8 zC1UzbU5L{N1$O_ZUxu=9?xP0=NZ3{-Z5e!$TlIi-Am&ry`464_VvZ${eh}*Kq(9LI ziM+j-*bo3mg;cei%j;b3vVPlVdG7q2Q5`~+QMopBdKZ42GO)xA^%rJ%EGsT-)cvLw z?-RqMa*%Z9I8IcCg! zDYBtu>hwvE>F%a6F{HzrI&w_(*sqzMDcUiU_ z!l5N5*u2RZpOove-FJ=t_VKbC$=0j^fZq3)_ci-qk}K}pR1RLv^cDukSh1%jGlPXO z!bae*m+<#Y(IEAw&Fb&&XF`LXo;d%nb2%$X&*fb1edz=?v@HkUQ<=8}yWK3O(`1Il$>!kyIT?DYD@l8n~mqb}1zye5IkmS5UG1gh& zpLiVEkh*YTA>af;gi>m|!L5OjR%jBDW{QHVnR~L>PkQLV?9H2NHw;qhN7|ND^Rrhl@?olznSz#efYt9x(6&m=rRP7n~wXec*->{ z@B$y;#vWq@#SFc(&ong;#BZv-Pj}_vIuuWP3!QAtdt2y2Oyio>n9G2x;lz^SAfU%&AK14go*kfKv$d7le#>>^=OU#9;n~=(3Hx_0uXDKz-PrE(b|_K- z<9Ny9YhfxDAQ_8@Vp$aH8o4Sj6qk=KaUr`lT?`jef@pDZBCcc5-aD~Z}2w*V5V(k^WQC8q_^SoG!DE9 zQ#(j6_oJoJv3#bDlXP>$T*{V;_P(-zccf=+9*%t_aDL+5@HTqlgZXJI25;N1>Wm#Y z2EU@HSs2D6J<`$8o$^SYcuM07`Pnw=@n9Ti-*29g%D$GIt?di))rT&soRy^K@+(xn zfIx9?+NKybD?8_(3c+Ow;xaH=P7<$%ZZ|8Iiyhv5^cB4Qs0f1b_lS1{P>ju*RIle$N{)nb$}K zo*xL|b-M-JKF?rq{aF26cW88?nDHh(N;XTNla>_m8$W=r`8Qb>D zx!j*(0^1pIDVen+?;Q(+NP2~~ttGJsH9fFHP@`9+E|W7|idf;bY^rgggjcA_v+QlH zCa^Ie>ou@G1;#$SNnQYU16!{EFwFh}72Fp^6p#xiVz%PR8#{dM+aKVE?|p!q^<(VT zzrb$y!j(2Q++*d$?djyqFhn8PMS>Tk5PZuU?Wdo6ddsWES<)6VDG09$K*<+UG^LPX z*=GLT2SF!Nu4j0IbQ>4-;EGWK^(I{g04SB#ZB23T)GtfzQI0PdTP?R@JlNOm<~u> zXja}lZ4`~I95<*sjR^LZ#>_k?27)f(k~MSpUan1NZ3gK zM{P*>j|GC&u0kzz0jCj;Ay-?mV#Tto5WB{(YsWe~w^V8wkZyrfzCuAN)5h=+ee-(* zG#mpGeifpJt0;O7Ofpsn!)}D`Myog)BQB;D{vDp)u!*wpJRb95D2-5~k9nYHPgQqD zAq^X?jjDK3G)YKtkuMt-5p<=cMsXL3?sS=}@kh>1;BX0GoK(nAP6_07o!lP~B~~9j z;5g%V$I_jKkVcb1jN|o@_hjTs9|uw{$#m~iA6rK@O4d6St1+-zl315JEXQsUWjN(> z=K8C-LYl$~htj=Cc}X$lh*!{DK0+MhvcvG`nQ8mi1f_U7#*Aqij>+(kUZyMw+@p=BCg-Wu|v6g9xTp@9}P=%Fu1|8aj4ywqk$Ut&x8Z%QOf=x_{ z1=0YSW1H6vew&u$w?5dM@{)h+(}P7!tv&16bB@`fV~nmkV5Wq7i{-B0#4Fm5#4EIWQ7SG3X*GI58wY z53_~RbWuQ`V90wgte%f_e1<~p`{)(<2MuSa^8x@ESYJHD^G`p)v#;!6kFRivYmD_e zQebc{PTQLn^ET5LR?}ySf7cB3@BP;E^1ih$xWqiABGn}4lKjH5X31!T`Qi#H(43p8 zNmEQCg>F*`Z+FA?HUmRBfOmV_t&TNcxKPk8Z`sq7lYE>1<$7%9;uVF8dM6fyCBmO|6yAyXF^PPnBWQ}0B8K~3;-b#p^10l{@+yMyMX^Dr zSAHfOk1xO?Fk7*=J>GruZM^yBW7x9uD|lAJP8Iugj}P8^jCXcdc-ub0Y9C{<>)3*p zc&C7-92tt^MW&F^FzU<1ACa^;?m-7VT&HmuV5(S$!7tRD=S75BmjN2LnRmIz5p;X` z!K`-cSQ3&kOseaZ!~Qhxj&^C z$^x5UH57ktYuJAg%jR3wH7kZC9@e(0Z$nw4Iv;;8R0qou*+FVdM*#J7>Wq@&u)8Gj{Lp- z{1*k5TVe37b@Dw5y1kFAyC*nzuL2hmgHXZ%>;c;YP~6-oK6$#sGkF7Fkp-VTHay>% zJ8eQ!$LM%mLMD(lf&*ycBNa67O7BlzW)uu$gcgC8SStFMKS)imXer@sETDL_SoxWKJ>!tl*lPYEv?@G=r4Gf50{41C4R zq%J2hPF z6mtD0WcMM)9$3c}27U_QGCCAm+~gbks4#NS!5~<%!0^Za+dsvh{MY{&_J@BBU;hWc zhuwvwW8Xl8N&o;L07*naR8Z2H6St-xFM35p+JGj2HBl3sjM?l$GRh|x7&=Fgm@XFr z7$R?^8{yqTPe-Tu%r4p|6Tv5`kPgFJ&Q9@|G(t7^8qSRcKN)RJr@6@S`~oHDk+)g& z{nR3`$z#j9RC-eTB#&iKgK!PoLtTJA*f5s-%|Zb>r?P3Y)amqwCRToI8cL;hO)Q4l zK;H1XQ9=NxtVwV8$nW9@-LL`?in4z>F0D}!eL_gL!Qb@HuNQE z;D}I;lrKri z4QYALKbf2`4*ZM*Na;8iG49c5K%dSwq?z6|UYh^rF_05F@1^Ht=Q~^OW(RfTcjDLR zHIIv_7o?GeH`@CXA-x?Z-*$qE=gjRD4>y+q!x(DDv|N4dSwYZK+w#8F1FqA7oAT{E zr91VC8K5Klbvi$Fe8_t`L?ovpS5w4gvm^L`t6A$^{iIB4;nkZ){TMbI@G-B>_a1mT zD@o7g0TzLWi%?NI0IYa52(k8#Y<~7 z0dq=P)Nq3_euh0h#va$OviEJfk-myH9?l^A_xS%f35@!&mm|C z&Ky;U8p`k(fF6}D?=)^DRFu$TtTV=7RKsGfWuC49NaW2FztU~!Lv zk?Iu-OeYE4OBotK9+sZ0-JpLi_o$dm=^sc5ER@J* zK}TpWFaQ>pu?Z!74u7X?PnCahnQkDEv-$SKjiJ z=Kd86Y|cy9*cMxM3_7&@B8at82}Ffvqt)|ql;Y3LfxsCpjr<*yd7bX@7xY{l3(%{S z6qUxia#Qh$Dc6?<4j?_}^hjUh=p{ePv)_0h+TV${`}gw@>%;B7xV=bwM%$cDVG`Y| zg8+RZwDAWoW@>zkG*=*-b+EZU%C5X8qgT)F$ozN{KZ;keD}d^6YI<1mQ@~tMp%P8PlLZy(&;=Zo5!QHu4di-Q z+>Fi8$;2KAd*5MN8xhPJ)_YX|vcSC`yK-;_m5%!*!M$(0*yW}evbwQk^E&s) zP&X{xEQWPivD3ZhCcIu@*hd2kitmKcOa@>(7#1vYfkhX0s@5m4@fLpl>9_IMKYM~d zexmsNqCEcDjZ;d8+ykSD!S#J9Nr9CqTBPVQ>ky0cmd2l;`N8*`v^!nsw0fFt@!QV3 z(APQrfMKPeHPKRk(jDHdK*Kc7A{pCz*DU_yq}2K4Xyo{=r5nG5hPo4rwRc?qenhGF z^2WjR5fVl_3!duZF;vQ#mtqYGN%3$b|@?& zBO2ZV6&CaIO8Z-;Md8!OjqI$GirAw{XW9JR6xN{`vOlkeUtJUT3CognA|@)8LX?@e zj$Rt*L|@gBbNP}>mo<)I6X1)lU8i{p!vcliA|eQ`#|o1l;RkR0Q~d8=Ss~-6c%+8? za)WEThS-V)H^A}~dwB}AJ$6zCzuPfO;cL=CH{vfCq8Rbh6!^@m{GJtsp z2>jjvKjWJ)brBr9pz2`tr48-YwJKUY*AcU5?a`yv==5DaF1@eEnPdeHwC|_(I#aOe zSny9ms{S7NUaqGl7uoOu$6~{1)IB_d*63-4xNnh7m(#a}bIgA;)~Ww`kN5;obUkz0 zbG)0ym^_R(E!UieLsYEEacsu1YPER+kcur-Ft5jk|U8(5zK6!h;#Nptk*076WrXWv={`0}{)KytR&IXx zrZIY{+5mKc=mJAn-65fX)nxRUW}#~gay!d>9Gevt=#xbtEA@=X{Cq9ew8E)Wr6S5C z6f!=S1_3X2A}9hq23VyqOX>uTbD#Ly6EOQax-A-#7@S_3uyXpgXTCRo;q?aGsB?mrKvAG}OKaqNAkS2X?=ayYRLL+t~rSx;fJOR5rhiH0oO zRMcBf#REOC;+u>XU}^}!@^`}`=1Nj-qc}g^D~x<}TRLiD0E2JE4iJfXjwnf!{SdWD zqN~$p)El%klty}psSQidYORlu-lkU37)(9nhU0ivIKGYtj$zMp`SQzlUADg;BN(Ty zC7&CC)ci9Aao&I}H&`G21UGN|88AM^YBzYHSGbWi+&c_d2c~?;%rf;-B4+tt72@^* zlQnkkm~bnjiZa(};AoCBc_Z9VBZJXjeQJ7t`rK7-O2st7$dAUKiZ2yTj-PQ}iQSS$ z>HMs~96JJmDa%}wT#QX5l<&_J|KmSN@7?Hqu0=OA9j=AXJtiN9+t#UnDVy(Q`)GeR z9Se$52$p4RB+WlyNE}&M3H2q7||hv9RO|s zT(|GoC3$Z}_5)ZQh#U7$7OjkgcO=#)% z_h^G*a7>VwQ}6YQNZdRu&C4))NCl}`c=AdLri0)sEXk>arK#77=sWLI7i8RR#FbXo z+Ds&Zsw?MXDR30eTPRV*1S$*Y<>`4^C`>!c9X4QNC0B*0LgPkiAD?C8KikSqxkenb z(IB8?xR{^O{b+j{;zu#Jw-udA;#bxAv5Wnm9_sO!L`78K1FfBSE<8(YxrV*9VufI} z=fLiB;Q9(;H__xZ5Mh=Q0q2H248ZQ~Z({fL@8f2F0lC~^S+B5uWx=xx#a}O2nPr|YnY~C-^a~DW0%>QS^GYu5Pm|7CewXuXZnR3{9O_us zgN=HUP7X?8vLPq0KBvy3O0mFRez8ckJ~u6_^bUn+XLFs%sV~EZrN9k(vf8|=zCX)Y zFnQ&V;8lZj$#4VIyQu)SjL=B+VJaxxlazDHxFIDL8Y2ymOx+{Bi{Tt2MkRWK2U*%U z)R4C@A=z~bm?F|r*qx>%HC89CBrQK#wqfq^8#y>M@*C$(+EURS&JHa-Myan*2vkO0 zxbg+|%(?tk6t4O{(uiC_<>g$pc=6zj7WxcTH$=#v*%E*9*s49{<_ z@kkZW1GJ^~@6U3Ct8G8a%F^B0Y7iOhvC$ zQ)!S9^r(dXzAMX$jvmf8X_hqF*5|Ux7V&2{R#h8SC6!%C|KqoK^5|+y%n5nm*5jTo zu!DMLE&geny7G4`w)V>_#Nb=GdyBqN`(S##jFJaDDVa3pHE9De!`6XyQ$LbcYREgJ z_k5CncS%}P)<9whKpcnIZIskd#=%j8}mVVmekS} zr-!-U#gmk->bJeq*~boZ2wW#xy?@&*K$;$p{{4dTSS2N1+D{^VgfdVdON2J_MrAFr z*ad!u*+)M}+_m*f8n-fo?p*0vPW5k2w)_8})tALZs|H@uyk<+(DX=Dm1iq_V5?3N5M85}CTEA1dOA!v}@!3Ys&NXb7Qz~xD z2gc&nQ2>GM=8$~C5+8ENKq*m2_ehfjcQy?B5gtyv0Bz=;vX@Z!%kLx<*6F0a^>mE|$_vHleVmH$bGcu|{OrWRmkC^3dS?g_mVOH*=HI?zNXNWuS6s=J9iXe10uF*>e?yWYkZ)QYhb6mG6kt;iEl%$vgCTJM^Ny1 z#52nMS;~imCqPrqwEi^6av&{7YkidMqgjTHE zpOH{BDRjg=*}+FRF7E9)-{HC3zruCt0k+%kZS(KcwVbK3Z=r!T3}p(1uJ7Rg`tSb; zKlo?=2;cipe;2>;@BAMA`Tz1y@JIjSKY{Eo@x9;u9)9l+{|5GN{~2IUeJ@(zmVlfLE`)Nr-gq2uRu`0U_de*IOJ{8 z9ym6gkg}Q3Nuu#3p!zi#Hs+ond+CGAw!U6wZlm7t?n(GZRXOF3AN64rlbX4 zYN`EsTde=p#uHE3+P0fSe?u9Dlyv-A>2=NBBXg2PB6QuNUvQ9V+&ez55}wRMA%x0K zAFByq8tb6+$cmr)0mJI~XcwuuHcKTQWEK)r;gdk5ogvQYfw0LxLyBvlIM-sSznvL} zQfF7*R~m|V0%-y(*vPzt^ip%cZRw%wDFF~Sh@+4a_w*P6kl3fS_73}+@78dA?Wyc! z2o}Tb(bg`Slmh&SXGDo&A2{-O?F#8f?P;fPYn%%OOd+ed1z!zA-K$!=cCQ%^eEUln zpDfN%DR)EwTNYr^+MDpbmr-p)aDhE``;T$`lm8PUFZ`~i^*MkSa0Th(7{fleLuAs@ zM_Bboc=S7ej<^5thqzdu0y41b9(x`5baxHWr`XvI82Sa%JpLyY>pnoP5bC^8;ykH% zzBMF2n87?C5pKWbfk1zwd_ep8X*I@wj>uO|7Qsu`_}U~Tk>DH=H(p(+;L}h5ycCkW zyr%eX?1MX0!Y1oq)pf__H*>RXfe$KNak!cARJi*@7<0~&p|pJ6$nT^Sn(Vjv`6@Er zb_}5!P+PC@FVf;tKF-5Snx9$*DW1pnw(rXq*cYv3qPYBFF4SX4DDR2(2q5OU5Clyj zoQe89=eyjcTj%muUbwkmrX(Hh*)AKrs!YJGwdL8O7hGbw{xy8`zY0G3KR(8j-~JFE z{N3NjkN)pR_@n=31zvm=zxMaPj}QL+@8IcMpW<3Sb>rF4G$@}`0@wO=fkskLN}Vvw z`yHyzb6k1YxlaAQLJpLR^ZXq5$`z}NNDWe#<4kl)+Rx5+2m{@V)rjx0rK9Xu@wR@} zx6jMwZ~wjsSVc+jY0@CdQGzAUxU@QwZ5^_-97~B^Uz{;40XZ1m!F+8d7`29$V=BraIS(@R^Wm1WlJs02U=bkiu%*Ri zo6mErnA#HD{&%OeFY^e!t#oF6TYmv(gk-p#3G|MsGSQ*bFZGkQzV>!>?2H% zLW(toMMwnQW0lB2fDFARch2NI@P4KDYbL{~PIav>HlK^R0)q~_D(+c2dOb(hoXSB& z`xGLlWvHk`+Y|2&1H3V>30c7T9d zpT1o=-|6uQV61T@+FqBwH%hS1>scDQm0m5*+-d(Fsn=`WxtBPh zee_)qn)A&+8p};MHn^v4X2~7*Wqa{⋙}W6MI_C@X}SCmW%UXxyL7)VbB4IIUtOx zxkB|1sL)J{%m9kay(i>tXSQ;Wi{QAkME_ne<(9q!Ek@#Y4eBQVF0d>Lvjw*9A@*x9 zdlP^158uKw`{4{gdW_nUAF*a{K)Dck(LIpDEr8$iIufkZ#cs zlyoZQqWcfb^R=bYcKA$elM%+odUpHU@xOscx5ZI}NB;Ji)ArhNew0xMO*S}S)2KNq zFZf1t3HbAOe~2zP15D9E;#qU!Pd7edn7knQnL~VfUZaDJ~Fugk5LM@v;KO zoNC!9kkVE%zy?|}r&-I-luV}b@mX*nU8KZdVuf&wHF}=WGc+>Kj~Eacm;o-BhZick zuoSss^CnS=`K6+BjlWZxY#q+|mdY`=#d9%FC4IUO2NhS!f)>*Fd{UrGPHE;b1z=+V zBD}ELa&K8)rZq8dmGl_p{A#qZEWXdiI+&w9%+LntlDTDb0r=AhEn;2+d|4V5EXV3= zIcn@i<4xOy(}wi%{bI_KbNNdtNh}6nD@?B8UdB7fxQ0FbSFoRc1U&ja@Xl8O*}>Mx zeH(j_nIvdr$@ASwOt!}})d_SiRaKOqZ7wsKwSJ6^m0rqQDOsmQa`sR%tMaVVywM?TR~>a=6g91 ztd2c&TVZOC`27pia9Db0``T^r%|@=vJj{sz+B>E&9iF1X44(F9+gzZXjLxuDXKRPH zS!z&QJq1go9A}b0T6;-wEI)$vM%0xx&aYl}umt&&2V7^4TQ~cTP&+rJ>xEz-d*<b*>Yr?ajqTr;>lD}Ju${J&9Ex+;Au<4nU z$qW%O()-~uibWa^!%Q`-o@)P{30db$MZa>CL2gPiv{rxCK_d%)P7Jz_=GfcSllj@X z4|LQqMPl{oZ7Psk)7{AH!x9LFKg)hLLz#pV&448hG-+)h9C5lwZ_1$T`UshFfHLn) zynEmJn#K3Y&-=gjs zoMaBuH@On1sTw zbQ=|(4vjIgUX8FK?LAWMYbB>(N`!)p9QtcZD24JAc@gt+WU2tqf4Zhlyd zD!%{#AOJ~3K~$jqLo3ucUELjfxA!4Dg%cpPz0d_fKN<`dq(Ys8>j0RW0C{=0VZ{Dz z-EQE@+mqH;_HRs{tEr4`V7{8(B8)cYRCHx3SoO3LRQPkC5}SglgwN$3mRL^+7#i<~ zY(Q0^Rb45y|3R4u;cBIKcqs z&@^nrKVM!bz=(F?mu(e2?vaucX*;Z}6k_CUC-#KOG~SYY_uz13+7cS$DxBWhzg}y{ zG5$9_e)1wdYtOgKF1q(}9;3EblzS~h@{5hq9+#e4*$whq@&Q-i`&V2S)LBnlcMRM4 zIJh$)7T%u4W6O(7W|=j{>R8C}8t0_eG%Cn`cCWcaPXNMeG$Jax)0Ufx2UI$-IG6iV z`uQmQas0WL$r!I{BdHzy(v<~b3)cOJ)G!0U0_@)auD%QGFY#>L;G^XuTtE6#yoGDn z_yixU*WObx+%+d*H_fDqXM&bxh;t*L=l5n9r8^Pe3)Pu>c{uua}(L8TLs;_;orrJNkb(C*=w4w}KI z)5tkB5uDd3`pi3nvXX=`m;vq6P(o(&h?s`q@@%&BGI^0}+u+H67&Y1%LgU4OFEet$ z`aEzac74K@*Ytk?c1Cy}@jxN2pM+Fo{d)4HCD1i-jVP zLTv()6dAqWWClx6aSN~n0dy(h90pqiep9if0>HZKh@e86#jo_4z|#O$wD8O^N_ZP1 z!cH{7%&a7B9)o68ZN`Z-CT$X4O5y1kb77&#L?06sfdW{Bkfw*EYVfKO2sMD0(xZ`E zhJ6^tNXuPPieH*DbrDx68_+J=@_Hn$2zKkQL58Jb)5oN+2@HhNm^n(rtJfb%(iXbRK3w1m(Vip)hy?_)u%d-f^Ti1QHMt%C}zMYBHyn`tEtuhL9G z&^`NlERXPeOaf|Pdgw4L;=tlMfPcga7V-#*6VO-u$iK#8>~$ z_i>>fSm4!+~6VAR>0J=zOT@%GJ0#h;8z5FsHaZ?Hy? z=Yez*KCH*5q8!*8IXbN)q>;yP%IT$UbPt}?y`2v*)Df#sk1haUl9^xul(M|k6myL^ zb_mp#B&FLOls1ZKuB-%N42TTKSp7Uv!5(bV>!G2&D@khaRerl@B!AAxjKXN&Htd_z zfiM`PrxYR_H};$j2y5u!_S>9qn(AK=d1&HI(T-8ISZ!|2Ns-5fuK>Kk+tMFfM{=* z=dPFRN$|{t4JUCS9ckxyqn#|@SvLYA$3d@kr!{n9aCxZh8w1=BqZw&IuG|^{;QcdT z(uY-#YwUflw@)3?{`OaR99z!C=KXY@iG5+48MRP26T3^bm~f+87wvF9gVOrfK`%S6 z0LXW^Zbi#$m=%dK`=NGuAlk9oXi3kZFjJT;SVc3kE%C-cT|{Ve&Rwp6cY`_tncL>y zDfe_5GV`#-Le@+k)^Xl&#Wne>RZR;7B0KDQ&ejK7&PvjAd7#CWq{ZA=S_l<@8MSVI zZUweuprzMCurL!P{&XhO@AxHIDnFdLSrT+b=GC0g!nQvSq^G|DREWmh_jJsR5Npqo zhZL@rOh*OF;>t6(ppEAB>Hh}NK3vJFB;fIxh+xPFp&jn!nL@NvU)@Hw2|b{q0dsbt z(2y}L_?ISQO~vwv@R=C4E7YVEP!@_{3=f;a>1B&vHuC){Q(v36Z`dMjf)7N`CNl?-7JPmIFHOTOXmUc~MV#9P9G{iNr zt!ob)b-boU=(Q#Wl?8?c_VX*?vlp zxZ%oGj8LxH!8@~$R{8FBwNTY4rL=8*q0(cT%Y2i(&ujK{!&WCS_=%8@#LulNr2Kd+ z`Md8mJA`VmE;D=E>CFm=iRWny*ffAhX%};3Bl-}SDtllQ``Zj`Hcp(&Gi$kzg==;Cl^Qj1SyvtUH&h?{`}Eq}%oQW$hNW|dh`OVN zx{?y90BQhow*{E7P8ZuvGSS6`0NTCihtjWTdW4e6_ZHdnz!9q!ydiX(5f$J%qT zHxjr9PVwl;Ef#2-l+A1mx}@8T;p~b>Gz^0fO`I3VRA=5%5se>GfcSz6((bU+4AJC* z&X3zDC^(xdsx=~qq@_t%g6ruQ#0{@gIV(xeeHptVwj>VdC zkSP$NP*G@`u#jLT0)!&fe5{uMtBp$YOy!q(`(@KJu1(~>dLs}XTbw(g;{C6G3**gqVedSKKK}z;?!N(Bp5gs}?ccyV&wm{sUHmydU-npKV6lNEywFSl z#R^6h3=DXVU^fZ~q&ySicGx)S0L1xAFrPRvh%0N{kQO|l3TcZ5jXSa?LHm*h^Vi%P8CU+-`#H*bnBTF^VZX@n41<$#FI5}KL$_HKworx9d_d#{yIcEZ$n)@8 z7q(;)SWhWKz*Pf1YmSL)xAw#am=35g5`XVzZU1cce?iKCv|$l-^_ZWwyqkHlmdi^a1p;y95Wv8U-Zhup7m2F1g(HFD8gjK>3} z%9O%!`bhb#e^*GbI>I-zW5kdAJ?DsLxz10Z!#Hx`{LwtM>v>5UIY@t5hcpQ?!nlh# zRD?tMu$E%E#!1>ozB>=o=hfU(Unx_~jAg*m2$;j3#>w7z9#|>|Ph}d(=S5N$85<8x z#}!C%cPmwUbLR6D^f;OF!E?Rc)`=|xIbg6a9l-p%O~0P>F6Ti_Qr=2Zzv%}}1cCux z;+Z>K3^qccPUn|-a0ny=<7K#84g17rXZk~4n!JyjO3T~3E|`A!(FtcI>A5`6(!<}k zo}-;8&S3n2!yHgoyXAXqK0iiyi`^bl-gqaKqYSyH7wJ;((<2}iJi&07%PYprkg_@4 z&FhlZ?if19{BQBuB)I|DU~gdA2k; z?!$gr-?_IR(=$Do8O&e^f)oW1)`KD>h3Sy&Fic9KX<4*F4mq@NIKmEZz4FQ%{{h~3 z>xGy0o(pd6kRu!+dqIUA3QGbh5;Oo200|6cx~HG_p7T|Dk@?Has`K6M+XKQJ+&MLK z`<(MVsQ8xgps(8p_jNNZnR^ltcEZ$<|cA?CQx}+{`TBVrbLzb7=}xKRm5$} z5)PvPhsyqIH1^f_36osW9eu)ZeRb#>de)$iv~_ z+-VxZGx2Dlz8z@YmO>&H^xTaTE!`MPc5k=)XuK69jIktrF7#rA=Fz}>k1tCvbAq0% zIo39D-013Sq+85AAZvIqXPsO(3g`~icycPAlA^GAwF~hR%Wj9==RSv9Zvb~Xa0eFI z{^$+hnJNwqkb}Lf=ZhIg>7gCDjC;;W0CsRd(yR>rwov@m+%wg4RpHTx(C_}g(8Heq z>k4{}n$G6$$^tBBz`Doz?KAx5fAK5$rLTV(Kf16L`v!gk_m3l{Tk{B4m*6;e48GmiI4T@x$w|LHG$M>$T#iI=wbPCI24xCFxZLLDJ4Xa?Yp`- zNP{%eM0hBncolRG;z;R(ax2C|@O$y3E>>3c_C+jQKiQ(jsmPS$P8{XaTF3xq>GDM* z_Np>M)jOP@h(};yh2R_u&LCLP>QHrk9`~IRNF;^svnJSRCTYy02Quh|dfb_urCYR!EB>cZM{ITsfm- zOK!yR-Sr9_IHmB&i_w@&^R3fhRY(=whrV>!SrWOCuR}dF##VD$AlwYv!Y7X?c+#xG zW3qj6=VF+BMH$txW~1kNc;wp8~P3S_bcvZgjr&Tx;OQa?B zk2r)lpB?!S%J`(7NIfcqhM2=1bx=Kt1`?ywUm{-UAfp0l3hB+;O@7Q&H8;JSjHIV> z1B<}CXqeXr$WtNb!fVIj=&Wn}oZsCNZnjD)g2~Exr)oh9po@ittAED=Gn(>+Noxwq zsW2nwB?KNS$?)@m5L#cBvs>7mzlGP{_!7>}?n1g^X~5dLE1vG%6Yew4U_}C)A%H{y z9z4+3?%pC~%*Zfp_P69mOD{dY*A&a*Vd72Edq*V1uDh)YL|8Qs9-@*H3A9bffEM9~ z#^_}!BkUqt2vCYuJp8(NXHtObN`;yk?GPdV!M=vBE@n8U=TjHYqM(i^4MS=gKqWkE z*_DU{WmkI#mgc+j?uoVdymBE@-RROAy;9tmBJ^%zK2~}fm#|m$x*WIC(vK{V`dUf%V`j_*VfScE<#{ASW{{T0F(&IHzVR&u8XCj8>r>zJeJMr}-wkaTjb?LZ( z;-YsvX$|eH;rW^3QvHy;$jj^XbTwn9htB4qH}E;Z=mEt168A0@f#)psxwY?25;(oa|j6~qP0lHca^CJ)D+*}&^DG5n-@)J?(Ph2=J^ThZHEkHen4k=px zn<|+GP0D=KB44GWSX0U1)2N93pN!S6`y6=lEi7oba-Rn6Z}e?7>ROf_5+0PnfwkX5EhC}Xwp%9Zz|yeqE^4WFM=6Xo|~ zPtqKF(q>~BGT`l6tt-%sJBOjPsT6s~X}(9LSQ;8Vn&w0g*)LIf-SJ^0q?FIXja-(H z7%T0*NfLrpKHs1*H>xS5!Sd(5>Ph6Ma+Ax7RrjzQ);8N$1JK&`GwQK zC`ED>f0DWoV6wkZMlY){`4f9lmk|>HtkA;S#==Oo$;&f)1g_d+FVDJ)fuw=So5cGe z(a)(3VdT<+O#)C1&$4HSI>mb^^4qQlyu8C)Bv~8KuA!9H?fn%TY z17Q5KRC;5}$w+!CH?Rl^+iwvcOqE}HWV3l=mpZu@eH9Ah=ln7TmA zwb*ey$Ez_t6XM#mYnCsw)AM^($l8Fuvp9dY8;|%B-KKLTi!Duf-t87K%?3ylnWFKs0@sX zVi;Cc{eX(uYsp(vKvc0b^^@U?LNV|J@|vn}6k{LPXlWuy$N=@WgfKLB^uR11=;kW| z4?fr9wrNZo_I&0ht}NNEk=I#PxdNE2Iz4ohqx3=($tE7^cing}LvPh*S2d3tE~;-* zQ0{9MjTAUMgiJN(AC33H|AViTfmL{fMvhIISdUSl^KZXM_EX73h%f$tLZQv`7YEKH z-)ma(*%~0+7*+t0Z~giRI+Yt$>I@V#>|lpBox#@H0>ut{oCAkj*muERRvdJXy&SLz zu&7|y7A$>do5?PJMzqv5pdfj*&8!~b=bV-cY(6jU>CGIJ!+}Ol_;?aJRIo^9v0S{R zrSL1G4eJ0yc=IcBm$C(ZcjpQB-jJ_rLI^;a0`k)wsxKw`)!wBURTLx}e3OayC3>9f^@q zuX{<4Ua1_9J^PkpM2SgfT*PK-l|xnxTd7rVk;-*6+Rs^?k%$Q$Q0LUxbClsYX>-205@~RAJR^*zC`pv)d zU6k)Mi0&{NNgGB(?iLGnIJ6j5_^o+YDERIJHy4T1y9d_!_w{Wm__py0N4_+ zBLup1F$xV?4s&=m`X>`uQd(&RUvA7YyO*CD4h?T2Kas?rlhh~#U|t_nHh8bHT`jpN z-HMyZG!qUQ+|-A*OXV=7|C0QwU|Esxo52l$2xO6Xu=(!$ra^3RgQdbhYbuC_*clfX zUOX(Ep^usSl;WI*;9%c520k{Txhd(-rgtyjLm0l9-;;QjCT_r?aaci**_a$`pVwnZ zYUsNnjY=W;#n@`o0<&Y=jl8zyNiJS}Z8;Vipx6ZCBi1Glcd_ZwplIE;xFFq?mWEYf z>%m+dZ60)W84ic%SeHwD`2FX2@;%^je~w*SaQ?#wc=q5S+M>Ao?(2B{7v92Qd4kq10NDrE zGA?By%1u@W(G<_-ie`%wcCAwsq)8JcXjyJ>Wq>4o6O-A{yT|B}4lIZ7*FujbArJ7U zGF%!3zkJ7d4b`wzGz%O8Fl2CsF<~htHkt1td59>?2bpt#A(taBIbyl~$thSB@@(Vy zy|D)Jh(7Ko4UdslI)R!rA(FRXlOEQ+#RuUj(M^%V>#C1vIEI7{M^FKVnlI9QW2pTN!2&EV$5ugMZI9nk;p>=FMEr1^mqe6pB z@)EMK8c?F*O1LPP9Otu;KkihnDwR?i6{kEbk@vpg-p{;`^Y;`RfzSW|AOJ~3K~&zs zozLIL4$slr1-e`Sx?+)rMH`yzV0o(7NRxC-iMNYwG7<{F4%-8A1*f=1nw``qX-XPC zxmd_oWcru%n$K9P5xAysdRzI#mwza@V#np&k zn?!T&RO37iq^zy<$i}@IPOr;Nj!Vi*6?*^ejw0maM|{4_r>^5U9$Ay*!_n{hX$Jt- zoUJl2do6#M-sK8Yh_u+qXr+zdDY*GOQP~U$sUl8bPV2hT*H5jz!H#Nddv@ zj^-s+cp#D~L$ z7$2MHa(JkS<5bF&bk9)7b37~!SZGz9M4+k-67PiB1sjb+1{Nb& zrLqZu&5dT8GAmP9z=oK9k*R6HzV{Mp9cw7PV8W2fQ17*472s@H(EsEk^zVKj=of%I zgyI2o{Rq$tFx-#xPqDfguHmp>@$iH10QvxU_8i~&7x!?ubsrZOxAFRN59|N-BRu^l ze*#?qsjB|a@m?x}n>N~I_O zDJY;=U9Q~84jl({9DuV+y#H&zi2J|#vv}`oe~kCf{xxpt$GF`uu*eGYHtlZcG?{aW zwSB!+m*y#nxh&=V(3hl|U&hS|(pL$&v3~M-#ELw8KH;UvV^E&3~FThx2Tlsm1xau^Q!*Zvl6?+E{@0nQ1hf+aE|U_HHr?LDek_t!~U%u_O}$5 z=Yqq+{53R)0^usbKN`ZCOdu4tur_j{6js6+*2hM8Ed`TEzQ>wed5PiaxqGY-Gjh6O zO7)t%h~^&ia23}0o9cn=^#?hNo@_QX> zf5!}>Qs9CM0m+=yHM%qaXxIYD7}? zIp67G(k-W(&0pAjuoKo0C$@lVRKbnBU28ZK;ILn@KDz+)5r7~1-!p)b5@FDS&p&!0 zbm;mBz$0LP27LDn>v9i$e+P@)1HSVH6H)9GVD7U9 zLGy#Dn)6JCHd+p2SLRgQ3&D(HO8T)Wlc(=qjm|LCxhd993molrN%J#OV-DGO5?ezi zHEW=}K;_%kdsQS9k-A0&JPa{Ciwge&X-QSS{5j`6st5P-kOIdz)wcY|*$;(zoL9CK z&v0s~IlLd~Rzq!D-)r$cPqa1ZHO-v$l|sKaWh%;MDIry*ZIpI8m~`j3BNky{b5T6n zLt|-Or%-7WH;@QZVFYg@FEnIYKG4Er$d;5oPBbTIKHxdl?clQ>28lqa62<1>)Ig6m z;&5XCV?raRve%J$che)*(le~#<$Wrjl_Jw;nNN#t;zmyN1;E)J&wggX?%%kJXZ=Gw z|K{)G&Kn=#)|&!gMPGI%Z}C7*H=0S6->w0XqPrhjZVt-uOwxwXr>1awuGcO!Lgr$s z1|?4><=|GRgX&otL9S`=99($E6gU!Afk=ximN{kI>(Qgc8hQIr|5TkIBf#TQ750h0tLMy2 z`RZI~0Re_5#NlNc2%R7#=P^2I{ILr+xKio>{2U7ZeASW=%^YhKe~cfvfjguKmo=Q< zG*wIYFpRduMr-hzI=wc93N3ogi=a$sQ%}xK%sPXK$D7VmPDavGxq*d>mKz=Q7K{*_ zJ2S5aN*W|O5P3^00p9ZGn1zlE<4A^BSz#eVkq2icOqGGux@QGLH?GaU3Q1KmH4Cdb zlNB8+_IkjrTW{k1zi=P&=WpYO?I*Jvp|>e|!dQg@ zP2tW!$kYQ821mtU45U~klHQOaWAr)FBgqu@^je~!Zv{P;tdHt`ZH5Dh(-j?sK27L3 ztASAE6sSk;hT+_S@~N)_-u9e0=T0Jbo^NoyNMm!QW$+js>hEWp&VLC>)5V!*| znEc;t^6JyD%rQT_3m(E4VO4^_UCN47kew!!>B}+79Kg((M10kU`F`nZo&Poga4Mg& zBCveIJCY-xw_L+P))bj!*atUa_cUl((33?#qq{W0ve@b4q=8t0)=e?hObAv>??t(o4WRFIt6*bPx*2itwJ?Sn4lY z{o?-!JiuZqlvo6X4hqBkoF6gI-wWEYnpUSp$C^-AONEmgbG%=?Tf)FOXUbb0=b@5A z{91j=?$O9P%S#ERkxW0lMXq{sddYbm{kz1K!mf3TisNQ$YxKyqZgz@(9ljwsbO4ds z09sN_NG@5JL7See?g(XRk2KpF)`g6hDaKeNgravrYtG+64>bitFHhX%vrq~RJt`eI zJO`k-T&dq2fXhAb<^lJ9?k)V@KYk7W$N%{OzW(p;@wflMo7n3EbUG$L(fW$U-0Vu) z_Hu|SE$RNf7Z`Ka)+ZY}dag@RXRjL3Mm)R;py`#~>bxrBo| z!()R$xN*0^mW*$#5bg9O9>&aYC!1mWsTrh^tq*s$OT8O?9qJin1@hD6s|O4o$S^wD zJjX0tHw#yYF75!Lk<*zH$#qNhaotK8An{3^hu*HmH&@hsMa%)EO_jv{qci%DWnP5N zZ8rXbqTuF!Mv9b83z!%7ag@l-D<>oAsocOK7;}5_H>pSsbLaliC2C%qq(b#~pRP>` zT~MH7@@}P2-oiSL|BhJH6?JbFcf$_>UtmhIGhh$R1QfD#=o>pcdAH%g>m7$PamgR4 zV2gjRif2&zO1XjXAc>Q|s|0V1$#V2f%*XRt*05=ly^5eurNIROV-)@lxD!`!)WkVr z;?JsfWn68KcMT(*L&WeOVK_v>9}p`LDF>Jepa_XnmT7QQAdIDnMh`(zK1caR(M3X` zv40yNw$m-O605k(MDf$n6=NyExN&`i*Evzxz~2C2p$x@Jq4B@0`d{CJ}(Lh>#u)H-lGx# z1uj<{zV{J;j@$R{pq)QMyZ-=}e_@Y<3ZDFe;Nh)H^!6Nr1Hy7-yCu+|XB6m*(Coi+ z`jV#ld)`Nld-b{Ue7R0#IJ|MGh#}Dl7;WGwzTwS1RUaNfg_Y$4>FH8Tp2H)yabhw< z4L%F?K{70IANcb=HNsHgsd%WL z)mW_YsKmSDyqhs*B8?`09y+4qr;IyMs8o_`Cs+DA}*fP)(SXwuQNqaM|F{W)bblg2)} zZ)|geG|C=rjggj%lqb|{<-dr3E2U02Os#J#+w;xPLtSM=_tm6MV5RBmWFhY9E%z!}WYRfuZMsi_Ar zZ|CUs;EZ%2W;0=^O2n4hGAV%4kf+y6`8;OEGaIt9wLiuC^n_jgJ9CFF=n(AT!jRX~ zL~wo!IKQiqod9wMbC)XKAoVl68#7|MvOaNd&#;m8;!O&8$c#~Sib|odY9Dj)kvY&P z))+7&9-@$jJ$0|0-gPwKp}BFjxwn&`_w=Yxbq_6u<#+Y)eQ{V2`6}sY8C8=rxlv3e zd{D5U6cd7wxK~tYH1uFZcrwO`^|e7)!qhd~kY&Ko5E~SgRMeE-q?{pcfUf$i!DAue z3^DBvCj^;(mSaKB*Q2mX{|n{LVV=E1p}7vjD>bjvKuixDg|i*Y3m-?A;#rMZ#B zE9DAGl{q$MvlQ3J0r;s%;wSM{$5a!D&5pk48ar0&J(hPAlsAmll3u?`vJ!6o(W8h_ z`{WNVmi>TA^3%JReXxzd*Z_f|aIvAMp`15ZSby6dw_^Y{`ZQd&xhQ2$o;b@*EL9R` z;qSVZ?C-Vvuj9Y`um2AI($~L)kJpc|mrFdo+wp^6ILG1cxA7}~?@iqPn_t1_-gykw z9{{q0zz*iyHOlaA=920|`C+`6wRc=-3 z6;New2yko;lj#rBcLhCYNso{AgRZQDpEEbvUY#XAW2(#VX}zEI)Ga8(R6S~|eluTO z^|UiFpD4E|$GlZFFk7SUpc$oC_k~kxsAKZu$hpVw$M$46L~OlA#wp&PiNA#I;5vxD znkjHzfmgq~E$<}5w$G#J1o%)i12xo!4fe!!m2&~tM|be>EjWD)3B(O&C?_N7socOK zhy-$Bu_M)_A(Yqny@o^-CKzOo&#id57+#1{eAe)O!Dt+9(_f`J6*iQ66~@{wVWr_$ zqTM)F#2?#X!Fdzxc7oPCKMEF;_+1c6K15=eJ90-X-?g(&;}CN&cE>ZBFFkS^(CAsK z2q#C3F$*I(Kw}=3B@~7e^k$1rV)x?#x@LifaNrFoba%x?gqg+@2alWWKiH* z7_y~IK{qt|UmBnbqZai5tUy!0aTOoiX#(^TpQ1jG;L~WBOT{xeWF7X|45RdZL9;L- zb)hE0Ih*J474tFay%AzYVZN-- zYMeF1ILzK`b6>Q?KyxaKz{_mIofg#tcx8mfU>@V5Run$^Q;9u(A$sk z@n7ut@K+C5_TR#5@&ro*4$|>dp96A>6R8txDSe_U*V~tcd`W%pj0fw3&Vd~UR6^zhxcBk zIIW9MUar;1aW9PZ`aDpzaJiuuRrYaOI~Yq7Vm=W{l1{Gzh}_MC(N)U(N&mL7z^ij0 z{&e5l8Re}P6!(O(9M!$BAybMaq9VW9QDYAH0f^YL37~YF$U-P`YL6nq@(7(mBwZuwE`qQ>qx@q zC*}KB=gwPWcy%AB@AJ)kD{YTD*dYT>XHi4s$dxdS9R8(cmLugD--KTyrPIwVCnM>p z+`uA$?2v*v4V+crU&}R;*lM_}phk#_EUB1Xr8r(LI95b#&?g~<@ahJot2gf z6YC)Ht!)$>c*1qn16EP&T{%{17+e^Fk4YMuf-1YRsyg+Ctfwe9A)xr5D+H9Vcz}Ys zVZm+*lXVsAgMvGo#^;*rM<%V=&L5dQ+bGPtY%hkO26~A)P`wQ6!ZLaQF^Ub@28S-z%?e&6EO{mD0mhBYWG!rV<3{VxuV|aC2M2MlnmO$ z@TeWVDWEH8B-K*Ku}o8i!cnY?IpepiieCC;W0%kJy-uVeyj6K$;B#Tp1{LXf3paW~ z%?=PS5NR$1(#WaarnZun!S4@wL1V%tTtdUN&*>cKY?JSVQcjRN6l*S3;-s~Vl0KDB zSMf1r68$(p4HAbL*ogt+WKGTcT?EoQv^C#6g6kuk!(7*#JI%f1Vb{-^89~>B&!+{V zXHW=w?~t}QD-);dq_cHhPJE{uoqVJR+}3Bfi>J7S2ROsQj`focVDV69o2%w!m!6X0 zL=O#R7eIK@)>$mRHd=U6YA%L&&JznuT@YM4?(H3s5tZM$HxSH=G{V#-W!1>4dxogz z0W&0H2z8Wvw!EF5{R}V1tg@0PdjE%%AiPbQGhCd;ss0{I^f-7VMgv8;)}WiUhzk9M ze1A3} zAVPg>m}>NAdU*Jp0I8p21L=i@To*dM&+z_WAxB2qYjr2T4}+yKC-tabr*d=3%O;HJ zJIihdbiuCeu=WEU?0UxoDEe5pe$nd%y(p)a~Zt{L?pbA z2aIzp1nAl^r-FD{shsacoGbb;FmWmf{#%>ra|KEU^RcSxF*~BD{W!IHy6+VQVC|&LYh{Fi#N#0PP;G0i=-$ZtyGhNr$R{8ILIj)+)QA+1bdb^bAqwI?S z^ghmZ)#Z$$go>mAO5E$VIkV>+Ug%*Cq`{T2X@Qmamjoz`tU&Cv)5sNuF3Ec8uthsg zM<|5wkPT62Z0_9r9onC|LQiB0kPUXyF9pY#vo;6Kfy_3aRNdetKHi)gJchi^k&OSd zO7|V;2b=%P9Z0(i=?AR69JDvP^R(tfH7B8YUAhN+JHuJKgQedB^c>4_4(L@FuhNYs7>HD?#P=NN(dpriu87zHd>Wq9fv;e5>@N%Z;cyB$sga+OK@MQD z0r&Fm=tk={jHJ1i6($SFQHwUL?#atsFWf9EJdNL}Vri`x&e^~!5A%{aX}natk$urzm2b| zGDqLGk(9hK?$b+J{Ae%Ljk;@bkGznN;Iaptk0!izGviclTB-9D<+H`-TW`OC|Li~i zckwe{ybo<>c>gPJ;A8y&7Ym?^$+^!PpxUwQfOAo(T%zN`Y3c!8Z{dI)L^>Mw5x#xB z6$dv)ng_RuTp7}wtIGcE0<0=d%SI{&_e3@R(!fGIVn}Ji_@o8wwQzTqkW|ejgU!(NDBbs zW@ZmAj14wIMhY#;W4}ImPSTn8j!!tYs@@QAs%Pf$dDD~sEqq2&Y}AU9T9306X>N{5KKw9ISQN`=VB_s%Bt4ZISSZ|+S*+zdJymEB6=V`+;8;L&HGyASJw0^GdDyl>HXW^ZH2iO5r7r+o8SyKr#FemCkcG$Ou-WqgC zFH(k_nF0#*-Xru~V9HH%EsY+GP)&Uu+!-aVz5feL(ME>Mb62mcLY)~*omM* z;fjs|rf4b+M(T9J=7FkY?kKph+5pP|E$KCH(xk}N#1Z`C`?Kp?=f^blUUSzI7m)^VsTP7i#2iglVzA<-AV_+EIB~$Jsm*-@uGEBwh{9L8y4rLf};QWT3RAb)65D!9; zwK|QTkBJ`A7{gZbIj)!JLwqRa6>%yzsZ`pZ^Kn@k?!I;xkTa~h!`+{|hoAkszlbmW z<@>liD4v{sfQP$}q05R@%#$14*xarGOH*K7p?=WQt^;Ttf&&^>ES!(!@S~R&L9Pjb zum6!eM|ub})64`>KV|or@6yBgGd{y7xd@Xz3>IB`qQ;i9c#qiHPHsg==3n1r+@LmeU zH2UPne+H68RACgIAH!i)yt z^#}9V2u0hKHWfbv#X?#loF;alVTrE=rnV@JuC5{~LZ}#`3PR{f=StN3j%6yv0t7B0 zVh38o+Ua5;j}c)3cG`v3D@2aCZW2KV1*$x8v-DGp*;X&zG$134wE)5pS#?|ZAw_6z z9Oym0snmqoVCmj&GFgpfA>O`9cjm8dc9Wk50DS>?7|^MF%F5!Y8Qg&0doP}pR8#=?<_*K|Bh>`N_v2hxU&K90eIhh9Qr(=6 zX-5;m?Y6@i1kZN2aoJu2(~~qc4^vY0*BulK8V=@tLC*$yySc#z-m-O%bkC&uYEUCX2m@&l zJ%>3WI#T(viuBvdRp^Qr1`+^rlSsXn)>{#bKl2M zoe<2VDUrwRw#B@aE69kXgKrr(_Nlw0^NgkVv8GEGSqWb zAx1bJIi@4;G<4Iae)i$iE4~v?cHKUgGM+8oAPfe_f-YnD|7b`jPr(rsGX2fZY{Rxy z4jVVgiv`T}CQ{~%ytwUw$2YisndXM=o)AjPJhkFuT*GIo9rCqq+`n1n#5Ygn1{N;( zK3%KdtElP%3G`$YXVw!H)5}$Hrh)?i^X@~@f{Ia-im$5YYXL&Fq%l?D_$grCCRE z;fVJUxiLpKMgc5GWg4ZEZ&7G-1uWx8qE2h0r5BXX<0_=_N27O}*eq!5vxn1*b5dyn z4MQj(jS0G4=@J@>tPhs+R2(E4O3Pe!&n{l}IOW8%O`x0yphp-Ylqd|QP&X_gmq6_L zm-P`cj|AK%1QuadbKJ~1%un|0gpqTS<082%*arOIo$B36IJGDeu}obQqz6Kok1^#x z1If^TDhmxhL322yK8P#5rt3|l*YTJu0`z7^%yD2iM68wYuiFjF?c2bux6$^mW4B)* zhfAzDgjx~x3T%D4aWTB3J$hnyzM!?&@#uH{0Q>*z8+iY#U%|a!w}UuZTbyjIZUj>- z(y=tFb6a_tc&q&@U-&eM2co*j27KcHB9$tYHsb^izqnPiLeMr=3Y`jUx7&9&lZJc;`RcD&B#UV3? z9}FmdP@>>C4An@JDa&oJv<^*$$(?+WY>Z>T;bZ22p`SBeFh0N*Da9PIG&ibuxZzI} za|#9WY=)oGo3(B{5!@MfQh?CXmw7ae;-Mz-sA2Ul%L zZ&GUNQBU?zU`DV!>7eI^7oTysslx?99J?9M&fqJ^PvQI@LqD!xhyfhog8d7+<$c{Y zl2R(zYM)GGMOp;ca+hP?$myqg^LO1u-71ymUCsaIGLB8s_~|KiMYozL{H?*9Lq^EL2%T*+#5=EVUUqN((Ft4COnt}BUKB$IK z#b7K|uV0$Gfh-tE9yzgAvRmMa>!A%ze^t4pw`olcP@i3(*a0|T(G|D4;=BXrs-A97 zacFknlqoG9CQqZ62(+(Q*CfR3UXt=oZ3m%Mnmhqj3yI|Zbw`*>f1jcQSTShaDw5Nkw})h+a> z)DA^ypF>}#01YybF~mFiOW{!x|0N!iVH)DbyKovJjA8ur5GUSi0J`TdS{6WBC}0*U zE(wPKDjlmNj@<>p0FeeXQ{n{8JxNi<&ew)}=v6$JVH4vr5Q9M%Ut1pfudTZ$l^J^S zpe_$O3eRIrql-v*f;Nun;8{gH`Jj^)(3nfO{5hsO(CEIuD~cu!(v=|jSP3!@o(rJF z@2PycN^Eq=@Y|-+G)b#?%et<|r zgJOXjUFj7%G*%ZTO1sV-Rnfy>S7EGG91*_Zwn7q(a{M}wp?sqSQvw#^S(&TY*SUIo z^u}X~gsPHgeA070;p9CkevLIwOE?U2BzZC+VxTjX&RazUt8T80-stKcvmFg3DLNTcm*KpF%k6GLozh|hF8be}5E%kb_@_49r;M2>A_M8Nb+F0T|DvBjMvc)u1N zR@XS&=tC`)Z=uNVBb>aq1!q+c@|h8z1I;5bdeKnH@lP|v8pARPUS4g?{nL-If<|AC z`uK!fc-1+Bqwn)I_MA=1 zW>Z_Zloz9Scy~h(xPj$lBt4bSSV_fa6q&1Q+WdTV*O*m^DzsLkC7)%g~*kMvj z0i_a~suUG=97erL)aL%wez8BL{(!Brc~e});%MBc*U=l$-7VC>k_h3V*Mb>afl%ba zcn538y;*{YhT(D8j|J#u2Zec2m3~ARk1KjEq(xpGDt1oSRcjXo47ZP@>imXWHcV9bw*4McRz^EUE=N%EiZ3BS(;A?>K1 z7jeC<-^cZ{RVUzb93Gkuu2uQY{zdLB>42=$eQ(D-)T7UnD4`5@)NL4!$=UOoqQoiv@~B?(O{T;)gmSq(9xQ0W(tK2?Gz}Q zu25OsOAEvLvwcVno@h}FvI(n>ucB5b$UeRr)vd@Vo7EGn6_<55U*1+iZH7|wB!%Os zcFH-dvmb+jX)bKed^Ws(KAWX76w;joaOVlu`#-|P{SWYQ|Ccz|4{+=796NOEAtmO_ zHo#Wh;W_T&c?WLE9(UVw6f>!bHyGE+{Q0WTzKo2daZt;({P&ZRp_i5ybZDmhTcSWM zTAsg}Pi7^pn&z<83Z4!_W0vnFY16&g<0sqOq*A@ss1D z$PL5WRbF{HJXaNpoYOw*E4)3_v~gcIp1qmnWF$S6&uFQnzm>n4b(5^F8~2QuRZ-S1 z3e3NK@y8o1Hz@OiPM)Lz!yv|I+nTNAJ%;6ZTNW(u0y33M8fdElYem?ATF1Ho`yFtx z>sZB&I$>zClbOwkmicT{inIhEU3}n)6&vhiaV=e`61^I3WFoc``WM$hB80ptMxntT zmVga(LJft)^h{Hty7mm~rozy=hjiP)AZAqcnjMb#L9nf(t{?99`t;rGVMx#YYjYJn_+hfpfTU3|F;agvGB)yKXu7f=J3(~2SR(j?|)%n2oYJ}k9N0*a_tBIr`-e>k|vs zJLXCWi|86l=Ach;IQtR4^ZFlP_m<+xi1$#+R1@pXaY7OC**)~9+aY>M&@L7UlhheIC z+g5V!wA}q7aqPOtYf=oCBQQ)iv+Zn7hS#CGqDC7G%AFWJw{Y5-?_^!(y({s(_J8Bv}SW^Vl?h&CW#4#Yh?(!x$UB zdZE6weu*~freBU{7}Y)3wRH6Z5J@9?jM=H&v{HGFx`RWR}q1iHE9WF$S6&p_E)$g_3B z6{I8bGCo7E(fJAWFn0mN!UWI->W4g79?)|@cV-DG-W!pxZcvH}DUPt_a*z7Y4CfGb zK9h2Rd5^B(!4SPE4h>ivutpfE6U9jK?Fv!x1|8S~75}il`n_uK;q?fC?q;;=9eF^J zW>-r6uaZ8Mk;5X;%*^&prem-OJJp$i$V6wJ?0%jU8Iy@^`iNtub^6rX2U~cw_*n z<4T%)#yIZ7;LHxPV?}|K=85G~v7u=y<`5g3p!G~`=#GTu}hiAJ-z#`Z;px4b0Rm2esVw)qG&umr;DsQ<;rQ+PD zU@iF(-tB_eP`OI*KH_=v4ZY$)(o%(OQp`fXue*S&M3j&Q#E;q!){UTRP168an=o?D zv?yg`ukg6RPzx0LNgisXhGZ;R3jZzAiF8YAqS!Ei0@9gZaN5KJc_BB0#By1eu}zAZ ztzMgARZ=PWlS3k^pmVEnGWVV=X#>diNNeq@l*M8%d zfqTGSS2XFke0sn){_*eP!5<0!`mg;e-uvoZpew%dPafgh|NOhS`}H$?>1%hO`n1%& zMPIL=)h{fYD{|x7OvhiPtu3B#6%3!G{`sBjwsYOSZ(YBljk@XjiTZFw30koQ^Q*S= zvcAsWUxv5q;_fQg=lSvfN7-uss^@;vFun*^Gvk`Q0%oRmv&+dydMY=(TqXX_#Gbi4 z=fyAOGnEjTh?t4*JO8%83^(RAs>~6p=N3{---+rq7-4oZoG#o3s5N9B6FqZbT~F9z7;EcuFk>gZr2zOTAAa(!FZ;?%u9ySh=<0XNHp!S2V@hj*VVi+yM}JTy#@^EV7BJ?A>_)9W^qpyv3- zAwMT=_ES}2F4Nc`zASBygm*W`PLa<6KD`uJoi>XkFKA{Q-R;yu?OT~IZb;kp9hTQ$ z$Jw0~=lv4>@ddO$!HPX3A_gXSAyBN)vpcx;?$6_J=N;^S=8Mp`--GO)W7$6jE)Q7G z6nYN#KsWxPl7|x7F$XJnsM@wC=@lpg&5F4d5nhSv|7Zgb=NtKLc?9{$?0`wCka^u? zx?kvp(5rQRpP3(9!WZ>wJg4A+c7<0{43M(4k>ojQQU#CRF}76r7I{jXYF`zRim%d! zj@UQjt9kAoV8-A%%{e(}Yl5Yh5cP6T)p6?)x?Uk1$5Hjempno^II%@7WbwhdvPVh7?lmM@(|f~=B<7~8=HmeCA~;GRO?vQ7l*ve<2EP%X?2j6@Hzw_V!Yy7!??*hN}x8K2X{sEri83eZ> z?Gpd|w||K5{I6fZUwi#;;Ju%_z@5WmJov32;2ZzbL;TWz_XXVktGDp1e~|Q$Z0!pA zdYzIall0mvJ}R>DS84h2-_>nw@D%@j)iZNl+uwWei#gBcxW{$K(2aVSg&?f3@=RcGUZ( z?)330W2)s#tc@#0w5_pBX~HH}8&Mi}#hqtvK0`SfNl)d5mm;0U@A^rVW`Qk-nIeea zKfsKjc1`1*y2DSkVF&U0%#+kUfgR9kBrPy#FHMqg@xl<-Zr{ZZf07k;D&-330l+1~ zuo=(S_X&F*oI~4M9C9;zveh)LQt^q@GKvCYPJQmVATapckibytFeZeNPuzGpc@VZ8 z(%{xIMzpV8KnOOLoMw^Uy0UUsxHdJ;Kf+bT2agx$l_@jH-}WW#1|sW5zz43 zu_ua$BfWS|BzLnwY~fn&5EW z@eF&kx9;K1pZ_xU4?n__2On<3>(gq#9`N|lV?4jO4Q+e;{_i}(2Two37vDeNt#@~5 z{nGZ2R6SysG$oImXiEB2Npztl8*`TGNzDg3n9~MUtQbSt-B`;v#7;zRI@Xa;@f+XC zHN`M^^Q^Q#iSQxA9CK z1IroK#|s{O;~wPUU&F1BzlhuWKf+V(_{!J5hRc8W75vPXzYpl|qcPITY3jI*q(>{} zWraMU8p>pIMeuW6Q@Q%A4xakn0wN&K1Mg0Uw^toyO#o=K^NF|7kXu1*csuEZmC82; z?gMhcdcW46*d5=`lvXsvs>6x#8Q*McdR6L_Ym~wH#qluk#~kOmA2U{FDy8M$R=y9T z;W9vt3>?#|uvJD!D26jHhW5!-a!m7m@nf7iQck!YzAELnUe04W%R?`#Z5xNCuDHCi znd0chwE}f0xyI%-Ft>j^W|q^O@p80}pFb%!bi36Jmxs_ehJ{B&3JeikOC@EpKD>_b_pKPKo)w|scT<4O7+1s#SCCWNVMYU;2}SdB;0>Iq|&OO zQK?wz{CX%NG)ROemX0CkDEC;x=sJ1823M2pQ-E5O-MCl02e;MT*%6kxh*LU zDnsCXmyr1_D=f^}Nw3!mUl`Rin^R9)P!Gi5xY4^tJpA0f92Mf-(!10Zxop_xzS$KsPpgG|`hCgw%sNC^TRrlu2u!=y45AT%p!g)^O35tywL?DaVw#dQat3S7@1v zHEB8BmJXZS?GimwZ=Bh<_7&&{WQ;Tb*#S?U0pI*K@aO}`8+Wmse+>uR2X3EZJ!??X zS3mTvH>anv!&BVF-S@tXH}AZQi$DCAc=F(%VhjPVWe2@n@#K5o2IPCd2MhkiZ@&fo zXA6G)AKt@zUp&WU`w%L&Hf@8&PDkg#WK9H%d&^Qe^iGy`j)i`zduf8)5cUV}dmbfH z-}hC)rF2CbrskSwPo>4#x~WRt^P@@)sgH^*m*;3?ElL9bRa01{uJuwy<=zAPbi9cu z77;gk17TeaIs{xjmKgTRW;RD9vpJ7hW{(?xm`WxM#R5Ho)g%^0*5%8I^1FM|6@QDKl;Ot-}-O= z6|j2%H1eVac=ir%-+l(w2Uz7X9^C$YeEvVZg}?ca-oe}FPjS!>v6F+zV4lvYp%)`* z{r7rMj_Y?^byxRmUiFpRj7Fr&b7(}>4LJEuyOP$1kPG;eweA@P;CSuNu#85(>{$=$ zQJ>(q8iPSPCm2`0IA^;C&3j=uQG$N}03ZNKL_t(vQk`qhL9jXICb z!F7{(e&S^?2KN%<2i)}DS_NCPB@D{$0I*2+R6*o)rqMQ8vBUmaaQ!rwlacgPJ_AL| zACLyp`nSX6_UEM%+cOm3hpGM!^X80w7D$Fu>3>N>(nk4bt2$`T$B=GyPOhUyBgT8MctT2)}BN3Q0uus3f^NgYiR!_&U9b#CGx+s5qR=tlsJ%qveuJ&%Dp+5k~@uvZmG$-by zHAIhIdZRJ*fq=Hku_6@sdd#o30nXgjum(Dw~^WFfiTHwJjH3k_&e51bm*JSr%o3N_QeDzH1nDbJHok>)!O-B6Fhh!pfq zkJ_jvvg$Pvp6hTQbKh7QTOi+Z6~J6pqYbNDUG350$%4%iEJU+6-TP{alW*1x>_i7# z7v@zeF6fbhpMnjWI{sPGLJT~wVu@a)sz*)46f7XjRn1)ST7_iX$>)%oHJBD+UU25s zwv2p>r8Xyz?5tpf?Mg7n($o#DTD*8*IX=5~-%Qhdp>%}4yQJ(TnZ%WF)cZ9UXAnPz zH)o7b-xTgmE4fB|K`>}RHpcQ)Zc5o2RCi=h0PCB;dLJ<{L?P_}UH8EG1=jW)&!Bj? ze2fon|KC{k4EON?RGwgw?hz8)NLk%TDj0Q;mrpD{ncjpQJ!ZO2Pt~_7g&TPaoc7PF zqi+6hg;nRBt0+Y6lX-K`G%r0?6|=uzeS0*N+QLkTI+`2Y(yufzQfnVlI7JWOaylm7 z_A13a1_xYg{F@v;O{B+Eu;N)Jyw1kMkQumO92=1h-4cStsEMOsJCn<=gTN- z)UinT>dbj@p$uSVPw|?pH*LTYdAw~j=W&8LXVNI%0&^9sRqoPF{pBS^sWNr|JCFL~ z&AGDU`5!n^J2Z^=Qz1=g|?lBc+s*M0WPem*w^!3l($6x>Z ze;1Fx{1(3de#etD06S_f%|k>>2sPU}BGy~#fHAJFE8-9!S2)eKP(+p?tR2NTlnRM@ zjx}k`yj^wiCe$PO)s3mJTz*yC8gjXMTRh=BPIhw5gvO64k(?PTQSyiq=NzL^s2HRp zHJD=OU95U_k63ALNOmPPJXo4Qx}VH05_wzWkd5#}r1Ikm;=l|w`q!nKS1J)L0Q3Mm zdA-@m+VwOm;(jnPQXtVXeO-`IdscWq4k1E*Mk(_uaFx$cgw1_aMIVyKjV6%NTL=`p zCg{@bAe!bL!GpJE0>khf_9e!Uo~}baSZcHNuV}V}!VTZ1`FC1J$~%q|h2tN$M7)mBTiNx~P3`ilqzik>JT69Dt8k811h+`abs}Y}>_pS)d)*|Eq5U zKlnr7;pcH^chU7Z1UoQoOA}WGOnZT9$BNZG5@uhTRH0^JUx%lS2U6LnpaxAk;)%q) z294YrmQ>-S{6<_eMKlkaLp(Xb>A5%uPyJGpYjftI0bHq&hP|_}pWy1^;e@K;;bC}i zIYp`hIVm6&J;y&G!`Pst1(2x@qw5NK>ziz#*cgG04px>e)3s}rN(wQ87km;DMm_cU zTRAYGz8|5%nr5%pSz`!&lrOgX zVgGdJnhg!TnF_8gjWgPAzCwE{SFJ=|Z-5F!&y3co;t~xX>O1&&eHZta2Y91B!dvDm(R1Pu3bfD_P8t_yOb{#BL z{-~w3`CEnA+Ne}K=M%?soL4-AuZyjcCa=jwiWH^(vUFo!B(dMToG;{LD1 z_kT*u$w+!CpOGR+PtmPE5{WrC4GHYbfJWifewSQy0|D;SwW_f$Sb zWhUudhth$@)FTTlSG28JX$x@Kap>@@D7S&bEueoNz(YVE0R0TwUxywPx(9UidR-Af zYqtCszzFMV;ZN&14$tpH*4J>D!)TeS%e^xjEQGwP0_!Do?ZC4=1kccR=a6-U=mM1k zL=Gk#2VJo6wvO)f$>;3YAVz+a>wvj8naz$gW2Bp@OeC@^?vHuJ_5juI2?y0s1;V~P zw-MeJx>Z+&W0T4rfjg_*RZ8Hu@!b*Tyf*XT{G8vQ0;c7c&NwUdDBhRxR%Lf{sr}ID z+I7p8B(vF8z%_@W5(sf|MMu_qMSI8XR*$D?K193eKXW{9QQ(@#?rJ!Wx`FH9bCi>2 zNCS%ksPr%zlXz%soS(|gE?e{Pm^N!S`Ak%>wjG|Hy^a0Z7x20EG2YWBxUJ98(9!8T z;Brx#(=vp7i=Ms+IzF9dSCrK~*E92li~HjDk;Ws zKSwz8xk^{;{?^J)FVv(+Bitz)U){g!ml_mb`SSvTiHIPo4hibJe4DtBxA(f0c^T z%d;%ZOZxw@_bxxOX32fnFV2@)Rrk?7-P6PzRb_rBw21gc#QE~8 zx>-Fv&D+&^y6a}<_c-qpuk(vISI9%8mWEg>Ujbm+;OwE`{4pTsz`PMd87K`yE!iY!HkM-2t$0k+A<114EiP^EH42;ZQhCFRq{mPSEmo@lI(+PE|0&Uxay zw%$L+bnSYC7YOK&eW&{gr&HtHL5pQf*(lv;Q;bspT^d?zb_fmc`g37`*XFiO1r65_ zk6)!k@p?hvSPEz;Ztf$hqUHu&MW9&T{<~#(f?SI1*B;kHkdZo{PU)ph9H(c`fh$LG zUYrBxn_wB6NrA0EyFeaKXs@4P!Uk9SbF}sdXXg#l&(I%z73Z%$M1OpSzG-2!7p~jh zeGVxw&vtV4)gIV=0-3KD+=O)2wA%*3qqB2-_cykL z#5CDK-94;{Z|X$80y}_k>GWL6yir`PY9x8f658;~&GqHmx2aBts@rE*#$E2OKXZ5G zZLJsO;Lcs@@ZvsN>&H*ipUW|MQJF8w@6%AtwR)_z=|y>$ZQncBfg}Fu<|lb4%_!YA z2tiTHuM=r@Vk`GN-L#_X44$Fb0qEFci+}a~AK}CQ^DpuKD}Rg!-~AYGy}kF?%=Q}h zme*M{Un>w&GM(XM_>z|)hS{w5hr`w-e zwtcO?ZsNJFhJ5a!`#&vj!OADo+WJ{&f}d(UV_kg81;#pr!<=VY+p(kv_cfi2q^ERG zQzbRk5T%Q2bhn>yNSw_^Yj8A1=d;>F8xL#udwnV*R2l>giOK$PSh+O~Nk8Ohg4u z&A?=C-6bxX$JR;1lPdy5RfeB=8HbAclT^p+4zEJYb={4abkpZQ3k+)-%BstG9JaF< znt*OdqA-d0WM8Q*B6QL^> zSOx+$4_z8QhqhV!(r{k6rdoSx#F+$wX5~^-6OBWl;{Eun^W5qc%w0GN?r`bzREPHw z@3N28$JU|+5RojXab*K3C)s1-quy!w^*E3z9hCXRHbtyDl=!n=PV^t=TQS-W_n1#U z`{fWnzF?`c56-2ZybJvFL!eK6HG;Iab19uO5@CXkt9^v9A&+)TAy1*7+ z!<%nEgl-?;`T46jfAbaStLJ!rp-|~|m>v!HyB+Xs?;%01F)JXKPcUD-gRW0-5Sm5k z(a_Mb!{f)V;1B=t-^aK9&NuMkRmZDe-Qx1C9sc#(e~O=9|1o6Cm~%5GWNgC(q?)^Y z(9nAF&H>*$6!{Ycvy9NSmTsQ+)k!W_NL8;6>B0DJeWt3@6}O_R?~m^-%Q_;x@bP8- zN56QG%jZcsj;Y<<>vT+CJH6z6#p-h}EL)f3T|S5WZ)@pt9sKIjvOUI6+~L(Xrei~q zd<7OwP~=x%zf*cylS#xGer1M2u)FT~U;l^y8SS6^bM&wLIWGR&e+S?BPksygK4aTl z;tP5ACff9A=G6^r`c`^AO1FpfeC^wD^m?66tnrNH{pIJUp}xn|^QL;-#5e9*{>|5p z%XL{d!C}ADF%4(e?DS@ilZOF9`zPwAef%4|FA#0)4F9Cc2;C(~MwW z=ZX)`fsYi}s{(GY6sUzG)dVtjH~uvdw}o}H3;6>|rCQUB)Px47bf;-zv9cyKLnO6_ z@~4rspfUu3j+9pFr11Jn30v9Hwg?0wR*Arbc&E1l1`uFC+;XZn4Z~+3LF>3UBGlTVc@J4NL5n!G(qTsO?q{9S zNZ(-jc|4pr>_n_%l%1;T2M_x?Z{qz_VkZfQBn_Jx3(C--JTbFO-ZX$#6H47$jSvr9 za^44B%RY)PB%!04_XY0{A%@lWGQLbA$QLM8vdopWd4TN%OxQwkfxR}&9@}z;K$~LM zJJ4oazp_DlykY7bc!qwl!S%LdhaGh8&?nDrSel1BnYq~ri&lG2TDIOa*j_a|7lVURNqg@^y3n<-7J$0a&4L|EI^9#~$3xSsJWrJNypiqHG+J|U&ZIT1fn73h=z_%IU_<3NqG~cO|=i}ws0@9iY)poxjI}< zA$?z_H4dGkY3d)W$6fp!q8+XaNjG3kZzI1~a9rel2H@bbsHK--0|?X%C1SNp%8b1L%e4DL4!|0J}g$zrAeJraX5E z;0b_V0P-H7SLMAm!f4Ft`2;*Y1D;PB2Lti&7~z3ENbw<*R!7Q-YkUmwZSL`o;`2A- z8}niuOSibiVKp%0RfGiXf-)u4!nj$|eBO z@W{9Bwu;4urlVeIh^3fTQHmidNHVAj03Aj}B;(K@10@TN7jvD(h0@^uQN|18zhq4|3EpbkfePXcjzwIN?ca*oz&!G%K+00-ZY0 zudzRyF~4<&*EYX_uj~|?X@YDN`>o*eqTvdAXuksXGw|ns4*dK>n-Z5Z&@W(g{~FhF z4Lth=fSs7$tT=^DI8nUVdXOBT6Mmphi;EAN+XLL;rb?jT`Ie7rqq6D#b#64(wEnqb*dc(67_blNPH5*-fFCNf{RUTnz zd>N$O*6Mu_pZ1i#M5)fChFP0$>hFR5E0AY@1K3<*d-WQoZcj1nl(aP4SY&DD#-Leu zq=SIVw1{b)C%f0xN_t*@C+%~oKGte&C07#p!Xd4$>#5SwCGA_I%lQ^RC3@s0#NVNT zbEJ@p9_A-RUlc70xgl8d*Z4QvdWUtcC^Gf(#sC1~iGjf@LCg>YL&ILMoAzc75^b=8m=5AxiScRcU(c#8M zDmP>ZvlropunsqnCW6mgu?2KZ@1Sd^AsvJW5&@dDJOGNW^{P;55N%d&2Y6tU(uG~! z)~8-;*S<7b0Z5Z@tM1Zch@}_tBrJhTXPd`r0|3?QQ(809-cUN`XELaJ5Ifd=7o*W9U2Y z0oVic-gtrvY;)}zn4bdu5)BqDbcUc8y6Qnu@!>0H`2XJq-g$e6{^%*bviTvl^G~tU z53rMKhzPc=VS|Q7Lz8w}>yGqSRpddkR+zhkv#Li*=2H`a<{ot`D7s4Z-1lo(c!&R zN!N{}hw9(*i7KzGrRAGBUhGeC8k%L*cT(0`){!x9RUAXbL-vMhI^UKK#TYLHg4qn z%k?9$NosV-DiQsm_QnLoR)FmZN%|#DoHJ$PcrO4Zh@3;Ocfj+8Y2M>ZE-~vh1Y2yS zL)7#aE(QCZM!Qc_3l+hv4ZX@mSbo>V_c0eO>uI@WNPVX8>RYJ;fJF7(WZqmm+o4{e zeozgXnW_(8TlCe~3ZoVIe#N$mbHAzdH|vqyt;f@MNI~1gWQ+mLD?_Ul7`mZqLwtHP z?k@RKKn#X?6Z#AsQCh`jiufuS;!3^WSHev`axJd$V*h0a{^I&IE^3q zR`yx*4O!Qm#azXCv2gd5vYotGhZ4(LpfFZEku&iK&mj~sJq`w z_wQOX8_DcL_f#{|bT5;qtq(h_UX~ilRMZV}(o;zV0Br2L8nYEqGmv_-mBz6)I}(Ae zmwRJ6j(Th=ZZ9;Y)xnnNnBA>#%DmWr-aS0LNC89k`4eW~bavtfJL?i6TRrBMqdG&m z^2ZedsGungvSi0zF3TVSQN&zIp^5(Me!o$isdZ<+dyVT>>H)$;A_gZs9&6YJ-GH2D zGRg2sTVs>%E_5cubv0#FDnf)tMs`A#Dp)TX7~?+5oKqw!7NMxcu5P2yp*Hox)m$P} zz#v3M*J?270QiQXy7W~!n2Niu&^gzF0Pv6nT4foI;jr5)4lYi^bQ2Rans*hq3}XHA zebyt4w%)d|kmRsOpHd3v62D&gWH^p9*EU%@J z^lo{uj#Q^#WF*CE?p3}S6||dksL$x|tVExqyjSPJq6U-;y7*qOqWQ)qBxgld!#9(c z4N-x%j;6L@O4&lH%;D{m14D=NHK*}Ho*|230zE9r|Et0}uvCrBT-#u+1{1-!DPHj!}A_?FMq)%wHNgRvvye_K&E7@g9WGcDF}^K^4mZYLoH(m}rEBxelIm_>!l5jUSpHP^a;p}!q+-_U9?#Ql zxo{`UP^Vx#P_XtDO8M(_(Au#%K-5->Sg+>RT}Z87LuzykBT&t*mcumAUbdwGOLWN% zj!o19)@qE9pDCZVg_^-9E0=sAapo1>+i70aMNQlYPL^q1J z2~uPWY9JCZ8^bW>LV+2by{%%%C?$b*1w*ts%4rH_LNtZdhpjPjN?M-&ZU>*FViIos zXd}-wi?3a1sc?Xb42RJDx<#FtOU^BUdW7n5Xzy}ut3Z3RSj_6^n+Aw`1H`7H zY3^Wz5neM_ze=x;nK`Kf8A(io+Fg|lE#GSUYbq>YF&Z@o(!1&%gK}?8{X&%JY8=Gl zw6(aSi+3nX_57)}E*g-CQs1Byx<+sli@asPWWi+^8?R(lG?H3DTIx6|?aqH7VCWZU z2aV|2XQlls(BCdVQw!h2NOP1CY_66*k4zWqCKOScKouF;&Uqh3^UW~##6sq@mPS@% z!)f%jO`U#c^z$j*r?i-NZSS&E^SHiSpkF}xIVL@WXfwpOgF%{z(MSM*pf`ndj}5s> zLk<%q{Z7ZNrVv*s(xheihb(q*&16n)mkEkI88pI5;sy>)pmp7(M3@`rH<`1>dgRl& z&1bo-8KNrf?a(QLoLg+=$d7O83k|(b0?E2CIZI-v_~w$=3;CG?RwTRtk4;{# z`btq6?Td<2Zn40J}*=*1OvJvUElK$ z(hDlk>k;n8WWLTM0)grGngp6E(VM(SE8W2LLMebN#-Yv{JhZe2QD^1$Vpph`A-gws z3kNyH$i@ZDo`-~iE?hKdlnP^&AW?~>K46)tBx#dkNHm;=p;(t==I!-*dMEo%shsh#81 z&9CF(?zi!+XRqUx>v!>VW93a~*z|@8ib-}5>EPiL(FR4dPa}Y&S3$+*`cS{5U)c*l zJ)k3aN4*cH&oUq6VP$jan%h5Vp7lm5ChG>jRIo^AMY0`4hStrNflNwLWO^YajXQ3Q zl6x~As-Z=w`h1#{W=dJ)QWdh&grrwPiL!ESS@SAmf*ieQ?g?nZS3<* zN}Zy3(!@pW27bL(@2rEC`C>E7o-qN6K&#G@a?Vi52u;1mnR?m5$Z5Q~$;_!F8JJIqSmJo~=Kmk-04)2k*bA zO}hBJ?fY$cT4z#?eIMwhCfA@eS?@Y7l{Z1z%=_%dA zqzGXEv+bI?dt%+cOJ>CHZSkE(%-qSdyqV8Fzf)-xAdD`IGl~m9F95l~a7Ywmk7}(0 zzt^_#AtGXLB1~HTWgZhI-9T^##TI)^5S)Pr0Z9Y2(a`G#V{WA>AX7u@6U3GJP6L@> za4oY#XuMvGpT~OBLRejB;w08$G)li{@9wH7p|~)Enswn8;#DVkHYnC+*fQlR7;LL!5|#vn^5Q#rDi(8;d!7s#K-V}Gbu^)e7l0XBV#hn` zN~Tw0n!?9K48=+#DHU?4L>YpH;Q*^}_j3l%zTqyUxRB!Gs?xlf3c+N10YKC#4f5{n z7^h*u>KrjUtK#PEaiPybT~>8VYi2V=n>S) zWRShq5c8>v(^G%00hqSU=`66>3j~)yf9CK~0s1D(7(S=5uvjE&^9sPDSI_YW|JiTh z;@|xSrf*&2T0X(1?G0Uk4z%t@+eA+i;A|UT4Nd8iJ|hm=t5bh4+Z@hWPW!MA$>N?O zHu2zyRw4&eF>&Rmao^$=)pXSmR9*2X`a2(h$6Iab#xG8@gY`(_hEx?TP>#p1QTO98 zx6(D&?K>yRIQ;ahKJVyMkii%DPNj{Cf&cQE(2jd~K2@;fI&`(45$b60be31^Dd9x| zg(1^C9F0mMXkziyd5uMXdpS0jiAMGf;?l1~ytYuB$$493Ct@2CZ9s4ykphLqkSg9M z3NRjM5mpfB*y>GG=4-0g)}KUd7YBOV##Y3JrWu%FeA+!H1Y({atY55=le_(wH`R44 z;p%htXoG+FU;NwnxBi3Q#0T5&;WvNhkFl4(K;zCfW<%hE8{_;B4~|1z zQRkaEM=Dfj;~~ytKGnPc+pm};zY7FY%=!DBPDavGx`!#%p+s$Uq>+>)g$T}uAx>%B z<8S^Eg-SH(2IJ}VQmz4JBs~Z80e}a9KJq-^&#+E=mwX%SK&A?w=jZJAD(aM}5;Oa4 zx^shIiw(}vutk?GX6+C>fS`e~_2w{G7DJXB!_2cd`*K1vH~7iaC9PGgTaT*gvR>;* z$*Lih1<2xkW7j>tK<~*d@@3y^;w`j%e)G-tJpYLxC23ih>$9d_#5g7Yws^@ZJZk-W>Dl|Ca<%jpT$wVo&Cf48HQI_SPUXUn;UcOM)om}V}@pZ z=>HP^#raiHs(!s3Ru$w1YGrKz%y$)LPU&+=lOZYt{UNZqFc|A|?RR%Z2oyl`IJq!` zWCyU@0<$Pu1J0jy^tK0Z?FM)5me8xAirM4?`%)$VSo~A84IVyzh_`0O!5TR`V^CNh##bO5;YP=2pCQDBMIPCVRte#^RK8l-$*x0BAe$w=D$rAn8H@wU(-z@&m2 z-*Tv_>tZ1$SM{ZfZFcr%A!#C<&0Ug#ChR1}q;OyqJz*Gz!>GfTA`C!`Mw6;dH6 zhCBPtvI>Q#f-3^)#D4g`VVlBW6+(&vd7`729sJS_e2ii0d#<^4UD^sHBcjWvsv9_( z3xpE<*y0bl%Pn1BLxL${MK$_HS>0_af@!kYI&E)#8a7hyB(`3I}an=YN617hHohS+-85o=daYcoZ}T^CJbiJYu>+f z`(nP6H!iFhiilY&%m?6MP_3CT76wkDYy^oI+AR}ox+CkK8;;msnb)Vi-&U3I# zAVZ?iXbPn8?CSs>ufFjHe(yi}_wnGj-@qro_88CbE@b)<8a_hP84Y_VI_97yEsQMb zK9$blBhR!l2DkiyXQtLbijynb@?_mze{i1SXjTZS(!CV^N4{CB&=DRCrai_z3okmm z>s<3a8g+Y>Vv;mcg;FgtM%!>&8R2Dc7sZDpn6$Jaf{x7O#*B5~p8;kstT;`JK|WLSJ|SR9OZX#$2pF#ZfzU&Dz$4 zxpySm)vlTAAQ`#Xy6kq~BeWbEP!0yKo`4eFCE)+XAzO|5h z()AZEt~g##Vy44y4dC=D&6s3m8&)YIlisqZ9YwN3W$w5qHK1wewqql*QjCzy0iW^H29vuLn(ji@3$LVFW<;djpov!7E zL~Y>7?$x(4+VCq7Pw6*ev1T&_L)Ax`Pp&TXda?Ri;#PFs^i&*HweY2)W2DTc<(oP` zP}Dg*I2tbcBj~PgD3GV5&U1URd8KGg4Lsuo)J-v#87fg}Bgd$9g*J)J;MR|qSBBnF zU}8wJ4z$(-B`ZbmywB-mBt4~jm;}H>Bx)3Z_+dxEV3scR=P;xukV;{7XWNwL9q|&M z1%0ZDh#9H^Gm6qcS`^wSzmhH<%uzLPlsYW$u`R{0$2vJtRq5C@K(K+}95O4mZR@*0 zVkaYabE)2k)yt@F^Bu4_aahdAWN6Gnsd?xPn@0_8DoS&pf4XzK76>6@B;in=Lk0x1 zh5*uxdGkOXJ{3ys#63?jCgr=caP(FveBHO#m`NCc=fZWUO#1nl)R@VrLqG#H6(7oS z&HD^gjNuHEZ5DI0nTbRcSRb_!ab#PQiyq8g^17F@vzXD~8hD%2Opj_Aloik;sY|8&&m#sxT_*0*~LQ z*>+0vZu~NrUdB9XrFfs?luD%KJa3d#n3t6yjV?1~o^g%TCC@$@B44#Bp<@ zPSCTMo5(rGSkDmKxS)ZI3ph|?+{|je548c>IiMRitX$jYNK7!QU#=+l`a64cfv^7V zck%RhU%`7{dxnSY1H7UiVT(%$_Sl4bFvEs;%qrE=6pdxqr9(lNWK#6XgKAuFDW6mz zBxxi@Ws*t-yj!*P_Wr(6v+%>UK*#KPt}7;)Y@`0b%`Pcr;#->`&Y`_ zG;gFjn{7m)yGVW-JSA0MD*FZsGL&S5uu&k9mvb5OEW=oi@Qe{m&HKW6kv(mOQl1xW z^TZCVF8^sq1{uvq?1FiLaazz5=J_Y+n~$L~gD19|V^it@3^Qd1`YC$X z6dRGEn3keK?1Il^RTwJTHWkd9K~Yc?NWrcxey7~c*x+`xu3Yth?Jl?G##N<@_wK%l zAkJI_Y6nmOA?sCfU=jqdgkisuukiq>L&G3zC7AvF7X29XkA*NFy%Pm1bcpAcQx+%v z&t?s*;+JDvEA>zaCLri(;hFGlSp{N_I9#%VBhyGayBu@ao0+OEZsm}ZO3bW2)PY%q zv!Nb#gSu{N;sfV;&aoGE17LH6UJ=39^Ia2{ypIMtpO}m$idm&>%;Ijw^OBm+@$MVP zw(0EKB%k#>cnQ9;*G!g3jX##_`BF| z&e5@f&Wf|w&hg$iF7VMtv7Z#${Lq5pR&QDRj+nSeLFTa3z(jzp$6B1!+(T8|T|mO6 zvc|Nu9IbE329x6uS;-w$YPwpyoK3)zdU%h(Vr4>YCtPb^va4N#Bmz_Y5Uz&O9?y?% zkwg|c!c#n654zXAN{OiTq2br-UO26yV|Ew&9&Ph}5etMcM1u&IaA%smGI*b(;W|0z z@Pv*kz_dKk(LafBX#(&hYd5l6j8hbGR7bhBN`rL{hOxODA|VW#bzYYqQ;Lj0AWpF; zCybG-x8Lx&%Cc2UT}14@VQ_}M)XNWK}O$PSqC z@|jO8bt&y?WhvD;bV@H*64Q3NqibSg#f=iX*$n=Ta|l4+I~qVC+pW=$xdYnKM6o%W zpekrjo?!p|Kg08%{{r*JPYP&Ll3ohR+NtY@8)tlW!uf^Z>)+ks{l7V*zxs1*ung=*fNcL=0Hr?~xY=~5dS}fK?}RziT`WJP z&JxHJLs61Pu@8}ZmxY8LbP9>lnwG=OQK|18rm{`AdUyO<$}W6~eeYWYj+iMlI5q

aMH-+t2_=d#zXvJJ>t#wRcqK59K@%a>qwa^$eS6x0pcU~SGW03Z;bKHO%Y+*#f z<-5zUK5UmM;|voHB~L0?yD%D`(w8%h0$US7*BP_Z@~u3_1)gHB*O;3b`Bi5$nV~xS zhP`j5!E^voL*d`J)PV$}``qpTn)INBCPL9TI+uE`)!n|Q`+R+(zN6*ZA?lx;h5if@ zpLZn4+|+S7G7+A&uDPKx70y>h+75w+e9!h)ib+)Bf;aOiDLrsks}*@<^`s&bNs;;> z$IqOWI4V&Ho>_!&m|)k|#OP(cd~5Fo()4l{vB(oKw^ABO$pmOaoKUXr7TVyh^+gz}Iy#&R(>TEAXk%_brvXWHus<=@j)p5j;RYhfaNI2} z1OUEY7=(dU$=Lnbwp4(9%qD*>EUuN%Yxy*TxY_2MZMtC$P+%&^&?Ofekfq(Y6^EDi z;qKr>GrIDNR#3IhXwCg8t0s*iUTK3CrM)%-g3;A|ArLi+uN)76aW^#%E-GV7lUU;M$;5dU=xO{+Pn%13dnx zGF}+R)z`aB_NN_?4WE(QP#sZ>coz$Yi9+6*=#(MtbReFzDMDN8?a#7@x4Z(-592 zQmuiyt79Yo_BRfDLKnXm#TEJ)Y^$Q~`CZy-9vVDG+~|Yo57wTBeNGB4Q_F+b4Q*P{ zm&YWnUmB3{Mu`{$co>-!1+{JyqzZb_H3!|recv|JQJwyHE=0CjY#B!Z(jEWASH8SS zhwnOdV6WJ#U@wBXDf-mW1em&D7C^DXBs;X;J+^Ib324`(fkiB5Q8Xq&oE6GQ6$G=P zN5%PQ)UnRdbfr#8@1ZSVrz&uECknH!eflWrkazO8Jei?~oBN6^e@l;wSZJs;a+0_D zze00e!*F;kTP9WuJK*%t#XOzJHR^m&2T1fow*Rh4z@8fAZu_Zi@#JSrN^E|3`-F#8 zR%s*s7a}N$pwzdvJ9YHKz6fp}@A0>d9%Y~w^3n;{Z;eu_a8=I3jjJjmq_NhRpsrjwEMlPWMF;_#E;Bs25<@JWvQ#@ z9r3lCDvAJYgVtUHHgDqTgXj3u&5ZZYfNPl%MmM@oLlChO#de2i6b#@e+eAU2d!Ny8 zDKJAoW6Ujg$RzSFG&i`hP)5ZkjG<*nn60=_q;Nq*sVSzClN`ay)>inWDTFD0xHu*1 zf*vpg=gtAMQKLH}6*l7#We7B$T}(i4n}1GhSZQPZ9)0EgR1L!L{-u^AVoFdTZT&QP zp3EM7IQDP2OD%;ksYZkHerRmXjf0b+wc-&9QR3It=XVQt&onLk_uYiIUihjfJj zB0?2V3Sr;)_dxyD{^X?L`MLfSe`COV4_p(o2?9K*Q*eWVM8_q7AE3z(F$tAH1Zv$%F(iP%Hj`Sa zDSl4^X$q$sm3NJGt-njRDfvlg7yxD8a%8{I!O z>4?+pPWNulnF@3uOQTFG7B&XCH${4^Lqv?Kf-k=hiJOF>U|?wLF^SDd1!Y9f#(q-C zRS$BgwLYk&*WLadqsaQ3>W5-z^E$Mw!)iI}h}+uqG>%t(%I|XcK9@)5Y$f_vLvEo7 z#ic-md8KanaRV54L;PevA=ZPa&qYDFy$0J-Sf~c6J++1zU70(BtdZ?4y%>+t#LXCX z0?IrmBZP;!bG4jia8xAo7l z^u{7rxe?UsQu{*7r&DT^v5G9hb0Vzu+!o8RuvCB*EAuQVFgczi{a&_-eGoS}8yi%C zISxwFvIuTZ!}_6~r+JuWeNv)7ax-&iQ&ES^xOsQ#Z}M7;1KOmBq3mBhvTa}FbTX2j zq&(JA001BWNkls zgKnb=n8XdLR9+NnijnWm1^SNN z(G+poG{pvK=)DI{7i2)rLCjq~Rlu;XxiDk8yNhKiz}$m@!I_A~v83{a)cA%eV~lE; zb<4i1T$k?~ED<7U=r!i8@lK$pn)k_|9SgWK8t7;bfe^-1Nmu_-PUC!Vuc!sCFXe#+3(Pje%4N=spS0kNMig zy5A56OT|Lymhy-4nRHZ%s96|ES*D764ji;E>uLTL^t#BMDxys2Ca$&8r6OS_bB1dN zIRU+O7Y!uybESYT{=9A*ih?0zF%FfewH3^RK1}D(Pq)NL^VMjM87qR2#^+&AF4Mqx z#(KtGS$&^}SjB9Ss2E1sN6YnwHMt*Pe+@Laj7H%M*($2icOcCe67E z6%|lV@G%`igCqp0sstv2EICxAnm5(t=9-c1*j9o#FG)^b`Tap36#f-*5 z-@)(y!GDOWN5J+WaQPbW$(w>7o&z(XFXH9IK|!WeG(WJ$>`Vgb9lc3P`7Q{sd8TZW zpi9)lo;NbuTyRiPbnVeQ>OExM;YyANG8h^L)XTOL`XoKlMF2mTDU>Q@9eOBM>|=35 zqZwdb!EmD;ciLD5+BL+VwZlFrthn$M24>rJb?8Vc`PD5xMlr{AV79|_V%~KM&6EAMqu&fVrN#zl0An4B(jqx7e+OlpqE z`I^EG(O^S^Tyml-eCajLUB-osKJ@q5u|pVOHJ5h?#+Xau2x!i6-$00^?#A6fZ1)^z z8t*wBpl-B)d0M*>G*AYC_VscF2*|Ct(PWa7ee`8aVc;iyYCzuuKY17ZU%v;;XTW|2 zWCnhx0goR8=yrIW0(ia$o?HT#JLuIF=8rxGe*6RI)yKH(SHLIFeg2z(PdENiRaxN; z1q;JxyLLRe5`1|181tjA;9O>GbeCkdHf!;R`WefRYdVn{cj~$uz8~|O^oNHT7yyt| zaQvhNDmSc>UukocZ_sx`&d?P)P>cZRjxWwb$eCD&O5<2(EuZ!K&=N--SqPX`V%Qzu zpGs1MMD^;?no!IT42t9eL0S29eJd0%5kr`P-X_bZE0>pLE@MG_T2nSk+KAK`7hS|l zlrfC2a9q-aqKJroRx`4-gV7@|ys`6EQ=HebXgSLDa6-Xh-wthBxn_N1V@`JHk#OQI zvV3vZe#$7^*d+d1N*wT0`m!Y_gxvTphxes?XEc*EUY&+Ym!O4VHQWQ-M3{Q@s;jYl>3pdf;>C>fW6BWR@ynhAe?WrR}){!D|hIN(AOM^ABfgkSO1Ow6*H9c*p!~igA6u)9&_mGW6v`PXAFkEm{-u+V^px&rQjZ5$ zkT!nfvn~i}+^mZ0f!JKWr*Xvu+DeE?g67Oiw}3nXK{P1<) z`XO-rNbt@h#WO#TDh?*vy$3|DpaWIz>R#1z}ry{``VvZGMN^3um(U|o{br3Cumv* z1c*aE!c9|RhfiRLM?=PzIG8alG=kPB+aWn)s^XK=#NQDh4jEE_F6$v)QS%D4NE&g) z6{OxN{90Zy=8j;>m{DGc$I%&}F2eq|^0Wz>8@to3+y$A^HX<}*rG+5vifl8%EDx%( zH|OGxv?fkB$(>B|pf^Mpb!s+8;hyVKZtx*$$~3g5hMC`O(wFb76QA+e#nQ`W!#FmK zGX)XbfapZ9Nuc>Ujjs&a|l-)k8Cq;tKfD zQ$T+R$PU0)C=QII=HjQ(%&HK@s0d1V^#MhM zL<~^V^JmsWhUSd7rsn& zUe)o41HXoeMb>49>BQ!+Ki8lhG~#3={qm(snUZfLI$nxsWMPj;BZ)304K%r)-Y;;` zaCHAZzD~#2{N}e0d6-jx)pG7kE?-bL8nLW9GQ7oN^?DkqX>EhVe_2a=a_RY~B`;F) z^r^_80(WbvEItqG{-WeUBG5R^UpgxS^ATS2Ct4ujyiJLaQk4T~lJb4yjD#_c)ne zQ*`KJ2uleKq-4ZmI2I~EOXk^B>;&sBXid@E?5>lwjzEFEdi+X3plvw|yh5Yfy$ea= z$gps?RYycoSRDmH^*RS;d1}#Dfd~+yk9;g0%@or+`nvvRJG6wq)exf@@;;0d!ns{h zUW?R#IOHP6+W*`I){1pwBZ&Cbtd}4|HfnwsEw2629rem7SJpf=Tk-r_OlCWwz81i_ z=zTu zEnm>6J0_Rtq8&?z{lll1t*gJ9OPlk8ui0PsE2NV3nQ3@(j-WfA=Ryx!NA*dTef@&> zNi$>aar72_r5RDIhWW4cuzu>Uog|L_s3ZWiJA%^sRQgImH@!~wDnM6{j60%WUQm3_ zZb}woFo{yn_`GSQ{Bnu>6x12vGL)p$DZ+3B_dA`8q^EQblORs1rLhCRLiEHTqcmY5 zT)%*#*d)PShww9x+lYpS(9pabx|dU&rzo$eOkxA{GgwSg`Vf0NL;y9sQ9A?n7m8=+ zGcGrR8IvmxI{-6!6Lf4XKl*MpKt(aPjtL!t$&jOc(aIvNhfPpYA=PTkgQEkBp*fAC z{++II{+x!qL!+i5BSk9)1P;sv$g*@}r=KiNV^$dIXb^zaRiha_l*K`;DEzE5ZX^r| zXo`-{g9$N8dCZ|?UwJ-cdwEUMJu-xf`mVEjK3`&G3We1=pV&Qf&OH@F>xwi#ti+Tg zGs5|SED%8aP$IJ8khenX%u2GZ4Q9X<4`Co1KugS5Xq=P8?cQMfoFkR5mqWv-(Zy5} zu8*95jG0BWYE>#(_0EH#DD;GTqGsEsGSJmH5~J#KFXH$jpKZ!+Xav<(BJoUWF@BI%O&fKt(tz5>=s`->LY-sv;c+%ga1P^Pr}zp_E=A{Z3B=aXOa| zDY{s=7P{dJ{2(XNbG9RikF$RDCb>eabO%hVOywUpsX~++Xo!f0$KB5>Id7%$Ky&PC z;%qLIkZ-%#Ai;anNIg7-pqES9>jhADu;JF+wB)m_>jFv2$B1$Z(IVs#>+9wlZX$E! zJ;gZkPk}Z^e;jPWR@SiIo58xA#TJz7;u)0g;QgAnjQPfGuT~m(59`BmktSJ=kV2$V zdrJ2?E%ln4?kT3W!8~^tJ5yd3_XJbt6ZH5onLjBV$)q*_#duOA8l&BTI?vLRzj2!+ zDd{l1NeYl8GsS3=?N#$+`}|BU)}4oC%;QWnKOLGlk69-gjT9o*3va8fHDcwBpx)z8 z)QzaoV>=>q^B4n=%pd4e|auyU;Di*t%lK-$qp;nm&n zCZdIM9f!}ja398=;YkOv>jViD5$iscyedn~!(rxGaoJ})>pNWajS0o#Zi?vX-iryb z(6UW_)U3U>x0rqT4Fs0(vJ!oA73#Hg>)of>`Zu@TM>s6 z(IOr*jV{+7TP2i3J<$9TO~rcDI=LjstxF+jl;Vi1lGT@v^`@Q&7X-op==Gq|7%ui+ z#|8`rG*>bQ!?S=Vf!J*t8%yyjoNvzL{JrXFm|ZLw6vWEZ!!6V6;PZwCO!fSS@f00p z3o=s|%HtD~@3pBI+ySBk_+;c4{pas9CTz?@E8Dun`q{eI*VCY}3KG?d(uQvJX(g0^ znjlETwU+YD@FeDzjgkkAQjl<^kNm<&PvIGfL_MXKD@nr}-~Ki(uWWOr1L*UNr$74{ z_D|mj#0{S+7N1nNhBjAmto05CA?2q4{UIO^%eoUseWsz_X2KepG^m{$tTs?Q0Pp~q zU&Ho##;aF9#q;eu*vm684yE|1#axf}K97k?1EeiaO@3w7EAG6t9zNI65C@X^(&)a{ z8#+`H7n?b#qvq9-t(A*tlEEkdD?JdFh7A6$5|Y#hVly)Pmh;2re|mt#+FNM;Tp6(mpqY=LIZ{wDHsF-*SE@9H zbcL?V)HZB3wl+a!i)ng*StpOap%%*?h7jw%_8Nf%YOYK+vwHA@5EH$`rj$QzI=3?M z>nZbNBuy><7OE&gRZA=BSwyi-QO~NcCRjzTsWCJ_8dArtyJLHra;18BkID~g>ZK9v zlqvd&?Pk``NIkY%%E)`u1KwUrNk6QZmuJb#~ z^YuYbKO}Xrd3*oU$w+!i_b@dmE-;dXw)m}!d$*AhvK~hj0t4APB;jj$IZ07-HR&P1 z)aNId+hjRvfQB6G{f|Pu<7D(ODeC+%W+=F^y36sgQ?nn8zlABk*(r zy1P-#bcx&M3c`q%Sqf)5 zhiy`|D72tyjbxrNLl;VL7=0U-E}E)<%)X23G4VzuMo|E}mcV4oY2Ylox#*zka%)S? zIo!JQRo)kvAPO03bC4H zs)?S4NVCitq}=8TuK^l@gQVgPb$gk*alPe20GmK$zhF1Hc)_vAnO@e_DZM;tv%$kZ z_y*iVp|w0#D24-0KV2XS}jMT3c5;-|jYA$+253 zhZ%nb%gaRa%c4!$0u494PQkv`fh6PBC6W9y(C3i@KP+#Hi=BtB30(u7RtErm%pv+A zQL2jykvD3CsA2c0=mp(UFJI=eY4v%ob@efE7h9ds+}j|P9f3h#TrnSbvIY-ACtY1S z<&y(hA1mgN34%d;|EY(HfJ|swIZzOE*t(fZ{?QUZ6iprB=Jni2+%4|*3T{TFsR1QF z$xNkwPaepS69={68iCCvC=W}_bogFr1o?DXBWZ9b98@ZYz`=cnYvP6=Hy&(+_}?kr z-^BIOAP%Zfr~f>(%kG|`W5#Y)pl|WX_3OCaU7*bqCb0uv6&QOblm>x&| z>aw#Mg=*RAp+~GO>zfq0np+7qLnCUXrzoGxx^VPsd+yFx$d!+MGs|XQi%Aj#{W~tV zp#I{#W6{u*{at11%XwAnRA`}((NRgtJaX5748wC|a&g~6CkTK!_|S{{f(*e8?|Mk@ zBZu&K0jeE=u&VALmF_Y}Z0H@CVoo`K%~_rGXz=*&_dK19q^EQblR&Wz!N9KY-;r5X zCyg6K*>YXVv-Pg#KpwlRN3j`nh_;NPvy2q-C6F{kqiQ>S*kkcZ@K81PGLxtX>KY$2bOM+ z{ydT1g9Kj3u4RF`tSgPfRf=EETaIlJLZ}!7t*Ay4?=zNT=q5w%%=9xO62mPpD)hOR zm;%Im%zW;YUalmHAHVhhmve*YY^umkpbsZo|8oP6yimP{y74m%qOq_xNZJVi`#{i% z(+9gNh{$SgKx&+41Fs_Tl$&VR5ZM9J(VL-0MLVXp2QWi*wppfg7wgNbD0H~ z8lK_Rjx=PIrjY9!HGAInoq{vV!fXHHlM$-GhjCX!0iB-Vb z*a61ni+#yDa!Mns(X~9hDTs^LciD+!H3bT7?zQo`8c4kYF#03f?9^&mZXc5vBR7Vs zH%IVIwOHh(2`N>fjFok$#f0?-)cAC~A2gR_l{CF)#>+%j6GrZy26?BSG(_{@CceWB z*`Z$sxqywK3}Faj&Vivim0yM&a#-cnk@jf|o*wQ{rkfDT;~3?4f%6f@&l7|}hD|Z& zl+Sy4lFdTW>-DBk?_*YVn$-^455xWFFIFgbVWs%Wa1 zoTiJL?}%vRToXt*cU9SxOQ}XQs&&oF#C;-T)C0OAX&A%?UfQu!{|zVnxZ+Hg|^z`^^+wkLJqNsx0)5;QV9DT<1H*Bt4~5`XVMS=A~F! z8Kn$QXS#`+krj+YspeYCS*mo2#1YS>zEu&Hb-!N#?11(R(DwlS0MP59K27YzUG0kh z@1Oh$^#Az_3tu`3Fn^5AfBYSs{r7)}XJ?Zg7Q*dc=^2Ylx__F>NvAjiw8@x_kA)HBV_k^g1vGY8cHTkNiIPd&^>s z$-lfE)aU)83qK~vQJGQK_sxyl-6;6t3bM%B+N$P=VW!Z)*L(J%*EJ75vNrL==9+~# z5>-UQb$guR-dBZ>E%%uzR79PMo6Eq2HOGl8GUs|(LsHts$`pB#Api_T$9@2a*ilHi zHwv{`O&u@9IAps6Mbui%2>@Z_7$9R22SFg1Kv!g&`wRf@Yu^#Cb`Y7rUrz6!{%^xe zBR9-|9M$$Xt%IPKcnGQU_LN?Zq(&=xAj&3~OZ^$pr;y+~=v{=jB_E^}C&bAu&ViZcG zy)EITfbM@w78|b8mGb0!0)cplid4AEnrB(UjRYRsvBbqW|0K^S93NVJGm;Z?{SK^x ze4z|kDqwKMqa}R@M)r-8X|ypMywRN&C<)Bxny56AUYd2IZs#r^&&?wwZFO2^=hyXc z3QY{DJHGnHXa@pul{~$L7YQPMTrHUOQ%-_%J;=2?JV>k^JEYPbP)qkVF;q=sJ+$tqcgZ7o{w+hWd{xUd@Qt|0Ye>5KJ^6;lh6p$EQn9tQ+Z+LZO7|^| zG*z*K0V+s$8-Oj^`5Sort-lL>GzrV-!@xR2=vp+$Xrx46&f^f0N zLedl1!I({4hS%nXl7dC&l3inektYe}4QRQ=l0R4tev@KV6LKtW8yYVYNE|#nR)$Y9 z=T@%Wo}#yDAQCuzNJ?L6sy!y?#hGppS3&dWT0IBibWoRE{Wrb;;-vmOOQ>FWx24M0 zfR65m&6f^E z>R0YWb16G;K2gqCW^&Vfu+-ovQn#^Eiaa)rGbz1*>by){>ga60km+P3J*9h?$i{TI zve4cDP-!Bwxrv}B=@Iax^JQskhEW~fA0x8yx|VCKSIghp0bB#}9Kcmkl572)F<%Pw z@*L1d0JZ=wF#TY{*}wP^F5kXD|K@9EJe`0r5>?|R*|i%`_v+3zfer*{7*RPIC${hGqo(;|Nn?wV`FK%+5&NS63y`K{cKFawBoV=D7K&L%5@KwY+B zpvb-|9xgO20BLULcg%0rC;$K; z07*naRF`c4M8w(rTjuHS0pV<~xCZ1J&^=ThU?(#!MX`rq5*h^^?Y&YjU(JOJY2G0s z4+?6)QtFWWNEb8+$zNiFD~LWqrST0Odv%Fo$yz1a<~FIk_L0PgmUk=lBaH}lSl-SY zeAA`--6kGZt~?p^NiiC@bhssO0^i$e2<~5f^6?at8yGrZ?9nQdENE~O-_#TLTp0af z2Blw6HioxvT%Plophgt9mfwLWMj*PYTmOk69p!tD?q zVt%mE3`N__`0C&KD)8nTm|mUHf8!eaU;95WxBnem{1rs6uz`jf?I@QNqp9sQ7& zwSI9mrtS)=*FxyJjUmzHqe0MHHhN^;-bNxwf#}!ZUco8r9P8P?EStZZ06cY_hValv zSx-k2aoj|#@0wV!Jr5$A&w`UT3bc(mo}kw@MA( zQAAZK08F+lM4KJL(bZiT{g19Y(+08jDoht0c9MAt&Ejr5fwvX0XM{>^3f=bnXCTp> z(yt~>6Smt8`sEJ&XYWCOaRof>fSv>W(nq=?JsX-d@FU&E zrjqD>-h7j$0}w`EvpTDgMk?&!s`9%3%N4YK7W<1+l?Ik3!GqN%foOr1w7riwtXw1aoW!-d2N!V7hDRGERp9%jE7Q;#YQk5!py z`Mq9NXEin^g9l0&jodgcK6gs&YO4t6XdkUA;j&(2p=BK@cvK(IyO3}4=58K65?bx@ zLC%*^UZg~08?nUukpDQ(0k;S~=ec%DpHr&b!sn={g>mp5YQ+^Ez41f*!~gmcZ~e|w z?Dy~E;VVBzYyU5%_H#_wV}hW03{!eT)K#3R(%_Lxp*(-vGLRd-FW;}+^tLooig6?C z=2^e2#c}I{t17)Pcy(Nxyj=I!*NS+Vq`l*Np|+M(|M1RdS#Hhs?j?Ml>9eZUr_U$) z^DYB=N~`H)Bt4~5IyzP7rkXNt4}dt0^ib8+!dA&W#_KJ4L5t!;{`?OLn>B8 z%M`inz;NgX1dS+8N&BboK5MwZk^d0al?QSu+k?+@sMJP!EHV zpQJ1z!6TN>Ryx4E^0&CLSvmV{muNkuEO%8|TP<)w$ zNl7LtiUI^fFlbYTVZ#O_7zQN33v1zx4H&TDjlD3u^uk-i3meeZG7P~6Ntl!giWEt4 z_#SdNqv@IHcXxGFW#+yA2`?hzoH+mevnsQvyQe4TMj`9o`#;VzPP|S;9AHD=LR;{i z>?o0<0SSZt?Bg3ywz8Biu-c zEHCzb9Y)6ZxCP&Z;2gANWy0ZPD$-W)ezKY9w8E#iu)?nkSSwy9sl6-n9_wP%h$o96%FFPf~OiGF1re zgEHlclGz=xmhoRPu5s~0s)C~YpPP5NyZ+qmK3=hQC zFE7*QJ1bV|V=$aRo!eUkiBsQOx&n2%_ArbzLJ+NcS)uEA*akWq2K$3PZ=v9(&yv~| zigQN0_>t#6mn9S3U|cMGQKXIcGBtv#dbp#~jIM#sfjhYoZE1*mP$^1)f@%=-{awb50(=^u5?`k=l$_cEE;vl@<4Vc7uICNPuqSihlSUg=4IgLaj@IlarI&c~#rx0GO%Hc8}0$+(_}EoiFKJKx;U;9+?~u_T(1dnxAoUuEQ&<5S6~mk3$r z+|XD9qlvU%ZzLqmdgk~RMjrgY%Lvb4Da6U}%T~s^RthQ;?U1_zHET_QUVdL6g+xqO z?!_a)2Ymzal9F0^Vc=fyb{jvFS;iWBgh7P*YD>YeQj;pkocKkwDC2s_JJCl^tAf$m zmVIT>7ahjQalb^_d7^_K1pWp8sx3WB?q9stx48T7%QN7u&7=1L@eS&kh^{%Dlx~t4 z%S=%U6e@Ma;2b3!!|iW2WU5s#eh|mg!DUIy-%hx%ftj;?YlnGT~W-J%Fl9 zB(_wX|5e8&-!ywH%}EfnJW^j6)((QFwO0DlZ0s}h1z+?U@>W`h(abJ(*;>x)J|}MJ zwO-zj)vHO)Tk`3_uhJW$N!A|uQj!x|FRnJ8ov%c%9^2weOBs`2699h;{27!`Mu=RPk=rXdFxqLo*AW#_ZF1UF;VfTwDs}0BK>V;zW8=X1mf= zy{r&H_RgF9P!Nrikt@g^%AV%o7|Ozeu~s%zTxC{2NWBPEEC*UCA&{HWTD5j>xl%!A zbdJ#Eq_`}^876B#oVoh@g2--`poym1@AUic^22GAt(Mq3-U#`sC9CFN>u-3>!Q z7?LC0J~jzL%nd`<5k6dC^HxNdPPga_&+_akeCA_!c=7DBJiVKl%G{`MQJ8CGraGS5 zy8p^weu>}y&EMqW?A$!)Veq!^s#_>t!5h+=^Y&yRRhgJLVFq6L>Nohu|NZ~O$xnQp zfBnDyx7mF5)X-UDotffj_DlcQ3`3e6A;SRGyK*2gdmw2N_TZK&db0v3s)*s0vTFj^mjM9WZ~w2y)2H*ZsWsWk(Lyz=5brTva5 znagPR+B_PMl1SyE6)CkDfcp6NwceH0G?b1**`Sr{=?eeaL>%GfftXxo*+m-`NL5ZM zY-HkGPuXi_Vn@-rt>)PLF1~6?5`6n!htW|xU7jQpJsA`z>fX}Hla%~_h+f6TcJ=IF z8S&jwAlAt;4{>~{L>dYi3TULZE$+NyzZlI?^lm*-7j#X}@O3=U_s*46v}cS;?Tm4^ z#0Z!1`o}@nb!(dK>p-~LMB)>@M*W%Ec3RuF`>zV)^Fdt~TuD+884N00mdGK^)w(rx zwR@c_2ckQ_kSo3Z-a$*-;xi*_RR1xr`+tJVc;foVn#|OYd#(K7>KQxo-S3PPE=MEj z5pEy|$Obb`aw%<*0Xn+jL{3dC`Y zQihif>uzY37_;~Q%kuH@f)qIr=DHy0O)JvIH0SIblO?U-b)Qt4p)}7aDc>jI8J5=- zR7yz5!~s}+EW6h)u531gi6e#`#3WFmR`)6%+7LZXOk2S6*?N0ozQaI|zbmP%iuI=i z-g>#sSm5E&*tjiydYe5uglLhz2kb^FJEyBUo`+}`LSaEl#ZIp}!iNWxsT7JT(?*z{ zo;bZ-*p)4B@f44=`>Cj0AhI{3+iXVfDlm(1fAfg?g$d3plnq6dS&dH}nySLs7Wfd# zoMNI|T$>TOKuV!#<>JwfSAYLLclN@`pB8xTA@%MfHrtIy83@X3b~F(auo?IaP(ra{X{KLz4InI7FC?QO(2@^I(&Wf=V8o2n#bG(#BNN?*&-1HU{$ z-&m2gT1pzzfLP7NSEqUV$=dq^N$x*#Yt>7uk`>9C-ZTE?t@VqI!TA^(pFdQc^1#<# zUha>NT^J5RF=Vxj{o(rqpRhTdhU*Y{(u*77J3kBlXcHcKn^f_9ubI8|jmaF$8sYun z=^1sX6vvC+$DYtgdp}$Er1K7+uSmHt;6vjd!4IPB&Njxq#l(MnT*3&VtxbKLZBsGj zW$gvEVeWB1=9yc@r|B)~S8}vV!KlSC-2SFR!d=I4Nji%v+@F=xSvj8zccgH)?3rA$ zuY~8C=?NP^B)m%1;uI1gGg9vueZ>?(&8tm9&Qo`kaQYtdEcBD$7jo@tx7+*C^=R2_ zvgaUUd0WJd!E$(SD67@6tTv8ZvfSg@(ARq-zJ?2#;&uw7{@m=da7d9K2i@UjMQ*<$ zM3OV>K{=o=Pi{lsqAAW3uJeAB67+Fy{i%%9GV_O}uWO3;Sc%GOEe#Kj=G=0b-V>L{ zIgK~+-+N6}JI4?=3}16T#M(W%th9_;%^HVNTSU>NV>X8T0T7g>gpK6}!_i23gc}Hg zXdzBVKag7!cwi%L))<-S@adxF!M0+S_U%KfIH{l6a0a}B@{m1BWy11|D#C^nIpO4F z53*yYx6pFS!tqcyG@61e+@Z)_sx-ftMaTTN>|C(eqw|K3edZbd&Hv;_`28Q8_=9aR zg~W-dqM2J;=7>gDcvQ@B{bsQld z|u@W~<245~n^B&78Towg7nn~BjMlm7HytE-0rX^4_`t3q#gyUJ8x)+eHR^ekz z^qawxvVBSybGrh%7}FBZ(#i^>Ohs+Y2IDRrDVmch*on$D%_Z$I7b+IG7GFYJM0!WF zd{oqo?#*K%D%GJM;X$Q{N1d7CtR;_k>`5^q$3UmITen?fKPYM(js#qRp(fKj&$M2pmIX~RZWpy!U zJ_lm$>}deT;k5rI&}pQhsRnC{9pchx_AuU#@6Ee5m7^d--j9vDM5m#x zhoZHG<_=v6Z!|FZ%~|y*>-Bfqd}NdxF5mDEELIhDXYu(ti2oSpNl$7 zj7zfg0e4g1aEtXXBPmQG;<}Nx%kQy~lWAODnK@Ki7M(NtrBo`B(B?98)jD*uavsUm zfw>eSygnOxuQ;LPspwqcs*pLkaWtE=Fc{~NXsVm6_0D=OtrQ>o<+G|TH|2C;i_%hb zTi%q-R6E?14&PqT_Tk#qMkJg?L`svJIy|`?lTqE)ZMMYrfwP${Vg6RKOJz{D-~l08gv{h>V1AQ2XMPJQu={oj0+{dX76Hq|nS zxk6t>sRhpy>7FNHoD!vn<$2#q>=MEdVxL)^8<@oNc^Oj+;Xj&gQb&ZoNiHtJlm{Kv zLp_`E(-~0F&N&AqO&Pp?!SIl!CmGbj5aL{1Z(IQtoR9@=QL_K;|ar6Fk1 z9uYHzAt@EC_+ez$suBaIb8&$Iujg^T?)lMJU(rUtXD57cU z2k&q^FDpo$muOK28&OtG#M83aAwcn_KjY-G`y2N4BSV{Pj--Y{)z!l~v}74B7=%iD z83$T(YP_n`?_5JPD`){LYdnZg7$(;qR79(L056TkPQSd3Eu1~KQ`HEWA8IHAuB9?$ zY|Ge^n3>}Ku6gWeN@X*S*Zy`NkuX?Sinv$*z*E)LcE|@fM*Wtq#MVa~swIh+2YC;a8L2aq?2%ec zX9?Qf42j|2*X5PNq#{phoOZD>%fX4>hB)8xdW95@Bxhv|tlyE!!pd9F^jxkkA{aDf zLQXu1;Td%nTzz#}R^WKByFWO637Qr3F7;Q_vrAF+aiHGU*s#*%eR(~osm05&dVKx( z8<$STV<5&j`@%+Yx_qs%wU~=bTGIXX&B9(h`k)$aYm9njDH(NH-3ryQv6#W{z{YxlYR8N43Y5NpRpF!#i zNWI;-K-&q`4UtPuWZQO`*1^N=wPH*Aj92fy&ab{u`Px&$JIrV;OjCrIxWTUJ-?ek0 z5@a4%ShXomEkD;3hE97(6TuW$z}s$HNgk8#$)uhNG7gd|ZlF~cnj+^<2r)x!Tb>U9 zi2wj?AwA}q2$AElF4JlH%lHT6~c{PunuUbG1LNt*D{ z9CM=ou#hNIxQBZ9VkvDLHO5rJTP&38)=FPusaKJhD0f6W8&lCflM7GNL&-i#zmmts zjr`vFI2F7J_}+I>+i0*{zU|E};E8$tXjQk%M<3~irrO&X9v^*89pOU*s?252Ts<6H zl>JtbsWLM=ZJOQ7SwK$!%=oApdrs8mmeRuvo55T{wN(#^haPqv_&FJ^^iP$ES!cfQ z^B?0s`VW7GTc;;{`OB~Izy2@3LY0}n_YeL)-}~d=#WQz5%ER-2$?oLK#0J%*W;)pi zjV;m*{!NiJ9NlR3y{5!hy-70`m|dkiYYz`3+9P8L2b?UN%{!^;^eNI)XwZ?!z!oe* zjP;e$H`#)JOV9_xqko_5lU#7_PNH{neo(>qHwLFrzDdY}^x6wR;xDd=?REbsk7~^{07Qv^$$O8yi`)FWQ~o z(C|hbCOt1Q$E&LDNIdl?qhG~SV}xwe2cy+R3!TjE2<%SLG)K6h;B*3${&RdB6jX1s z*XKCXTkL^zeZWO|z$qK1S`qe4oFlrYutjClyd~S7|H3=|-AF1C9aYuJj-1b30&*JT zyvO9am9FN`0Rrdy2DjC-Fm*Lr+-3XRFHLKCtsZG>&9-!U3{f7VK_X0b$na$5hy(k3 z0_f1!X}}nomm=N zo2S6#{@gXkC3KSUJI+qe`T9M0>o&}@<$bIrLYQ6Yq|y#=3NJ(V%227)Vqy0+c}j(H zW?qw_OyP=(&@~nNYX(o!!5v}j3a2O+I=YjtG92)bJtUUQPZgD#ID`GxW^`05M`OHP zWhmiE(*~V5II3xdgwm>wd74qzAFIA&ADk%+!c9r@J^gS(Mw_QC#m0Eh2IHiQcvsRq zA29tW6VK-={aSRpy{)c0mu@f)k4&v*;2DI5Q8ci_IJ}QjGDs_J?6nCVT>U7J| z%}ALrQJ5ng1>v332o1Ke6l!g8%9I6UrHAg$UeAuFJ|TSmmp;esXHO}=w_*AxuX1ws z6hHAZKftGc>P5a*UPkpkMRx3|zWx-cW>kv9lbV4(ZRj9o+#L@rOUoyQK^w_RZSAU0 zSLd=4IZ~TYjN_uwO83P{8&QWVBs?M->q^j#rc0ej(l=ApogZeN8m(;Jl~;ivJTU@e zY0I`ZdKR>JpuNs(-RnbwhMJr2va?TaR?t_W;o)IFYadAe=)TNdiLM9j%xzI9)teX% zjz@(^^AN8O2FAdnwc!?wSGkNKwGdll;dR>ft)nk4Pl*dxLola?k&?v(rM|T;Cj4J% z+VXn;-TkA+a=X0J<|A#|_B~<6au3J$e-8Ex*`yoBqGeamS^xkb07*naRFA>CWx(kp z+)N0`#WwEDykne1+U8ni(#lj$DdmD%#blYlHSt{NYa1+=)OZc*)81Lq{ai|;Bg7d@cP^u5m%q~uS?g>6^19ZZyxuC!gLCbH`cS}foJPDDzst(=8Lo$m z>ti*RFGIQc^RkhagLkgKN|t?pcizEctHw4Ru9551AUtV(+#EO>Nsn+tAur)WB6TS0 zF3I$gO!=R#kq0-j6w_I!jZmgSEfafAsB9?p8ESa}m6<&-s~}pqm?xy1SnjT-JNG;~ zvv^(<-B3JCf2==C_64D&P<3UVD(90jPXbcVBFr8}T&NVCnI*!>Oi-#JfV-enYo$m@ z`QDNUA!%%yKvO)Yo{!za=-0-$fG!m8)$#`qozQ-A=$Q8VVYotieNu-yyCz0AWW>d= zDi-y7O9j^2r|wp%0F!%ZIC^MU3;Y!Jn5t&HYsz5sPkY%YIrMz+Sh`d)uySK8TYg!z z;ZyHd`mQC7rFKJkYp|v<^|myx*d9RG+nQ2Av{U1w?Xi9`zQnltJK+UdJ=iiUh=D5# z&G=bkJSB}?)EDy~W2pYTk8K;)H1BB+;+Ua#G79}hMQxb@DB&^E*#dLOtf zrttQ#oIZ-mjD80sL;tn|F*Wm~*pALFP*IBIQc;Edrr~OL0M$l++H5<{Xtj-%BB7{y zRc`oDr=`6>h&5H!4NP?g-sa8C7x|s1f0yYa@YRp}31`pz4!8A3d3*Z~U%UHTyt@4Y zy8Q<5h*|bj;6ysT%6W=$-qR1%F|VJt@v!8lK{}$l=|(eN5r)#up&}V;CJj#`w_acM zyp$@^LjDsKZMEg!+ zeNx>xD7B{@$m4y`hVkvzfU1=eq1lXv>#<#ii(w+QZ{aD^J?9hiCtO7>0M$bJEELt- zAYs6(Kt=o{`=xl$Y4F&h%!>tEf6YuG+SrMBeU_`!E=s>jq?&+;7D)9EW18g;UAr?# zWW#)D@%}j-Xt+Ccq#3lb@(K|ZlQ$Y-Ev;cu>2FFd`|=q+!iO3993H|NHSsk-WtN>? zQKhhP%$m8)eV!_h*y#mZnJoxrR%)q8fjwJ9PT5Fh6EcoMGq~&F8o3@`b$T_@>&*Z9 zufsL928Ux2BhhK$%4T$XBd@t}U9XM&vW&ylMcFyrKAs#)?R4WYyz2=di*dZXjLSJt zZ+GS)A0!<5z+M*0z25rX?qw+W<^1uo8P;K59=8J5+LOcWA79U9koyvKTz5Wnz^mMk z-nM0ZM_7ZSk@N^R8iGA8p_465D$;mo6+#o#gNsD2C4`45iUX_lPu9Qd)WdO8>;Kx4y&>cqg+Vv4nE!V|AdtW#()3 znq4qLyR%r>I_aLP+Q(Js<6V?yj1ixc@QAC12NAAl9zcDZy4R+c)%uX}BGp-9T)eSu zUg+htu1XrK1@1*^h-S!*arAM`XciuyVKgq7t3u2{k#IUfu#JRJq(!8M6C-v|Q*~Ej z@!b)h^MW!(D2s=H3f4v&scN3LDEXvrtJmqk5k6cn&(#0(SD7!&c%`DS6}a;hoIVds z@YxrbKJhH|U;Y95#lOICyL)h{g1+%KymQ{@szvC#K*lqtDn5kG; zrRD$JdX$1i3A9|p-jsqHC)Ey?h}=~Ngx`NQY9+app6a9fz;#tIs9bCyWg}PH{!@%z zv^=c2;>3tE4IcP&R#m(5)bHeYksOx1lmq{rPNQP3(NZN4xGI?SN z@m%I#fl0|DQ(bE6scM$;Q{tb&uZR57X)N02^f(GnZflZnWKQFg%a4t>Xk!{>5sLG4 z(TW}Lvc!vlA$l5uUU%U2RfqQo9~M~RYlemVH(W2kCawL7u;KjSGyM9mUZ7vyvAMh9 zr+@UjdHw}K3({7ktsXY%vFr*xlP|W za5R!0;YLCj0W+ByA@aYGSbi{ES(GFFFNGtHGP4;GrFeLt3bj~XpIM+3MW(&$HhVKj z)d};uGy&S$SP-2|8P?Q#!4&7go8gdn#+9Oe5`7gms)*;sGc$}UHN`y_)O`?CJfykw zFjA!b>k5;YQ7FctE|t8baHu9vQfQ}hs4$$~8y=v|Gcbx2TKr`wl#+8ly22fbS+SgT zinP$^R!;jJb^83)9MbMD#G^6ZS=rPWgJ`RdMI8J?s#nvvH1PN0TK3iqN5y z4%?~MlKSl)p5bZPKU1~C_ZW*{mU^I^wLZ4K##lrdQ}1iDuuJb-sk9uVn(oKC5z;#V zrJ)P?avHLRV=>OnM!mwoa~XpNa%xL9qC!`Y#qdJI6Sk#`aH`Ub=rL~e`70n4Ka9l9 z2Q3UZ;jDTHaEdF9JVe)xpgqC|0CPou^$X08&duebm9EZ z{uO8c_ix!6sb&}nL!9B?1he!U!m5abpIvO!IL#@05T(?K$_CX_-~k`|;Ya-JKiqP0 z=S|MHdmc?Q@6@lL^94^ozu{B=-iw^hdoJeRV_)7tMc7LLW+rwPe5of?ov@R=9XAu6 z_f3!rvLlc(tLC9N%yCUJ>W<;|o!>G(Aw6eeJGnb~!r7Z!Y%{F$?Z&Gct<$#74i`~Z zd~^}BuW5d?DGp;RA(@$!zR}c3rqT{;5=n8Q_`BA=FwwTnMp$X9kNL74L5Es+xHcoV zHXa&$(kac7Zl`hYM$E&$Hp6Gz2<+o*T_2MujEqLoIGQ(U_rvY}V~xh@VfqxkAPI7U^Uug=H*s1bVrK^=j3oQZ9m=@t5M(+;A67&$hN%rlzXhBpYE^~_Wz@DsvWgAvxvOWVrOU8$mGnAX(#>{E@f#1y) zq0`5-!XLZaw4~R|mW_PtgMeOp_5rnT2x9a?>f-iV6IhZ|C_EGOH<#wGtg>jj6Lt;{GGs2jz-cW+(;-Qe!{dcQ<*07 zkgG0`Ypq1^Qd1OM0f`e4O@Y(I$YVPdHzI~o1c)M15lb}+8*B$w1TD%emEy+3c8F=q zlexz{^CqScx`poLHiMpDu-7xRHg%LkztopiG zk-M8HI?UOcQ*`7XaC0c^W%Tx`*~w}g^&K!%e;E)pYv$* zG8b}z=!{5ZaxB_&pNmN>Ken$2!_=8A$|N9K(Gn*B_mE`shPE~o!mJf1x~u2Kl%_xy zkAAQo_E735p>Jp{#cdr8S>Og^FW9d5J7J1tC@GWk-peR1*VuhPqQCvoY{c%rM(8}Z zZK!5C2sAfzNU2u5e#O&?m|j~LL+)yx5oQ#9XSQ|97861bsFG`5mm+EsjDp{J=#G3b2v>>SCDCKw!DkgJ_ z1}+Ke_hl%x&!Z=EaJ2VLi-SJpC?neU<$k%a5H0ZWE!IbiAXuoP!yE^Wt>fOf#gISa zd0TzOqgT3|Bus?K=m_6_u!aw7p8(=K04$-_OqC6)%AGsP-~PEDDd^2JmPDtf&e8WJ@7}wuCs#`%z<;^t%6E^nDW2SY8c+iUoD( z*Op~u89o2bkm>!BQ@_8^`(Y`KMoM?pHgql-rg5dq-mRvTj&4UNc{MR=f?QO1lqjfiN)4#nvC0Yx{?$V$tNCKK&@%L};y-3YS9lp;~{ z6fM;qE=`Q>UJHsJX^I(0svE(KkX40ghW+^kqGxE`M-Tlol$ebPI_xOy-Bz?iWHuXJ zkwL%-Z_lOxi>tRHR3`I&Lw$_wo&b|NBVBR`0ShN{Xo_EEOg;3nd6c$EAQ{PU<*~SK zCh7V}&c{HTQ2roJp6~T9hAj%oT3F)>nqn)mLYx@I5Gv`y)pOvPQc4+L>+CaWjEy0O z5ZK!wZLX8Z7GdgYW6@_c`eayBaIYy@6D1v=6(sWKMhKDx*SyJlO z4L5+s=9;88)eZHB9?ZEd`S+S|5aY1t020fKHjM2LFKOtxZWp4H&y&Re!Lx=+w2fgr zw;V0QEjN5O<99cbZkUN<;EwR^0&92)-Ds~XpFwL)$EYYOThKF3?|gw@_^JPkPyW~$ z7y6K*_u0so*_4O2k)~!`K`T`*oOjU43J@0z17llvjc8xq8$2Q^OqcmU!1kP&aYE^y zZmo-retBjqmk|$JqHPrN$@c31+s0n8b01_uB~n+6H!Wxni9aR@F~8h50qt5zEo?N> z>8NOIj6Hq~55Rd)Y(*JAJfseXDMOa`17@x|pYIinV<~RdzK*%LL-r*eF~RF-hHeyW zbaNC9qn`L`-Xk!j6hWgB*N08J&=nUYH7LfaONibErKcOvBtgY4d{$8NK|wy=Rows_ z+HO*e4mhFG4qNJ0{KX?eGjObNQtf@RlkIC4q>>_^{iy;X6jq8H4ox4GEcOk;UlgWk z;zY$zKFVtzv3pe24DqG6E8dr?lwv})R`p!DL`*wW6MD^&SC~~P#Sdmtd%o0a##ll* z?YVi9KPV6ZTY<&C^Q>xKIWl+AVTs3S0P|RCM*}}0-5_?pi&tHem)j9OETDXCnt2p7 zyb9bo;q*s7%QMeT+&aHtqZ5;Cc>C4+oV|HYk=rN}qB}Nn!G_B2{EXfGS3xi6c_&Hh zI@Y*-mW}XZKlK?t^H;u~7k>O{{<8itFV}y@`Q|0(D+0xgpGKOD?u5Zn)eKb0GVu>Kh=IZ#u|9-+Bt;BS0;c!k)s!q?0?#yGKH`XZFlcsyQ!l}L|T(NUp2n4%y$hf#mRw!wxIi$DsWk*NPR09?bXq!a9E0B z3inmAxV=ktSQM$%c#{ZH&1*CKL))g+VyZ4La+vAVkMLq1y?MfRpILX{+GU^!Ws!5* zUbi(Pu3TTP5_kD6-VQE?n)hyrjY#QF7qUU%2;UyCBrt}X<}@J9kW#b!ilWT)lL;y( z&)ngKANm|GeC};Fw|;|@`On$t1)Fk;P@1Qx=}F=B+~qL|`I}5xqlTrI!Q*?=5ED1R zYB&88ST9{P7hsdfsF7Kx>&`2*IbU2V{I-_nE0JScHTQ?skEE6ybT9MA@QKfFX3i0_ zmL=pUs`~g&VI;isc&N} zLTo_y)JzjcBk2*2@NEjdJL$$01WK_SoF>>x%h6FJ!EuG@U_Xwy`vKQXju1dkf`I$4SWi@<7QHx)tF-!*)n>*4~M#-7r|hQ?aV! zCrH^KVuph7z-+_PJc3fW%c?KcwCM`FFbLK|zS}e|%c8p%mF9~FAj7jUwn$IB-kH{zUg9uO}|JOPc!@_~inpUGy<+(zmZg$=%4_XZ_EvnbK_rd-nwj z{P2UG+R!gQ$FJQ1BKj)Jp-kg;eYxrg?x)yQ{j^z_|7iS|Wq;FWdS zFGQ<4v(d(1tM`>QPOTAb-u#O!CX#%wS9QP>b2Em`y|@?F=fs#^{^_IUBV4SnA3+1+UgdORl~~2mWcIu5I3~ z7O_IVJ|y&D9LpHb>$h!C-!7{|Tu+c5-O}G$fdxulroJxU>2gAniLL=17kmv~aXeZ( zTN^IHyWIYToRQawCY)LNn<|ePgBt`#Bk2)tAlUAUd4d)bB1%C$;itN$)bl)Iq38;V z8&&r1R$03%Om!otPJVz=AZbWP0!jtQht*`RDtbw4@5a}GIk6-Aqyz5nyH1X6`s#c~iiu^-6m6X14bXr2asujc1d>Cw@J9!5(w~j{%B#3h$=c zp0Ql1j#rL*CipIL-$a|6^24E=^CU0?M5MUaLACsKW2c^2=vAs5OIp5R^BFncnn9+` z?ZP{1`KlUTNf>5gZ8asgvv7q)J+wK?2Gqgu+gum2amFgKU0rn)wCjqF%kV1WBXlDV zp?qjFSX;X#86l4Fp#cGj*gp3ZFJ)p^gf~vN%L& zPOYg0-|Tw5tjf!8T%rCLw6$>!#i{>)-7ZAB0UOF*R-(XMpIKcOv=7soXKdVjY!gwSPyr8K7xq4gI?_fuhX1$AwWYWahQI6}ekD zn*=GvGN;hVLl{_l`HxvrE8nly=0obRET^%GCzSKlv2!tbSl)z z^QE<2*D%g#W7-G>fm8y*bWg}aqR!h+Db|DvBwT1abG;v%r zr!;$4bq{I>b=bpU*ttOGGqky`^#c`pkaQ@bmFGVC0{1@gY2N(IbIf`RRm-YndFdjA zKRgTfPA7|Z#mm%+NcPCN0%#962u14Jd3M48T|>#gp0X7}BOXE;;XPgA>vM0$+%hnh zh^E&tq7IVInu4B`{V)d1cqEdvP?+v?m?cxiJcY|xAan^Ag(Gia_!#!WHIe+jfdqiN_4${N=4qKtUIDWfY-wKNG{R(Qub-o(3>0zzYXUSkmG zbLUD;H@K&^-yC`MM!|L?oD^YpFPP$UxGyk^Fp03O!tHw#ya>|-I!y?|Bv3ZWqgxZN zePc_VPhfX~8BiVP!k`n{t9x$#(HH)N`JcSb=EuIu^Pjs*+9$Xc$7U0$2&%xHvxBiyA!o44d9?%qvu zP(#nr7@LvTW=Xk`*`TmO0Q$Hn%ZDPU@bQ%6Dvi6U>a_NZG>@)p`7I8{66Z_9Os~E0 zeiE~ePq87kH23BftheNGs_&Dj`>2eDJa)A@g4Q=r<+jmxRj!ic7}Vtq9UJD)d3MSx zmV1N`Ck#@me->0D!ff)WIP)d_t{0x>Cx7CTy!DZLeDTlzg585ZW%}t0PwV5kYojbV zq?+TG%UiNW=f;xyy2$uF;^W9SWaa&_NxHbdzHV}e`&!F7ebDsW)z(RF>$q;mb=*@F z^!s`2a(}MA_PuVeTo&KgAq(``su-QzUoCxB^(OscOBB{EwpSDn3o#Un- zVo`uwr<4uoyhkq-_GUblNm{u5=-DY$6%$D3icF@&s)U!S5#=I zig+rlJ+(eS>l?sZz>blG<*>Q9KJ(q5`6QqGxBfc6|KmIEmq?NtIa09D`!N0nu?zc9 zF``_nd)u~}oSi(5UW=P-ljq)5A)+!%JFz{7WM8qIBq+rB%GR+6WlgLu^0|c(wdHn; zN0RX(etYiAIP+qF_MX7tt?AV@FJljx%vtf9p`A3g(gs^mi^%oQ>sr!UTi-?K$9n;q zrot|y(QC;%Q?9m!Ay*th+w0jwYANT0hc4QTvvD|pHsj~QDAXeVW6sq>d=+iEda+ai zNf})leI7puF%HsR>;{`Ix?Sq2e1vZuC~UUE*1fW4uoK2H?@%eqMue%tv!6cY>F>7R zy1_T3U^*$h@t3!F{ZBUV=$`YAcQ`mKAr1hNLaoX#|I^>(SAXxf_=W%M2l@H$`z&*L z1LYhTE^#&7u*57ms`o;uv=XBb$O~d?T?Y z;o);TbabUmelxuo{dV>wjEwO(C51`*lOHtnxGDj_4O@8Q>e zHficgH%NV}%^*kk=3z+_g9f)#Mgfm@)5<4*;3NFQ|K^wYqgUVHzx}WNXC6KGYt(=D z2ap#_6En2f=6g`+?o7advdeYUH+u4WYo?(!u9BkVk{Rfrudx}uSQkp9Q;F-rSxOq2 z+|Kd;UXUgkKhvzMrVFWwH0q$QWZoH+zR%OLok2gYm#QR>X#QJm=fR!F@xH6^#`gk7 z%m~w4&hYxpQ>_CY-u^EMFW$Rz+T*~$z|?nFhP5g5#mKXLof3LaudYWQ&U}7;ZJpnI zu5vVz9^nRpu-PcnB$m{FQuh5+6cY~Y45V(n$)VU`Re$zQ}<`4AnF!76lw;&K==2V^)-+$11|#?jKW0_ zzmeVSK2kXQ{2l5ib}+d?R?P!ed;ruB4l;eT`YCtCjI>&;AI?0QsG@W`+kyOIgt_H> zaYe1=6NLp8UKSv|PCo^HdGh5#HDXE9ho51=N_ja6Pt3?sr(J1oCA*Mm!))znr|S5- z!Nk{g!^sBJM8m(C1p(Lb^m>fn(IWRF`- z*W!pXP5+1B(sz;b^O1rhJs)+qbz<+D7}t}SKN-{ypz(Hw8@hC5+-i|`mBZ)=?=uK+ zs(#3|(Wx0j*-f#7ytY`bw0G{oS$G|{bPC3YcHgz-&gVZ)`N~JQ|E0gA?*0|1f-}Uk5nKtHuuh8>R z#iowuBn{RTUYGrlj4=FU!y|2@%MNdI(~$PEvUy0+wscGfb#Y&fw=C6V{2leMVOtw{ zeUB>C(%ZGSJC1tDPlR_Vey9(g%_Dmk9kymvFuZ(kSMah(ztQ>%v|P`z3DOWJBa!&G z+FCGx^UN{%YPNp)z_#&>t$!<;gt z<;FMhDG`rmKpdr~Ch>-I!62V6*A*<+SYD^ygw%~Vc`Y~Z)}C9bozV%NQcFA6${PZ$ z1>VQQXfy>WP2Re$SE0seG(MQdazSsysM|MG7Q6)x`fydqT&8_LAgHqV)A5ag=C94+ z`v<)xUEU77dapc5b8mtU)+RN)cYSRbAGzCo30*Nb`pQ|g

6`5-JA=JoOK z=CSIV5h+@={r=AIB|RERk8tCl6yfxave}x4&#rlvVN5I=uav$y(hhfU*DNkR5YHo86?x{n(9Lrcfig|ZwZdHCd=C#Fp%>@O z1G{?!@-~#$pnk)?b3xB_c{yRPFIKical+jfPIyrEh*nf4iugHob+&4XdCscrjR@9) z6hAdml{m@1G2qbS)Av#KaN$O1LPJw1iSf-%KUBt~a~JnyT{5xD6q~r^`{M& zw_@`w5{9%aWNG(EaWCK|L^RhyNi7J4(56K^jY7=^Sr2W}R$daM{6HsaDnHAZZR{3f z{l3F;>~o{uU0Lg_+80vfBVF;T8N@n?rK-am$g(_o+HuWuNd8M*a>ID@(em~T`zPuf z9w>1TR_;vh+fqHS`8QmV5C#>}(KQ|d_x=l~N4O>kY@QM}J16%D``IvI3rwm|XLcLm zfhfD8Fu9>#3Y3kN@rkGT)Gz)RPyPN|{L#yAa{ksgoF+CV1VJwqOF43J4|bno^Txl% z{OD=kIQ=q@^c_wn_`^SViT~$+{}sOfM?c2j{rf-9W|O@CwK7qi9tAE7qJB-1G9ux3 zZ=XHSsjn1YJL1nr9Y&hM`0vLhi6T`g#p!CSshV;~CY>ny+tUXx4Waq?fWv?>@n@o( zW^g4@urLlgEtNr;T}<@K6>VRPK7|sW7rgjdR`HXPhvHo&cAmPH?{By;DD~+f38R2E z-Z;>U%oYa*ot|l(F}gFHB;0so$QVnC-M<^nnmc;8<+JQ;_m2=x-22LchSa>D?(QB_eHWw+cy}F zaFf6|kvTLJr+X%^RJq{gM_=L}|M5TN-tF(_um8PY*8|PvYa(d4I&Y$HlFz)jeu!0Uei2MtpC_@52g5 zBk2)t9*Cm1g^S6Q*&WJG)l*zb=i#;U2h(q)pIFU?e)vv>qR44=FR#g--Feuwiv8Xz z@DO+%<~M-*z`0j;7d=0LavN@M+1#FBF37xr6QNXPnjTSj8R5(o(miF`fjq#xD{u4g z(FOathY^OdgOjbohRV#@oyzOa7arcRKAv(xl^J28=!rR0YQ;uq#tsdth*UO;D|&_S zbjvoTP@21t60OnZ84(KgxVf4JTPHF(4lr-KYR1Hpxl0nb6l^DZ4C@QV6bz=ep;4H` zjF2@9aRM@`G{g5*eJO;AB$_m(Sz1oCZs)6MkbGCJ83G~FHAreZet1@!Ru8QgTrm7V z6IMFDE6vc7)w%0I_b@IRUX^ye3+9yt!lbve${t3J#ry47cxCn-RBgtck@*kd$f6Xj zj?#vMkux|%jxb`jtbSQvO`pqv(@=#AW;8179sl}!W~|s#n$mED4-Y826S#0Y$voR8 zh^R2@WF93`MT@edn1gtAgL;sA3%>fL zuk#!K->baz(O1}?yv*%dc=Jy`$KCxWxU+-P`58oCrJ`(@Ijw@ojLOc^L||kv45ya% z1*DiqMF_?nU){GQJZ`G-hXPFEC%t2&v{1|d>)wZzd>tAE&dOTQ zh~~j5^w6_VF-zweq4Xw&wGh02Vv<5_UMfyi8VSiOIKH`AK*d>x@yXl|no@6|*M+WMjTdU-rbXI1pV5f(_zr2Wk|U{)I4=Va_ud7zhNAM?tz)3 zRKD4EWI9Wmt!y~wo31130mFex@iR~kdE1rBl7t7@q2@~M$hagPzjzscTZgPs#d?w9 zeqlplW1&?y8jeQNBiuMp5zaTTpOn3b=l_fxpw0w5?7TSRokLNr&;(;qC|i&jWM?N8 zi`Z}7!TCE-XM0}vz$4%d;2Xeez*`{a&V25{!wJsMQTYfw^&Hc7ODTov_Qc6EC!C6M zD)-HRqKe3d&E_uXGv@KA7ku?E|B(HIbJm3qC`@R92d6XNIIY~@D3i>bYDMb>DjN{f z+Gl2zJw@C|DtkZJ$wls_`;271hW<0!r;^&*4W;FPg@YNE)edL!@`rvL>Xu^}3TDKn zE8mT!WMi3oPh>tg`8(wajHkJ}M9$I>(n5eNZX9q?P$Fcsn;3e$MfA^&fY}LHQhm+K zQF@*2bg4@Q1zbqY$+8PU15;kwnw*tB#5K5tpoYhUe+@%^Om2J6qtb;r68NzIGz z(04VAEMw`>ry{dC_C|=JXsb0FT@4QN)dfD}8nVDq+6at7OT1IrFkPAl?+D*I5FV91 zXHC&jvwc=GlJ49RYWaq3hGp+K7m*7SP%5vT2=df9diNFBK7xy^OhU$2GtJDvLw@&H z{u#gfr(a=y{)@==8|VZ0*bn{3{K(J#BR>AgFR|q}sQa&@o*(rDMRaCnrWW&VpHMd8 zK}4a3(T$NLjfR^7GI@FyHryLHY71=-6Ra5-M;hN&RNIVLdXc)q zD`o&#DuBUkR*$c>*cEH9rqO7dI_?FEZx%_XJ@#a%{SnD< zNT`FS=CsmTIkvHKuGx57f7veCydD_;!g$~w!abRC8m;EFJY)IIM8cYw>@nYs z&8(U3owSC(6GKAh)`!u62^>ZS1gq1>v%Byb7KsBRt*-t~_m&;8BJpHghI?E;f^Rjj z-+gOAoo8g)zN{x-%NV8vW<{3QL-|hA-{E}aERRug=Xl1?jz-d(2+N2vHOW%JRO5P1`kbBf@(tYhQY-ZgsT`qBagBVww1DX(mruNvGkg^T9e z!fqSpaY@p8kkXt26g-N@d4@(Pa%GC|NtO~Xca}{T-P3)7AEA^mY)W2PPX@CmD_V+; zNjt+Kue6XH!z`EAZ|Abv=k!`_SUhjzbXg&5G>$Z9zL}MDst*FJ%{E`^o2=S&h4-!< zBe#C7-D#SM%zlrxamLH+{dRqQ~ehrl`L?7~Au z*rV*tn@1l2Z-9Oo(H}d)oCDTq zFYK8?&bZj@s3&{QrgQG7Qe*m9|IUI*RZ5YT3r19tQv8rENt#63S6<2txXeI!!b)py zZ-ydTJZv=tH+xoVZQe|FB7LY)+R8#=Ufui3^-fjwoO!WB?(b`9&$mWi7n=9eRbEz9 zE$xC7MXI`To)yrmLxj)@^zd89H*egsv5VIDe73t;^yuFsTWB*7xTWB*~9yT)M}$WIeSXa#_JqRSA1PmsjhSv6>58?E1IINuDA3m*^{C> z=PR=-!b=aP`0h%{(woK=xZ?ekGJ6ZM@v18naZPkRB~I`))t(|dp0X3pV>5QCBt{CD z**C2$+G3cs7VQv+HRdux8CJS+bJ0GD_9@8R#`9pT!kB^{@{<-O7@<1*^uFVfx1*?< z9aRqJYmu${QkJLQ&wglAH(O`Jz-YM0bC*3yhmzBCOM?$|X{Rfahukq!_e$=C5MrsV zjj7d{>tB8@%kO<_d_}^u+E$A3G+As|AK}{{4(Wr@ol4p5D6enXz4i_-eD@#nA6z`( z-t-q-%rAla71Q370gH_0(do87D40inY-7X33Nud2ry8UwdZN+- z^|VS;5wsC0i*zzwq_!0t8Quf`muMfdWE?n$^Mh-xk068CVYrG=WU0qwy3u(=8Z5Hs zd2i3vAoI_G6J6SkODJiZb!_JxtQ`quVUoG)zL?EuV31J+h;($;jica!00Bt62-1EEKA13gBZZpBbHLTTd6 z!Ou&27R3yCp=9_D>mf)sPdXDZZUOj@d% z!Ymu&AcU!e7&Eig6I9pCFVSyjEMnd+lb9E&tH-oltGHL7hkaXDwMBVD--F7*aDJfaOVi=8}En)>;GEvnL|B=Ub+NOkW^ zEFvb1p{coEevD1?7$tc`(ZUcT#JZuGL^nK)DEjXTZi%|0PtEHxl+){jjZ)v~ zz6z+X69G%|k2uP_3r|uY48r1`yiz53^j@tGqsSd42ZjdDhBsI4uQsEEwC^MCiJG8m zM(S$#5lZY(=X&D=npehp(9#&%)&sxtwH2eo5x(`12wCJwtAZP5YFnSBg1kMW@2G7E zg(uy#gXsdMbL1B2*WZG(IoVAzrr0{KYJ6d$qRgOB>M7_gCMJqruz#!a=3ji3(?_rK z>K);9I%V2!dEq1X*qput<-F14rUYw8)(DXg?JBEK5h56AAyma!p+DP9kzxi)*JkbX z_gZa_Q46ZRagjaYTOA`DV7@EEMyovwR$3p;h$n!16%x7ZT6tl>8dS+tsV2ry(lbpH zZk|iQF!SMRxwQOd@4#XIWbwQGik%kCs&6+UbYs0C&Y^8RE-Z4~=1-3f=&ZBPdgFtU zW~kMkTb|690tX(egD$=p@0cfI?WpsV(dTB#r7ok0ZR2pD)xn{%_vRw4z^cNyM%|Y< zlgqL1*)Tq~SXaI;`qVtDSE4G~Q)}18k}?koujvRO4x`q0fPkS%9qRRWPf~6ALSBhi8_6y;E_(4~$f}Dh-#=Vwo&WgD>3X!M z_x$SZ(8cHFPaR6mBgo?KvgbZXcyHTrwXu3H%Kvbg4@c*YtBmDRGg;!PJu~9;&4r_p z^awW(ilTR*S=m%zSL}59y(?*2TliknM@q#!dm@BB6w1gwSfRjlx4rw8mDL-*L` zR$-FZ?T6|Za&Z+gB@B5(_`A7f5-{SU<{4Q@yU!YD8Vd@(QMVxkp z!W#ya!w%*4D}|wtrGvV>tP^WhG^#RUdK`nh&hVfhS{(fEI*7&5s-gSdU|euNgD%CvVU`au77q+NSLX?my}60g)--|^D4~O z`!B)xwDI}KeO?HI^hPSvyO14@@Ik=kb34LPUS3}>=6Qdgr+<3GPyBa3%O^f{k5@kW z1tz)R&a`2Yim+pLUeL|+iB7e(n}u)>C3YEUqvO)IM?y|@S{&y*Bxx-SvsJY@s*Eyv z+%L>6+9vL_m@Lpp1+zXn#@bxUH=%uauJ=4&U##(#YGoYbFy;y#VHJ8vu#)lV)Gj@^ zEa8#iPh5uz_IS8M6YS_Md=*G|7>4Y`z79F>dI^`+`M7sSdKcG5j<&3$zo{$VuMUrU zYuV>RPJS75-u5JO>01AuG-pf6V(nM%Ra$*lg1)Uhnn80dms6md1xF+45pEuc>7K>C zE|>)=7Pp}-B%`#d4Lt z4ZMOKwzM}vwcY`qhG_%0l>J7Ti=t(AI#xhW>{*$5jvi<^T12qZ(wkQ+baIsgFR-?2 zLD`^OV4glgtp#C%vZ1gA3RPw%o!QC+y0;7??qOt#u@J`QsHwBkq^P#mxKftm=Q33d z&)Nfa8cLMETfvM}CDHoe)*e<_XQXH=SA6Q4b+wwJ-W;cLdtFeoaK}i>;Gs%Qn6q47 zp=c;(STC9dw~=jXQV1KPQEA?w5t`b@C_@wEa-VVIM1-eb7c?A7td)8Rv& zN)5xId6K;wPtt6emDZ-KhJSQHH4oWJW>FW?&9iS3_0(DlQj(!Tn<28#loe1U4sX&v zUo!e-twB|o3P_cvtdiex!>z5W@BqtVtdE6g_XIk^hX|BxBsD@4VT+C+RoO{lu8*MJ zhn-N)-(jk-KYJ5Be;s%kcpD3M7R*yq8JA>ePiE{0vxx=dZkV}E)fYhTq30Dnf0^m- z7nz>_1M2j3c29pV_wRg!x_yoFdX8Yx1QGsSeSMpu)ajTocua%!M~jnDUwg4xFnCM& zno}w&vqeOd+TV%96_;$PjjHi-D6A0MWKmx!+QJfDo%ZqB1c4(P$)ZeCx%VD?w%j6# z!wDnkS^L{cTf1n_=^cExDE!qxMuOGP~rB-7$U zC0|?m!_5QG4EBXMg6jw$K3H2@%X?!Wxyg=Yh;ni1%vP?;a&lX^{i(a$e({bU z*e6Ufc{I&Tr{cN3_|#Ny!oB1L-X6;^@G|X7Xi-Lc7VQSe{A?3eJ&K@;$@=Qjns_l{ zVcL-oxUU#(wpw*VZKMY1qn)W|T{faS7eqa24GUtt)178jEQ%!Zr!>khiHG>xjdBWY z^9>ZO`WQNQNZs3Y^;XF^)H$7;N*d<`n&i|lJli08>Ub_ZIDugJ-*x(fe6iOSBa-7T8kB4YFAzpNP$f*!a!zlt)Z{2k0tCBk2)t9(ahb z87;e#6%3=h!s}u?05Djdz6Rl_3JRdifo@})~Bf3drY@Mwok$7=V6*D zyEE$9SD>2L59N_@Q0@S?IC<_Cyl|U~O@V3e&k5+({;cr?VJFy>gi$3k74ORs($d2< zs!Z%;!z>d;_Qtfu45z3t=?0Mvg>yEXv(>^`-BCsSEZPth^uT_$B(>HeN#t096A~UH zA1NR^f;nc<&IoR~lcMhI$s}zUXiQL=A;VDE!R2}(d6L+;nq8`f(y`i?K*QkxE_*=dOK2=hdLZjTRI2FmE_G8 z!frFdgQh z!zBMddv6|W*>Tr-etwzf+YIK zKQi;2b6>rZC0n(q>i4sye!TzyAOJ~3K~#yTdhgwPmOOdR$;{t3f4^UP0#y_$Q+{I7 zHb~CFU8nXj=6Gz|iuT>_KHKe^+0^jyuYWcGB%n!{&Za=q1~t`{`ULGvUQP7PXHmbQIq!tE!F4qfqo{5~{CX^l4N>~)-B1Wlwpgw#f+yU{U5;=Unz zoI`9+nr*tZ3N*PX>723clSMmg{HBWRE~=!dcbk-Wb1$Ed=hAV)iYv^bL(ccv=@XJS zY>upG+RR*f?bgNW9QW+x;e@nzsCykb>t9#snEYLvabxR0oy)78{;?ZwpPwJsd4^ZY zpevtm*ZC~I}G)>a{AK#li zP!TjZ>LKVzD0?xtwWOTVPQW$cF}dwZ=gAYg-E*dQSEYTvv}xd1l(uo~SUG{xj^N|4 zFdeCzx;?{Y{sLvDBSHRe7ii;UegE=-iD+lO?^nZA{_Mb5(%ZL2-C z@sr1-Ic{omQvVs9G(u;a$@|j1WlewCu~F&t&7HG%10xz6t%<}@VhS#aRTxvKPfnqB z--6DWCO&D~^_8D>-xQi_&et+oSMA^JeM+^ZoqC__w40;mxVt>r*m>%YyL;X1X~^Xe zR=)=;K8xFSpRC+-bSFS2r|_ERCXXxhxFe_EqP-NF>x@Ti7NC7?VTo^QOe8hVIz(%x z#$(jgEK3hG4i20~k1tKD)L^C%GKHFoQql~pRtP>dp7AWcY1Umb3MOalx?NL+64D^T z3$5p*3Qj%kTB~U#m=nek{FU7jmUO@ z)C^!ma6wXsoJ^%W9+cPt2mzHq&?HTR=)V;ZvX(GKu537sOzgGOC6=hCjtU@{3Ettb=g zGLBo4Xqb&G^~sAN05vL(xC(N5#2R zBbGx|5f{T~gSG?I)+;feI~;!k<1~|vsr(G21}XI+At=b0$_uO+!}*HtsUeI|-v{SY zj?&nMPA=`W;)!Yo;&G@O&sO96V_0_>ojQi-caXY|^H8yib=yZ=e(UWNgG;HX80v^& zT_LW(HQte-Y2#uGUdNOVO_+J;46;-Ese%)q+V0riIq8T`st5t6aZw~E65EKJf?&eR z=nmoA#;Y;z$P*JQ>LMGdxeZV4y;Duba|sk_Fdy50!L`0p68rwxw%25lkj|N!!G6c6 zqzS>!9yO``2%3((;yQAhCyJk#C`zBx)>}4wb+u~^1wt9GkB|}s#0g(78vF2cu>tDYQEZ&niBpm8lW+@fZT4W3ta_YdEGf3b@ugDS6qpD?3jb zXOk^wYN^w>z-JHLWQxQ^t3cH!!>=MF0lQOC6Zfu>Z>7B}d32J8bv4qtUnzzmd;F&{ zl{9@%b2DkiSWWox3Y2CNK=I8n+DYNA=-K|(j+*i(X{^^gH+hvBN$)EJ+={wwdU2YG z!Bo|GGPkXX`2HJb8gazj{+`Cl2(9=&+0H0w0VQ>a7M*84;I)q4=tS|(QGz&XiEW4z zjT85p+wS}Xb;nuhA#&Qxuan9lsdO$4x0{Hw?jEl^rKS9uH5}M&44J z9xGWnjn}NUU1sA!*S6JB1dbcTe#xb4%|52C>0^VWg_k8P zbsYqycF~c+X%wWDwC)7S25Q>KPS?wy{x6Xzhcv5n)3 zq$f+Wy#P(F^iFG@+p*C6*1h9xbc7_kvD-tpS0;#W)roTFSF_F|bYiQc5dJL~T!_=1Zsf#{U zEy*+Ln0?y%lfiINM2eg;+fod`gHpND~^04Ibb%mdD)Lzhjkw&o|HeQI- zo5}eyB@Osh9ZXGumT~x-8keTbK6W534+#{+IXpsDgA|TXr>3!4?4})5L=Xy`_DMrfgc@OpAk--=9ydmHoV;vu z0AB1~iu}llBB2iy@fuuB?8NG3;M2^QJ4u~+NCt1)IkjeYXIPLPiQLKh+%;+*PA7pn zq+|MA*LeVu>OXbB(Hl1A*o6X>ace%S2Z#hhS&4Gz083Tb^KXMb>KfaOOvkx)r zUSuZn0W(_;`amZj~pe0zxgx01-`Z>wrKX7$Z~^ zL{V^zXPA1o_|A>v8!YvNc|}tqNu`j~7sNP#90j0Bv=rZM384FyH>G#oZ`-z{ZL3?+ zl!@bb)b$V@P@;HhMpOie27gJQK=JCR#8FeC>hLM0LQR>(;UStt&q4}(%9{|}INhI` zQiNJOV?17}*zZU|pdU*sRpWCT2x(F<=VMJGP8NVpFwrLlsbP|#`akox$```Aj-TKe|Jo#>RpW>!p$x#Cm?|dU@3Qh2?bncN(e3mjw z=eAs;8JY#BJjs~l443M0av~ttMLMDsILYZ7^7EO_ktWZAWQm|V_G_Q6=3gVmbjKbh zlAb9v>39U34`~9uPV>}Jo^TWtQc!D1twlR!0*Z*oQKsi#5yl8L-g&A};9LRfse_~> zBQ*szDN}zM!KcY%N#5XT{2S8B+_FLgQQCz?9h2QwydcO9D0LR$vM`sdo7jH3G~VjA zzwL8O&OzO@(b72q&BUIQB5fDx4D)E0rwXaQTkrP#jt7LwW!oaZt$AP_$CHYq434QJ zqAk1FZ;Pvvc$Hhonpy&0JuV4gF0~U)Ip|ECr?GWj&0RYaO>KS0Nu;<l@!wiHxC8ahYYFi5)2 zj(FCTR3YcwZ(F%662{uE329O@M>M*|8?%kKX|bk|Jm3PDJHAkAlxCn(x}CHHO7Cd^SQ?O37hk32zA(hJFbLli?B*+1PcI+NSY z@98R#7_ZoBwRwV0;ux%%3{CG?s#_qPUt_=3L^dW{S`{y@jowk>L^&=^I(Q0+_kE&) zI14e6)HrKs!mUEZaPA0G8#duZ8C42niS}qEq-BYl4m|D~jbOx~ML?yP)B#gFD2t$@ zg*X@qKp|+~chX4CA~M?!45Tev(AX&wl1Mr+OB;`0YfWBM3Kc?#zn2Py2t$pzMbl9` z|8kEcXyK^Ep}t59HpOmQ#Ni~wbEM8cdjEi@AW+3^n^~nSkmi9&I+t_`oVLsYWbO_^ zGmjL1ZX@5qlukn@N$PBla=4hV5Lqg@7IJvAk8(!GQ|5Sk~=b*eY=KD zYtY5n?>y}qy=;U)0aQ(K9Fjby(y^m5mL8B+1ZZa3vX+?YsJ$8?xID|)4(*UQ=*gXX z-FOsqO|%K$AheMz)6rA?HX?E!sHOW^=kQxEF)aVmT5;vgY=!GvsBHg%Zqy{6|R&)nvrku*bw=q;Nh&h(5q$#s+k z;8v2z&s{EO`^>~6x29z~fX{!oL!HU@p!Lh>4%NHAO@7}F)6zZ3&%|*`k#V|Fpi-jo zm^`$*Z7$wJQGkw+bu$z*Q-t*ete?T@8meIhm4i^UgYxFzDkn=1oy%<+B^O(-CX(Jso?ik_o18P{~xI6|7l$~j1D zj(;1E>*8ZMVndYA(6-^J&e}J)Th?x!P11^DZTr=>*V%B*ZA1E9S_8`y>of&DP>Zzk znzYd!F~6o#;*iv5d5CSIk7sm%xK=WA&AwT}tBBdlB?+UXzg_1#vc%G@x7>ecBR2bi zP1aBTBp?*TaRCU~-pV3!Hj2UHr7dkBit~YX93)7yefNy6^Zm*)bp4U?B6{r+HNJlx z&o6DZ>4wa=eQvjR==kA4Q(KcGnV3pQ^Fdm#Gdjr&q&*@{-`5!{G;K)EajZ?P(J7B{ zW|2jIRnVZ+T6J2;c)x0DYKbCRSKrpoJ+B!fNhpm%ScsD$Ax^gk?@vY#<1t*vlU`jMuZu|2-nWI%`TVoZ)oDK^i+|lnscaKvYbRYxwi%n!w0AczG2A{C z()rik!#u)nEhFE2H*ufanrJ@B0=+bSUbbi2Q9jLxz3oBTQGIA8#wNt<&K}bA0-@uY)EuKMvAE4s{fnIDS_& z?Eb#efXQNl3rZPc+gS^YrJ$l9h{tJcmum_Fu@0OL)}4 zUh~@@e@4d|Z6+?Glen;VNC*e9veyL9@Ba1yPmEc zDZF|6w6jN+42n*FI(fW0_3_z*DUTz3Q)7|zI>_yYbHdcXQ+iPKR5`4fZjK*m z9`QH{R_4Z$n71n}B$sU(=b-K}m@1K=ltCB-Pv50!4)v)WZzagdb}K(QO0zOiGr-Z- zK1s*OPh+>u*4$2rOn8CkVv}Ag(deX+y#nLU7~LfjnsIXL2$9c}$AZ3jTPBxfi+^Wl zf|Vj^9@ECiqvQ}E*`8@zib@@|lvL^%5y#P0O7|k#PyJo;u547}7*XX?ds~ZZd~@7{ zhh?|UQeSsm_;RYdri|Gh>g=sicywAsK{WT7DXK~&w+PYU;<)xG9WSK*EvMjep`tHU z67!>jOP#Ml+ny}j4KXS!N1s8CE@Pl#$$*OK0o-1oJgLzYsTYa-|HjgB@sb)8G^r%DnYMNrKP0MoGs+K9id zNSdEZC8lt2q6AGMX-ZwDlFQLr3pAw;omy$HsU1V5bLF%RIZCdr;dcC{@#rq4Rg#e2 z0SRgCOB1j?NwFwPA?nM%5bNVDhYhskpRbM(YHWS}x?~xF2RMgAI(0bS{ z?TViQQd3+oi@RhaSM%{VYcK}POOP-V`AI3J+bYHZQHiJlB_s8&wKW+|NHE3r|Nt>RlPo}uCD5< zyRZ9q|1P^sWk9hEAFEjMEbWJ8I9XgiQM9c;%kmdpdjGk1I$O$eiCKlJGzO>lz$$tR znrv8=!hc>Ne!eqTBC1$)ZdcQa@ani1VpE%c(XVDua2cG7>D^qA;Q2N6%4!ggzTW(h z4q2Go-Hl5NoxXWTu$+e9d^rX>Z`_XR_YHqp$uN@(BG?m|+8O;Dh$=PV zKR|{q$1c>UHPU#+J}T?%y2tnQ`>@j{p;l4z_0guz9IKqRm?N%P^<`Vr>#`rWUH(WMB~6gV~@zE57wr0$oHI9VI&8HQr-){M8MgxA}L* zlg^&aS1UzTCCRS(4zG`AeFNWuu9BJT5xAFAe2No;mZn{kJ!UbFCv$4H0$s#;H;?OH ztzVUmZLPS;1Ak6pSZYi+sZ8l-GNhyqZ@6yTz;(}sNMuD;du`3b@BumCE^%lt>A@B- z&OIlr^rX8vrac72V-Lg4K17W6H=5d2vNxBdtRD0(pRC>09^n!N{=~aDJ|tQnoGsTo zV03Cu&o>!Z^ORRwk?%DMuip(emt86W(!NO$k26Qmh8t6Fn>=pwDaf3`ip^a9J#2Cz zsW2%aAN984F<5xKZXLGuJo>7?XtMt0TJKxmnc)?KPpj3icrE!sw>@ul{@41qR`KJB z&N_L@Sk+3trIFJxFi}aq;=zJ;JTsQZ{VlmQxBb}t!PUq_#?`Y}yUj+gt{!3Y^k5W? z$am{;>aVIZ524j`YAgY_r&H{T&lbJ3*6^kS5T`agQtvO));{~SYH(ZTC@ zX5_n-GRe2N$E*+(9VUqVZu9z}Kr_N!&ve-(^pD$@_>0Tu_bJPoqrV>9F}EJmX7A|+ z9qci_da?%uR++kez=gUFG3|35m!_>}waD{l-ABD|`#0}5V)*?}HkE`Lb`CM`Vnn`& ztxkj6+m{_Rs$FWHFRFkl-ERtanp?RxNyDq*?g_a6Em(-XtfPx`&%aI?;A}&pOCt6& zA^gw5S@LDK{r3r`C`a7?&o0W?bHeUnl7;GiwCo;gnC6G~3(H(^eBYRU$0vH~ftEev zLg?q@E2YVK8laRNb!TY%nh^O=CRgVUI7;;4-+#Dmo%W8Y@j9ecR&kztO|q|FpHz5ou&cl`1Q$Cz330o(T_+pK%QmuGqVDSBIfyUV-uO!8U@ z3kys3>=v<~v-2MbN-Fi9UzWS4rm}eCURtA;hl$>2iEalOeQuLhX$rpfKf-OMsQKZo zPER?F9EV{7SG#!`j;x25(D1?`jp4pNuy)sL{-Wa_2>Ta@%1xBhe83HAp48j5)xVb5 zp-2SW?%!&L5BwC@(Tul zjP1Xa^XnsL4v8rKkGB4!s8hec;!OYlMgOl~ft!wU&xsTE9-W{+Gm5OMV3cF#e^%%J zyvqGw;+XlllwmMOu8(4Qr+Se0GwQPy-@`K76u%vRx#0dAV7##Nf2OK%`{GJFH0}Bk z&L%1+f>`5}5dIrFbc1Kz2Il6%+HeaXUIGcxb*6Gd2j1%LQj=Ff&5G8{&rhaTZ9X>y~>- zE7_2R*QvB#emM=h)rwtPq#;hot&;2CZW$Qwr_mSb9xS_{$vJQ zNh|A+rKm!e_veqdqZ(hNYld7Tq~ny9gFb2-pLIm5br(WwoR3veEMc_-0jr`o6p4N*GQ3IweDnihV7s30S@16>6*8F zJPT^Hza%edW-0;s$0UwH#ACO6y=>08`V!Kh!?bdeyTKjUzU|!>ssAN)M(g96rH}fh z-~Y)4_~*ZzD{~Zjtuf^$0@@aFuHtbFhK;DTuCIu z7eo*o>GUMW9<(A!tZ}f{uH~1?qOywq^_E)NpFaiVG+3#jL2WUwuo$AF`ZMBLOeucz z8D(X^b+_6__VzT(cgcSuH-f+-NZD12t7Hsj$r+Mo7K ztnvCl#mCdoCA_`6N-aBQ9v>Gj2a$j^fEz~WV_k^J)hc`7oeAI;nU<|8;3!ASRfIs^ z8`Y3d5sqp^{)xuFe@v(V8vYv8CdMTd$6St7)B`#$jhXY=FzkMxSJL7%&poxRc$4yH z`ZyqR$*x!Qn0YhDV7{2mYNI8kUQH3JGYzB1Ar-d<_1`F?N<0?sU)IYS_(3QC9V6_X z>J7saNcdBGY}y@a{^%x3w~(>Z!B0GAt$+FI1L^ZQmdM~*Db-&$uFDrX7eYlJzvh>; za>T)+23gHaTnt0*=?i&y4p{lAYjR_iuyV$YyQI4erlEXi4CtT&+KGQkuJ_NqEtYXN zdxF>vfoXIwn)a2uzm(~^zF}JnEL&VndM&|Pw(js+O;*P1O_8g$K76TqteT!;$6scNcljI4%*-3a~%=0>DZpzn2;5?F8p-^H6QKJEuY!g zr7aL=@F*JC!3xeI0`os~>PR0%`ZUaI zJ_>Ai0|ne@Eltg2#U60YVE=D{VL+YbB|&)016(7Pm7gbn~^ zvmEgG8e}rG3-g;Uhue}M$z)Czx+3AqTQ;k-Fe>deV0)_gKdi<5a+Ng$r-WAgS{hfB zG39ytxmjO%pAQJL-ERq-Y}O`Tw>PV{lYwUwKqz)u{(lQj=D_J9Gx-r*!27TP=(x$W zyI5ff3Q$afGbrcKA713)_Jkt|u$Y+m#wNsNVD1W|fZ@d8vu)$@_NXxf&s;_Mii~dv z%r2N2W;&R%7QPJ6b!#U2!(Tv7d!A#52>7VDxIq(l9G}KPQ=dJJA*ot&>2O?tB zhoIcy-s$8qc}BU6FJKC)RdH!vPjh>do%Y3GEB$eldgOgL&E)q;j*#|^6)Z1&N$7GF zxpfH(d3VgCzE{tD?99rfwP>y|12;R=*Sma#(H*p82xKmL*dme_?J=%Ud7tr6% z2H;HU37xY0$G}z_&L4p`oTu80o`m^J;*g8nBFmk-!>-0Ef*d=j`)v4fYKy6SLkf+m zNP~CMhR*i>z>JxqC&s8u*BPFhL)(5iGJ1Qo-43lsv=7S)!-7|Z9Opy z2`t{`ahLyN_pYs5Byi%mb)*qP_|3t}2edKt1XslK;A{%WQ7j|zAlG%hX~{9g_HW9U zi#g*k@OWj0rIFnp|4fPp^MDWxPlZVwr9nt|FcVLT&#zeDsICA_70Ex%+we!6a1)$6 z*fo3Cd_bS6-;OiCxQ|C1hAo)!XHf97i3l%1{Mha*lW0WY2>S@t9zmQ9=zDDcc*zq~ zV9W}qyqG3mV|KODjd z=|#|&CqZe|{imW)`o)H%(TC<;+jQSuDaj|IvxW|o&yH=KktbHLW?G2{sHheoKZ9wD zX)-y%nyTl*Kh5tM_xx;dr|L{M!FV?({n{eG{DX}z_X6`&SKOYngkof`g8stE#_(VJ z4^)*rmb{SPp$Rf~ zsgcbUl?tLDIEk=w^69E`k_i#&bbNm(3XSsX=(oQh>?i>GAt7 z8Hv2!{-80WdesUSDk&((&qu-(W%~}c<=UZY3Hsm{D`b)It_{#iee>3Rqbi)HvEYho z!#3Jey!2lft(Y&GdGL9`7F9HW%KQHP)KP9-cra%!3H;7bdYdtkp23R+ z1)mG?nmy=kPtteLN{wZs^QOsPGBQP$544fCnS=k~Mz=aJ#32PONkN^H2I!7}fgCQP z*6&lOLKkU+>EEorSfAIY(<{-J`LrKhK)XV~-!k%fC-9Ety7i24s1FVgkH^_^&4N`y zzq6Fj4fPEii8Uf(3Nnr`pHCUGP{=t9A~peA@;+zqIboe z1h=)MEEm`kj$$)KjMNw{RL8hBvP`KL2F5#)JKU;7r$2W+`BcQC1*5vs`AzbBg&@!> zd}4)CTX~=>qf61qbq4PwiU_Orlfl}q{fFAlhliCq4gT;9n$wGFIn(;`d-(Tow$(*u z%vd(IUksN90t0hz2mCvtkVJO@=rOMf+rV>LlFm5`65k#YvvSdTd>4gq^B>mDFV*2( zH(z>C3D*&UVWwP%&3JbSuyJ0W5K-=Din>Pp9V9I-KmFm2=k5cf$8cc&`v}t&iZw5f zt>8w+Hh|`foCh`5c+X4SZHioU^<*$)-$^#Ru$v&GF#n_+#C(YhSVL82yR3pS0>doy zl@dh>RrFI1s>K-8(hz$?aYAuc5Yi^#50A~rWCknk7!;k}%4aFWN@6Z2%b^ zn0~D3$W;VhUyF^wuer4zSze)1p;`oSM@)?ljkSsq@Y5f%ifP2WR~VO#2V%``tHPHS z99PXmmLZ~a&~mvs5xgQz2ST{;s{#IY(^J2L7DErW91RV(96}$bpHZ(fu8nzaIg>87 z7+$U+T5YyHuxbCfHSPO{Cq}6WCbDsJboZdk@s8W6D=Z5sU|8|_lB#KUL6%ZQuuM%v zNCa0Y`DP(j?1WZ8ILml2!J$Qqf+Mfdr{^u}IuD&>%~xcN8$ z%sWrS{k($_MH6KUU%^b6!#{8wLV4wWj(Ksy3YCTFSRER3S4%9ZK59b_YC|^Q+2h6i z4pD>)nlwS6q}#f0aP<*NIkQWGt=E$N$HpW4^uyreaM~yA^Gv*HXjp&GBZ}k4e>h18 zock0ooYM97PxtLB@9P9;ghPk|LCZ%7?U!fF_JFT>E2zSf&|9Cf7rNXb-9y{%A%2w6P7oa~Rm&t6nD*umXL@Xr~Q}1QG{aMcU2{XbFvD{yf@n#Fy z9qhXOp<3Pk!AFj-+O z1FnBDJRdaXPSE4;@6-uHtb!QCX!^^eZSoDXP9fw|I}yZ@_*Boey+j7QP&u_FWlJ{* zi+n6Y)zY#hJ_|Gu#Pv@$U|YBpOEd)@MHR6rY@O~xLdaDS2OnEvIBim0rV2l{BjK7H z1E?I10I-;S4oaa3Li>L;G`eU*jvPF@+9lSuFf*zu$VMLJhp0e@QR2Bp&m_^4i1y!T zzJFI7%B(>*kvc1qKnn(!-ay5{Nt+J;A@ zdtZi*7gIIuDc0GEbkM_{w&EBWU&YNwdbd2 z>rEd#_1N9LZta&#liJX*)9*y+lo6wipA>V(g&56y>g1isZ?X;uiZb>6#dAq zWC<%oZbl0L?cs%&KxXXUf`8;1u{$M-BDfUT++SGE=*(3_TGcR%ic!SX)9F<5sV+~5 z&rrl5ECPlap#%J+fg*q@;)vo!2edph5W&pcv-AwK#tb2CkAp%nruIv#o`1k;3P%}J zhq;z3Yd3I{!IOziW|whr)E%Yxr>F9MfcIMjb#%Mkp2N7! zY&h&3>tMIdpY6T}D<%#9Q{SU}+H>n2?${RaHXzrP=-T~Cpq$LY$LGCPz5dTGZF<-? zucJlGUbpG*h}57e&*|YdvMUUTvNWkHU+KPv2?A4byV&J>+x-N@@&ZWckX>_aegypv zLh1aqSinU@&8*EAVx20&_$w4DS~gPB8}qCstil503Ps4SY=Y~DGuD#BQ>UEoy6p}YDGN~Z>Um+*2C^z(i*g+_0kwlpF!Z`# z2dSFSbM2LHIhzLt*QK{y04^!1;J&Uv_z5CNXa8I&mFRHY%2C=U2(JEU4(xx>)PBhB zC@de9_z01Yg<~3?kwD)ag4nHGz9gm_M2e;}t$ZsYtY9f14PP6z)vsTi!yZV$Y!-Ls zi5gA}jIi4VX9M!t#no81{i%6hB+z!7#rin*eFa>!yeOVoNOTJj2s>Jd&3%0#naGe6 zOfs}(Q(UCb3m+2!Xk?n{u>&j# zWOhREbHwzgZ)A_~hUfLBw*8`qP3MEE&n`Cq@8_?gMNUi3DIV5eFQPHxnBNgXg}ZJB z8STCT0%+x6eHaG3{k`DQr8x$I(nm2|WD{s-0lTxbE6v9x>bTTwkR+Bf@?hgs;`5R( zS?J9MXJg+(!lc7U(y3(eoxiicDc{4Zw>O2B%VYTKGNKfU!EjP*sN*=E+{AGo;1{n+ z#Bd?#h2`z6g{2XuNu~5D-bLIGK*kNZK@4L^`IqFHifqDECp3){md8vD3X*0DHM+lv z$iEq)07WqLnLS!ySX@W3mtP(WRm<4Y)wu*dojsGC9b z@5UYHc*c0YJ_ZEZ>o~4H(yn}^wg1*c`q?$T+B%B4?}(NCkHo^Os1Sy6-`sx09 zbMV^xg&B!pO?D<7XH5tMYrZAdk0y9bX*Q_TToP$=#7qHE8P_aVlvkGB;b|m|r|Sbu ziyix|;Bt`tnyG<+gJcF%}zD2xhWYAeZ`u=I{f`V$GJZ}@X^DDPHIUwII3|*|Bm?Y+B&UjO=N$SrXoaW7~ z<9>m*@U{@9YEE19Cq+~Rk0QHij-j`^8om(#BTP%ncdPq1Cu)(6cx;LYA#>S^Im&fT zf0RyQ1u#r^g@QPUX{Ndn#jz5p}AMcQ2;!DK!3}TB4qVS+Ra9$O0o?cvaT8oE;T)ZZL67s?khP%6Ek_RRP}Dk zDI#Xq3h|j_`The%n&x0EiiCN5jMw{ep9d9h!_yzIf$4wgVuw0jn}E07pJ$8?&xi9# zol{*I+%e0Wt`hCt1DQX#j79u$i&XQDxw+gjZzeq-@5ZueQG6lC&}4^lr4>-D(Po{@ zq#bPti9O<~T@FE2id3PmG?OY|e>JF2vw(E~>`nGf4MuGooc}TS*y1xLHm<}I>1I4y zM@0DBuTz_R!?#47nkAIaz53)fAWSB@jCzkCuYisbK@r_lzb=T*`IK* zEHt6J`%1xzC8Zzja#YS3WGX1IrK)AqR0=e#QQY+gx~`qbnk(RIeVMe8Ky2C z895&%cH=z$4v6q@gHGC3RFYM!29LP8SN6}C`x z!xq(DJU{(dh{P+!CJ)bd-|h%g9K+`Bg4;bKI~#Ho2X)Kv_)VL*RWpe$_NV&0I5-^i z<0AeFHutt@{8KNq-a&jxw+N=7(Ej4;RFud@~n8M0nkTw)& zPuuF7Dp|JQ=?R^E#|F6>oQ_?6xc5EU{G>y64eo&2MdFc+aR57hSm?L_# zQtf}o=U1)cBxKq5WR7kLl&9R^dN$rUGCuuEEf@;F%UZUQv9`{M@k zY^QGcG z`1WxbHD(gI1UwNnKzV{vgTV$*uHHWyk8v;OJ@LVcZyON!1-0Tn69sg{z5b6dFiQDh zs(#{Rj0s67a+oR9UPSTV$nF)gzy+d^zQNF}iKPE7X|x{wp~F0%_e4gM5{D&bae-Qu z(H8ZJ$kSIROi8jLi!n)2C{o$@uG$o+?bxM?K~ST3mzl^`3>SB#xo%`Z+SgQXhi5YT z(4kx(oJydS#+k~#EPmEdfFhGwTRB~j?a3%Q3r!UKOXi^{gM#Lixx7ZC!rG0Rv&A)@ z@$D9WN|cy?p{CY;v!MeRxV@KQ38oa-)BO}qv>!ps0G-tPz1Z4rc<@-WhHO{o?&5eO4%5&je~7;NIRzx~eF-EL1Q@JNb%t0eFY zTKw|k>ppnH%(H(>8)}?0zSNAePZ|p^dDlF>Xg7=;Q|fxwUetf?dKiPUb8E+wKeoKS z)-9?n#=w8EWk`Co?cql$M2JBMc_+*)nhFfbLdFZsr5KE{QRyGuqC^U@gyyLr(9EXg zH&0dzY+;!mKynTLxYFkykG9JoD*x?vN1|nQSJdPmj{VF+n*oZAFW=B#5e2C-+FiVD zx9m?qbGIzl->jlt7JxWX-Su-%5_~C4=cLqoYTvdNZCOg^oez7u;+WPA$vFeWRJh3eYomM4tRBd9Ny!+4ysE{2fmi7|-5 zUq)ZO+NE!zAS9oOF1Ak|vQMsDf}#OG2c8~lq87@y_Z$EvAAJgYT!(D=lo=iRujXL3?{i`&VSInToV>* zEKw9F*2!b@A-Z;!$R2+Fu}v+iRosNVICV{{@vJRz*Fuldq_7Oyc*TnscWqn+(hycz zl0xDU6hT@lFO_@$)#t1E?vRmpNay@0Ed#6TIl9FD4yCg!^=UMAbA-pH3!wxPTh|Tr z#}CUj7W0^lOoZWPt|_Ij?3OPe<5jhu&&vopoa~g2x|Bj!5$2`O^u4BvnN zP?1<(#3RVT(cI(v;@dqI|I8fB_-%^OVN_JB^|rX;c`8v3a4Ej@Ri{iQGjVEcZpMlg z8B>;)dOotODz-1LgFd!h41bd0YprpPA^UWUwInV-L?R`M|hHBY%rD$zE%YJ1c z(^R+Z@iy5^hNOQX^f_r{R{HWmORmNRs`5_w@X^zww^mvCdg(dy)-Z2Q zLYbjOAW`rC$pt9oRUoS>OS@6U5HAH>D~Lq(Wg0y&-ChMLyCV8kHyeW-^%DFNc2A`! z--xhIRoCSo(DQlz78Cv94-{biYOiyP%3hsgI)QE$awzRUW9y#+6+Wk=PPhyG-6$y{j3!*5PW!v}XJemav^?=W3_`f% z$dH1_W!NY>NB!&TKttSF{ivg6A%L1mR_I{tHQoyEG!IP)&HM*7PK`fl)&^HL0@Ex9EgWb4E53q~u9amA^mXhzJ?foFC-Qdkw%3BoU`lS1IxTwNN8lm& zM3_%@<$VtN|2#i`ei&B!j*C|6b*K04cmh3GzL4!tnZK`>alGCOhu*Hgr(Q4D^hRG- z(A$UiOpgXlbz^pHp^&4pQoN~C+my_+_~jP zEf)z!N$;p~eBD@!mavOUExH)Q=>dVpRD_az;{GTJt60%Hqxu76QDZQyo_hyjkZG(> ziN`UV%ARh`Q1-8|yuq%R5~K9Z+M|r0HMYBnLwtqVSk?Y#sbm%<~mD2ZF43P}}q6T2G*rpx&I$G*2Z zZzlrne(N@EhKp^HN(Nl{bZg>~@MGEFeR`jlX#!81!n{xVu`J;gT_slC9mdP>Mp)Q1 z1DNI@#}M|C5C~&KliBc$G;X)S5&h6cFm0R$!))X#Dh+^ecag7hT0gjWxWx#X0Xxrl zzY&z0@lrYvX$S%|CzC8^dxGn!4jB;GFxdib_+Ps>REr|pDXx^9`t-HMMzlvsCPKdy zZay1;N3$u~YU#(eIq3GG97mpvW`_sLrc%_@MGL%Z3GtKq2q9nyIQtg35f&EC%QU#E zYHDov3tP&+C$(&*82)gl_|WVDQvM^G{?$QjN48nVVq__qT_*1AbAsW zlNIkk^U`?gHIhB)-WJ~Lg{|-FdLT(reqBYam)w}zQl9T*eXJ{28x2a&VLZa2(Rk%7 zLLBM6x(yf8+thmAGEBc`YAUT#5(Fu%fk-V$S^g1D3pTS)_yEpX;ldxbU;A{;TZ=nO z>q@FM4DzY=$JWh`hnPH65dmb9-DIPL{CdL2MQC$go25yGm^8{yL;5QbL#;cfLXDfM zheh*dobGR6!$`3XM-vDmvK?lndw+t;4YmWVq0~o(O8UPtEzx-a8x3zOc+CLsn$DEJ z6>14&Y|1*NRJwcD`Q`5x%{X!;4H>+?^h=93RF_lVvb|nF4lH|YgE!_LxL^s{2y3uv zsC)5>E5m5aGof1PnCbnlc3dC_9+OLUny zU$6GrYV?M?Kb8fihMXU|a3zcGDOr-0eh0&0(&T3HZXTZ0Nv>^DY~gim2VoJSMwSms z3&}5W61ts04C}t22z;PxJ;!rs4^Cy_;ShX-L~w&1+FLBxGN22?&GtM(sfy_(iy;*+ z;dC{{?%ZNiuj90~KX~#H8WIjM-E!hc3Fb2cQI0SOPfv-P zx(U}m`f0Z#BiL_;e9ZSm9o32|{+-CwOznG=@3+2vMX+3V&y$raZ~dP2S0`S{tzCF}br4h1S@%6WN$B7-y5CJ=GLHN+T`cwo#w{9 zcXpOeBNWL&!B8Aw64=^8b&Y6)kk;TI9q-mTyGvTWPZj)^LlJZiUZ z4H0Zm4^oP1OV+i#w~Z{WUE&GFPHT{fiEK;N$XE=z$?3nx*PQzzp_3ZSyr^JsP1ce6 z=SVhu^#a(OSxSEW!d0zNl_j*iO%FZ#&GS9~x!qPyef; z!8eSuT}q_-Xc~i;kDBO@_cg{3!~vFFxl3C-ZRNO>A2?RusTUF5LsRaH!=22ZpK(x< z^PIOqG$!Z^N~joUqA%mdoYXP3w~mZRKlQt%Uzo25gb16nhPLaJ5=uRy`%5}f2rCKc zG19~)Fd_!Ih?j$=6p^iS_6mqR{9^^|{6yRDhMnPGkpO zO0=p>bNH|&cL`j0i*Z9W$e5Cvc|yUdM8w6p3>0o#4J*`Xwq~rQ2AG5&8-!brdIBTi z{Xg(|>cHPvA=!AP@3BR^`>!;~qyy!CRdgo5@;{PHU%qScf85I53=w$}Y`?DYq~p{u zDkakpcRR~6Q9SkRA^@e-kv$K+MWz7Kg#Zlc__gldix+b7hv~ zok9@)!LFuCZT+=cx}=#7hKu<}oJ54AlAG7Q`s%uE556KS;({}BqOb2epa{NmKVDnj ze7=1cdEI@yy1$>h-X3vu`%mJj67Tgc$M@OY+(^b`@sH01V_kazk2!hNzS`!%H}G(| zo_U}VAj7sUP~VT$#!`4xCc}}1*NsSQ!Rr4$ zON&0#D2JJ3Tn>Z`5GVJ@c}$$|-VQ0h_tV6b`vNGJzS=ls`AI)ktk5pj-}$j%_V3H)bK}e)r}>+61_#;GlC;IC>Z#iz_l@ZT zSCRmckfAYEBAd8Oe>r!KFeR*c<5U^20t3LlUwGzZMu59Si7=Ft?Tvvm1jG7EsLZvD zeV`pngapHj)YGbaCtn_eie~b~4M4h}>NW7{#iXkswq0hrj2p31VOqkFM#Y)_73>|? zmeNI3z39J|=0g-{-e%bFd7W``Q^`bbu3(pk7PXN?$4STc0eqFq4bukzv95`k1Jul2 zcedJbjk%0fOWDAgD>|8F32_RVAzFoOcsdL{6M@~>ZJX|ERfMm)yuxAh-{hfTnK7$E zyT{)oL;0mO(L(dWupjMK%5%NW$GUYke9(|v$qdFhhh`qfN+^T+@<2qD%L8U`){4V( z;v~ZGAZ1AE_~~5iZ=La>dWU$Y;-N85Q220@^4!VB$ghM6=y_mYrB)n#_g<^G1RpE| z#JS|nq0Ufs!X0>gZcRV zr;B4n?yQHxdMHxF%oLwLMSXX3E=cP&G=}Vsd*)NGu{sB>lsSe5b-h5JZ5LBh)dY$N zHm2@{qx6zT$H#lo1P>v`ANX8kyf;1UA{o601Tcd9;gQ8CJe?~)l|!^}$g=&AUe}T$ zGad3$^11mN!*CaVkwaPLi7^Ecse&fQGSb!?#21j=IxPs6oZe6Q{rwK*j2m%!tH{tF z8S}NvC_f>INie|CvAa2YoF2;}6{*Tm!x0f_>6V0Qu@(r4hC}qRUM|TJzVE>zUGR-R z!|NTG`8-NhZ`7q%HjK>6;qUu)0O)`MZW;OKEiH}Ul=JEZEn7I62ZagZ$H}~8aTJY1 zyO?C*gN(WNSmakjObxrzKDoa-gaWV=TsjX*l%106tTnjN|Kp$}2TXf^|C`u0jeTj@N>KT8;(ZABep2CiS zKCZ|)zE5D1ok)fw^-&~1oH{p3r}mnj*B~;2yb@|j7Jnw(2oVc;tx#jOsfl}c7G^Ga zk?dcu!FaO?xCAqWxPPu+$tY(Xl_0FjW?%|yMrJ@VTVzxa&%(PdlOuzRe?|!ko|@sx z8oCoOs3i1TI)P^GFR8^Qj*tPpcj&6sL^g>Jf(Kh2y!oB1-^&-hO=Ov#l%mXxMVJ*Z zH4cOl0)YAx4w}Q70b9nUNUAlx3qeE+BYPpcRX>FBsJ~oO7(cV zr?~ySL8!o$s@r!%s>ft5l`@=5#Lkp!U*zxMa`gM>c2~+nD!mdRrNWYS@5jTu3Q~PO z60?<%d5$xF#X-}m>PhCx$dLI0Mc0evhp0i0MJBx%yPNA2eQT|dx9(0mi&6!iKwW@%QWm4dd48b+8 z9KTE4>S}OYT-MGbo31M;+~2?E^|)URFW2<3so(}9dJXLb&%GDT38^|aB^ zy`x1K4CQl}yYYFJpP7M^(<6oz@?}oTm}pL12Ds3z6E03HK>wDJ;j+Chue}1(r?= zdQ!P7hly>LA)&hG2fizUS`UFKGF}NMl7>#z8(Odp#l*#vYR*VdwgR$gS6i&vWHGMs zTkN8S#LgzX5D${6raYryE#JuyIed#`l1rLu^po#8aYdqYSutvhwr2HJG#Zxl?JBi@ z3@x;6I%V$H4LkUJR!z@YYlOKl4;W~gsP%6H@O7{X^4l5_{Fqav(8k%?#nLj$5}nbP zY$cw|Y%6C=dA5KY)<^^rOp>)S>u(Xb>opQ?N9kBV??UleTKJHdKQ^WIi)_wFUFtU{ zq~A1bBo$9g=-F+m>wMnfvc2oa--J%jt9}XfK#wo&_sT4o=(K`&J|B4hiER65G4YI!r>Yj`&l3MkTut)tQp>#jk z#df=hWZZL#8E?uw@|SZlXXg|8(|)}%gxq<>JtRh(aBnFnnxOinttO%xUe2xiPvPkJ z0*;xw(}0Efl;>626BkM*Q;5bM%T>79!N_Q+jkVPAOQj{FUX=7xQq}SuqxZ{nF8}RDwax zgi){qs68Z%y?w_F^%Wp7d)*@AA+7f60`x!{`{bE_o`8qotUpPE5h|JDlH|B%`_tg+^<)^wTDE`% zbdX9;K*8>|kG&&?1;;LFD92#XM7|CJY;Mm>A`R<^{iaNg&~U$PUc2jx`)=@DkZ)-s zPZF6D_DO-aHvsYn7WbJ9{+_<#FZ{~9J?1mXFDK2YQT29-RA|Bq=wHztE< zfjZ;4Y3k)}V@5Rl($75XFjBZ^oHg1lPhhd#H>|+z?Lza|cy=@|p5q4rJA!VnL5qyv zY)@Z=+7>!ZdZq5Ul{^NYf3$Cp&i$%%QT67g1XyQw{Z)n8^6_Mq6zsTfoP}$FKtQRT zrZYHNFmEg?Ur}1Tu%TJ0)WL?4?}n<)9>a_{@M<22xzyOJ(T!hk9B{K4Vwq7A2KNj7 z3Ro1tKy%X(ORxsshw#&c387S=L=xumk(`U|z9T_Dzgw?=U}qNLNCDbNYD%e2ME%Z7taxuCbht#dR+GYWRdoC8=yTkTQ+gS8n_%FljF{mWC$!|I-N67a z?bl3($F<*H*>}&O@D#%qQS5&zwSPa=5ph(ilV1p!Ki>;~t3oo?kj>_Cxh}7BF$r94 z4UqFS&CW+b5x>GuOe9?pKLeT2yQpPaj%l^Z5`iE^yVH8${EL8511k&NKpmiNS_=k4 zb5f62Oqb!2>5(aE=ffuHiccm^&H0qMzvF0MA39+Opb)t69u?R_S2V!+-v$*XF%(U3 zGw;m~T{mD!ZvK4fq;bj7-UpEceFq&Od&c2PP)d$1k_jy-<&0@h;X%PYeNGMJxwlam z6+Lkj^Cw<>p&VBe53D$DUX<(yT(6qo`L80~RG+%7A_iM1QAI;RK)-pC#78C@tz)C<{x z{H>n}xqEir$ZU8YM8Ne(`4vF{(4sNPF%rBy`fhv)1EJmM6D`w@AQ%4nmOp|X+_@^_ z?1F{?Dc{k&_8OJlCBKtqdwB&>=4c}RB3{KI`6e{fgb4Lx16AXnb;f0G+<2!O8_0M? zdF~7*`CEzqqlfp}ZCMlxtH01;5ip@6uUX}6PLkIy{Rc-NFz=frwqJ6XP0w#Wlz@Dv zK?8J9nSSRXSJcbAt^IMNN*{aE+~3eWZkg&Y;EoF-i{>3uxOoCSjWrt!f}PNP9y~`F z@0JNEmNzD5g`XWLlp$eDUB^@kgU5j{OUYZQow+3RDpg%Ay=2PpS?4yvnLHFJ6$z%(2mf5kbJyiUB$%yqP}@5l+FAx>}Z zpX(>PE?Oe-=wR(}PIR59KBRE44!x)R!4VUNq~LPwFPvh#UvG##HUpkpRV0{WmJzh@ zb{9@HK6a3&8)hu_?o^(52ix4?IHm!fbaMRjyPem}nY>M?mOrCOX~j65AHhPAbaR)p ze^%A*M?_ULH?K5u?H_+0v#of99zPPA9kcP><&SQhs=Q6M2QBq|Q`OlVI7d^vN;`h2 z=}zx+=fCYSvRdQrE2d}DHsxyUp1LIsSzzblv2?q&LycXGGt_9F$~C;nUr?ML2vV$p zpDMx^xZ?D!R;HpP``uTr0=3U4D#z(q_cq~S2N?quqc4cUZRvHQjS3zWFG=dtT;cce zHaSLh+8oo}NGfYx2 zT(C6sUff+W0IHt8xbGi;ey||(`>JbChT;BgILCh|tnH)z03$HzN=%@E> zPYw;xscHjzdvMYtar;5ma#%>LOn6~w)<%&K7S))Uexr~G+oH45kR-|4wzNi*1KC>V z-Mg%LbMFAwzs4FvAK)R`(h@RYs-xa9{Sbr7tA{_s;KO#vOZ9{U)G6NQx``Hd%9gKN zQ@bq25(lP&#lB0u`ZAlE$`e+qTizYHZtDL4!so`~9x-7v?jEZj4bUWAyoH&B^KQruPmzo0mO~4N4-Z>Avpp?b13Q2l3*B-^v)3I0RO@OC3^q zvOLZ^KO#5Bf2toN!8D>~aN9)nb`m4-NFFtOfy$Us*8R#?BOQ55i-sHExN^FpOCvrR z1i*^hzbe6&lG26S>oK~c=cV2x%tIf7#~KPt5TYr^TkPy-f8{SWx2F?CF-5@4S2bop z3*VZzQz83XUXoUUY-$y7blH*OeHl~~j$7tplw88OYH4-$CDZTa?K{ik?MGbETkw-z68#7oj&ly?) zNHuX_99ghGE*!NaNZdGCNP{)-|6q>GH)oTVK!JC{HoCS!Vn?RGTvSB$MwTb|Gw4N% zB@1WFWbA%9p62d*6J_~zqtuOzL7{LJD$x|Kf$Y!BuutXDrGRs4ntV^+zrU2@N0@&Y zbNB8I-oWl64fo`avV-6FKIid0rS z8Xfw3D7t10P-cNV+VjhO65~K!kxg+A8PZpa&+hnCRcHFDc5!N+s}01l`x8F~Asi?@ z{cIVxVcSx@4v4N(M(UyRek7GyRtAbI+1Y#GtOvW-6JbV08rFWG`ZiQ+Wqt&NWv~&@eyFp=Om9hb<0m_y`st48^ua_@!%M7l|x-ftBB^f62zI% znk}d!-^vD{ViR^O5rM4Ql>@>!*?2wR$jo4*#W(t1(P66vMfX($x zFibja=tFp;OQJh$>>V?kS++;n163<8xj*TIvPkU?yQ%nC?`o(qfct5Bm26Z}01v*Gl$o@!L=143ZEzYD_ zD>f==`E(LnHkjqm1xk_4)Oq-hKWQY=y?9E&TI}$9v_&@EZnn|)CpSlzXD;zD7_5uY zVzTmkkaOCq3!Yt!H3R!S04bEwL&RCUcX>o)@D1jFC+n{){IKT-7AOIWfs2JpYbY7H z%g}q0gC~k+!LD|cS2j*0?^6(8#zhr!oW)?Pwp%$HmYt61kZC{}HkOC69kMCegq%`w zVxcV_nMu4{pA9w&15wDkpMH;Z+t5uYxE!ZQl1~^KU?xLr?pUsuY2rwOn?awc>p&0r zb}TpWUk2_p;ZA?Sc)cwr%%;J#Ny!l9IOlSM;x`yNBB4?t%OVOr_%veEp9OQ<(w%CHNO&#b+ zDdB${*>99(I-?8{t&u0;wjOEp zkdgi+sswK_Jz&s-|FL19{SzA~Zm)la5qS@09K;x>HZMAWGT4rU@K$1c@GoZZ$23_8 z34g>m@L@^?#E0%P74?yU9s{+#pSsmk{cl@Aj&A}@$JOlZZKlp_0XTW2fg2ssA2%y* zWm2+fEejM&I9E3KuQwz^NbH%-wr%i!ED-xRu=9;ytTnsoQFFexwg(FG2r`OCI~vaI zPEfyV4IU9ZuY#>>*dQgE#O*Qz=JQwRS9^R|1@1zrDMs>FY@O~7Az9Flz4+v_1p)}W zaqaT$iLAjZR#)P=3wtXfxQxa^YeW&{WWm_bFbfD3z%wePwc)8f%S@Ck`tYNjG*|jc zO*qk`51PxK8%@;69F)vOhHNwn1paDV+-`@uoV}l&JfX1R9v`+(un;{hX>;$f9;e6vG-PuA}k*F{(Z%&V%l> zmGr@7#LO$M>0oKtM7j!yNvPhMC5#fgF;LkY)#&fGSWI3^5kG0>Qg?mXbN4KrC3TXr}>vI2`Xf6Qkf5)tN+MqG_+e;)$O55bqSa=`Hee8^KtS$4F|UavU|rz77$5UNef7LIz$pX0i${ z9-sj9X6~Y9uV3uHu9?`n6U&I`yZgdaJKo3%U5)GKUVoEMn})g zAhEGeGO}(Go;;nK$X)fhX5!v0r&BbFp9h+(bz*Kl`=MI3{LM*Vw@003H4NbmAbUUb zqG+6Izd+FyShET}(B}Op2$z7bobJ!IV4>SV#!wd4J3G8_RitPOITQd&;oUJ{2h4>e zhBY2fC?#mOT*83#s3d8?YsUj;#kK2kn^0E1IQpj!;4kaqkiW(`wd_o_g=3dc-Nl-H z%3eiQ-+K+^g=aP@oC(NdHHMQHtwH#BQre23&-9|7mrs31?I(h@-_zmAAExJQGh|lfh*J^NrFJ-p@;4Bx1gRRqhdd z_S&rd<&9QmW-hdKxhfLP{~`}Oxh6E^KAV?$vH*J~fg+Xe{;loP*8Ox3Ur8^(39A?e zeHXUIFW`_4hMj>(0X0enyiV!rqM*=kvoV;}nduM*ftq3Rc`=C6V{}8o{y>h*`y-+3 zxz6qtf1R)d1Z#1kA3@jwRui{}4+})B6tnbr3gn1vfJ(EnRFR_t1W1l~BNstwd_$wy zhQdr9L8S_ex+*-A44i~a3&4p2uz@07kpAM8N^~YBQyr9nkB5FR_#yQ7hy@TCqg_g7 zK@)f6o#=D+U)*euKThrlGv-;CAE{Ceq!f$)S2?Mf#6ghFzxi^#uc_{90`<%Cb7dW_ zRnr9ClX^?kWLbCCrU%}T^1~7^Fp0;AVt~8>X8S=sb>=Vlf=q?s|0JiyNvQ(UNQI@t zT8)Beoa@(CZraQDUf>Ngj`yDyUJGXP z25#@OjKI`|AIQAbPG@{bl#6RyqS00J{VArG0zWwBLZZWFkaL;hp)oM)T2m-K9-+|E`1A~-ESAIgwZQP4 z2UV$Bid2sJPV$2y^0(5EH*$LCZHOXHly(#&20csmJ@1ouhbuM7lw{Tl80<0@0k?Cc zz(*5w1vw!=U{Y?yTvxX%mx!w+^Qe-R;a~*c4Jj4O0L)#tJ^CF#RVre zorn$2d|dLRciQ7(PcNM{Q;vDE28T!>TcTr;;9-%lh-PNCuToR?KPgc-i%1#B+J=ZL zf~BZXD~ZzmfVWv=nNjFL-F`dP%jT|nn>6rbq>MEP&9_;14)}b|dUAZtvBs4{|Jqa6 zr}J4j3VmY`MvE{dH94&_vf8fC>AHIV$0;&X(W8ouKtq>WR*p-R51WzVa>IJu(?O_Q z$&Ga&7OH_65tsl z{`@FfHKnhy%^H66)NO@r4t?rpobeQ61C)`bOwWBBKHZgFs>LwY+f4B3W;$pI!oi0>ia?go{ewk{h=qO3(P#GFRrntK1xHTk-oMQ+apKqN8Sdc@PvO<`fD z;eCY2<~tJ6w@YTL;)_8&T4gR7`-X51ep|II(GV5fuLuM?*@ak{xQ!wl+uCja7p6ob z6&5FrvkJdBXi^ML(Z5b$Ctq~UyWtvrJGjFmHbD0FkY#InFygX^Pi>MkmG)ZmU*6RS z3=0}ve;eq1r&G9+svtkerxqhU)DkjQ(RB;F-jp6YH^i_Lk!iGin0&%}?m_bzE;m$W zqKMB-&7Y@>T+PH!+XfD}+Lwf=>SlQ|1@Fu63^wbIq=}}`X!0mRq*gvI8skB2pupX% zwY$bP9DW%@#LtkT+zDk zM_@I<|C%roV{t|j#_uvQltsHs5d{4%-$svyy?Q=4sDFJVkInOr9-QHcmL)3~-S zk$GFM+xesCrYF~Aluq!=J4nE0QmJRDhTQ$12d58`IDY+VsM0B!|NXq!e&G~& zI=)!zeIn<7-d5psgU854+(7ue_S@)pSy|+CTLv9A5g{z%DOPDM*MzCD_Q$`OAouHh zetRo4guJUwEEZ-yak$F<2seZ@LF}1bjs59OXI3R8APt#ZBl;eq`w)D`X48-%+NR7o zTE_oEPzj%IOqpxNG&^v=CXu@vQI=aodjIusHO5cBB2^?S;f($(M@Oz>4tI+zk(HnwI0u^N7ZP=Ijua&+JA^9)vp1;0wm~71ioQCKQQlN9FrY^Rs$w7TO%gGqHrBzfL(M50SdEak8$M zOdm4Y-Xcx63NkL%o1ii1NYMok_g6wi-Ehyt_RDL|>oQY}QB1e~&bGy!&wx!FSL7xO zLEK2wZ1YHc=elBru|Bcn!{=0HA-Uwm* z6lf?_{i8HLEo`+ZIxPsNDgS|14E^|I!~6V0B)<0BTEscTc7W$hfRES9)sAN%@|AZ4 z$NR&Q_l-3pa!6C%5N=O2m4S&VhHVcf3p5$l?>U+)fzM@M{@0AM3UV&87UtR=AM#NJ zqQmZ+7r@pq{_GnIua2?9OxR2Y@%F8+Vd0-7(L#O?2lGzonm`CQc=exe*E4Z{>-bq}y@~A(CRWa0}SH zenTqe@6|9TI>DRdmW;gY1%qJ%kB~&qm)JOV3<(z49$Uzd?VP?KzJM^;`03Xwd8!%b%x4qX#ea?L5iHVY}%x#xqwLk1zzGra?^ z6^(hi{-8ue)sfCC!qC>>D5{aGlc}g040diWn3-OZ{?0)S|B&6f#>@3K4WxAFx@)y6 z$NULwdeDZ)@JwK9@vznGjhH%MYmMf)Zr44X0~4%&ZtruTnyF?16oF}hz;ZGJ+uo8v zA;`||&t$gY&?%PB^1RbBSkTF%=9*YTq!gX}nI~a_Rr5kIKY;bWQ<7`S;%kuN^N2j3paw5${;W0sr{?2h?n==oox+^;n1Fl4$+ZC&Y5K71CjG7D`RBInI%y z!~{+SB^VubI01Wwq%vau$q1j^-%pnR=-l)=1FctNlM?Nxy0^;N1LHRV55L*A?NtWm z?(H4r*SusURfeDOYGL{ZF=7kt3z`Zr_L4`bxh5}x|BRe9jZ~xu3nMA&`+||e5sLAR zspR7EHMQ6KeeyJghnrp>q1?LvnRzGu2dg6&E=@ddp5*Rro-LKH`I8n2C~d)tnNrA2 z6-k|9Ow=IrRx-j%Czw*JWmmojJY+!Oqo4p9G)<%u>&-Q=C27}*rb0K85A41PcXo}m zx)G+{=y|@A)|$PF0!r>K*y3FVQ<_Y1gQc)b4AMr8QtPeoj${NkBv}D zaeG&bqcv#qim)XwUxs^+Ughok$tt@-JY3uv?@e*-gXF`Ls%($CkI4C-dRnu|Gj!!` z7FgRuxXrS?dq_Qr9*1Yn2*L8lY8r8+=1|Qo?zWGT(H^82rOpE{twTp9H<{VOru}R5 zj8%&u_sE~SeKH8Bc0t955ylLwWx=Q5luR8UYJj+pSi|`b8#X*JwyA z1V5_(>ra@^SWQZQ{20J{wEM}_7yD%%$rD}=c>I(2^;E|D z*eMSda-(qYqQ{QR&VA5aJagBlf1QnXwabbyf=%Sd-3>!y^Z#)t$YfBZzPd_?%-_Dl zpG@nSei%cOi}`eXqk7*qRcyFm6x}bJ)RfIEJXczQ_Z7n96PP3hH}8s=3hCPVQLbo` zf+SL8yVmLx%z6Sponu=76^#1jEf232nsP@Vf+{!p1F)J(EIlxN`Jt@|3X}wIgx9>B zJ@h0`Km}2#E|LGPq={Yi(tL~Zulpf6m(^-SAq|9L^y>pU0431N^*#_@RD|eqgUb&3?o&jW|d}2oRfZ)eT!J*?rA*K@8 zWgR$zLZSs)rf$e@2MMD1<8OIJz}Q0bvqj~|MI#`Q5_(O0 z5Kz6oxX@Bxk;&1+q~BMFh3B%jpr+Y zF?)W`@NrGi+aW#&Xo6?-YgU@Mo9^WoUrX$L!9;&6+i{1aR50&4;iFu8GR|TxgO9Et zWeHtjm<2~{2A(RGFEm?MEd9pGLc-|XF)gQ(7e@HEiS7AztwU_$U`q>MR@aw~ixQ`7 zf4vA93@b_@D1j=60t{Z|x1m?3NjR_=9@%S7+$FDcash4c%OpsO<}F48747;k49Vuo zVf&+a&?3x1gr{}jB*(=)pM36X?#k404VS=xcpkn!<46eFj216Lz5s%jw3R#&~H9F#rQouNwF$f4THrSll&e>Fm=;;27QP#C=;mR^7eEk)7@+~`mC@2 zKKxdB&OON7qSfpG{=CdH)l@0VUdF9lG-@zc&9J4|Y>=`1i*Vw^>1dk!^ft^NE5HL? zZGMD@gL_ZFAOG|V`XBRpFgy8@BZYa+?%KfsODkjPQv5^KsU1xqW0H>!30Bwrv!N=7 z=IT28%5`OvF^k!|=a;b|$2jRGwom;(jOkahG(=tQ7fv%Jf}CSyv~7eoDP!>;m!`e` zvK0RPCKUyN0_ghD?>b1+h6ddaqCrm9DSF84%QkQp`sD{w?4q{ zyB#1@nb>>61`61)xW5{o4Mv>O+~Y?CY=P3!r_Ot$D@Zu|CXScj0|CwXBY_) zgK|TO#?TXPtxEkODT!8%^Hb`TzW>`{WUC(F>pT#b*vqC7vI?RG2*Q}Q0d`Tg0;ZV+ z2>KE3E-HJd?E^^vxw+i?0fV=Z8gi;3t;m9ds`|^oxorB!n!0`3UKiAn9@m3ZkXF>t zFWG;70A92rLt;lPNk21fWEZfe>0H4tYS11=bbMx~}mnTl0I%i$CUjwIq zAXqQhnat7Qpmo|}9o}Q?7wFksFEIn+MF$)Rc5b}0XCb< zlL2>ZqJny#uXwh!5tBwb9q!SCA|(^XrAXK$bcJ(`@`Z|}%~lrzJ$algOh00GdQbTX zdX?O95lz`|H;vNsRInI05%@&SIekw_Eab0@4#XAOyb|UjvR6LGayFe8Fg5XW+1R!H zJf=6=sAv-ZBm4~r5%PtP9rZoWequAUYHDhl+IWX{LoWx`!Ypi4|Jb7pf^TPf)>H49 zfbUQN$bE^1xF^8?kvRP)Yz&=U<69hYj^;Z!C)fl%1<{Kk7p{NXpIX>jZS=<3Iy1eW z$((dK)ApRqmQ-{6K3JoI3bQr8(X(J|x@bA-aDGpuT91kProqJQk<0OZ`Lk{7 zcOYR_L{z#WWAzBfe>(3xyr9;aWQ)AEt}8~o%blv?h>|gc#ah8cJgHnVz#%DlYzYN6 z21f~Aa5>dkQju9>{K$sOTHGXFdx8@1Ku-VDhnlwZcYdfUpT?DKgYiVYE&W?DuF3ld zq4zU5J&~UyDuD8Wx~|J4(eKl*#_-jAZ}FC55phd*t*5*HC{5>MiqSx>4u2pEV2!Jj zbiXe{_;JTKs&&o{9BEnw-X4ZHm|syn<7L&HWXhFgtg}p1*%|b|&cJr(k_eMHkxO7? zws7Y#U`z*TbeVIaqf^k%*_K|$GA&9dN3uWv@GMLz4x#g6g%aa}hzy=9-K*8WYqkAl zza?MqIqviys7#T5t%?6*>* z8?dDEjgat3I*@3+qwICd{1OOjWm$u|aPt6Mip$opd!dC2Cz{f8#O7aBj-H-V})2*$;Bg z4lWoK+bY7>JkEM)V;u&6oHVF@N5;dP*qA&K18V@_b`u|_pBys0P7mN8x_ z*1gkadGoww^Hyz7H9#^Ukpj*4Sq7~=A`tsoem~#|k5wV|3ZQ)29E~N+Gq?F^Hmo_| z_uT9EVaDySlUXh~|7Edw8w?kt5;|+%?fJrGWc%T}9@2sm`@(sdNo6%?GFuB_Kux9ZKWAhLW*Lfs;zRCM<&e>#}q(8Vy+8*ETY1oSh4kjwB{8X`hH! zZmg^51+O=|hb5!Hy%g;C zhX}UuMR~KF`6RF@JWdxeYPv`qh-QFTc-B@IFi@jXy@Bwf+{I3iQ|9uFQj!vZdO2-S z*=Dj|kVZ``W!_oCO>qhHvLI_*Q@&MX#R>`YVaTAHQ?rF7_HI&RQ4xS%HaoFOCi0R% z%#7WQ({#@ETXEU=GM!eV>11Qft^aosn0pMEuk&KqsxTFm@^CC_bxW8q)xpeC8p0){ z!HNJlwIzP{q*+hir=ME9)y;aWTgJjL*JI|`Gp0ar(Cb; z4zK5rp5B|Zg(ho|D`zEv3|mKdK8`B-P;!BbFhBy5p?ro)%=idzE@a+ZMEa)uj+v$$ zClC+s-5(|jUTKLq(9i}z3?7)y`GH5fIr{5(zKO{my35TixPoj00-~+sP*tkJN1#La_A)%L zbI2qU0P94Ne5zJ9uybU&7?3N75jLOsJ$C*iw0ViY&xZ!eAJ!G{q zhJ8XB*bmZB*6-?tXg_Hru~%E$re-B$Ha-i$xDhapxLWjX_b1riVuSzP{6HNZF~J5u zH!)0ScF4oAE)H}EbUWfEk*a5>=rh4Efbtbn=Gb;Smo7Pq9BAZ?jfyMiy!rjy+Z&W{ z&3{~IkQDWKotUlLZoBn<<+j^t@Y(sXMemv%67&4hdkU$MYoK|{a|I>rkWeE!+c+-D z;H@XCS(V&#_&x4Bk0?`+CYah*_(k>6hnGBP7kmLisdhEz?y>FGB!)<8{mbg+Z4mAh z@`K^%R$^}>?uvZuy1W^|rMiWaCRnup;8tZ1Vl99Yva9u%e{@hiibGHTK^+Um(T`*4MxgZz0;m)=X1g7=KJ^C z`8ltLaj0G1R{x(d*1IRJ8bU~am6CLZA4W?j|f9B`a9ex@_xJ=NO+r~Z+EAGk0}e@;vfedI(S2~gn)(+a+rMNQhxDs| zV#*9Rj31Y79cv7B=bK_CarqhjC1z-CFa@elV*8EO-8iGymPVBi$bvP6vZvHSPD&%>ObI&Qa*Z8yhz(0or@O;8E+Z5OrGccwFT9m(lV0j5syxv( zRt@HQAtGVH9Y^Ty8zdFihWDj#WeWITPqkV*EaTA|g~G?VCkzr(MWGcP&<-a&G&}Jf zdlw5fNxI@ev>pZ0u^YLnbA4b)0%uVS$S~^ndkrDbqMYF?=gD;#jZ+z~TTc^OX|67(8cm-+pO1>ner1Vm57^(2wsl=A#%#xRXaU$V5wXwM9kb z#Yq}x;b4@CLNYk+@j8piZkfbKJs$7(yQ_lf=O0+(^x`vi)|Uni&d+uD-SYh{3jM!a z@&-@h9wJPdj<<{uI0WS)VUt5CH7T@Wkp8e3NW(tWhtt)`8PgVJi=*O}NY~B9{706` z@4f<@fZH)~@iG(z#?_zaMsI5TK5VV^74G=tk=4N!Cear(px1Pgk@YvHv zI}{jD4p?;!F`~kO(GAATD9!YL<=iM%dGv(HjFMxfK26~#u|Lyr1&@;L>B(!s_iurNIKD< zShNXM4v66TI3x>eKk4E5I@hB=eyd{Ab>FR~t1ls?>17q8LK%BIl;lz>FOWy4r_f}1 zw>Gnc%UvHmNq1(SGF`xx&XAN_1-Z0^bv85h3%b7m_BnpP#z1K`7+|!G?6^VNPY z)u6T`ygmuF2Cz%SC+l=3_JF%a)+%~6f zDQ6N&y&Q}%#s77D_8;(iTp}Um-tDKUKc{ef)_I>N z6?tDf{el9r@#ga6yM)bnbv*s^MmH`idY=L#L72$ zYeIQ?NEnS;nL?w}YHQ?f`fMPd4Tn&Nm%m;2%gU>X78 zuDd1Di5cxUVbdey0bdJm-N~Qf;f`){dBhmJcebKn@ou`Wx3<-+YQuGYx1wTeE{(PL zVl!6-U>-Xjd8UL!G-lb0NmXL=)dDn2s?*1Y_cT%RR0hO|DzGs#JHt$W11dw}e*jTb z@_|$~Y#+M&Tu+%O-XDxz1-=inWK#cy;tl>*gR_0Te2ux48$kW(cUH$x@)bPA$Dg2G zr72RWcyaM=TO|!6he|?hp2BdbK+U02&5K)x*0do~>2$7@V_H8B_@2-uyb(^(bDSnz zYdAW@MMN<0qg^6JjtTU*sRoxxSq}t!W^kHL{^N9+LPja?ue`k= zV&&R(TC>%HAMU{rRElVxxyAogZDjQAuad&-Z9yx~ZnU&V&ZtqW=K}38mkU4vT$7^( z?4rs7?wjAx%GH1nbR%D%6XpHCn;6{Tsjga`lAAyESmr*KM~pOwcI^ zQPJ`nK1oA7M~ADz#Cd>V872v!p=nanTb~qlm_m`06tn#WX!Ljq7Dr%%0vH6ysn=Pt zG@)3w0G+{I8>Llqek0Msbpn1hc>08)m+9<^Gqnoae=mxh!(k}FroQ`K*t)umq;9mp zZFaJpt%wm_tG@h8R`JCB8Py)(p06K5`-pe#=fBGR3#`0E3Hk(nT@1Ab5@RgMa+wAV zGGA|g+)@fg?ckZ}yUy8c`H77teb==GU69ZF+j$)wGpiaAWq_Pcsr!8v$8Cdvn(e#r z^t^I~WAc)0-o=4T-UpUGwEcq#3pqvr34Xf4`lx}AH&_-W#%0v@+&(H#pGjP<#bByd z=JtUL>vC;b617sUPXpet<^?2K=n$r7xPbiyRd*}C2yEkMNw#vR# z3F`XKFqQ#2Y5!!0F5rk=!;r5I)*{;I1KOWCPH&cdSgVf(GfQ2p$;YK zNg_2-CnyQ*4x1Ac=r~;Nj^T=3N0npI5!=*Vh`$sxnRDffm+K{{Q910St{p?mf?!r} zgka*yiWm;vNhvc*k>SSB=9&@Br=jY&$tVnP%`5|vOIs6Ramo>RQ4q;jkLmuw$~7BT zAiAKC&H;^|?<)vS0?MZe|BKY#Z^A`Lb*~+??FZLl*Ikn$+DK%yVl1T6ltte25EAkJ z=8=zDrcC7Y`RnW$HAvcrM|e`>m7)D=)b27~J%+ZVNaulpJAY!YTtX{TUx~5;W|7@f zEjFHcnPw$%bW$4YVZ@Nc#rrNt&rwB#T^EY*K#3-@!h5Yw`xTR%ey-{LO8vps%hWEX{7M+xkND42H!3;v0kWu&Ao5T?6?2S<$Ef@qQ zsWe~?xPXzyWoZf^_t2vN&2*AG73F@;S;$WyvWi+Skf2ej)6P|mV;VFc|}8C&tzm# zGbuxd6sjpo?asU4%E6)) zLcs)5h+KfJg?#W17c7CDGxssgLFD1PUIhcFzXCS|2pK38IO3DSi~*aDWO@aWZ8Xq}G$9WBL>4xpJ?l(K>a2cUI-L=WQ#sff%osRr(%7t|9?A;S91Lgc0KHH>{) z7?JWlfb7s4p3$+rQ|Ur+`sa#pRi>WZvmkAI)>!ziI31bb zzJYRmG+?UKF}+`6DXv^GlT?+I7hf&Cmi_`SU1^~yEh zHV9in1FXK0*Qlk6ji!Iw=$kod|M|}0;LARWGdN@#5;EK$b=`EsXX!Tjcc|}C&ZYI2V>1O> zD`M^bA28>MUt=E@eIRZ3zqI`)%$Jnk+CGAmEish~>W5-vD^y3s$?aahm#aga z%63ncW;UDm;YLek=X9On+{VLl@KvIO(3`SBw?lu zobu7;i^p+loCzxosr^gr-_5sX8K#JNb)%Ww;I=ny;#$HBm_ZSr%XP>Y?Jh$7m&{~* zJ6Wylpd&2r=b+dkXo3WmD6ssR&Vp^G@TY2G>$|s;I&=G912*VLL~8t>)T1wy!p&*$ z(({Zq>$c^p0VK`b123$QSE)lks$hJ%k_$|>VhrHaqS7t#m1=0;gF?@=X7gdN)O56$ zG8_kSFssxLxW~(P8_a_Et5`G6S^{^a52;C%TJ2o>jsH zK5pv6h&-PIgfMAb%-sJl{nU*s-CExZ1PrIb6Jv8&E62Xzz!2?BYY_xH1H{hbbJ4jE zBGUv5=__5R)Gc%y=q-wxpR;;1%Fvhn$7fO8x2&zZc3)s`+(!wbCUJkjnq0IowYN^t zwyLkTvhB6`TEv#gAG@cKB+l7VEGiGSyk5x8z{K%gQ?DNl?L(qRng7iCe!~ia-35`7 z5)u@!ESJvzfq^}&LNp(XM;ewZMD~}nSBG&Q5+T>wKU~vNN7kzC@&z~Gvalpp{PTko zT_jt*EB9{9Kayry6YMBAwejBx_`YK^*tliLF2-M|+aXL@<6HH9ZivaoMW&31C3!?m z6Ogfza$u_11Ci%{d5uDKV)_|pD3~e{$3_fhTlBNOcHZcyY6IKcI6tSwzu!IV5w@lU zE32fq*f3?$eO}f+f)qKDkoNh^0@t<+_zi-lul1_lc9II8q3S->peL!$&jZugt-;)# zo~N};w_yVmc2jj9fZX;n*{e0A1j&+$%}S@HUKe<>%`%1_20xw4umNhGK1zdS^l(Y( z{WMOJxJH&_Di_|4_*I-T2lal%eK?DY5~-#p>lfMbeH`O2({Hs^reufHbPEryJ|0yP z?EYq6BX6!&$mz0Om04*imh{H^7TFGZdRW;?&XaufzM9KwEg4S!q+xY@gevLg^}iCx(ciy7MHZ?S;8EAev$+ww@8;);udCLS82;GS$zDv|+mmxH4bj{F?5^vK}U%Yy-7eBgt>v|9qGa?uOS zf^Q?tay_nCEMj@GtAk7v*p|qB|50k(E=GJO@}MeEW^VtjOs8bNI_8#8d^DpNjk8$7 z`{5pi>-NL{sJ)&)9xH}!!8j|pDs6;j+de)7BdnKMmg4E!0i zr&ebTs>U|!I%qR@-`_)>&Qtm69#1jzMR?zIux;N@i^=Co+0&y`%v$N-u}ywh)BI7; z;IcP_-HGkz!TZ-hI_O@~ajC>sUMyKCnGnBB+sr!Y$biu*4%32jSyBqv`E&`NSO{JZ zcO0CAi^nji^e2xPDnJ2|<_?01eEO46NCfp;hMXe$qLS8z0$oDO4BW!2o-j9kR=6on zB+|9;Mpi<|o`{H*t6SCE$)zb;27Kr&#JdZUycx%dpeqL5JgT&CPm_(9FINOzUkykr0NvO`{cdwkrZ?-$hO|LpVJYG1CgN|U$zVQl64 z82bK?Q-u9n0KcvGBay3K0}+~#qft59^V*8$at*dFPVv0J*ceQ;9;U_UTB`lj5p|mn zspDWRVY_oTXaXC~T3tk9Zx(lN>qd8X7Cdl*$*_GNZ!q;2luP7l@Bt4qJSopp)k^Ek@a8gosaOJQ4w<$ZW1Rmt>R41|BjgRdrMDlXZ-aAJvJOf;CuU z2$!pLZzFZ=>3MSY5qt1)oVgeQdwAd+%Q!ah(~Idh=$SG89HgaA`?v1(c-Tl-=DJCp zl%<@@KvwQ7$1a=_*6euq_=muZHb5k|#6w(!)u3fK#XTBFtCSi_(te}hhI=!dlqA#8 zdCyI*MUf?{Bx{fcOn>1>QW%(QAUKVq(B*%i`U7Y%kXg}M)u>)L5eCf$VMh|93T07P zsde5>MAHAXH$_~a$MzNxTwM#u*5TO34_Z<4K6_pfPcs|W}u3J=g&u+LJ0^NBM#59uVlLby_Lwo-+xtq%KQxzP`c{FQ`qL%q{}1;-2)_jJAk&_3dMSpji@s zOP!R}v3{YJfh~lholul+Hr^=4Krjl4BN$Ka5)z3i(KZdd?B&WEUsq+&K&1>~>8VJ2 z=-~&AuCfd8O0(JI;cq>{*~LMc=@vA#l76+JaDQ)!_QM`o(=Q#S* zERK|rSb`4IVS%c&NbD?2jN!zCbTGa`;d43|u!dmAn0A)J$MGW|1k)g`8q_(wS0s(f zOR)+I1q6d)5L07jyvDa4@T7^QkaBMj9KMwk+5uBb@uu7MOC)(RVneeLTs6a0hCqhF zrC5bp0-Avo0kH;`2fp@=Ii9w&U~nj5$q7ah4xY_9cygInzkHCyIu0DLn3}zp{kLtr|M%wk%a62C%?Q$A?TGNQ7a8hlgQrd@)vBQ# zQnv0KqH2_Pyw&pePw(eff3@K3se;5pe?`ec!Btmg{KkJB;fuE|aO>wfP&go`(~g}3 z)kaEEaikSN#L}qA|5RP8+nO(l02y$x*rH1z8LUJP+0-Z+pi!@2HAjNSp-5th9S8xe zVRo*`pZ(RN{NJBy;dDPv`pB!`t!1K<^W}R_5fYCNTM1zguC$J6`C0z*3!md_cN{@F z70xdXL$aA9Pw^O9>dC_}n(oB;93gPmV+Z)w!Mhk6faTd5%dO3*t%FrUp7P-1o_il1 zWbIfV=g*$!-uoWl%$bvTjiFpW^Rruc{hL6NWfE86){hIH`0O~1!9|=~V#}6!e)09! zlG31XAnm}7*XHco8-sUSZNmfiEb`e~r>JB?9-3_0F~o2D`WogZ0*bP<(BZOOo~>IA zDvHSr-~1-L@4bPAMNl;iG}=7(ClX%xlY;LE7~!6~+T8kC4`flaDxUq<8rE(|aJj`M zLc62fdvC$~q>WZ>60Ik)EQU22qc{&PgfhFyf=|&L@KM-960P+l<-!>CZvZ`#w1*yg z_@0PdTtJMCer}ninKp6t6hlU67sNKmIN%$Nek{>%$f8mzOtCQEWW+al;Wd`yU!A6~ zgJ2C#GUhs#q)0h>y2X>nPtr1%AXy*Unq>R-b8Ou@h?s;kXCC6wCr;ocLyU6ix>Y>) z8Q0S{V0rbcm6@p)p)eGwQmNE2iLz=;x#>E?`+skcb_;9*jRx%517oX|m%hN$YPXon zEDsK5+;>or3KUgkRsaz+fnW?yK|+DS6A~^|NNr%QZ;)nvgrgk?MY*qp@$xR*f7?TRx?c9#La$4Vn<%76crcwQG8cvMEo+btxQANGFhr5LM||~ z!1FE_4m8I(cX|w|52NY`Rg2bR@X@WGILK{tPvKLC*9v2+#(B#x-N-%PSj*(eOR?E7 z5;{yxcKGJqlRV=Y{cOE-jD1g2w(m}vpIE|)P#;L?t6Ca^u&t*2r#IGk{!i90Hg;~V zSp#DuFnXXk+wl4K@-Iok2)U%NP=GQA#)y6OGrkAEjys%4Tl~F-;DpAYiS!J zF)+de`4oP{001BWNklJIT={6)Zuxe28XyK!^RnTaFsur9@y^o&IYEiaf z7~nHs_!bLG2Whvjj}<6mXf}nf-`a;;^4xHh;@ljcyY(>MttXX!3Y})x&S`dS8^#2f zm^jY-;t4A0Mq0%s?7Lv;5)vR?}?7 zrm?;%?AQ(K*TC!lJ#5=Cz}Zvt6h)Q953^;XVW`q!>$a3X{lF*_Gk}57e%O6^*M9PQ z`;q>$(0}^v#ZM)|il=4hDEYEMeH!g7tu6Br;_FA@%ot616`jNqw2Id(?iE#WW+TR| zjn8Y+c#nkA6EqoQnOAXa-ho|Gkr*P7dErtg{lvH^{WRta^yCkVAo|YpY6i(btK|6q((0fne?ync-i5FZ~Fiw`cC5haSEsM3qpQOj|5Lpq+byO-TD8 zcmWqHU?LzPkPxt$p%X&vq*0 z8Uy^}?c==jy{CBl+qUqvuM5BXhiym%AB1bJ?%>^Fo^it_zH$2m?|I(?oSPUW4=t|Q z*Wxpu_!$t->NN$|Tz!V8PM*dlv2xZb)^X_gM&ABg$GG>QX+ovJtd5afdkMNb!FwoL z4w@~*c4Fv-w@|OeP!W@2f`LK_HYZr6ZBj_9BneO`Y6L%MsO}Z2J1os{@Q*8D34-ZF zTO=1lm}>ngg;ShJ>_U>*YHCO^8VDxD#U6l32?D_u43122!?l;t-vDbBqk@%`Kx{27 zf?kwt*h3FJ^zg%hs-gsfgqSOY5>!jOtmu;&yu@&(qN{{aObVnBnx)FrX!IfVmc&?E zvokEuO#^Gt5PiNVlwxv;ypl3LKEnLDf>7~bQcg|Oc=N9xrPY_4@g6(ZccHFiq05{+?C#;Hf|R21S=dnnWIg}i`X(N0wI(E z5E7L-Dhau@s14Xklf9P(wr{9Xwcj25QGga8HF`v84?X-KPyx!1qlM$Ao1C8-!7_+- zWf2|06Kyn%i^Nl~0kxi>LN1jU2!v2*18YD~R2(V=Y7{ReAy~R`sKjn}HSzPGh_Yq_ zEKGWIDSAO0FH9{dcp>x|ybX|+V%D00j-o|O1;=NMtg~#{W;k+4nV(fiV&LdXP)*l9 zMFNBneWpdxZgHpEkw!_FCW;!5D?JoNgvGp%c4rJnKhDJ8^;9{1+VG99&2#pAgEWoB zrQm?9^d5D@pw#jZvPNLIFEDl95Y*rk0W-|G^P5<=S{QEhac)BJArgMnM!4s}6TI*J zk8#<~F^-%X!pSH>V%NbJZ=az5eJ6SQ+qQAnHv(V$a+TZ<;KfquuhDTwXtmdJ$9*l{ z{jR&1m>i~6Eb*e}5Axe@dpehHNEzyftM{GdsdJ|QOKK`OUniBVWX5vCb%tBNG#Dcc zI`KO6k7mp)PO^6EILXjF24z*fpW(qRhz#(ZxGxN&qQVgB#8s>;GV5<}+r3mGH2wbpjs}LlM%x(|_!34pGK(2ThqJ8o4 z*nk%ke>D*2G9?nWLorjyD4v4g0yvAP;p9Y<6O%2R z^GqxaG1~#D4@4z(wV#u79e(Y1PJ=y&lG1J_w3qiHNrpEWUJYv25^5Vz8U(T2`S?*D z_&>%mX+a2{PP~% zA>Q!D26#_mDvYjLjjcddRcv1@FjrFHo$nfAeqK>g>UG1&h_ZG~)afJ^CeH~YYaCzx zx{!#$+GVbPy5adhk&#v`xk6GEP969B?(fW_%^|e&<3I2BNYWm9=;3=q1XKFjv{44? z!v5Vg9(lM$vjw&<#WzD4Dr`^*n1)jA1K(6aTcb5m5kNB9t(31ne3p(5B9g|obau!9REkZ7)SXrFspyViP)AMKmrWGGl0)1V=Y<+2cGI5>&v|l*O#{ zn`yvMY6xeQxe0^jpkZ#U1>A!)hUk^R>@S^}vl7bk)mELyokH=_&O#~mJVjmxgR0)El%9fq5agA{D z1ROc+qqlT`EU9zXjg-T zQAhBK!IbtKP$uJH(x`?%oaJS2b(E0z4+MwzUc^pO+Xci#Z* z_BM=FND}UO@D#uNtGDsKcRrV9`%+Gv*vQoQZj7|}#vP~mz=sd;6F045*RIuk>@UB{ zAAj`kNYY_kp7ZjTUdey`&416@b;B&pwfN#!PS9?)KvFuzGS^-^$YQI>um6|-!PImM z69QY;j`G{T{qsEInU^6zmVUp9O0F5+>_n2Cc!6&nRDv&$+j~@$xnehS{_^s< zVgVqr@qKtx-mjvOsh18N?WYs2j{e}KU7AS@nhAyRq*);MGyKixALlcAgv47GbPqGS z6Oz41xRNZ);*LJXhd%lc^=ug}96PtI=VxDiJ=-^r;GH5Co;o?pnR89DY=C-0>Fdkb zvN>gNK#=bB4UX!1;XnUU%1dA4F{;!m1FYL%DG& zRL~^l8gehfJ*Uq9mzMsX@|jaPt}`GZIJ)Pae#8*ZUHjuY!q_ zuB4!0gz1SF@aKOvOSN_fA*{n>2Gx}F=Qr{0cOKyUFQoj+rTr{+u4jCH9b&iPb)LH) zc!crEuW)|iS(xf5YT^Q{eJH@m7UrfF+CKuPS0hVnV^zE6z_wu36uMy*eryPgVuM8s zi-_P8hvH(`uu;4dd|MGwvSFbZQ0i-hwFfiIlBYeN&}Aj0OykZ?|?yGWc zhPVMXiqXJOe?e%cEQwiZudif6;=$LT+L&kEnzJm;_LJB(_>iC|u99%9vWpvkdMmAO z^>h1|JesAk1+Y>>`%@V7$h@L0MV){oNLJ(OeU{yq3Af$mn4NSawG^LZ?jIQC6pBm@xdrq+9@~bGkWoG`>oS*5(q!pHn2l(^9xSyGcVUp^;NWN;| z-0{Gz@9=E6>=-w^Gq7=dHIJRx8D&7~k@*hJ9>t9ccH3s8UP02>iJ)!47>f~)UMlnr zrkIW*1>_FqQHrG&VK6|aMx&?@w};?UgKrm+M6g6l7nL#x7eLC;XN~Rtk~3VJjK)-I zG>OIeU?BuHUZPB$7v^S(-cqWhDU1ykq@fer-Gf6s^fjQ7MZyvSqMm{N3O2QLlTAYi z^f67JPO%`v6tXS~94wF}kuVh{SO-jp6EzkVEhH9bu&)k{dSN0WB8st=>XrsJLci;ad z9(?Q|bCVkwpWcLT?82uBgisbWW7kN$Zry8I7UINTbV0k`m!S-`jYYW?i}I2{1qH{7 z8d)gq;RGNp6X4?kij+#yazhj!FI{iAsKOSzLd;`?5JDN0RO(;K&PP#O{+=l%)feW$ zprL$xJRT|EtA^5Y0MNvi$5fKRC|(UA7;+h*<@RG`H-h3#6_YfgC65?_t#W>$k1u|6 z0r3SI0&5>R%Tj(X*Y0cJd;nYH$iWtOf8#8K5rQ|2tx=4xoC z5*LOYhaQ-N!45P!`1OJ1Bw!J2N}O~nhF~&8B^JLsf)J37-~ucpo?=uO-esu=Lw?*5 zPHHrecQ&@!OIT?eq1zQH25be3!53h3fpr7Q72DTR5nDb~%k8gpx3fQ_8>fdJdg$Rh zQLk5c_A^)W@R6L4ePWyt8UT1KProstJ!kpG-H_Cjv}#C0RMQt#;l#2qb0lYJwuK+i zGKp0%ebCAV*mJ8e^c{O~b(r2b$?=py}aE z_YBRzFbuR0r-24z8)z>w$nD+6#*!t=##&0MDpjfWs;sK4+?QD1d-wk4kNYAsOUPgw zcMn#__nbPF8TsP9$QP0CzWcr3<&5&|GZ8C`2Jb-KIIT7mSwYcs_*Q|ffKUV7f-5pE z&v>FrjY778+k*EgjUwVRfAv+0EP|E>VscHuQ)A)$5byeT&oVO;LwkZwpqtJ$(5Dt* zvVosas8SZRfYcNtV4bDar}#0&W?&mi(J&M%o_sMUZ-ID2R1v(@H5)BHg0>)0irNS| z1ZihJT8=Zu24%}ob%g_)T3oZUwpNe}K|QMEXz)Fhk9NnGF1q;ELGa?4$y(%+BBZDn zJVIX|tY#kP2@bE=(A#5JUX)VdWGmKG!?6gb&}WI$=pIecz#STJz%bk3KbUc}Uf!8$aG zLwS+}g`%iIyajQ1N}E0F#MQ>KzBSdlnvJJueS0nMlTEPiD~8PWlt1^7249srALbDe z7#m^Kkfg%J%S+5H7%t76WqQt1sqZAWpedx|!sMQmpZFIk3yX7na0Ql@dvI!zqMzM6 z8vOV_^L+XX2_OBCM=A~#2U-IeU~J4$i5!;~g=RAcjVN>npZmgTVp~UxQ3?zuiSRmx z=DmF8a|=9m@FYu1{bYUzJ{v-!WsV#bPMv(59ixW*2kI=WR#{nTA*~9Y9^U_FkMgm~ zd8RKMK(!C`!u)cJPkv$<@8-DUW=mFhlDLdw`KCUZFZ{LQ%0)QKqfagKM;|b#t5aw% zK8k`8v{NS7Ika@5bjq)h z%e`uum#Q1~-*HitoM{*f%jLzj$cPR5SR;Gab*<|UclIB)4`gfkV;|ftDiWsKCIJan z{qW=*3KxX863Q(d!>A62V;MNVQ0Gq`c!rODZXV}7xm#gz&d^+*#F`o+p6KK%$7iP* zA6p>L+K9sH$|?(U3qgHKgTbL$?*Bf|-FK`Ii3hPPv@FMtH@JAdNg7p%V#m&%HSW82 zFE3_vNzyL5=;H5(0FenRg(|3V4D?yv^tvivKGER!e{ThEdr%vq)k61>lDlB3(6k^D zhjAV!7EOf9mkJ*E_!PG8*>?K~T7XLu=0=3o0f_nywk_0hr8xuY031;QKm0?MU3(+` z-`{Z@d9rNeGazhZV0aTZ-Wc)Ru?DA~i?LCJlA*bRYRJQLE;Lzcj4y5{iagg{TcN*C zdE`q4F7uegfQyjx19HzI=aH8 zxgOLQiU>0Cp@gZw&UCtkVmXIi4;0`GgX0F@r+oZ#^Gp`!*nGzpvhWIb?=`&kHIpo7%9kHorfAnt z%}|$zH~SD;kY5GFsz?1MuuIICok?QAq4)ws-RMlOvG!felJ6F+g5L zmUrO$<{7SAMm7mkvjxi-h#gLqqHQ5pn$}=@3~>!uDd%gp9Drj>3x}^MnrCI;U<7%B zwFV-kC~c2n(%K;?G-Qz`p0>$(?3s&9PQ>iqSzm8C4qIV~QQW#^uZu3a_|`y`LLF_N z0f9_Z=NTP`Yxa5`f3nHaY7A-^9DdZWsTKy5C^mSPBPKjL96USi6|pKuRvq$G|ys=N@y0zs*|evUQ} zP*SSmb^SR==h_t1sS<-vT={#4)^QY83eRW0bcUC_v|x65o~3q#tpq`Ck$MguUtnsk zm+hMpe&(n9=o^ARe79%rvM2IwhKDcl9j_WxzB4YD$gp|CPz+(uxXy5#GJKFHv&N)AEc9|y* zPjPuJ=joGsSoW{PrX%E;LyJ=IvBq3(U_3Xzr_bX^*+@h_A06RlNlI$TeCozc%l%8a z?fRnN-+JImLR2;!9$8PKSw9@>&)QEQK*HWFg)2c948OD!*%+C?2q2+|4oe&MC$R;rTEm&zY9ItTa zJ(gN;os=GCPJfZ}Qv<|92Qc1p<2AyY-UM5Bz>nTA$@cvV{N%rQj-`eD6opXjiAk(* z_0EW&{fSXN^Vbm{`&fZ*r)aUt*ytQT`!6SX_j_|5xM%|5n*mV|wpwL;vvSWX4d>4( zfBks}S&YvW*{s}qn{vkv_~7T;eAOpN6l{W%+dvw^>;)lL&`NOAN`v5w%YqHk$2sYs zA!}s#wk0wVzU8STLQ;WNq4+{5a)n4x5nK$WYN^&z=KHqs!1*@27d*R7N3j*042C2` z$#ka>U3Br^1%l9*)<}~ahsPP=hUY6AvFlT;{HKJ&r&h`R2t~V}JTrldHDynOY8c!_f-|vvH^ms#yDQ#XRIV&y z>X4G_j`rs#i#0)6`XV34y6B>dZ!-wO;D9hV;Mr*mg(|*OHbmC&j_>Q^ z*s+W=$2`~?1r`?xYC$`bhfWBZgT)1UjFtf<1 z))McYo?+o!g&%qAOZfD|D?EA3qE$zP;i_wLMmJ|HtR@VNCA|FhDu49*+bOh4*376^ zwsQ4eVQ|3lQ~zw7{rlnYp&1sJ2S6-aM;naPl%Id6;Rk*w=ED!n@W;Qmic~k@TTSXc z4c_{e3636BPM&DdT21log2~+(KYC}%Zh?LGrOXaS0aQM9PxswG)Pbjf5 zL^Xp}1(PV=dkQP~AwxP*CsrUcNFf*jhY%aZJ8(^d_hq34;Kb8%4(BVJCt)GWaCwHB z7*kpeLnYvgJBzG~F8+sO&E_i%_C|d7T~(^RRgOH@W~J$w7%-eVwMf(x(JL13p})7y z%MPU6yl0fhj^$jK%P=VEBKVb<`d|b}j3zl(Up+z+uOh~fR6-0>wH9NohQd)tP@Id> zUlXnxXfWKfL?)A4pv^CqG9IdJXpI@=mC*kjnacb;b-ZBfW33Lmb^7tR)J-QpM> zTIJk@UgE@}Z5Zf>TW&L)J>TN!8O6jY;P8^ORwB1{c`3gr-Dy`ev#&X!{Tj6uh#yaf z#M1J7V#9ZxqQBq(a3~Q?8KB`(5}Q(pl8Zr%f)SQihWWieJWOgAdF8z~@$|_R7D=#! zmZ&F2Qp5D+CTY#{`A5#Otec7Y2dJ1PKXAY06?Z3W8ui?AU5f`FT*7B{#8@glF`Gt& z&7;aszGIZT?@D;!0r=>Hf9a9E z^E1b|d~OR!0(Op@Z>jM;udlH*-{gx8FlmC?gu>?JLK$taQMUQbLrPI;=6jf4+Qaf{ z3yln7Ewx_A3JGK>Wz@mid$fUU+{in2VlGv~d=Sri-plj0-LN~^Ah7(~a~)lO{__dW zE4JwnlATRDd8HeFVO~%<`obsYd58Q)q3eVwJ}e@r>AalqchcctmGU!h!Up1fh(B0+ zy&K{ze7S8&I(NjXYCK*doFB%^1ci%edlSw~r!&oiibtfz@#*>XRqq!mx+G~AU3Bqx zqnuP3q0BY{8w*;7Z`;Z+c`}cU!FwrltV0W?8WSe82CycCm>UDRfw>6AR-ms6i$kzN z2)`~2WKE)|jf~gH$nh1AT099TAqH!Gc%R5oEzM(8pRSgTcC?3G}D{%_D=)B+F4}uv8AXg7h}su zXNQ^lt5ZxJz03{U$GG&mN|) zvWHxt85@cUA*;Etp`kuDSYN}(2I;f3%96a)NBHF``AliIj1r=rgo+J!`i=Prf1yUJ zIl_^Ago-;(lM6gObq6iuFs_NJ=Q9tTV1D5YKl6?QY}>SnTE$QwoagkJBiKTiUMc9Q zZ=-);E7n?WyAl564@a0?g4m8QQ5|OY4q+*uW;I))QoBT@TBX)A#FhgsZobnoJ`OLr zIpXCv_tDIt+FyZqf~#Xse+%Qzm=n>BU}OFrpA#|XSjAp zg)uYD@pG#n0~|cw!=7ulbL~w%JUeA@El?@AyintN-uO~xq>t9Bu&o#R2Zgaw$I!U2 zxEe}nPER!%Gt0d3jhi^%tdJM5qfZ$g5H^iO?Aj$nRYMfPft|vxisuWX%bd7aAXuD- zrIjX|`f~<*&T+ER(KmObfzSBe7J_I26gBf8LA34 z*z84R?dNOW=#E5gjUUs}d{E9&iZUb9E2b*MRnHAOc60Zgo=-f~B9jvj-Lz^cSS6?6y$?QtNeW)`+Lv(hVuOZRB&zijM@uXfGdz7Lp&oDLp}&5D zBZo422VaVdVqST--RvE_HykthRI1dun$rU4QCkH0)s>FuYaMRAN~^6X16iWc%Tf?``q;;{{YAOti}WeJMM)3;*`t^t1TSp=H2TuV&9)hbgb!--<=9 zPR^&6JYJ!SYJ_IO@TB4O-vf_*$#Li@1!Dtg*Lk0yY_!*MPE(TCrhNZ8g99$P@uDR@0zUI~&&*p}c zy5R}sITA79_?=%+%V+^3ATIpE}bAo#Xh) zBmBhMMtSUY0vP5FFs3bMlk6Zzxsa*=cW>35t54K|NNyYTPAayU**Et zV;p*KYu#ZDq=Mo=Pk(M1)(503Oo>G(nRD+hedEih4$SsEL{shsD?^j8o2n6c}fr zQQ(`)XyQ?m0Wp{=q*acb^BnttqnTAvYeELKcrGpv@Z|BFKYidBC!RaVEAM?7@B5JO zXCD^QD5lwj?|zN&YyS&WlO{_mOB_3XnAw?C5;2_c4v7zN{7i-a@H@vjGdqr*+{*Cq zIez)y4Rgm`6Vzf)Z)6y{$>RWwAvTq@^O8J2JI=zSfg#|hcfw7*G4FW>&b5>Z5d#gl zI)$;V@VQJirC}5!#D#;nDnTEL=oz2X;Dy!Y&kv`G+dQWTpr=#${cr39p>iU z6KtBOuz&BCEArVySZfu&VmjEhFm%zy*N^f~z4K>Nvab>s9@{@!kOrJwC8>%p$!wxgsMx!V+blX)Y3sS()<#wjgdK{dguAv17(X_CV;j#oG(jw+~B$Rnj` zYrOxHO^zNp$}jxnIEPMbXH`9>*WwIZUcA5~kDg#+bT_x&IgYh(>y4gUZ!$EOS8*ub z3%zMX|3u23-Abz^qzR$x0WdzIURQqgm-muoDJyvk>;S!WL%XrW@#D{MY3c&bRw*p( z+1YEZV&K_Ihkc%TJimr)e_3I%@HetRpc+8ZG2aXQm zyB2TZbB3#zxPEV)M-B=rt2M|i13iZRAviOghj=`(> zW-EiXLdSCBVtnp{r{4);gxuB1v)w#3)6u#hr z2Or{zqb;I1!e?!EZyDg9{@6>Yr;2gGpWrZS3!kYC4UVDK$%FyLftrY0YQj&wyw2^H zJxj46$$EIHZF6m1xv^gu8x}SX!1;6V)h`*QB9ID1nc~`tS0Ap{Nm#u%HA`Lv7b#RM zVwGlPlH;qEMdMgn^$hle7uI>#I+lHTk=rA>=%R~nKdfmxRB_^1$}LMe7@BcSXnaLI z)(H?%h~lF#u_~;iXtfcaVq$~CV+RcJmV}5R=Dmru1c zlRLaolu@Q;D!lhEPV?lG&$4OjewN#NxV*9}Oy-R6>Bm<1SO5E0`To}pW0NI*<3D|x z%a?no7@=Jhywi>`K6n$e%R9Nex(RHBx$G?O`M{I>)uT0Dci#@a^RCUHf>kzH+MjoR zbbbDWKnm;-#f}Ku?t$rY>YD;XZK$Tg$WGz$!^)FS!jmU*GFxD6LLt7)f)gaML}GC* z#gl^;V4^aotjamvMRT#n^yTw>_Q=z`_LVzX-cqpCo+zpsj3F$ zOLw^GqKj_`9d2cDuEoKpPBB|-Vzs&%)YELYnSG)N>Tgoe3M1imNc~6IR-u)6Y(E?A#oUxK6e1c>A@zY|5)diKpp2?X1qM>7|i5 zrkf6*OcB~yjiOZ&Q<^~*0ZF*`H;RcBF&c`AI!eFJi7|l;>g{i^Ye&M9Uul5^m18r!- z*C(7mTd=%rQ6q>Mr%^zmf-wnDL5+}04?e$&Bj+5y{s*Tye{nYr(}Oiif%26@D;#~| z5S5-)_Fi`n1A_^Nj?D2VA2>*>*+v8=hI@JI8}@Qt|1jzWmp55y2NF>mmL#B?ev3~YUj(kg*A1N*0H|~dj`}44} zBt$Co)&rUQ<%d>4sz}s}I1P$l*+AThtd0BOEtWEulTy`b)@Cs(W$V@&C;5Dfys+j+ zU(2T5pb`x`p<|^FguAX={IA%wGwUr2!8#509m2LV7_S}oil?pZvou!X|K6c+19AWS zeXS{@pZC4j@EPwYM@!Xda39)EgYp$m!L9!-85~u!KwlgaivjIHT~1$5lf75fIXjz` z3(X!(9BxkR`g!`FA#$fnl6KKW7vC_}$TkCaUf07lSM~76f2n-sU{2d5p)5Cok}C{J zKpOJoaA8ojNsO;Swa-x74!WGsy5vAw5Q9_8NX2m1>uan$0}p*FOx~iR%3^Cbj~rnoiY9Np|7CpmzfJMTW4EBa1ITL5^*0ajeczj~xzB-()@(niY#3R+$C{}8 zHbN{|3JjK;EnGLDK!KptsRB^*j_*tjuect*G%9>>6+SZKm@U8=gU^c~CQTI*k4qz@ z3cj9$O`u%4r7grRrd23;VsL;Fk12DQEZqvHF1qOAA1Brpb3~|PsC&=$(JE8(o~#g@ z4HE!U=9Q^Yd_*}}NgZ$KG#N!521jj?xsthY3)<5c%|8qnpD#N|G)?+C>-t0Qh!HoDUKC^1`4JR?m$m z1PvSTL2bF(N@z8ES@m^tu_ST0o-~%iwFM)1V`v#+MPVr&=4@?<6+6Okx`3%#Dru7< z5(*3$C2|lImc?R}qwzTHo>6M<5|?7j%xunQ&kWKq6Zm{9x7=7|{F*xYL=GLRZqY|x z+)5Is45Tg2sh}FIb3BD$tOsAPMn{xfkVtu*Dlu~lM;~XO zYcso8M?}FY;w_R3&RK|KupYse*FDNIr}AJ%nQyoG)EAbxZik_Nu;AjdAx{&MenYzu z26vBg%iTjvP6+S#Ud!dFHXnVsi4bGNQ5VBNU&8mjWh+Hb#AiO8qc);q`e^3+c;xUZ zwcd>0iIm1l3@W&ICo80U@Kc}U#HnB9r+?ypj?Z1gyWX=ETnz-aY&A@7gQPag=y07c zJ^VDE`1r%LGf!i+$;~%i!~Ng?9sJk7nCDYpycVt0&{od%x766NyUwb6DKo|0So%rj z2$|o3cjjBp{0K17r;PU%rFbTy09F=+!K%fW94Cs}HfUKY>uvdFd(;H=qlh47aZ&iV zODWovGIO(3lCIeq2@wr!m~d`*O&xDThj1;Q5XeJQ{_ChSweu_q#IFQZtML|mf*K#3 zkJ2IQH`*vR4BC3d3s{R3{riW)7f_O}307Z7soL3T=l^nJBkR9Qr)0`NC)czR2h&Ji z2y`Vb9Kxu zw+gR&1zgzDWco~lvzG>FEk-!4ppqgIqnMD7s$o^q>oCVI96--!42)D681_tE0#{fh z?PK;*%zymNV=S-K$o(Y5Rj|D*9*uqY zU7f@9ly(pw@@XV;%uLU4{8+(4P1wC-62z=oH(%uASr=V&@uEP&)mxNb`-K|6^cyXX z94$g_iOG>P6bK0#oRtpn1~S2@Vk-tym5|(0QCu!mDp1LU#aV$B53#|f!I|beHuG|J zt|Fmx&{>N@;EIxadwsS zj59VdfNdu%%z{a(n50UoP_KZ+5s6)Q2!0KO<*v?xTv(_SuT;#&Cz-W*Q4Py>1K)o$ zG*&EAhuWMkB#e3ZQWYX0c_0Nb1``=1@@OQu$lyfKIH8%QWU=RhnPrPzCQaHXO6F6} zyEz)!JY&%Wi>)TxvH|*Q!`LY4F3ok(#Wx5om2k(-EpqIlQcxq*h?n=DnS}dm=fHXT z`(vurjJeqr)KpOKP|X<`jF?*yobS}WDY+=l3BHKPOpG&CU3cNhj#N0Y3V>aibMR`acknrsrUGMG$MC@PYg)Ey^9z)Yz0ujbYyP{xg`GGSir#sCpu+rov`wdAB7+X3nG-TsyNvelv2;cd&zsAa@@_cln zBSd9GJk3Tfw8M<(GGfix`x48nP%AhDOYZhyqwav#S}#0V{n zS*BJS3G}k}AdbX3#0PRzd;(Z(Y}m5dFhA>&Wet{QRa|d{Tp~2__?ktrL^V$m&$DmX zaMS1jcfO*+&Mj5`kKb|m4Z#1l}mFAI9EmEDwykO7{z&ySBq~s6vgC<`t`wlZIP}Vw4Oh? z4J(eN^Fd&}p)ss_s+Tn@1{!jAoOg^_i%(#41Oo%gYzE#0EoiuBlrT7{!>YmJ$S6=r z5aVb^o`V;c`1kKQ%z-_F{K$9ruy?$_YqRg7i!Q!xpbCSL=k`68fBHtthaVH3yx?j3 z2%A`n49J1pBQE4_X{tm$f~^Ue2n7&{;ulwOO;7BEJd45v9fyfxOd{lYP&BQF-w9~O z&Ks4;Jx|gNLmso6A zBsO>|nA$$xdcR@*@+yD$dj-pm}~F_DJ0$z0BAv4qD{wLPSg z&=c42D06OwX1+?SIqjm&LaUB#3{r7zpc05>BorlD#Y6^8l*|GZ35qO0R6|UT@px}h z=V`Ut_}pV@W7MI*N-DI6l^J)2smm9*!EI%?*+**n7_9XYZ7}9tLG*UfMHg20cRkQJV0X7Q$s;qV2y%bC6$lT=c~gwi*O;llZx-J_P> zJC}L#T!hAb5DUxAjDv?~x#xz6t&@(U=d>hv6~tjpg2XAl@Tdf9^I*Rx9TG0i5f*Y( z$uk%kHSD`uuolo715qDGj!pCGSM>AHW0#peH;ATHq+KwwL-?WlWB&3(ZDyY__&5o+ zVXvq$YXpxVh{UY;A&$*A`N+d_v_#11#gkyFaOv_Azw{qIP5l?IrCPa_tZ+n0jI#z? zfn&$c^W2e?8?K+=wJ(dI zw_qfuErVq0ajiB&1V$+oE==!au&2Soiep7~uw=)`O$^quEQY2wS!yn#c^i#tkUNUZ zkX8*lcJ_1oazvZ}Zh(Q_N+1OPM|_SIs#Un}RW-KmuQ5FX|K*S2nIkR`gi-0_5JKMq zrW|*IBf^-CB9xA5x~yT}_^=A(f>w^d^@8{l6KKW7vC7P^PiS>0s(Oh?oR2st&JXPQ)yKw z7D2LdfGElff0l=fca#7HzU`@Ch$_l*l7(Pwv8-nB_@n1})zyyiS6|1><;y(r*@wty z28g0tDX4%5>I=r|bNtj>hp1H}e*Jfrcw(gwjVuZ0xpnU_wSi$?{|4cyr-XASz#4;d z!q(9iZ+m;nBTvSB{L_%2v@BRJRFjx{?z#mxSfdgNSq6J|L8Yg(fNVS;(izq}OME#Z zDc}$ZmJ*N0U~nkbfmp~j2yMeNJcS5?XSr>dTFO{bPnK3tQM{9o%c=%rz!!>hJ}9XY z3sz7mXhbQ82lsQdzK7Mp3f~#k*iUFi?4pYhN=KiD7h=BcDuZ=MjZd z@_CRgPrwr&YygNY)p*+Ah|&Hw-)07*naRByQE zszLt!&-L?>&pF=p0hpdMcok9$*X@EWccff64K@jrGpoYZ9nTYod`$$yVWEyWS>@5y zuaes)5D_W(sLgJH9z$hLx!w^%b;EZEtFz2z>3C>+=veRs5@Alo8%rj7_ z5n;LnX%}654RolEScDaXLvx;)+7Owof)`ShZSDd+dB#bznJh}ttiV;hIT{B?tp@}sq^4tigyLpl=t-BBc_*m`&!=p8Q78?rtMRj ziQui_g(~$}~6MFh;R@nP(pUD#hi5TJ=_%TI1TQ2f5=0!&T$(EANbW_>qkN z>vv|Dn;%4M6=NfEgwbKkcYSx2r;Z5c&VV;9j4KeUv=o{e)Q%AaMdI;MgkX8aowtw- zR!OShRt^5P>c<8D`PFHo+MGM720iw^I*g>I0SdS+;H@; z=g`3d6M-1TmRzbx2pUV$AiOS$5b5J{VfQt#V+VZZV+1zLDN*et-}$PT#~<%!c43gD zzed|RT1}771;nluM6JtHDcvZnTiZJd){W}XG60}+?p4YdI?9E~j^ecw0|1>ZH(Vsj zo!YWMs*_=Q1%c~H6ENP;Rted;&aiLi82fj}oPWe4-rx|t&#{rG-W$_!mc%O6)N%cF zRrcJTqJ<&$N)#1*?;B$FY=yWD)tDgmd6A<_l6KKW7heZFVdz@V6Y8`PI#&=y79YVv z-liR=r~{X35Kp>rBNm$WB5)Spu^RYQ_cq!Om97Bq*vLzS$OLkhIrZK1SilNZ{h06h>7jO{$IBI`nw7~JP-9K zB5!-fhg;lxONCnw^s;Y@g937AxZ#>G0KDU$O!DR|%qP_g)e4Lcuwhm4%JZ`xJ`e#b zK#k6ZS4<4cI2|hxbT|$}#O&Mxj~}_f(Z*)Jv;d7XK}~t;98d^~3CTQhf+PktWn*V2 zu$+ihTfvIqf*Mwf(AxO*O~SkAqKhv6|3zp1k>!qs)r?0^U*c~LEwfnc3KM3hXe`*O zfCbHin;|#gmmJ0m%zLz>jMCCtZU`1REkG=J1cfLjHb~o}t@8MVkknERKDUJbi)9WT z@rbQ3*xTf;duzP@p3O}58s7QC;0mRkgR{bT9Y*^to=`KO?^6!5WI9&as&md-i#xmcX)NMDfni zU&-OsVw&2*wCr1%nXf9%}`kDBgtTauYfBjV)pti#$6!g15Dx zboGWfRibK+iGJzXdNNiD0>43AS7GNj%{FfVyHm51lK1dXg;*2Hk zo8ZAmPcymYB0I(x_=ER9#Z3DyD*Y+V9CqALVc&rk}&6PzwO?8 z&M$wQ*F6Igl;s4VAo6|x>bc$1_q~4a-E+_P_g%)eK$?0|Y~-ZT*9kn{ioJj#W@BFu zi%`=NodQ1lla7ynWQcRqmjC%5doG>wgv5b!7|9XI2_ls1DO)BC3sZq^*I>k>u7ae*8gr;bfWTo*RIq z3@sR+Fg*An;nkOwQb{PRGE@!h+-`aB-Yxv%-!D@LTwQbg)<5ZT@wE^M{z4%&yh9Dk8h7l+z0R{c7$sNNSxY2R^>^f~tNvN=Ee3*OQ zvxRrvU8mVG7#UJ}sEG`q^J$hrZ+J&kfn5%O}ybVX=DULoY3WL z;ibz1JbfW$VysQKc8s-fE2^c)N9Mx7V9H1Svu*6%Zy6gGe*R}`gshis<7*6-AgMve zDj)x-<%T^%ImAu%w!v-e+h!OZg4=Jh6mieWwh72{aEWK~yB7TK-{#i~AxC;&*Egqz z*Z!YkH!?}-IWZJe9D?%HQ?Kx^9y-mXEoDyRlLRYq^l76~lteHl7H#ypOJcs#Mg%}% zz$NjQw?W2!A{&pZ<)4D~$6EB_Nt0(7pWqk{wWRM)B5Yz>H0&NvC z6D^v-1jvMvCUo*fET~WuHx(M#C;&kmrj+2bxY_YURVN!3J%QWaRcGHW!#5reEUk}V z2Q1^mtNgu>4fA8~fkqXKRZx#gw6n#{VQjqLItD-gNl-C#J4&qt&I#4JGTcxy3a&P1 zSz2A@%9=9QO=;BXq%OsqK-YI@ciS;vO$@88Rc4DBmg;S;mb)yL+NkkVyeAOIZIh*H zTv((>f_h@yO`;htgBV1?TP1TtTxM7Qi8VQ-=v7`;JpsN7zgWWw5$8b z1LQtKMJZGXA>sK;yLtF2;ep$rUA>hhJ%-T~sTRC+afLtl(^vV$Pu#@$OYr0?En3yx zSesF;EpzLUA$CrbSYEo!BM+bD^7&&VhVLft?m>;K&Y3s~ttZX&M+G z25Z`ElM=F7)4EZ3biJVCt=I6|H#ma=PN1H^EeC|0!0l={^-|#KR6?_Bc>FssKNr=C zA>Gn)pLKld?>TA} z__HstEc;~IcKmBbXb>P#KM&))64d!ee zFq=cwnRd$4_c>nMt(2UwwwUwG@g`kgL7bo&-1;uzz#icbexE3b?XAD5HNEK7c!MG8 zqH5a&4E|aVRfuZtxQ>QMkg9<3k?akSlmd-G%i@gogsMVfTfFz3@Zw3!saH}o379a= zz8wulCM&EL@!rFBEeG}~$Bqbl4mN1#P;)~h=1y)ooG@13coi0E>}S#XBZVBntjJ8sw;NDy+sRpaeImx5Fc zL1Iw%{kJL)+*Tk#P%)Ho(e9orLyeeOlh~*nbqS#MuPo8{UVJy9D&O~e*A8!3HUdkb z!tr7s%iU3ewQ*4m3T9(ripr@C^M!`^Iz&dfM+jKyIWIh7Ei3D7ltx^i|B8pvM<0Fk z@pgbn+$1ci@N6gLQL~jxgA;hMNV6C5vXL>S0dEYbM5T<2O2|+EIk6$xgt*b@WkQQJ zvA4(se7jd3VFgNp1khC3zE}9*9T{g%%rV=Zq;PSwtF)-ss=e}yNVxW{%mACAD!DI$?fuKH?AJTiSWhiVxH!0|p zgxq*Q>6p+PI0_iu%$}CsnpcS6F^DU3sa;~p1d_VPszt?6Y*_Vdj|5eEa<%}HVw{T` zJW+ynK@yr-hi2g!6-N?;PS5RNHvR%Vk~W%1Jk4@O?$((tw>h0JG7_pB>+I&{$_)(q z28hF%^au9->Z6ahEv_4Sw_9CWtqvgxy`rPQ?)@p3XFb#TFs4>Qfq`1!9s3h5UR5#^ zNAdJ5>=-3zKs64MK(HoIE`u=}e&k5N8UbfbF9$M4au^YkM6fnTLzhs5I0X^Qa6=d$ z@HFQQK@Dh`>FFl#eeYH#wkpeu1(f1oe{reJsWX?j`>shIdiWgQIX;4$_;xB z&wi`R+EN}fNQ1C$N;s=jjnGw32!=vZq@41dmoKtDJxjB_6)`dUSqYrJ==j6g2@c$l zGP5*Kt6Pv6B`*oj%#`?@FU+AhDkEin_lrX;bbw(c*J<`1T;h&9w^6AzIDfjymmWGx ztLgF9Q?9o7$b)-0cJqNv1?T3z<85-U|J}M$6D%q4oBy?=Y+!a7e)+$LFMrvRRB9k| zY;T<7-TMZa|4_m!2LegmQsh-`K59622!8X|Mk%Zz%N!MUvoLjq7ry#5neP&0l(pI0 z_{hh%Ff^Rd4KP&R&5@&)qsK=1sh*Q$+&KM0tTVnE1-%S)s(?R`OVKo zR?rzZbEe=Q{>B=ouhdD6Ax{D$BL#Q8JK@R<7#oYHmgeErSD>>NV$4HGF#&|QZU-$# zmA4u;nD`)y`oQFFXw(d6&%`(&d|=0r=Uw+C{JTFh{GAUA>#L9yhOq${8G>>>W~9bvRKh7}9z{*pOO5UKyoatGc*Cx$A42p= z(mwj=t`VR3nh)um?4c5$(B@ZxleZ#2-ZVmy#bPnaVZulPK+=}J{LCyq9O z;1uzSa~@LzZ9&KlK@>FS`4h7Y7AvS3!dmcj5$6bE&_oEvZbrhm-bFjtKuH`(RQS{c z3IYxT#*(X#KkES_*v-&;3ot)z0yr)@sECpHULg6qHV^o4F8vG{788q7CG8brvg8AhI)>$P_ zGBTgxJ3?cqMmuTqYWF|BN7#<0;p1S1EW>LExXpadM2k}5Ss|+mtoNa zl6nO+HjO(?SX``e;#9`{_XPHAZF2nO0dfqK4DFT>+8IZ8<(xQcP~#{NPA&-B*OZ-O z%EhS`T~o&xgGx#WmOKdF2fQt_%znQ3%?^iM9c>(-$rv56JUe%RM~(}3@9xkcqf>J@ z5tf|e|2e+Q-o1u>lVv{r!8X%Z*O^@$!{kcn1a8=6`0P)BU2gK!2}9P6+02<&4(;yn zu@4OL(6>Ctp8-;b5?EfZabkIpZZd&bgQw{6-VJ6t4gT4mtYTVCnneR|0>LJ9rOHc} z7x?xIOAPPc&#FB{k%CPWYb@XV&J4x+B|iP*w{msf@~KUDAweg=a8hRG_p0aoY z3fGE=H;(D+|NY(XsUHP`6y79~^f!LvH@I}^((8`hd+)t`?sK1eGk*OW;!9up5`XxI zfB3p%x88ayzy9mL{+6BdM;Xh@%ly(W{nG1>J@CK-eD<@S{Tq5jef(e%vw7mwS@_ON zXL$ILXCZBnNg!lh){efHA{j>L;=O=zsEzbuNQf$aqZI1#8m*Jbuz=0!PUWQK6p;dh z#kPTsCq;Kc4JZ8 zXdeX7fEYo8rzaI+V=fyFNgKPtH->(n?|t|2jeqyFPatt&?i5NP7O&C^0oP572BK_w z>;)j;Qimx!@E&6Wh3ne1}M3hi@mWi5FyuqcOZ3#c7fKl zj4veT@@(LW*~a#5B@Pco>)GC_VasqO7C$7)a%YLWXw&Vq>G+)Wb{o=^4mk_iD(#9g zQ<-HcS%9iVF%+FZuuu$ma?{I64RJ6RdTLlh=oKOfMtZA72p~DudaN3ZT0~4NPtmx( z>Bgq72ZN)tT5#%>X}YZu=I55cHBb?}2j{vRI9y_6Ot^T}bKxqa&X52W6CJk_@YaJ3 znBeffz=UYA%_Z-xPqwG*jf9J6+&yW}ttbYJDo`LH$0sEgT!)rUadmx-$>kAl$XZM` z#%UyjID2hdvOyAmzaeBFef%(CgLqH{u_;-u6h5FG&+zuZ!TpBwXL>pF3IwH|=1dL- zp7);6HsCB2%FbOCwv2Z0UfC=bRR}>qV;N42=7^sxYlXBT7-PT~j1`ubmzbN)x#{3` zYENb~3lBD--3f$s*jt;Yt}T{|3c)Ii(%`jLnTcJNSC4lPNlDbv(VZ-`A$5-T-F=X+ zJ#AQ6afkyYr$&>3qJs$~3R6a{Fsl=snDV@9zjArj^V)2@i&sfNESV26!_gYF@VxSB z#=uw+$>ZShCS^6<#TTAh=G7NpX1Y}&OG|X|w6wxQrxPZhUFR2u3U1vo&$ikH7T2m+ zZBQAo9GY<4vqw1e>!bX4|GdLrd^rP65MMA>Tj0kZ7{-@`)ph0SWx;0-AGXjm!xWm( z&4DZ+CBfK&A}G(DPB5|uqk`a~GY(K&;cL%Mlf5)eJM0E;Fg9Ri3#X=TW_9Tt_uQSZ zR+->ZdVeH`O-jNg{_P`Q%hVJ>3B(43-0v!wEGRU{*fHs@X;*U1M&3 zj;}uS9G6bDkZhJaj~!s=yKajP#NH$5Wyj_P{4TA^g$5DL8dPP?zJ{ud!!foSg@^aOJ}Z-8MK6H|&A;z8gOLK)m%S zCy=d7FfjzBvc`KPiTUOd$EUAT7GJNC+31DpT>`#`4g66dLH}cTQ%KVL@4x?h2+OCQ zdWz3{<};K^Z%yXVqmMrNJ;&bv{`bEn=jx-6A8o`Nvam@wDvP=0tMd(3l1VUSL><|= z25Tdr>ke%ZH?BrewMb%mO?Ux9h6aZgFi~2iRw0^#lqg zccdJcFbofuz}uK<(^rx9(MKO|bF8$QymILrr>5q~N{0#F#o`Q6H0k-lOwZ4q7;wEo zmg$m@wHewr#Dn9OwL9VSYnGWS#Oq&AE)lQ$vbhTo1uYc18+m{VYDm&Lx80$<`;KWU z1R6dd)p=%?2dE7S3p&foty3(d>tv>&D}lmT3JFk+xv9;hNs;Eg0V4z(5G-CcJPOwy zQ_pR;5y`rVo}eYBUaR26;w3?F7h``-8VE?|8|S>b35>M6r{joz}jAxnt%tB8b)@f43CuwW$<{6kL!^!F#|CYyC!C3 z>&A16YpU&Ku^F+bg(iWl-eE1wGSgb(CU&w{w=-55rBo?nH%J_=vyk@D#}754bI2GN z7)-hE{rfoQ%e2+7cT_mMMfl6$!Mpf*S4*vA*fDOn`HTZDKzwXv$%}$cr%SzFqEsrP>Yk_;FNrW*TF06estyfMXwLGw z;lX=5oP7FKW;*-ub^u=_%q|P7YjEV|L3Zu$u=sp|^NJDS+*ymMSJ*P%U}_4IG$HRo zzB0vu9SJ8d<-B&aOt7w}awQg-CcRr?U_BR(uP8cLLsw#4fVzYW%?fKP<7jDs;Cikz zQr0?wfBEndmD(0=9H?W{5@ty8R@hx#G;_TBeLI;NANN8LJAv z`V)@9q~IU@ZkN?oikO5#QUb7d4{Y0>a^XV3)O0tx)RL6oO9TmMFue(q$J+tUwDyv( zRM@f4Ff?R1c|6B^$lMn4qzOq%mOB|N%+Kv5An)5!$0}FAsOCI;+J^m&Vu_tnviLVB+*%tyTA)C zPGeh3tcM*m?J&8dG=0j{bL%88fDOa^OsC3$o1r0X@(>3FUw!mNR+b>imBJe)5A3HH zO8B+kS*F=62-Z@TEBwrlwK%z0=B4#XoT)O{Epz&0o3H)F)3{0pkKx8WxcEEB z)T6YhC6<9om6i??@K6p|NwEd&*d;u8x2LKepE+C_cV(MYplYu{v$ylyBndavq1S8% zvaw55*sSc+>vyVe-HIY26bhwM4MQ72Nd{aqmH+@C07*naR3u|(Bcq)QQ*GO8v5&-n zEeq-#g)4fkn@Lo_iXh(NgXg_BT7K$S!p+1uK7#EPZM|hrqmMrN=;Qx4<~xDExZLG} z8v&Qb@;ddAB{T(+IE?fxZCO;2s`XG2d>)v;*kx$Uapf5l(j%I*gBN*zz4Q6oUE`Ernpj@XD(ewMG0c? zCW*=tBN(4ks0TF|mAEmMUg3i3rs5=)wM4C?Zm^^qh5?bd4jB_wM`{RS31VYQuEepW zuuU6v^(Q;){cTyK@IhRz>ZxRc0jqfaEhzVjH?Ty;3n}B6`;BIJr|Ra-%@82L}l2k)bgznxG8r*O-mF@EL1IREDpD;&R^($<7;KG9@y z$Z_;11Vb0mf*p0sST*Otca^ad!lS1=OS$F5RnO9y4!aK@;8UiKTBTHi`|b+V@~G}k zQgEqIN-Rl95Tg`%f%*bTOiy{L)arH0l>ki(3VAo9xwyhzH#L}?NSK-N2o4p4HL!nc zi%RJ%dA<#wHn2`uY8K4RGb1ZBaRO zcAmorMmRg;xiX)lnu1rvf~LKKssLWfEQ(_wF{Cb#<#`lpq$QTjb~YwY8sZ)%1X%W4 zdG<_#n+SAdki2B^*0a!E=i$G+!j8eMeEfj}eDD@!>-GVzwlfk8!)}-&3v4y;-otR^ z6DeQ*hH(B;ELzoExcRX1>7O+G+dr{9^dF!ILLfQ<#9H2Smtka}%_EPl(Oj>g>2{$qbd{O2DroV{A`)QMGE-Go&=N;jzy!qBEV@a>!z z8Haub={XadMarWubUAUNi7~x0s_iSRbu0^d8>t+He4gj0S6KLJo6A!HwFbPU<&|$d zzf3s@ZCfTJ1zlrMx1FX&g|Q6<4?n-g+W-C{gS9r>#_GKD_FX*u=oF7WzC^{Q813-E zk2To)?wdH@zMXDXfDx)@J70Tok-2V#PI(&|EWTUg(c{xR@zM!wc@>p{Pkm$$hYxL| z?kdsQm^fZIz06m>eg*ZWH*}cezWev^Yri)V%^OA5VEdrwx6Aac9YUS^}HoT!O^!kH8z{SK1EUYb&cLJ1@s&*M$ zn_^AM%!Y9aOix(@lmzc2Rt~$^PO5mELOpfVoaN2|%RPAN*hnq}HdQ%&^wCEjZzpWp zs#RHX6`rcx%$30mEhJvcH-1n8MhX(=@CJfcjIq($og2t%JomMed|~Divt##jWjT;k zOOOc#9@QKxtL)y@AnT?yo3OSPTWG1;I1LoAX_?7g!qj?$SB~F^v*7ckd1493D* zxl1$6xDuMU%&~p-0>|2;>?(~jKE8vbaHOspIqY6cjq9sR`}m=QiTT68P%4bH+H}re z;+f+^tft$j7ae})jv+pJ^EzLD`sBBW`V^Oxqh`M@aU zN&|AmB!bU#=BMX5aQ_Yt?(OjWd=~FR)pFtDJnKgawoD9js#S&H2nutHOI*IX&X61A zo%;*^$gQx@t;MTC8D4oF_S_z*4|&!W9Eq_^uTSvu^e7)aRAT$U4AZNg!c-7baPWxX z%4*K)qQ{36Bqi%AjbW$`6kMFo!PUSUGyy`OlIAE%rulYIUoMuL4N8ZhdHoK`OsZCub%c?ylN1X z9ATjBxN%tdnU7iq8Vw%#O2(C`97z>1jt|`fx9x6o@#F%h=gK&f(KeRRy5qx#h4!av zoatBwMjSiqd$@6H&JEk(w|>s@?Po3j?fC`H+hMG$W6~I8 zCo4ERmvXs1&YT@0*noz0KL5yZoS!32Z=z_gfmS%%DslQH-Sh#bXw**6$0C$u^_;|F$gu6ZN>^vgSGH-UDO zdj2Z=cMkHIAAbkSt8oyb2Ab>ZoPYH!^FE`SIB*F^Z`wy`xbnIe@_Kvx8{>Pw@iu-N z{H?*8Cd|J7{`yUx7dSdWOg2tzjWgd3t7yBa3BzEEq}(Uw(Ru|LviRtTa7E$FpU4ivQtr zxAC6+aVl=!rgslz2NUBp_8kbUmxT4X3TKNELb(jKgi#wGyNfnXE1pVC=oTjSj)<~@ zHGbip6>i;M;@veExZZTpciQ*SM<0KKc%xiNA2pBHY}F!o9COB@)iQoL?-kEQYhDcB z3_ylU5~x_T2za&N9Y%%IGXwm2vV|R01EtvTZd!`X1P6?aDz(v^{X0Fit?<<^S81;* zlogX3g23pWjAIYXbNsm(7GK;;E<>nfbWDj>x<*lI$FdW81w|6ophjc4UN9l%oQXjZ zLJ)#PrKkqM$VPn4CNs*0y+P%g(;*&@%2L%BGhkGDC4+&W#C%d5LLODK)VOkPKTkgs zXth$Z&JHM7!RMd_og(4l)HsDTc#Uy6&?`VRp49kQsuH@8wAnG5aodq$>cguH44guk z#cI#CDn+kiYQq-KwO!nGPi=!Z{hr)zjU^T$;9VE59h`B@NtYLjCab2yj-@pY4<7`g zTJ2h3&c^S0d#>qy^zr`{J+6z^bQ`~FF=dBOmBK?(Ql?tMLzl-Xf`vS=r#r;1wF(QD zUZUL`!PG_x2wj(AYle%j&hqb{ILCT@1hNhvJh;N&{qPw6=^Y`xComny70nX#A;LL$8)Zif#E^?JfUy^UxfNCG(Km%2!8g!g~+T|D`_ z9=xLBX=fQH&!()d1x6cF)RRS){C2E>_XR6+8GGx7(qzt4tBzc%h^zA4DbMWEGF>dT z5zF1m(&3iv1?|OoR*S7jse-Bp0@bk2@SrlkQl-`1u(TV<3bySIn6l&aiv^fKAt}?H zD(hjGZg~igLo_Fs66@u?{2$*s&CTyFbL)7C$4)J9zH^j13Ay)#7c9pPHyN;o$Gfl#CRbo0o@K6<~Nm=T`7(B<6crzvLz%?`ZdJvlesZdh*((riJ=3{rEu zdFJUUlJ0lt=AKNI?Gsxtrp)jB-Wg8MIMfyF9ryg^e>KVWcT{?N=(s@kOLzZf@TQTZ zM~@z5Y;26Vxw*|_Aq1X$@<|?i@WD6hG(7+O^Q^9}zV6tOBS+Y}b?cjUjz0S6oF=DNw_8+kAK=%bH5-ZXp{>31EjCrDKxNWc?lYa1;Bh{Og~EiqYh zykeDLEu>MQ6s4nz8o}d9N`_Q~&RT(X1R)`WK-XG;>N^>xtgv7I4EEYu4D(SRk|-=n=eY(7gB*(^la zC{xR&Um`1XL{7rXIslBuENh0F)MkB%`hLQz<7mOc9tkabi%LIJ_Cyjo&@$xtp8 zRMR$A16E1|(*>F5{#zSNcL#X(Oq0TUtP@)8oTOTzS}!v_V-O3*d#;|I<<9+%q#~S~ zYg33r2+T|`a_rrMEEf%4IvrxGP7&G0)m6{V3Jg{~D=pBHrA?L0mhqZEFQ-+2B9yr* zNBP%Jwm9Cn#Ed=4O7$*U-l8IW>G_L{Col7}A2~wDk5af0y8%RTl_nQ1EU~b4j2p+x z+%l>B#xEIOxtL-sbOmnR4UI(DH(Ic?oP%?SDEo#>IEhO8t-YRv>n#UC4CQ*@mYX~~ zTNYnHIY6T(Z>u~~)z=Tiq_-{x0y2{F#QEKvy|kN<7*sMQw=~(ezs5@!ODwH4Vvab% zXv2`@kasr%(xTdWZtmJ(&W4=r<3hU)i>nrOAWo?dr(~;!Jol)NBzilPdG3`JvcyxE zE`vjD4&K<{%*hJ#i{+jJA|uO`&ET4K;$MNYP?)+|UXKxx9EI zB{k#)JbTVE-xWe9?~!amZie{tM_=KqkDVh6kkRJj??1*Jx8KhB&QVTvwox{1Mw>He zUdNi=vy<-{EcWpO#hdn#5)tmd|9-ykg)hAB_+yVf_NJ1gZ)CN9-}~P8rv3gt`sm{g zAT|3(6g{OQAu4+)>}C;$rUvh_82&B^Xab?cu^Zt^&9iU` zYy#dX-UzepE|0yiz-@cB(QRd1oL@o)Mlq`e(h*D$tSWgZ$U{`DS|_o^z9=E;2qHZj zVhq3Tt+8(#TyKHjqRM*`Wo6LdOQ4xYtVH{Wm6%)*0@f%4S(^`T6+UpV#A})2Fx)P~ z>>5jAbRRJyK{hwp@kpN~?W2!A-Z}`Xo|Tnl=9d;xAMm0Kj*c>1AEfM3)>=&p3fA*w z+J2Qxa?}{Qp};!Bx*z85fo;5$x42jvf=&WmK|@cCXboPWS_#Es>?(8BddMJ3Zn z`x)EI`YeM_q2&W-r{`&$7WN&hGQT`a;o3;K8jDNB$D+HCU`>U6`$rirhDbyxLdwWE zB#G%Y(H9WP2o7w{rm}G(8&rGoGFjaQ|*VXuSF)#84KNL61qCI+bgLw@_?>O;V zuLT+u=TdSjU_-AYLkOA?q}RtQNn95~7qJ=QG6t%a!#52uye|dosOmVo23u(L97Sms zm3CClnv7f=1yQ-Pp^OzHuUloValF@_^ae>PNL0cSV_+pfFdk0;>+$MYstD_e;as*% z#a(2)vW2_2gKaHnl!VkIz2U9)<7E2yp+XxtWg9$`Wn`{Snh9x02r3i;L1Qj+AwuCb z&T(8qP(=zLSc0{P6B47O)?z|J@FgsUCXUPHNzOEcaz$u&*4S2UViUzBp5T;_Dup

ICKy%HbK7JNM3x)?1tb+H7u_a8Na{lZz3rlq> zX$5CNryf(WJTq11(!aUD{-G)d#>$M< zVb|PgTxk{+gU>vbOOB4ck#Bx$kuN=dg!FbbOmF<`qUdhNN=@@dMy2s>0OeNN$4SL>Qldr6ohVt(cx$Bhh6B{8^+JWqTZQB#(r-!(*68D~%Hud5P<<2lZOrRRekwWfit|=GSg`g$WnwK@LgEN6=gN$7<*LD=1PW9=o$3Ua@&{1$s1qb#VNp|B z#?nf_rwJM|hKI-Sp@{btkpg~eU&KECO1!Cahx_ikk3ad7KY85;=ggTiOixe0DN4_^ zwKbl5?zz_;+sH%hqmMq`Li7roR00wVuA)elxYxp9Vksxu%Wg9bi+G0=y$qSEP^y8g zdRT4aYzbo=S=X{PaeVp%mM@OLzy1rNYR5n~NjYDnTn;c?vJ|PO(44eX!dOcha_-s- zAAUy}$hdfUndQX-6Do*?_*g}#H4Fuc+uXFi{Wep%0znusfuROe8=l-5iY)#;RSXoc zec1D>?{geT201uvajB(C+-MFn#2^8;$pXjCaGd1x_6{oQqmMrRRwELF1&ZONu*eJD z^Re}uHaD6UM}5KsDOXqKITbFk=$7!(qR^Z|m0T4uis}|j;<<6(Bp1$mlwPB8&(08) zn-(b*Sjn(uiv~kzcaacDGi!x?2LhEw!4uyQR_6_x2E27NvkLQV*r8Q|)KR0509A+e zP%G!`KjfI$T4HDjS|dvsO$Z7$2?Tc$D{K$AMF)jq-RBcE0iGD)Tb(O z0~w2;K*bU?kQafjy6D~Q6+#*35D`o;adz3uciVqM%8`Q^H8aEb*cv-*iM&v%p-s)r zAZ8lXH5}3YrzU2Ui>3tQBT31%jqygX!gVPE-}7FHPeXezt@QFnO(bDe2~yB?kS7L8 zmX5So_fzDZZ?mtpjbnO%VP`0(l|Dh*#}6HvP0!V(f^Is1C#vXE6F9InFtw~W-z87e zsC-WoBvG;=qbNKN|&iZc+z00vP-)L@LkV<@CfH?edRg-i*WQ$r|;K}Aq2;GrtQ zXFh89%aOqU{bWv%l&kpwPfj~_?@X91FLHWCQ9FQ;;=6{MC*k9F75w>Qt9Tv7Ys&dW z!|B;o-gTtPO^0{!%BoT%1|tbB8Q|1~j8EPIH;r~Uk+;a*FxDF8)*L0T_)#H90g1BW zt333T74F?vVc(7t&t3sjvJ~Dhb+yHju@%Ns&suvBHI`ru)(Yh!XXma_UR-yyI*M8% zgGY=96Jv1>axYLoFb#5Qs45yfQ6=wCSK+0pGMA_4@IIkkGKkATg-jBBTIbyPdCu>u zvTb*TfB)Dz|JRo*xxjcMjsygg<_w z$yXjbi-ZF4@PYRx9JxVwX>OTwOBJj&3>G;bS-WOB*obU-tMSIyUB!D(@I@45Du}TZ zn()NSIlue)7kPDdjB{7Ek{RfB0he%LA?4y!#=7zB7+T@I_YUyPY2nqEHEL>5yeiAf zhP()%o)8;_$(`lGN{J90E>Wrj&{adH8Q9pIS|i-BBe10!c=mV&qz-^LX4lYZ#zQ3u6q8nxjhX`TL)9hnO;Q zP-ZGqQl+L+4N|G*2|)n`6r(W(22ah@?Wy0wX0gDl%@^9H+pP6^t!_R*ciV1kre`l> z-~kV?i+Vtnfg0tSq(W7t(wveqQ#ofw#&qvJ=ieW0L`tGYhT_SO+-v2E(9yj&Zrr$W zPMm%A-hbkvV#NItKD{-(82my>(t&{iuDa?f9((Mu^V;vZ=N{hq&UgOY$G`8s`*803 zo9C8WZXpcApZnNrSi>5g2i|wMMTa#JH{Gy}txHYDPdKmvDV^!7dL&RhiZvMomLPCk zca!0oOAP&5;Pjc8rDZ5urI{H9`-Lm3P`^akcStxip3-V78pJFV)-e;u6xvNPNx-Do zLWC0mpHVeUbY7_S2YmbP!+hhuI&F6iwis~5&VXC5HuM(r0oGgJp${)0Pf8a87{y@e zGw^3`4_HazpYCdL;J9FHp7q)z${R=FN*m%3Qr~e{YF@cMl1?@(8TtFnI>vigQ z4QqJmkk8Oo$T(6-I8YS4I09)=<0Q5jaHcuUR65I3)zh3QE}|yG+I;eEk=**7W&|#z zUwY`Bt+3(@s)B2|d=(A@60p3ojFl9L`Uy>p6cuqoU|?Wah~mR+-8#eZ@vCVi5lPE| z#9;eriO_Z{sK$Ah7%376CR2h+oy44>)}CW|}y@1$UC94kUY?o)fcA^UqGBQpEr)U>yG|w~u z3PJV0SkF2x8Xl#uTqTkaOMtnMtRibz!_SE2#T6FM)RC-$GcCNalzI&7D;dY1p1^8} zRNLSoF6LJ4Rx|%4j_I0w6?IT|5ni%9uE}ON90n!IJb2To(-si6EJev3>PTnN${BQ_ z#qKC%VqMBNiz!~pEJd4mS_8KGj8Q+uNmrs3RPj>a$eENkN`afk7Wtk}SP2HmqL4GK zDxdqt5w5-RQg&W5%-8oONDv{B#mfLoHA{~euD>YZ-o6#iWM!O2tOO%8OsCmjCq4 z2RXR^M||*4f0rkcojlsuL0}ze)?~4EoV%Z_^XS|GTq;Eg|(uJOg?6`b+wW@4d28Z;^VzV2FYM zaHwYd=$^-TWdAW#0@OLK*m*H~UVA;?yMKUp?Gqa7QCB=I1X~w`{!1hapC!SUorZNH&O4$O(9y-mu*$k$N zb4{u}meG+xCMPP?nh_cXgh9faUl$o(-Fr+aWY&Jbmi|+7027 zO)=N*9N>Tb@BrgWo={`19I{-zZp~tUq2L$J7TkL4tuGl#x@NUs!y5h@ArDAFuqev< zQpnA_Esb8!iBoW9j$D!BJb_UR9u;uTP;EBYbYzmPttK0{ZRFte5O+MPM1iNRLT!`s z_CCiestt~Bp5?Dj#hlVUP>%^x0voV-W09M#8Ro9zmil6bilwO`cTFy!KRC??2QKB1 z-Of`%n|9obHz9Gb$o17F)+fCL+K-AktN6LV5DJ~V9=KeTO$8;3gyK%iox?(444S}( zvQU-0T)iL^y7R$R1rHrkv}>@I9f;uHCaJ{2*+u+%w4jd zQo%#HO{3Vr+Z2!BI@W7LN12L%C3gS-AOJ~3K~xetTIK}R{vLL1-on8{jx_F}2Dx&i zW4rfh1&;@@gaUzB(t@L{hNF`$E}ofX>-H%&U-1Bwi$f%*w}M2F7=qL=7)9*7c$j9R zz{0#kjK|t0tu*BE18rnI^pvh<=}ZsxdR{c5(QNU=(~sc_3&c?m-@VhYGJ7pyU?H_^ z-rU2h-*$$$ci*b*{-sfpvf7=C<^`iz%|orRdD}ilHZ?eLVu*Y1OGuItES{K2Hmol* zIJk~>W)YOOgj9zUn&~11QzPi4vluZLt9Z3}VGMy(l*|~s8GLy z4ntnB@vN*=QEdL#kv)m#9H~JFe6DhZeB?3;sFH~S86iqyl*xFJ`JsgV))}VL8Fu)K z*lb5hQz(U1@{(F>bt%-V0bEHA*5%J4nC;C@~mE;=-Kt3e)`ita;w>v6HhbE%Xs; zh-3yVcw?EEPbh8|uH9YcsTGS6CDVW}AIP}r6;Q0!2`ped8hA7-Fg0(PooloG(jG>} zJf}~kXk^L6aPq`F&E+0$dtER8@&ueYV8BFVsS@~%!CqKy=ITQY6rXt}PtSAJrXK3) zGLKGIp%Am!C@~%Ho6Iu{f308GoIyR>sZMuIAGlO@ude665qy_3vAnNsP+rT4k=5s9@JA}iLE{JWQ74{ z7D~88ATX>ngnJ(VM6kwCE(L7AG-PVhFnwx>m;nMxjF>06ez?Zo#-+?J^ySenPFb9V zN0uPzR1_Q@Dzl+?j8i94YReT&!I1hI*N!dnoA11m|L31d95|Fmn?8CnQnx-5%a)gh5+wHn1@k!rQd@bEC(wryLpCavM8 z$7=Bi5U-TQ@XoE4-D8$-{IJEhCKHlE0o9Bv`W(0HEHPhm-2Hfil{97F6N@x|Ji+U3 zEz)#-G&4(6a~b6RsTDrAcY!zWD6x2Yfz0(0^~Y$^=K71^#!59 z7j&en81&%9kp?vi_9PqDIV9bVGd;}L3==1m+9KpL??PVsH^^0#&Pz_FSx>_&k3JES z*?tyRmT0CSltPR#MCCT?H(RQM3)qDjH0mYKJo7lKIA6s1UNYB*b7LggMPx|<@0!W)m%P0#i6_?-sA*;6F>~!fXkCe zbIq)3XV^I#!0J0`q-T|+xysbwFdbr*EsKH}acM#39wY@kH*C`SOiOHx(HPX06 zR&OvpKf{5v%;v%~46#RV~wHsY~y$Ii`TT(qUZ;>iRNiv|(R zMu}sG6Rvwz#O`fVoF0$yeh`8p`;Sj?;CO@AyrRm>b{08&GG%Hp0TZL%(ynBOO+F|Gdy-WM8gOdmYLQn4;)N*^~)_=+cEPGB{%~sQ6IG#VaxWEtF8!{ zI0kqysu&=tJ8IJ@V*_w>8B#6e1_lwPr1hgfj9agCsD3u_HJraAuf``;# z3~X87!=L=lP7W_yL@gW526k<-XN&*6l=rCS+0#kt`7d{$;713b92Z!rJ8paRHg3EH zYH2?+euyj`BGeV`+E-)l|2W2xiHvsAk54k3ftkq_?wFWCZA|J1*mf~AoG^a6k4!w6 z1fv;Y!7?;rIef_B)I%1MVmN-dPR$A~iU|uLyLMT|kHP#j5Ga9HMvHA;vD5N^7p6}3 zk_u$rvru<@|K17a%tm}LNMM9gK}iy&o#ww`3bMlWms?)*+Ft(pGca`!BvfpcvaWQ7 zi#K|rqM=Y$tbvMpDi&UUlV!&iL#hzF0S2X?twTzsW=5Cq^lUv|+>CP62&ZjB(l zpzsSPNv*Zqa?34z``h0>ul=5T?)kY$(jWfthtFtx&1+usqV`o)9)0vt?!5C(o_z92 zvMhVfZAV8(x#5Nzc*|SfLQl^N|H%64SHH^FzV@|ew14n}ALQnnZ+=nd2k_nRewWXE z?sMn01wp{aKmKvHZr%EV`_IqM^X+ecn};8Mn3TdxNBI$ zD!O6dB2-bXRv6BNW9>zL(5$f#Z^pYeJA94zj+HsHoN@Tab379DbELS7q`8jP{sspN zH3+Kt#Mr=@dc+q`_2JeRIq5H=RSt2bfI`@2y*5aXEwfy99DKS#Q-`ot@mZdWCf4AL zCGkorR{E=sTHBE+ESq)QS1a(!RzyDhoHYSnaOgM>HJ8-T5`!4%^U4iIh`V`6VhN3q z!dgw=HLPI`7aRm7(u~NpaaOQ6jCf3^c%FE(>PYC&W2@PekgF2&1+f{beQkOxWh{D9`(Rj$>$UNmuf?m7I{2ya)+3ditKGci?1Bd;&@W&f~I!IL!&{ zlFbODK_GPkLekD_=k5gQT;E*jlBcg40?oY)sgaJIK3AI3d3}{`cC4Xmx~Ee>G1QER zl=FNYs(7(D8+MedIWePNP-8lDYfjc$mE4*td7-CTC1J%Y(@DZ~yTO^+Id=A6Or_mV z)%H@b(OMq&8vcDib6Ise$yi!!lldZ^BAL%KNeB8M%^X=~Fg62i=Mha+aIt5eh%79k z#u7=3UDc3_tP*Bv-Uqu3=RBd!<3+p+a=X3hDA@voi-bf1(CD0g8oU$2&>=Pf6r91h zyk`kQM^;Fwwc41_L(=BRktT1rWdrNiD~}&@5QN}8^=66j(`8=ih25j`++QxU><7@G z#7s8Eoe$0N=39Gs?G-UU_`xjG3f{)JEYFrMZ4gqiAeO}Ta%iQ_k;!>p_v(%O+njP{ zSs=8uopNBxa_7Kx^)R3Q)+7BUJVTz7@=;G>Qp5Uf|yRs!=Y?A#F%I^oEi zp^+K7>v$s@4JJ^I9Pf}?lJ|7pds7SH zOCnlHg_9>XplrlTK)Eku%N3p^6=oKoxspe)cyT;=Ksb6-XstNnvS)0g&|K(aVX8=5 z9H_Exo#mR{LSF@b_#=;3!5L3uW`_I!Sr~7PV6{lO0{z3n{QPz%Rz^`f2&tjB*Yk&e zB;2#tanBD^@Jj5?upzeW-rUQs%b=Y?+#|Sj9b;q5jBO714}SzpZ9^asCuOeR4C_mt zi?(W)Lhp=%Azf#mSH)O+&H`d*92NOx)!bUci^NM3&Ufprw?2a;ec*uyc<+1Pi?u&} zr7rJ1_uO;Od2PjF@kNo4$BrH2um0+(3$IhKQsaC5m_?qM6K|NS%C-~H})zaWvBWf@=j z%2)W#cfLcKrZ4zf^?IHA@4uh>@4ufLZ@iJ;`@P?LQDpEMe$|nyHyw%*LA=8nORvJ# z!2*|Ds!a6@fs5G?d15idE+uqzoL`3zE1U^OS!}K#m6*tQl9mBH5=5+MfqyxivfM0E zFBqK3XcuDcUxfJaDQ>?srcyK%EVNe);+0szNWfrkKkIrT-nc73!iaA_BAi)rpax&; z$6MD)hU=<(F3f6y0(rh5@^pr1h|Nj_vJTX)Dj~fCb&zFBmica-q};urx?0Rsf5L*Fi!Zw~qK+Mi?Uae>gjd{B=E~g}-+w^x8sr6gBE#vUDR18C znHs9|*xWkOyrW`e!LfX#$&K53SZNua9=D{4Vy(xwma#SE?YsK;-eYq-IMIVdeF(zL zR7O~Vk&QxaDW$&Tkub{RLuz$?0q2po8PmW7~) zwqGIk31cF>`{kCoE1=lv%dgy|^c93RZiQED?Rp)Qe&eWmOCU;5XCB}H`%5mhAOc<@ zys46C0gQ6uq~~uZmCTK@V@D7D>xHKe8Wv{?n4m8)3AP2xcrikAOARDb_QA*h_eiph4;TX<%u6J@b&33PGZoM*;(Nm-^>>Q zyjlhaEgMHe>ND$jY9ga;1TP7@E?54;@5X%opIUtHz6w$Zku0NPTD)#|8C!Fl9`}Sc zroY|Cre0w~1RwYfW#Kk3RzRza_Fc|ML3!IQ@&#JJVkqJ%AXp6N%{9-_=NQSyLg`*e z&i)QqBS~xc1s>f9m7y+qdsL`#!*)J$s1b_<8sH zmw)*e{_!9G@fpRQUJTmpHedbfS9$vBr}>jV`4h_J^0RJdjNti+-n{u|I>s7)HIOSq^667P#mgsA)dIZc`ab%v@8gt$YX@9gC^6(ANkc~0_YqBn zw4Ks4C6ZFap6yB|5%)iy<&zx?Xj;Kx{w!O%BP!R40ykq zIJ$;4tYHm5JAU!1dhJx9FRP&fB-QLAw_i> z6~)>TeSN~_jU&v|3bdMlnvRt;MUBV1Fwf5p4H#u*$z!t^6$93Tc$}}$Zf|9LqCqqB zsKl5^u_fuG%6LY{`We~Mz^Kqn>a<*dgceD1TU-z*l|qGUZz@v1I3czHt}Rr1+C;^r z&SkZojJU34Jj2$a!U5C12Ha)ta4sjCA=%Q1Bw;BZ(pK z78S*b<^`U-rJx}N6H@mLQj_6LZk@N97vhkvZC*Rnwpx08fG8|!nlF}WZrN2it3EXy z0z4qYkkO^VJE^Heni6YAecQ262#O=cU~!szKImkd8npyzgx7#pprodo$elmtB&x%! zCy5LzQHpxUa%#9SxU$Pk=a)rXUc_n*Yq-$hJ2z=yIJube@U)>859U!5sbl+?a_Ml$ z-S;+`WdOA$tVC49gzZ&Wnr|~vi}5zkDV0nqM6l3ob8HEmtzbM@?+Mk@7YW<@10Ixw zh6{mwkt9agF&Hx#w^`0YoEQ*?7zjgyF#=BW^A(|9hmr(b+#7RZ&eIAbu&}Ts)SAkU z?LCx>i>x#(CJb;`CfWt&T87P=N?dV?aOiZKHW7%S-3U2)w9U>-W3Jxa&)rX@G#d^A zLt`bQy6o86=Q%!W@ixYon5R#*`N5ASxPDuahaYy#HwQYAEE$LPPg5Q%a_#mWeq6Jp z-hj&xbsRfhqrceXWtWwhoXnVO^&o+zo`yXB^f;FcC>!GjfrR*u)S}UJY#B`WonP-^ zVMh4c9d)LbLPQMZQk$1;EAh6g1blavWU(e;JppBbw_WGivZ;@0Z-~QTZticeX+XIi zI7vc*kR(+~-qCCd!54SR|eejYWRQuw$4M-iuxj`XLfp)fBx1u^+3t|5Ic56 ztSdNv{8W?Le3%b(nPY4$<9)vo@PALG%$^D%GN>17OOCtloMd5X87+))O~>KG z84FFD^O9b<`AWF`&6fXiXCFtWTs{n>E&7Yf%{xkbud;%b5>^y%l}cn7w8DE{SK#vP z`8BI#BV1e+Hul2B8x>W9#pl_w8mtnUc}zxk{55CW&%I`=PkiSwBR^StPP^xVEG+yh zjF;@wxb@aspF!T;bI(0L6G{4P1)E;TYX6OIe1k84`ODAxf15UK;_9ofW@u=LIF4Cd zT;%DepXTw$AAbf}xqttDKJkf9@E3pa7evvs8(aqm2l@Tq|9w97sZX8PzIX3l?z`_k z_Uzg7oagz)FMg4UiHY;thKGmw!$17P=Y4<8W|NP9{NvBq7hq^;h^w!@nz6Al%H=Z6 zW|P_3S@!SW&ygcX&f9i&c9y^V%fI9kpZEmB!^6+}nrrygMR%3U1IBlhIzG4P3>bJh zN+yC7gbcL6FRB^IUE1~jt_hvLMnRxHm| zkCtxb^IYGjc_ni+|38huWT>QM65u5vkQ#AmoQt;)Fu7dh$dP<|F>QnffjELfA4ywD z+X_L1WRhFpjnAc?fL9M%VRrKJ&cw5bgyb=4x5L`aZkXy40TOSQXl280qAYngU`18rsBZmJ_9TLJ~sS(6!o2{%Hr!V>ORpQ0_J#G_b4KO7s`cz-+jXf?~Gw?4*s{}r#XD6 zAB}raU*pVEb&kX(niEq9n^0dMu@O_*My4C<@j(G+D(uT&XZ|U%Wx%Ppidc!6SiEF&$04gpnP0)Kp?Ox zVL6)=gPN@4Q4G(!_|Jaj+d%PIws1h$dAu;)j=zd{$w<haY~J zX0u7LSbUy6&quvp=aEMqIj?Q==FQJ*Lx1FvN1l}+9T^$n{qKK2S6+GLv+lRFw8WRb z^rdHzvd51f=QE%A3?KNw2cGjaZ@&3v_U+sEjD0`<`OmX!*DiW{d!Mn-0}njF-FM%8 zURw|ZeCR_TdckY-H-Gat&mc&v)hh3M-}|`v=9{0jV|>@U-o>Fqhxq*GKhLpa$5z|x z^*W#YfAN_>Owky7+GB+%h$n#Nb@Zmok84y;<;tB;epAFLLs9b1XL2s zB~^IS7!0*r{O|vDg~?z9V+Erg@0CKYC5)8XlHk1|wPjKpgSLP+xCmzr)+)}xU8jo> zJ9M-_Rt^ax#e1Qzy})l>*2|^kyh`Qjd0&WF{l1>f>FfLy0x|^KnGD()1V%}n zqn5Oo(`8JUu|BM_pmo}&jU~%7-8xD|0PW_9c1Sc)ze=RxQ^flYNv3)AV8BK-ij^fs z2Q%hp3`?~P#p8*nmJ_bKYJx*YW;uRzJD51P_*)@}3}NI+n~pSbs0lE>3}R6QXIeNb zK!B)aeleu+^ai$V83a>A!VtBB25q!ZXQeg4{8GX~bC}2XfjS2+U|oMeUv-g6c{z_4 zR6}0sr1L&~P7SL8#A3W6#$na3rvIhb{PPg-UI`__Oa7S|^2il~$7)_oDYwm^%?`9a zL{Qpzj0rJf2m()_DI#sur-%`ZO=lssx&2}ucXt1$rG{52z4C#$WaaOzm`1;t7?#gs0;j7SDy6Va5YqdIol zeYXa0LUJ{!LB*1ng;LrnOa!OMB%tX%B`tArZIDaE6NQ#iTt&>B|HPzgxHqCNzt1lF;x*Q24KZUR~w z-~ewt#n{msC}lEY-$vDefR|jY7qwH0?IzYZ#0cVxEG`%}_Zu!NwwOxVWN{TW!pwY% z@yb|#Lg6Myn?ZX)!U=1)c?uf|6X%q zJ@cNT4aiH0Su+3tAOJ~3K~!x7eznu}VpnSct!7RC^q%ubTMNt>t);SGV6vdGc%rJ2YV1_fdEvw z`$tV43){@qLP{mey3vqkYMDDz;D=MaILeHSWqkPEAY7K#N+IaEff!r<-_*O8K72(Sb=dejnW^emQl zCCCF_o^k#2%NZcgxTw#CE)i-t-xJvR?ACmO7ZhGHk~EHE_Uzfi_rL%B)wVQE*}Hcy zuX@$1Ui5M9yYIed6k2*d6=}QO=Chyu>@(Ugz4TK4^iTivIc@U*y}iBs(I5R0+qP}v z^Pm6xYK|1Zz4zYBjW^!N4L98Iocq83{qN`C!GlaqO|7=AtgP^NfA@EM_`@GQZ`+xf z89wuw&phK8?|ILA*s^8IbG`=Tirl?>_ny}_Iy%b7KK3#C`ud)C-yJ)4@aKR2=Y0Cp zpXT9*A6{)AA0OwAJMQ52+i!o~{nxMt;F%tR&ZuI~Y4Zpd3H;AD1iZp2a|r!XW=|+= z6Hj$R$mC5`{_#l4u_eWb#X8T9(SV^%0Y7{Ik`;l#gHJ&mk$AQa2TUvqH6I}=)XQTW z?}4hfsPiON$p|RQ5|?O9Kb5nC-UZDtuF}xwoMv|&v)jHlp6S zLIdlHhH|JR&NJ7lGnXu*L5ho;NJUVu1gm+Z+Of3fDnT!~#a_rKZ`x5VT4{GGn}d-A zQNd%$Bt?n~Y~R+TS&w;Sf0k#7N&%roZ_fkl*y>5riobEg^-%RuUJ1WwyVzm3&ccrf)k}G`?O!wwky>asbjak?R+Jq>9 zo{eTmjgX1Sm9i2b1SkQS7<}M4W9K*?w@Fk;r9e5Ykj^(*nxAE~Z;&y&h2H4-e>1OP z4Zloyr>rcr$&z9o4WUY@V%fUMk}fxBuQajJgLjV1Wr(&ZSj9U!j$NBS(H6xpB9Smx z8d^hJe7-0nj-nA_n=e|3=2d@uC+;LPLEdjz#e{~m5wf^!*;7!isw}ZLZL?D8CnMsi zxn*WDN2%;E)Uei(C5}ZGaWt{qHmF>^qsrkKOWSz}6_8? zD^iBXgd;V>!s!w-vyRCF4PLuBCusC1h)mN?O{)hJSpTB<; z6P59%O;9p?^bba;X_1HK2RUZ9V10_#JWH(*p~_0MmC0}fampnXLDO9I|Lj4P+8G}^ zQE1kZImdw$Q#>_Q!-TmFe&awNS8N%i63JQd)K47F;ShP2yk;@XE-rJ|gNLc51=I`c ziy<$&W;3-`#((Q+ zvHc#+A_!B&3gc4|vqH5$KW5n)K63T5ltxsEpFUaWTkESVgP>Gp-get<&wFmF$~V9H&1bysM?d<}7bHl#h@yx;{^LL9 z&;IPsn4X?qZNKA=J9yKZ-n6DBUBl0fZhmRx;Q9attnQn*?e&C9dP}r#P@X;lGm{3fF5AUg)`!JYco>krN<~8F{X*LR6XL2>b1W)EkQ! z<4NK+Rtjh#K&>Sc$gBZl@nT8D<1&XYDMk!N1h3$XAu~Z9N$1*>C8Z=;t|l!ys9FLI zXa+Hfg%mI*TqU+tz=+}yT(>eiIgzF+dC?x*$t&%=;hg`I+_oRi5%lh7aO7$(Ss5f# zL9Ni!Qy}OG*gBkHIK%v0iN!%>yOrkE&#r8&sb5>69rkg;QD56iWA#-|-b zeGn>H=9rm*Vr&_xSQ<6(u86XMwx7f5DU1dYU?7t`OIjq)AyrXA zl+b%DjzF`VBvp?WgYVegMZp-4NE3_CE$=uG2W0u9I; z5NL)~hltB<@^r}Qj#AW+6Qsf_r}^9?&)IaCRg$zjzwADja~`#G52|#D;@oYrnpL{0 zE*D*LX!YP z>T@~!)cg`B$J?xn2YAzsB_2MQarXg_bwXy9(?=WwyCCYdr1gAktlLqZX!Y}^FyK9J zEb{t9`ONp*+%+!T_oFi$zV{e6zGjT-z$Sty!D&JTFY>xX&El{*&slJFkIxS7NWb zhBO)@^(`t0r|1KnBXtGTmQZN|3852;E+R4!CNvnIQHVVejui0D5p@;sozCje@uNKX z)B(grw3}_J>-yQY`%1p@_$+__V~14xD79C3+xC#%mkf~rS*yXs=`%DN36LPhFg!TI z`t<|MEi5rVGmSG2V+{opv2nu)_v~BXFTdX8*iwZc&A4Ky#{ab?Vz?0S_?b;S=66#t zF&jzPE-BZQ1MVu!@u=@ZeFZU&Cl4m{*5{DLCf8j(#AP=G?Avd6@-a|vkjUUO&yI^6 zZ@&gw)52G*$2&!xp^(L7ZP>aE-tjKO#Iz?ss1{?cyCxv=@Um^njoXwKo&ZOg5ZiG$ znpHt=_jgEM7|rRUt|C++J1?|a|-s8lLH#hJrz{^oD;;DZmIMGTTEiNC65RnN z=uCV!lA8=#9k)lQkOa!XIoQ9@BB=D@jG-q~cJ;$+`{3%0%3n8y>G6(A%0piib7eK- zlHLZB0FmHRWqnC_>t=ZOW>BA-)2}W^^rg9d2!|zAL!t(Up^d?X1|=^-U`)6AuqVTjb;`#D zWH?gVGzpv|w~;BKTAVEtYlKLAmMH5~MW+)gqMh8yE(fOF{7bcn+MK|XoM1ybf=u5a zwBu~t)W^_(M{Q30g;9gBk`cO;_5HJ4cWEE>mSAl_Ph_}gXoYalQ>_-*J6pgxgHs_0 zJwt_YdYNOkvW-?IcqfRls8{;d!It5S!%w!DZ--=3K&6b6GKF%5au1|!2bvK_Ik}q? zypBB8EYInrV~S7_ta?Npq8Wn2;IMd%@u(yOoeWnog8CW}vZ@vpao{tQ{Cx-N2v>_i zbjm#$B_<%#m0Yn(hSdzC8G;g=lR28RCaf}^U4`iLnf^L+&sAdeyaBfJy!+3t+LW$R zsq>j?hpjn38tR;#HNQcWZbrFu69884Z_{CPjppR>SxbM2S0z=8P{3j^>JVvBkHJNj z*cH$~a3lmgd%b}*tl^i9Rx6{nQYT3wH1gm>iUnb?Upf8w1WPr^W!v6j17U2eh>esq z6U1~D8i29QL-hBBOf0rL-?7ej&ujN-hb-z8f0O)A1bY5|_TDtulB>S<{QdXN%ro6{ z?pX6&D$N5DNJv5gB-7Z8e#W$)f#-&Po&vgw@QaQPrVI>};6NQC3DJQf&)U9EBEMc)^h@4@nY8Z)? zTW?JGUnUzYR-j&vxUs&M9W}?yVwb1Rc9=iEfD=Q-IBwXzg-7SgeD+5%mY7z{v1><( z-`p3IYQkc56RC_d!2)?yVj+WVv8UO|x&PTV-*{#LjUy&B=iaL#-ak3P*B&~_-#>7k zG-^<@DR16c=RbU4ic~5r>MlB^eIP4z({n7HZ&ROCderF1E_!N+{1Silt$DumgC5T< z#7u6sq~i39tT)! zdFMOdc@f!p=+L1TB}oC^^Pczc#1l_&=+L3nwq~=*XFvN{-tmriT%=Hq=6fgkf0WB${x9^h_`@FL{iuqlGOO3FUc zqT~*&SBTde01Pq25JSAa;MKF(U#8h@hSEBTNa7Mzv3SkMB**7U$tE;x1HoV<-1jp2 zWIkuvwV02Zq<}LKBEe(SN)aZ6#jC;R7Eg@YBF$Gq0Ekx#m1kbCXBNe-5~rvMzL_Y3 z!>I??q-IM*cyda`lw^&K^LPds?yE{d6r%>KK@C_0C^L{h#ZsuAq=$|i!qpCe>0*OR zDqYF2GS1E|J+{{}eBL6q2C+GL^ekF?j?U=S?B035FUqD#7Eg}6FKZenbygdHg}F)F;}c8GlNSc?+J=!oDoOzu<#tDyKm zn66q1gvceY29Ga}HK3k^bdB6rEr`NF341tlAG@uv8XeeN zP^iGeqJ@YSA#jBC32TVTim|<*_EyC^$I0mhdM*KJVe^#4<>Z&jetWx}S3lyi$Y8pR~8NBPVO<4FTa4OGh@&}%!UXFaDDg$EBWb8<=P#x=6iC`KlD z_}QFWpPXS&wT4MUzCm0HYQj#YjMfYv`K2MJf{4|%?WKBC4$hyBTUcc{OtqBdFEUjwJ|$PhaK;mV5Yi*?^Y)e8__R&HXFm$ z#}-&v?uC8GEjB9=n-aY?#AD#K!Vg;w{vjR5<#o1n=h&0g(MUKtUE&{)@5RMCDP>Dk zl8BZjbh*`Pm#F_Su>+r>vQv!4NL}a+5>OC&d_Orsf6n_ zHeijRRty!GZ@W6()?c29=_0?Cu;5J8(9=)jT)?07Im={|Ue_`By`|THzq=ye5e#z}b zgin0p6MX7ZpJHWYWwrf#-}@ei4jtM+N&d_4+GLrLWiP zY}&MGgIe~;kt46DuOWuG5UK;8n+VMZYNujaY(rjqFIBXZ&?#qFC#bblOJU+OF2et` zFXz|x0Yt?=&y+Vz7~wjEl;C|TK!c!d5<;@QUc%&jh#`g;;-?LRJcU)|+@R42eKJmz z+kB^WkfbDFEK^k3o0nM0&(Uf$$???PI0y6^>|B|eYv9GxtS+)xp5t8q40HY**bE~% zRt1YCHyO_6*A>hxUQdjWdc)YLW$V;= zc2CUHH5Mls5~q}^XNm11n`&F}D1C7dr6hia%v5lcvEE?StO+D7h!=9>aagQzs79!9 zcpQ-rK`K_=YH4~XiIt+&y!fve{bWEJ2J(AViYYnXtP^<}i};`nHXF`sc$mvN z<>#QAOJ1;RBx&R~K361=>aOT(-QKMF-bo=93ex+p+$&O zuo!5QOGHLQW=g2Wlq8{H$BSz?AtfU&!V!lU;=d)-Tf7$>iu0bSa>_e)l$l)VleJT< zG{W_5!e^{f6K2oPaP;Ugi0>#mQAX-Yk{HsAVt@&%Z7oXd*H%FW_m9CsgHWzmBzCx_ zLnEPIYH%X1F(VP>i3v=-PcOHqC|TbyJ7Z~F4j`wp~6P$y0+ydXdVTOPBt|hnINL|9` zzP-f0H$?2(H^uWa9*jql5~t2B@{RAG;z*}X$J8JzlO;JsmZPT^_|`X-J^RP;MA&Ks zrHESHvvaFZ^Kj>Qm*`Cu{_&q2D?Th7<#vqwpWQ*@Uxh38mzWxyEHR|1;Bt#Ni{#*) z;4`@Qrk&Kb#Wa(MoQRPKZkmFTywBd&8Oqa(M3JYTTH5>eP#K+~rOJp{QlY5T@R&-2 zGj0cmOA)!0>Gr32_=yu78TIsK9G_VrX0GY@zaIB^nWP_==;w}(gnhKd0$MIgC-*or zg0nHXO-Ox-n-&N ze&ImEhi_L(CB^u#kg8F}?A$CkN32k-HmKG{h?59`RS!`qM*jg>dT9*v9EN!L_=%IG zwOWnaZo7>KAAE4N?c~XmoIH7w-Me?c;C4?u@dQgtOB>o=EU*c1%i84i0s6)Vr!Fi|y6ccp{KQ%{QwuK{DJk>aCA##< z$#5E!oGsho2~ILop9d3?#Fz4fZVsuLqst1;@vva2y?M$+>v5VC8Iomu<+coLN zO;Wlb4kLUo>A0=TT6TBpg--^Dy5)@P#$UX^S?!^mBQI?*eni0y`J%|g1?V^ZeM5Ksx5OWG+ z9ZpIZV+vo@Dn_5f>oeHcW4$9HBmq0GG?E$K`X-^BHZT&@u~D2cmOM-1r)k&`yotap zVdB#mlOj=s_d=?Mo?4t*JP|4ph~gP6*hx{o>dAr3#8@mIhZl$Q9!0S987MvniSL2q zh}M;>hmeUtc9=k#6vs8FZzYf(I$%A6ZcJB4p;%0INig3_Mhea4fHdb%P)p5}mE)h$xX3mIhi(p?!uoGaTzY zhR7lZDp#Q%koW~uNEaV~7oU(1F~rMK;l}8UZIsM!sPoIft#hVZ# zpc(role{{6Y_U+((xUcA75k@VMP4M1RD|@PO zAN73@#TmKY)9|Kil{>F# z^ZcPcX+Bnj^*PG5GJRm{sB-T;Q+(}-E(Ms!NzWL1hbG z%DCDUyz$luANTpIe@^MRPyuml4o)w$=}zs$RcpcH3q`a7$ppqklqx04W1grN#+cD5 zLt|8s)H7Kwu``1I_-@M=|5Z8iEcnRMwtHAilGTMD0BeMwyS~EK{V~gFxXo>8&;lRDwI|NTA=co?z5N~+8?Ju?f7n2{P^ zJMMY9Ut>P0|$DR&` zxD$(Lj%liay+&UH?S?xMsbLVufV*D&*B@op5N3Oh9>VQrBcNg`L=?cL8xW8IAB zM`WNZk+cluczA_$WJ|bi=MK-u3+<2--LB)Z7YA3LjGDma z^9?b4!qVDFET%vTnX!eKQY}n=UL+AM=^x!+CUrf>--&FTQbMV?E5w)vPvkdvzs}v( z$EF-{bm&Aow7e5*Lac+Pgy0fa|^74VyVL z7M%s&kmr@YVA4le4p;cVqXx}DT~Eu@aj?z0B^Xp=ezAx!W1!+dTEj?YBos4KtUsRi zXBw`lMcwOX06_*tN(u*YQQ0AUuQC)_Nj`{Asz017#RAITZ3%c|u6 zv;clA=tx&JX+&u#C1lLroU41y+#z>$DL$i{vx&_*LJjL~^0#xAQQ-`ucOeG;L^?cB zz0XFePw%}tB9|=hOQMEZ9+S7f8Hg{WQI-a=DpbQ13R>diwNJ0Fw)%n(zf8qwYiw#ZIb-Kzr+Ti< zQQs8d14ZiYi({0+d-xw3;~6s@4J(htWzaH{5@%#v-zHYk)gEObU$*O`sxIvqy7oGn z2Ih(KM{tNTC_7+IqWv}q;&Rp4lp541(_r*A<8HhK<0FV`2TC^V}No#peKn+pY z?8aUot3`O|A9;mkPGuc6W}?#4KR&;A;T;_JGSM6$XEAcAV^`EME0`p`j zT^FWH6!(%uAMK}#wli*K@AYw!x7?iu`d~)kbAW`Wt}zM%o37_u9YManrr+bcD=$qp zk+5ax8#yuyq|USZIn5Z9QX4!O)!LgejYen5r*-m=9MJOI;B9fcM|m(!ZCa#u zWV;a>ItxN3Aa$lh-pU?gNa*PE9t5BdC8h^b(O=glRiAVABUSyDF*Z zTM0pXZQl1CMBQ1;+_@9G>+K$R>!uAC+y{>jVcnv+6Rr7210vbv0F4S4d63hfl{OA- zTafS-2{db01L6f`yL1dX?9}nC}35?L(nE4im{cTFdl8S$mv4mfoG|<(yynd9c>) zH*ToJ32+2t#RQS|Mn*xcvWuZ*{1VU9RLU_4!n-wSrP6z3NOBhT!q0x#$Db^e+;rH; zQDTCntpoZh(z5>dib^-&TjC3Hab0Of2ymlk5h2MjOqKSfmYqq$B|bHu#NiAAnzBK$H8g3Z~#S(UE)&}oP1m6es`wdxpQc$v>YP7w-T9wB8iI>4qkIn1Zg56!>rHw)& z;~cw_DLL-(5r7#z8=afW&=UnE^LIhokJihi7rtfq9}OiB^pn!n(k0Q3$_{MyogS= zASA@a(pZyb#EGbK1tBpw0Kw0_DO}1LA{?8`<4;rAC^Smek?CX3l`I01wD^krqylvB zAA6GAzU>2_H#yQu)m~+Mqo^NDn-nZ%&YSkyiQjF4y8iiOo3lyS5Dy0`!a^GUWblUv zX{e$!g5(>dkZ$@?fm2=^H`B2kEVqA?*f!-41|<+J@gBzGWM!@|vX0W@rdPh()I?hb z93s<4`~Mhg`L*$aU<8d$RktUR6YoBmDQ$KLFH;Ebl9cp3V7Yd_p?vtsy|tSz+YjaZ z+8Q+FYYIvdbBao|37A(|Zr2tk-F+{iI-J5aAdHvYAJ4d|G1e4fIAc;I(C3Ig7LVj+ z+NU?Bw^l4s9bu)2d$?b)BWLfIg{*=WrzQqjEP381w%#W!)_QxvzJAO`P_u%FJoP<& zXgaO)1pcFU0_}Jxw+do$5sD0REFI?;9Z#4Y$=^WI0V0s@-gm{jLxuFDAZib^eYKz* ztOZ|&v|2E5(Dpika=hrdYNe)N0!J+T6Hz20__d;~q9}$D3+a?Rp`fa8^HZ5Gpn)tx zfGI;}g@lq22M`EGnGuZ6!q(3HBnlk~8mR;n%0)po7|WTS{_JN*s)U3L8~hH7Cf|b` zFR8`NmXM$Bx2l9!NqHwir-M?CLu?-k-$|KsuCB^M8Igj&I5DAWn)==OjI5>h+ln%` z{sM8sv2A21ZcHb{hbDL|IDY|^&X{5N#gF`)o;@k32n}bS5_7=^pUF`0zCxO#y@$uL7v zikQ?M?bSYuTiJnFgJ)_#knz_liRa>9^kbu_yrc9CwbDB8C6h;dN=G-U!DLC&#kte0 zqnCK(4cr_Zc^4^Usn-MCSXla_by_(}q$rU+~BGD_lqM;x96x&5foSkxGs zH4H}^@q1R;)Hlm7=)9jo@mKU#d*JEvRWa_jBz3fv+z~g}d9edqE<7R5K+~zgpApm4 z{2CCrsALFB5Em?9IqA^pP4_Q^n}|o4fuFZQ31oCLRhPy9p2>hM-oBAA-b=6avnCm) zxkxp$NWg`qR2$49m8x|>wD+=u&&pkDS9x86O-{d!M+9y z&xnxwcHGHzht3uH`2|kv#-*@zfx<~`(`Q82GwdYDr#RB({W7L|IEZVz5AqncmUr&5 zcNSlK-H)1l&YI{weZLl*5WxlrYQ;V(9ZPlt=Ywdd{ay_Ty=bWVi4UU%pbe-&=n@Gr zca{|K>S~_pt6RKb0Uk>(wU7a0=TA;RXaaH#l=)A|5hT>Ov5w$RC0LXixwDhfT89a) zxNm+M&%VStR_Zg1_Moh~L@`C6y_y4_fG*siTKS-wGA)6mh%{$^8ix4@N`gOiPI;YN zE8Jpt!ZwXLX^g5{w3ZM{g}17fG!G_SI|#*$J4 zsTBhGtYRpgmpyS6~To$AsiD_$;hFJh0Gd9U!wjhawi=sg5sJ zLg%jh%u!YudtL&w=!Oafm%dMPE#(&;8Hrg&UJHa^8_K&}o7c=+XS@|@Oyv>!KuMQW z{9`;qYuDK%beWL&g5H=|w9L^O6kehie2^vhj)fE$7&Dt?j9t0aXB0&VQ{x(L=tN4M zGgWegVAu>z4eeb8jOq*7L~+#iO=?lB+wXvLtR0#&HJqG^%;iMD>Ze%qQl4Gl~)-WPZBQ3}XsKrz( zCM zMw-i1S)Yb~TN#YR$1q?0K1(N2Vg6iZd&Cj}19L&Ms@hM9mbwCAy#Yl(qccg zG!8e_LcNSKb%1{9dCQVcLEgM0K@^YtT7a%aMKX!kCdx_b*t-(X;n~PSnJ97Q1z^h% z`wzvhL}Sp5hlI)<2oJN+kv{tF(GjTRc#11Zi? z0cMegp)5cjyatg@)XqI+3U4!%R)7CuiZvJ96mNl3vOqyV1Gdcp9CNht37yGur9mmz z30L3BKbL_s4GojDCI} zMZeBb1QG{&Wbe+Gh;f#7>?`-Gmg=_0tIlw%vXX(t5N)1{@px^ zL-y=}`%wQ=IKuyPH|?gq6gE@hTKoEpv=41584hisP%b&xa-@{s3*5qv93-qs7tT5- z++VqLlqy_XN!FHj&Yx7wMCGpY@>iM9L8GYG%0@vi%|tNHp2ouV4dVLn;7S*4f2F+S zAl@h7tQ0wX{qs8^z%?O0P>hGyS`ei@_XgXa$$)q=^X$eoy3(%k;<|FktwE#>)YOg+ z7@OG98@ksFWWeO*CD9-NkwDj8c&^5wWwCBGmy1nlheote1sWrcdrt{G{uYaFoO&^U zM5e(mjPZ?DhbL@$7Q>vm`@9IPQLx~UNBc!3%Gwj`&0ZAk6T9C*{Wx3H!*3(*^q7se zu)CmC{)uW_igTygBx_HP_=^)(a+ED=!d+q14VQ>V?VPePCtqYFJ) zAMOBbT%|x2UhL38_3zZ=-l(?FevV4&Y}3z07}G4m z9N1z`aAQCa17AJxBKcTp?A#;1AgPa;k23!842g!<2Eegu$RZJgO4Vv5M>s=q7?#MZ z`>%)CvvE*LOVeNm*UBg*7V^gs9fbs-t^lhYVkE4Ms*O`X7=Dc_|(${ z0srKKt_0@*U6w$I*ynjaMXWPdFa-+8bp0;Adf~$1cKy?J-G0bo&9(C`6MhZLu=yy< zlfLXz5;^j#3b5O4CtfgW<%3lyQ77M1bs*i{-GQQfvsb3ciPzosB0&H=vj%H-_tYm7?Rmy3gyy%c%ov=hzD^*;}q=N zi0{7wG)MlZz)_2L!*TQf04L*5Er|g|Q$g#*iXqP%*<0A{UhfZh{~8kGqqTAuq$L>p znISHp=Le(%;c)!poc^AoViyY(R5#;37ebO1VF;DeiP6$szO~YGkLDE<7V|FI{ILu) zkG1Q3E#mk7B}5M64c9Jp^Eb+`EJ9v)87W2Jpwy^Sw7l1dd(Z^iID_s_B}#t4jp@XH zCciHcb`!co6_#*}scJH<=dba8Nn@xHEo3OcQv-Ai&|qSF-0-sfyiv z+5w%m4Lw1}is%=V0J)+D%ZO{wp3F3VuO~<#PI)vVFSH78E*8VS{HOuTSe$0gL2I*C z=&Q0!nqvl`=3ixrFfV~droLILkQ)|#RqlZX5@k5#@0qs;sbKIwZiu?gqY|M+qgNVt zX3ULefFw1-+M~zKwWequ*3oy6h5>O3fc}C|N`)voP6CN0$5xiGr>roAe)u*J03T*Z z))OPGcRg;e%j~gIcuivSMQkK9 zPDwLliGGxlRj>9KbL2YbV##D^9sYYWeL*B#k#5lNA4b8BK$lDtY8DeyJb-`O(RRi9 zcZ;i?bcfvjG#?KXAv4%?XCw$Ys6XE~kF>WRf4ii1G^!bULM#$%30w-a2oh=-7w~us(CTo5-+cQ@a$NrzUDX?JWtJLT6>P*`9#3$(HkQ8-;2#5)VJp zRSntdm8EHGfTNWN~Em4u!38Ef?bCi(@qSwm(Rx@ke|atS`b%UGP!@X~#j5CKf*a zM$GKLX+gw_xct)5r_QI2h(>H&+_v(6PnR2>@@qGHL+)pw(?j^9tBJ`WG2wKDW>e?B zOX+C#zmsg8`U{Y{Lg#;ef)ZJ83&GF@P&CUR-{&3QU8QTsneZDv=%tRI>1b&gd3Yv3 zR}1~!UL^|i*_PuoiYO{jFlI@JY zwJsb(pUiR!Q5R}F7^Yu&E;q?g*N9P+hX=f6$yqGOYf9iP=`y0Dj}Fmj8Cs>hj)}VrXkf)WRB`V6U%{6Zqdi;uMg^wIbM(!V9A2fDd9CCNtGSfFXNC;#<2u z{f!bu|L}Y{3pFPmIgWemS-F*Q`v@4AbQ&RvKqteHB^0$H?)Su)oSHe2(ZgZ&I*b{1 zcwD}TIq8+a@XwW1?|apLqt=ucx1LuOZaI1{0jDW+>+W}Mv zk=!ltTP?QbkL-FffFV-))qW@6z^W{%7uLXyH4D-L4zHqU0AM$${`-B<8OjvvjCs~X z)2E)Npo!d3H24@7qF3zR_^;_4u50=jO%rB3GmR)UTZu=25S$ z82}01B8{2T;mblto7>$4^qB7l%iP4ob8}R*0Rkakk80Hx|xSr#{b>Z0=o~=d}cWS&S z0tsZYd!a;d+t{eC?XEk zCQV}MomJ)wGHM3~NhD{a_nVuM7wqTTNT7`9^#||U=%{Ziz<@BI>OTe-U1@a^ekvcF zMQ^`9yKg;%>dQ!cG;Y#U%?(LS9T(PKCz84v)}Szgp<|aeC2I620-n+J_4QzDdWvfE zKbDm(hq;XbKM-$cqJ8esvCH^wherkR73Yt zz8E0y|E@m&1uN8iu_?7&H=NHmJKlufIuFw<-JW+s*y?%irv=|{K{RH`%cUSS9i2na zX@c}WMMXuB%q#56-T7sHGJawO?IOW35p|PaIJ_4mseCvAKe1JQcqnHCG8mWk1pEGN z!l$fX9K}{I>cuw*CGuJQ35F4&NG5tym||1{UL|{DnXTUd$3D~38zOPj3}pw?pHmKr z`O@PbuTURy>yd~gh2}*>!bG(LH91vEl(^{@f)%m!d+rcL!7H*!jX~`}D4$=N8j|FN z8oA`V0}7#z*8A`AFp2BX`+(UOzuiQ?QM7Kok+6E%eL8GN3iNgyZi4aF+V_P3_nkez zjz7BI>|((T7H`<#Ebahy?0I_dD_$yvtn!*rk0cM+@n=Wil8XTqZLUsXw^8?+3_v&% z7deogqpmja24CWLDKdw=eO9<(7;LK~_IUr2?75CC7ShleI%gGe0_L&0N{7SJGK_kI z@wBsr3jTQxH8F@w{#QO(%796N5}d~3`)j{OboFkWMU~PRxot1=St^AoUI>dA z+RqYmJ`nA??2Wm9ioU$x4gOz(c9=RNNxnS#6%TPWRU?p-{Z}?qvaKZn@uTM`%dXC4^=N1ecw#%bq3|08_^ zo##&*67^@Pd(W)AA38ViCfE-T`$)iC-{04PSmJ}&<(L4saa(1J(g9$E5p+lwXEl^ z1!>|UTTigBJ&fO%5_wHxnV4?JOqm%2L?p!!=w*jlpn2)cBQ~YtHw7>~(EAe@53siG zVh)~J^lNZ)7LnP|Dmi6hkDg$I9dv6pSUMQuq3M=Z?KDNXWC&+N8teYo^(S0Z^m zpj{<9NOEPd_WsWO1Cd}KWPJ2ge>=(8`v)R97Jn27BxSiDVt=K_S(()>-iFC~87z1{ zq*+$(XkU3?esR}Sv*V9AeBXzB$G>bqF{C4~kG^x#Y}!I`J{Oj{dmUHaS7R^NKJu*%z{=&HGweVG< zBcgVrLlZ46<0t#NfXE_(4|`LZvVBkd3!Yt@%kHC0*Gi5IUn)}t-mv#Oy-A~$9(N&l z6Z1ehtN{1_v;dF7-|X~MVYB5IhnM7v37|Bb*%N<@mG&SbTMFez4RaAQ8C;;o8mNw? zFO^Uf98XB94FUq1hspgVgt2?A4f*XXY zaFM??asY{Zu=^f07L@8N(kQ_13{s~!Yi_pMfR|NDLmR*N#!38ic-JkJy|WPf3IcXG zL~hQB2l-SsUG?wr@dffoBc@sNf{12NQb}c?uOCUq*zq&UT}ibo_hAy7?gSrx(4hm= zG%71?1KtK4j=h}rrByl77>mUqz<|TYDvXf3y*Iszue%|hQRSj;wmf%nR_hVZo!Yd8 zuyUVN#qWQJo;rP6Cu=UCh>G~Fls+Nu~JlWIQ-p*S^o~;VxouAYzbiN%cu76$- z3Mf&qWg))L@~k@>hQ(SqjF82=IE4LZ+MGm<)vFkYtLb9GAGEMc)jqjy5RJ0Cf994S zss5WqLs3;!V;XnT0+c~ao4i%C5U+WzG^o|!vqx|}fW^#akF#7T&qzFT{d-BEb8aWNe1{m4_3O3qkO#E8LMd%hXsRb;H;_ z3;|Rqyz~Xdxx4%O`y=8SH*Au>qT-;TOV6(T5WW6*zdc%;y-kPk_J55#_xJY}YpKkp z&*!FmW47;uw(Z-N>&{EsUjOd0i&m^E8(Gt(L8^9MpSLF8x7y9M&#BF}A1lraPg&Vp z8kSey1m3NhA8|(FNn|S+jaGYDV9VfO;HYA5K_e5=)Jn#GP2wb(logf86j_sV6s z5T#R-LyY(lQa0f@2?s?4!Af^&sF>~FKO1Xq-pEGc$kgK&6!>IZvxhbN)sy()LD~7;C!jpbdE&4hu2BAQD&wF^IMIh6eKDD?n1nF(;WQ z;&WR3Ws70r5)Cx?(CUa`jE{{~pW^#vk+fv1U}F;}6bF+b#up#1SmQ>UKhDSsZZCu< z6fG9C&8ABfnExBSt;9&Srg)^*Cf`J?VG_0ix{R{5#6wuLzp7{NdY4iTSXf&uHKt^t zbR_9>cGq2uB=&ns_s}M-Qdl0Il2=+FtZx7q&QxM5BJnQou8-pk9$3`4dl^k;J_JjK(LY*@xa^_M3%#*CwCfpC313XY*RdWC4jm zr%KEsDg;TT51K4sba>&FK!?TP=4To?5~*D5qpHxgh4i#3K`67#5sqG4&;5{Ur*p$uV{jP+( zW{16f<}izU4_y)aN9F41NhXA`B9-Jpt)!yKeN^vt(iqI8?>?=mF<3l*o4J`%Y*g>M z5$Z_te}d&W&l2jK-oZLu;>uVWsJ)FF7&y3Qv|)g~k{xbYcs#n1mzLx{Z{4l!J=d(f zWLd%39p*6&=;TSY%C7nm7mkq;y-<_145HUz?9meP1bnGW#?&1r)tAgECk|AKW_{fd zLQnT?#b{0sc9rFUfR1mL--p^<53Oh`?AGjJDRyP*8Sx^e|Ls4r)`~3wV&|vlV}JV~&z~p?hdPa`+n{pqAmb82f{Bf1#AY zQ{Aodbts!eO5XG3pT&C+A-<5!gqU06nN1-(_-{+7N0x8)V}%AXm7w-?kMfl_@P z%+|g`9Cr`uTE2i{`XK*`V``|^P>?j{ZbOwfUDLV)EJ%BvK9&Shg-m_E@ZFtt{W}8z z$!y!AzU1nfwjB@VV_OfEuHKTfk05N0EQrF`ZngqykK90vu!s616ZOF#yw~4+?m!?h z;YTwB>94-HUoWqKi96ejjh|dZ{<~0cRzfue<&$C z&)kmDw*hf&ns?SZeSm<$XZk(=yW2uHS`i?YRz3Io$kc6Q*N0@|^Y1#Q`|9Q5dWN-$ zN*=Ca53(FQg9_tgo(dCKXaDA#$Q3L@FFt*xeDHAc9tx|~-6_pMWsy^nfSJ1jw!GcE znN|AhBthv?GI~nnoKl7O-wobvjZYM*+TN&`hNA+?ie*@eux&%T@aYMqOJI4B<48n{ z5*=xw0D}4 z*~}^ZLgOJysYw(JB6CO=myBCqcsvzr4prQ&_J|tm4^y2k?i$~Yo-qkO`0_^3lFnL^ zAhURRB!c0Lelr;tdiNm#PQ~3DrjS?}2OYc3bh%`sbnb@>tJTBeaM~3Eh0@^c(&oKo zctmKF6tx6(Y5Boxf_(%jl~01>dKjnA_ykNpSQJgdX-r(}6iq;CW-Bk|e+t2+Ms01n(eKq!cE;s}XU|_G_Uf;MoQW1a2rvo#2Q~GI9p1N01~U;lTeJYSQk(g@aS* zLWl>u%WwXZJfTKjiayzj5Xy9oURaG4REDt)|AYLwt*U%Z(J%O*Qt-^{W|RKP{Q|?J z_Ro`~RjT>4HY6dQ5p19qmdEl!FiqhiU{&-SjT+*KuVqws{T1r-tZQxL(ImpPy|Zs+ z>IXt5Dsfa_bU7$M30}undh$Z_EkWvMnmzrw(F%@^b4&FoS~f4b$WK>=4=_D zdS%PRoJ{fY3=z_V6Tj<>_a|3J{mK&|Tcf9B@A82hu{OQ{+E1Kcb#lgYU%Ze|bAP>` zg_CGl0CM8LU;kn3(H6#T3cZCR_{lNGEz?NYfu)lBJN51g*+qhF-6}2Wr6bgA!xEkS zafDQd1=pRaL!O{U$lmy?p{qaeYq`-jcw8uo4~!TBD`mJ$MJP;N z0KMfv*qy5A6no9{#o+o)%Dci~gg{*9>q6Dx)aU!u$pcCsAL#GBtn0NbBFhof@G$Z5 zeP%52)HeF=lMuFqdU=7iA}`k=eB&UeFE5CVe+{hC*3~_-{d}~20WkwV>xaJZsp(tq zho;_JUocnM2-x9TpzgIE?fzaai^z=~Q)mg_^V0{>?vx93?31JcUqlRISMc zsNf$h$wf}kc_xYj)RZp!a8>BNd-m^bA@!PzL&iKUF~h#XEX1UKevyAPsN(_oKPC9d zg7s#N3R#04Bje@<;>FzJMjV0<8p6X$pkWAy=jE3nExIE=a~aHmmmMAf-x8w}l!eE? z1(hRlqE*?|y$Qe0b@|I5^zs?@+lGAcM1Oo%70dEAHC+ zX_UD~Hv7m-h(?UDo2H$KAcvPz_j+K=6La`Fa%m`a2IqIew`cj=><%E?IIBF5Y;yvE zS3&y@%-DkGx9{=l@!BDdKA)feNL|d_?RF(paFdA~IT|U8y#^J|63bH{6Q};-=8%cy zh2TWb_TUnkh-Xm!xq*Zy&%DF^jod?BX&xpVO!NCzY>@?t$!m)dPVVrVHRT3YjDmca zk#PS?ceiQz(H-|ME@`A@o1AWh#66s_mI3p>9qY!=4HUy;7tMok@RnFY17-fUdi?+{ z3bfQ5PlWDiODJQEW0YY=F$(WcHL7P~4gmq`CkrEi-&Cx>8H?G(Dy0s4g>2MyRWoYp zD@d4E4r?CX(=LbHsP=@3#P7I|K&{1vu+jcrG@s9moA^(G$4nB?70ug<# z1HPWM4!a;;f4#F82wHXYwWld9t2FTN!1*&UApA8;eZ||Fu1A5G0-&q=zmF{k%^@s9 z;1!q>6d1Y${gLf%yd*E+TWl!wwD-BajMx3={%s#(opZAc0e7eBOhl|4l*=>w!qF!K zJ@PUqT*3#CViF>MA^-V?kWhRkP9Y++$8Ix?a}d;`RO#D4AMi3&8sCr!&;aGXju1AP3BY&}I1> zTPnqx^=LmHEj|(?Q|I|kR_F@t&vOmJ6u~{tG!M!go&t_f(gIz5qo5~pxZ zEh5F8Vq0iChx3ZLcV`KFpPA?AWPzscPkWBe4Ur zm+g{oNO!|MtzZxgCxI~4@{SNus+J_+Ne7psaCD`h&IzfuE=j+Q|4_qdBAkv{lf6^x zudFvBeSmBx}t=@w4PCBHeg8VN2Q@MRQ^m{*U(Q~9L4B^{sj4j^1 z7$i$tic0VePvbAVyGWu=i2@O7x_>XnC=077UC*uVn=iNigW&H^ZD5ju#ypmGUFW+- zDTB)46SEv|=LXSj1Q)kKf|liMg#Zo~OgxvKn`?&%E)P|`QGXi{W;PJlMJNsbV6xyh zcDh+&5w;l3u>&+uka7r(B2^qfJXQ+!91pyxSg{sCOz^l0Mp-xK8yXTR6BK$VzqOw{ zgrVFhC#vdSGA&N|>ZaB0%K{?PIt*S)BfkJy{}X>}Ds{3|RH^IP$A@Camia1OdxHtI#c|KU7YUgd@XW;`#hiW^-F{JzN zK$n+}oZes2wE0^8_|nqC0g|HnL~MP2Y#o7&x|lqN9Uz&@<<3_YTH_UB z*tj<+8|@!Hk1MF>aMK59Y3+vDuKTHLn|!RRhp${%we6sfpSQs+gkq&Lowm=es~ye8 zi!OU#f{PG;lg9Mxo~DMc8(lmwZiK~R4Q#-;v*fsN_^yZ$hAFf{=0RM&Qq1&KC8qRi zgd&A*Mlc8u+8ebjHQUo#?SfkasTSvO9Qb1lGJBw@-W0(j#l6$e@@fv@&&GJgle{H` znG0y*l=8p(yX6|GwJ;88LmB;+krRvop%cS+s8;Z)F(Tq5gXVZAnuE>w)Nd^rd>m>d zTdC%h!WGZB;|>(RBTaj})i*->&u6zZ9!0ZHABD;<8X072zxs^-H>0!a!i%xy!84rZuR%m+;_L1bUc?MViDV}6beU!knPrn8)DQSl>YoOo z@}$+2H2k_Htn9(WLADWd8T#V8s81t2xZO!*7JS_)QX zSA(;I$C2<3{==c0Hb@Fki$Y7@`-ssZ34p`P^6J>%C!u&r{y_k~_7{7nVd?Tvly2XN-SZ?RGns?4Q#ImaX@Tj7_Uc@DTU9z0+{*6g!C`cdh>M>|rJY^FHe6 z(N#nSEV{R;8*%#1;@ebgMU~ygCUj+s1J?%cyRWPB%dK}A)(J}aY)gAU8}-p~i@1zb zJD$Mzd4phFmZT+n`5IgVi3muDvXW&p%IUF@en6dcv6gq_cFvKaYTU2?a7${HHib+S z9NUSgxP--sj{NHrO^5>djTnJPgfxF=#h#=vBk5w4o`Fyw|EUCC)cKuNHR5qwyWj7# zd`x1na6&2@IU9#kV=et;4<(-tagvU6zZDT_J5f8s2@N0oGl)`7G=|>^PF*pw^Jj`j z`mDvJr^Yo`9L^up?Ew5;OmbLUF_9U{nw+gDZIF5vkVT`z5_exaM(?SC`T+$Bt~twI z$o;2v{gvXS-R5#*>icNQ{jwiFb<&`obOXxfiU(;)wAr7|b?3gOi=Dm@1`QQ7h%bD4 z=iYY*Q2qFy;}sP6&@Vj3_wOd!ae{Tp?&TnvZ|@AGIT`$#bMC%^C%iyvb{`z<_X|d5 z=Dx34NarS8mAhyu5-^Cx0B7*0y=}DT^CCdY<=I{ej#k(G&jsN>My<{wdV!J!ai8yV zn#8Dxkfndcq&cDqYTzBM(`ob^W5K^|Rch7?LTyW>NcaCIH?=TfQ2PIGbyAo0-CO#&TjV%G=}(-$zT&v(4a4h!j^kPMzJ} zBi8Xu8jP-S!nobxDrO`8EaSvD)Evcd|7K{?es0s<3Ni>XEfTCsfN?r9`TBDc+kF7t zk4@M7Ioq}#Zpq=_7=ndAZj=zztD(*?5w27~nm|grAhU*tx!kwBX*P$rK4_KR9uwLqTsK>j$bCtviqA z%DNkD8hJ26-XP%>;U+OV-Uaec9wg&PNxHwYQ?a#Oq=uWO>f+gH9oAex!yq$` zp1>bCu|=jT*7?0i;!$KNEiRH6;FY>lmyMzWDT1;@8PTyMKcM`D@S*a7UO2w(CUN)*sKI(XV-ySc%B&uI#cM$8_d(4>+q$~Qub^EN|erecfX=%BO zF5XkKU$8Gb-)umllhzj6!C?@|R^I0c1O-=zElQgp@4BVw>TTQlu=xUm+fDI2*@4jH zwl6wuu2+YkSR0bB$^?qtnlk758ZI#ZdywvedcK5tyVgRNw8JhE5dNGIRd2tL3_LM+ z(P>OJDeF1irNThu?X}xh$DiL1Sd!i&$4=3k#)1M{q>hb~0m9jKMTW@WQFzX2Hoqo+ zey^E-{#{6$OV@KrGn(60qj16Gj+Df_Z&{p!Q4?XTUIV!* zI_Y+?9bjW#*g^q?zy5CzS_k|7%qfCNxOv(Hq~c>|Pg0^kF0hw_?|Yu{nj z2Bw0*KwYIoO%x57;=#2OlrJv&@KzBeWctl4B1BBCbz{+yHVS##AQv zwN&N%Vsec}=t~ngt39Cnb>aY@sCo!uEI4M(pCq+2XNu(CjB3S2$y||5^(&fs^p?M` z$t-1>)f%V6!rZeQT%b@30F^9;g#rJMrf-Um!+W1@V>dQ8w%Irv+qP{sHX3VV+ewqg zwryLD%{SlA|NUL;_3mEGIdkTjXC{5o{5NuY?IHoP2skA%!_WaYiB~@^(*5>i^-(ms z%I+}|J>CF09p@3w3r6-T41!m7i{w}@k_c6(1#U&4=w)u;1=8zG`LF!m+)Wk0Ji`LU%-Xy&{^teYS|T8R?^c0K zl{rA?I~E^WiM!==XLMXEz-!;D(teJ;w76b|9ir^29|S)NE^iSOprJM0-yfxUB-Gmh zx`(=QhNPn=4;$d@2f&#pPi9ll^bVc~o|`4f2#4=$#$?H%xn&~vYa<{Vb^qWSGnaNi z(ScGjs8T}jb$}s(;rf2Rjh;0+EfwLDfUAnpC>YE%&*r&;UN2m$X>g3#gF89`Hj>Nz zLywL>HC+@nyPQs+2d)GTWc5prpO*KJMjgo1BD;WDN#j6D8wKaaqR1jUfXmxd^AeV; zXb$39xaKm!sEcHL0^8S!a^1Obw-YhUJ=6@RrJtsap*cp8RD&5NV2~@`>)1F?mcE7`L^JPI?{dd7^mHcAp9*q$kg`d5)^A@7Ad~A zs}u)s)2}mOi*{e5c$`exEs~rAxyqrg7gVlR_k2r6y$!E(ogc#SQhM7iMRdOD?GuUbX7fIi+XDPJ_C^nKwLzaZ)EyY-o+Qf2X_ zjFr(!IVBeP{8kn!ESCx^ko83~wt?~G7##HL@n;}4Ar#=0yS01Cxo#<4?0D@Ubo+aj?;-w9lqg-lF zb<^@4H6xe@;L>E<;sRg_0H^Cw2PKX53a?E^2zTEA-J?m()eMa&!%3{VTf#9)^C|mj zWa9?V^^I(C^{N{0A(BK33<`?=>M>WsX>mUpDv1r1VjCY4l~*$Gbds26Ip=C6!md)4Y3uH569c z@$OhLb1lpyCg4j8$lC~5>aZgU``azx&5eBQ!0?xsSp&+xr5rZa)d+xI0GMIb(cZhX z|2ckPl>+`nq~|zgXMM)6L)xHRHXz1=GQ}&XH;uI0pOu1st{pYJv&U&F6d{Dx@YfF~ zQX<`KM=%VHoiW=59@EpH{L^$X2J31Rt{x{Ab1{XX#Uv9~iAb(xxq^tmJ{!gj-9F1T zu{ZF6@u)WgYDcvHNdu^MB;vs1!Z6fdB&ldvAmckT7}*-2MD++ChSTTqfk%fLUjIS$ z5tJ1q;B}+hV3#?{&PwH)d|;WRo2<*6Ku7G7i`j6j)P9 zG(1w(V~T+M`-GXA6ScfzXnN~~DaDa*ya(^bJ8+LpON<69y$Yv8aQI#n1SQA#V zgJfRqmpCz{g3ukrp7pFtAU0TlL@_xaCG=Xdqs&!|=Gxm*wga(|uI5l2O_3TTo4k2T zSjth(ps`$plDLF*qq+aD2STo^3O zJwDFTzz9rH>?SCLzBt~d2n2;|g+ymYvO%fYON1{5RtB8&EokIX5l=BejptjP5<@}J z`ur)(V=nEbH`nPT<)&)fD{ zsVOUSU%bZp=JwUV@c=@fympeI|Ids~_w_=;)W$QqpS$`9sVUkP8?s>#HNWd0aqu8& zw>kT%UF13iu;a_DFCEy%4bu%V3*iKir;zP=!7q z+;KY#TwMsck}DGiBOBXlmqq;s;H29mbg}dlDOVpaPqxcJR6i56qXmwK=|X+*<~?Iu8E0u ziLK-Y2+jR&Uq6p;t>mI9UPzRQKe(X<&qZh@HVPm-bu6%U_P&*zC}07h7ZY9?N-9Yezd|&070jsLlu01X zSW!oT#qmr2$L@#y2g?LO!6H(EEOUj;4h%-Tq$V%;8aY}c)1%Vk@+M#RF9Vs!WjH_= z5O+z71COH)rAZhrTB9Gf!g~s_uF(+eHf&~GDD>dlRbN(wl7He)r#q5`APSG7wbjr| zu0R?znm?k;vo4to7z>g2&Z8y#a|fepK_T?D?r^@(lmwqApWLFcp7{ZGAfq^0;a}0S zs&~de>{)6Fv(t=EH6khg#e zk}Q|Xfwa-SmV27f4RzP2@!sumy*S2-`&o-ZI?5u#=E3$Ajum+b3wI!RjiQ6Jq)TB! z+xst8XbQXE!|acdxqq6DrL52n9iGTC@{S?3X4bL8LFFF1_I6VrI8sJnV{g4G_|hN4 z1ze=5K-{2Gb1Q|qvEC1kb6a>#zB)FLfMFQJJP04cEcqYp z{e7()+^0}ZQK1Zz*?H+}_gUi?=(8(nCZB1rq)eHnQpAQ+H^~x3GSOLr&>+E5Yi0W> z^9iZSo1JhQ?@OAOg!7J?gnX6&8!Q8P*3ch{JR@s5`uHS`^M!tYpaol6?t(Sbj7sQp zoP?DpmgH$xQjBIIQ3jx1v1*2@!MUF!TfbouC!(oX9w;O;%0lkd-``rs-&dN4Mc_lH zh^N6Wv#Y4g95;iF=7>82qXDM1_EEG5(gF-(=i`oQ8ESzNbi4r|D;6qb&SV#*3jO=u z$_eltu7(FEOE*C5!qWt_i3h z5N^-{q+FP>2WzfukZ{KSjdwj+Vo`D_c0@l{cQa}-O|qM1q#E@f9HMR*rLo|ugshl_6{i8)mBQmxG5!sLW&4vHprvRT0*4)p^Y5S`3ic>0_Qyxz zO62aDCkS$p?n8@}ad&Zo1B-U>lYvPlC6_LMIoo06m+U)GD7yVFz&Q&FGCowe4-?xM zhC=kWNdmtdX;unn z*Sgd3HdHp0so!usCB|B|5wZbCm~~Wvjr}7R3y6{?oCir@X7Bi%NBi*SpO*k~B4T%5 zH;ZU(fsTGt`>nzICEJ}XbApskg`209VX3-Av>9YA?PZj_++9pY3xP0LA##WPWt@*S zte84)&meI1^CKT;9DT0J^=DV?JNz&?`2x?x>F*N+9Jnwfnj1l~CKlnKQBtG47#@Wh zY<#=vVqC6yZkv*BbTCz*YMtU$erbRKIx{hcsarmZYHZK-UX9cErHWlgfsra=b)Erf zmDvc!GtcWdcZ{5Efi)h&B5k`G?>U@NgKRu!i`C!SMOJ)1UF0m1^6iH1ixfj&J|{m- zCpEZCo)gadXw?Br} z#&Z&--0JnIoNV+Qz1Ffm>D8>mS-&%x?;Q)uTyA&=_m8m|c?Zc(zTn9`=ni=Tp_kw^ z&NNca?S8|izUeA3Frq9oL^4Mqtl-^F{Hx~S&@;d(@s&$H1&BK3Ny1H2I2N22b`RgG zaEfa6A{5~{Y5XYAy}I>AU*kC>Kbw{fEXclO@`PPK{yGRA@qm!9Cork2zILauXk}4B zNzG*@(xbAb^wo3K~vP2`-AU*&$H-MARA;#|5NhWsI zD3HKT{>3h53JNzbcf_r!zTc8YD)2??+v|JY>YML!=p{Qa*#aF6QHzLD5u+#Hq*N;| z4!4a|1J+VqjeL;=Cy*Fb$ZD)&QCw)^V~Jh9Yz=07)VGrn$?LHEfF{UiHSwdC;1+_v57 zQmppG6v)xiOWv*m*Hk@RR_RPbRQX3^SF@((5{WDv3N#RkmC_JB9}$6PI;m^W!pAZS z&l2Q>$!s_^2{GU`Q1O|2C6kW3zjs>c(Z*%nLHeNWc#No27dh4wWD-^>+AumaC=QWy z?#}Y&_ad$AwqQwpDG1JK>kcmS-Pn8=3#KAgCV(OnnwB|@Bs1Hm}9hK z`r3RGiMfOX1|6#bg%{A!hw1m+4WZgN=+{bpbmXSx_1?YVDat;MoPlN=1AiFBzyzPE? zR+po@_Hx*JF8tZ{2Q83M38P8F*B&VcF*F-I6*K=Mce}vZ8|VR%5&Q?br)uJ?e%;@9 zVb+x{Q}Kv=6AkiC&t6zRbtoI+iOVERfi4ub%K6{hd*c)pgYDq*5@zn-;7_w*jDq>M z_nyavm1`R2O++<6U%GC-)~B5htNnIv{;rQ#Y`r8>Us8)z5=;$#VJ`|ylGE3c-!ze@ zl1OSKKY|?ZD{h)QJtNd{pLa;Tf^AN?jDEd9M*b__AMH$LppYNc7>!%IVonUUIK?01 z$EngSJ+d$mXvH2zE`dj+V=G#XT1PVih=qaRz^JL0jESkd!}_x#&DX1&8@Zu!rOUP1 z5vTt~LHYAVkHb8A@+dz&0Ysg5I{O%)qh<*loAwG+gOMuYlT(3C8!HAyJF^wB8r9_7 zsd>(K+G#QeST zyQ4@Yfb7NNO0%s-d@XtD=$n=uO5&ze02FhC9xu5u%U0j`N;VzJrP>bt_`hE%7j?(u z&9(c`hy^odOr;wC#8htf3E|=i2$naPOf(3!FK&-t;(AQL=ePTrSB5R}lD?|u=rcEn zwS;^O3=Jb!R$lnnP}u|FaFrB^y3Hn?*(?;uC;$yRbcr}r*^&TlXAusBJ0R@fGy%5M z4@7u%xdR)<&`cUyqbg7}Z9ZtDDS8ntF#A3nl885!fUuTp%U}(2sFU`Q`4(jAxrggfPwHh8cll^sk4coc}@!VDtry!$S=4gfUr!HB+Bq zk%MdSPwQ3%1{Sg~IrXf$zkD0NDhp|G!frg9(o8p(Q7EEsrgun60)v*n(K}8yY?#ow z;3v>-AXH-MHC6PiQ5t@gt?wy`P=|tzk+U`9UX}j=dPwc~f&S{G{{@|Q?;7oAX(P4) z&Mo`2ky9kiUn!=)<0}nu#u_uSIV)=h zFcyP2KK>?OPF$uMBB@E80dXRsN^|d2W&4j>`a004_=P~cTs|C_n9mI)MG8W8fXGzS zK%gmRD2ktuBnTogibyYsz@q_rD`lgG7vME}70h~QZWW$UVYn2=b@&(JQ%j0}@_u6Y zV0FFQdj)yv6sg^7!9KmAGkZAc&*nxz|2{NGGH9(l@*&jhiVDrzo;4z>vU%~ejVdtM z`82=W2qJH*zU|!7dd-}hdQJa%iPKI5A&5#QDrrJB5@{Oc)gN(QxUa&kR0bF-lqSi#j$TQF&v>BZ|18~bJiQW=rFuOGmCLz5r1cZ|byBnNBj zNCD5Rr}8}6t+0_1Z!Zs^Qo!`N;P-*ftf7Rx_7e0m`WJP~;e`FFXh)1Ec*fI$^l7-Qu9#3hB%5GWL0d zJQfhUMTR$Lhb{N#DB;orSQCcFXV|3EKK!rDwv?l+*=8KA$xA|qhr2i)9(R71q#r(X zSN)&rMrt=&Z9RO!IApgtNdQ9Jj7ubxYy8IvZHvGZg& z*t5UtwO@%OPwoyw+1$FAj#(0tmV)JV3A^=iry(kwijCV1 zCH3cYKt--L3izbaDte|krKFwQdF0Et~ zq{GpL+oI<2(?B$#y0#aN_RTSFCG3FMwPozwNQtwb)FWcYg4OhDd2an(`!oGzRW%fv zwYVWg3u2_`;?Uk8RlJ0T4?)vQ&*vm$pXDtMy);XMj#^2{n-d0^PDx&CQR?V<>k0jH zf8F}6+wa!hW6Rwy*uQ|5{REEI`z$^pv05@76655PCzR9n_4`7FclM&`$3LT}WYy>;Njeew7VzjWkV{o1%GFEQF zzClbVd_Id38~`<}k15Jst9~x&9I*6=sKM6s4%>6DJI1U>k&gQX-u$m8$5~!@fyVxAFyRCNgb^#6SC| z*iYC4o>yl1_+y%@5V-(LTX-!{oeL70fB$4`aueLaO81%5p0o2|R8=pIL`}^i&q6|t z*;L;GsGQacu5}g0sQ&hLWR}@tJe(%Q)d_p~%OY{N0dbLvqIPROv*VT{4$6Ax4#m{% zmZg3P8qaw{`$4+|x9_VK@^A-l(p>+X**4hRTqH7T>FM?t-v#4N!0gko*o5)F;IaCV zLaxyOBBqw6px6*YRi~HVb+iE)OCb@D&$Abj3~ys4Pif@`VTAsT1%n5v+Sy(=-;xP2 zr3ZroUt{3czT8zM>z?KV&nHPMmBe1e!GbkQSJ%I^E;`+Z8FM%pbRccPY{4CEo=QUk zZo?XH1v;9?D(Z?BnH4B%=5mu%yLBx}pzQwS8K8ogc2tS){KvO!dvg% zacQR=vjw`Ti&B0YOd^gCXPtmBoBop>?)#*XnN%cOMTAr#(KfqUEz_kO_dV^;aM9mq zb{b@SHm#diW|%hi$H{6^-if`>eJq&GtL)1+J1-JsW1ukTa>eeyl^`k_aPjabp|#Dl_}Q6{iwdxM~@-9Fw+xw>nT}nP=+H+ArmAHmC)*f zwTkM9TZXej7okc;g&bH+fque;c%1^=(mHL9+Oq;loFbeD5KHZijwdfl2U1FDG^{pC zAGc@4i53b{o@wO~C_2UF(CzvN4=BkT; z>cnXKH}p8a+pNoIEBuzw>~Ec3Wo%7fVMq;V%5*SgC81=k6dXmEX^NjeqJXsZAT8pp zwi%JmABh_5|LpQK?mg4|grXcw+s7Ik+19Mj8(6KewPP(Eu{dis4frY@ZQ3VFk86&@ z{!$-4V)aJX_P}>2>pUXPqqFaAqWQ!ajJr{KXe*ESOJ*#lQw8%Pl){M)H%chYij_+3 z^nc6j_Qcyp{ht@0Xe_naX#-|&txijD&K1)!Qn)NKyc7V*hUyW)KT$kA%|w%VUoIpQ zx5y0w68c@ErV?=tJmebq?AzGg)k?!Dp_oSN(oler2B7g9vThbq!JDC<%K#X+ELH>- zj1_ub?Xj|b3{!*5!2bqH^7h=mDyX--P%Aq3YxdJ;-3|_hN7d-`$m0uv$>8nPye|`Y zb7h-!`IGK2@H_mHo$H1sJiea88*TC9-8sMuDDIlTsG6xl0|wP&#;_@iUHj9v##oMw zac-ybKU4h^zu4Ki>@On2 z{mnw^aR|C;@Kfb_J@%LP9cgK0{F1nK{D0UszIAtyc47k5PeX%FknIsK*$tFIy$fGd zuY>=b`)kn$S8qw83!oC2CYXg<2$w`+fJwdX`4khGbDp!k@{Ki!XqmsyZN{M<`VXRc zRJTgPtn)W&WLO8SzCr|D@T0#Z*Y_kB@j^-aqCeWlOqaj6@0gKE~84sRln@13oxd7X*H2SE^AsE zj|cudlx__?WlYEL^F}i5JNx%h?QhZoLzH?SxT&9WIS1fB{6Gam@NE{-jsGDq zWDjWDGU6(uMaCH%!4|=kjH<)L2^K&sT$oo;qaM7NnJXE6(o{%sKaa90(XVxiMC3e2 z?qKVjx(vKeQse>%(;_NTjyR(mpANEB@A2ePl1KlH_Bz$SL}8;4F$qEj$KYe5vKSl3 zQ=tHf<>ORQ29_EP@}LRN4uaX=UW+0u;g*Pz)4C`cQ8`GO&Z8>L(ch*l?yXy@+C`)8 zoaI!y{SX$Cyh}-wZ(g||-Uz;<$NjxkI@e+D%Hq46c&BR&&J=r-Ol5!?t~Ko?y~nNy z2eql7X%#xFgbbQVB=CZo0b}>URsD^5j}sqRhTx!DJ8+**rTG*V=N-fhep<-_4P>@l zE~~yxJCyb|JW>>^9}F7s$z+&h88|jo1^MXS3MGMl+;C22dGjk5R%x$n8ju3d0XX{4Z_>Q{K0osL`T-sJWWZx+bDF_sD(*VH zdUJz|Ozy_eRlBB2{|UqcO5Zy!c6$0Uc(0s5u;V;l2j{_GrxiLDu?7doNN~QFoL$4$ zL|l_;zvQm2x*UUvR*rAaVrdxLDcZ58Zl?6BTaNM~e{ft86y>4q=>PlYY={cFhtJ2K z4*niZIq(?d4(E6M%6W`Iz4AQ68YrK44k;IH5GCPFb=4Bpo6JWEVaNura?kMigz5J> z8A<=+ZIs)vehEzZ3NsA}Mrk&M-ozS@Eil-`0!?Dv5oUWbLiwsQk^GTe{5Znl^UKwu z0XjgR_+}_kzn@D5+Z~>XfIjQy@y@n@lJPQB7>yaRteu@B05|<=Y-=5Y(W$EuUr1Y7 z+uH`_r-Dpb2x)5FLIzAsCq3L%w~QX*e{N%&)71eazUzva$0&oY=LKFc^qyvknDEgB zCq4w;MF}@}2Ti(mUMjFwG8XZs1fEFmmKI?| zx%Efe-y;pxHFl=>@k`9ak|>}_Mxqqjhgag|5=f-29$Y@BFnqJKr1@MY-IloH*&j)g zIbsn-ef4Q@XorZ@ohakd zu=p6Hr|9#uHh1(Y>zn0dAp?!65--5qPTFC`Z%QKMV^-&d__B}L9>70B6VvO>;|)?j zHyE?SRp9^_^nCaO5g?bt-F@rH?-PGJ0SPcOA%R>C`=0z*nPS$b0lBJ$wlsQaI!Eyx zM_dFP+^a;>9IPDWRrYI?e|yj3FLJ}h%{f?e0W{&jnE#4y0nq}sHWrl7=#DaF!e}8o zg4oHHh1rX&ZVwMkG5)lHXm*;lt`9Vz0Js6~9V*FZ88VlpKfu*_uUM;Z9YSPY(dbf{ zP<9?6v3caE?d1Jlo6|NlkosO#2kT^4d0&x|znz>sx{Y5k@&pXRzE6#3;&Hi`JN{uC z96-n$XbdZLzBTJxsBpN95ELDF6(Q6Skf}|kI>00QF13A8l|b|s zgT{N)G91n0Gzax|YOEZZf%WCR;~xMQ$MZc07s>WA>kSzMp)=l8{XYgrSi{)QIw{p=frR080EBZR0GkAXw7#j_mu#@97w zo0n>Gg`QH68APK2JEQOe0=}QvgR$y-AVjZ=_>KfqZck1_ddhE$;7VECnjd>f2~uhgSC)xR?9-$aQpL=6fHOXDM}@TdX6>jCoFR8lMPtfF83H z(0{^#JzpddtEQ+V#AX;me5s-EmM9at5W2sjN}Cg-xl#MBslcG@{SU$c#%0YenP zbDf|jWyWGK=&$txqFUWZ9o8v2)Ajmu`|n?U>6pM=M@kaD{m6$^dH0-2zVq>aLg5cH79RcRXCk?uMjLf56p_KsEC~uEr#Sm zh|ZRo`G#k=jpziyRLZk++*YI2Z$Hd_)xT1;@iGTCN>RBi#J4+rysLK>gVmt&&Wu=uJUF=s2S!O1<{bJI znwcBcOqD0b%OKk4gqo7 z{l{5muXC_#9E+UoonA2UyKKti?&H^2Z}yMck7eWb$5U6aSA_-E-Xd@~zm)5bBqc!f z-`}SaS7i4#>_$x@mLr9m^C)wk{-zfZ$R~?gn;|>GOFy+T_XUzCVTN_feXh%&xjRTq z@=R{PU<1UoYcan+kd^`2#*Z@`h9)8W9`I|@u17xaiLPe4-Y##t!#a%_Y<(Uf`e-Y! zCWh)S9jPMO_$A=JfuH@cjkX33VD{M9DP@j2%sr7Lj9#ZD#-!l=#5qmB@VP8t0H*DL zSsB07Pe^3J9--z@rjHFs=NHz0j%LQ+9YZroi*~VFzTrzjE;1pae5c7(ItHh1wMNA$ zj~Gq{MG(smbY*vpfhw+BuRSB6b<}_d{(dCCp1o{#c8)&#Gj|gb?ovu_3y5cD&4n4~ zpO=$L5y?mIM`RbhduMiVWAfTPm3d*o=-K9ZIepTl=iu3RjCnx&H)lo6&3LQ!++A`{ zo@WX^#|6KFw)EZUW~tS&_PW}TRbU|SNh3R=!j(pNO~p+p>S?x<`b`L!?RPD>9f=Jf zFCrCDi$I?Z>!lOqW#t1{TZO|cdD#`RDP0FeTUZNZF_L|B=MK)xO!Rg)TJ$PGfxn6= zpOHtnJyhL3-Gp9t8T48w$FQnV4lJaCH6~t4!_tu<9`YSsc?!ys)bI&-%sJ3TPRi#S zQbt_T2V-o&m1;{RPD_7ceV@rR(8e7CGCl6^e=BPpnX7m~J#JC*fIO5i?3Y?j6@=gr zCohSqn(-@&1?`Ma8{GYh(4&$zv~@;wlj249*wa~q&+LLF;sX1dLwH>myV+x}ZxvCF zUj0Wotez}k{kzi68>;R#RNr`&^-f>xpc~0Lq5X|%u&&r`Fc|mW=`-$2pIn2ZCx6;x zg=e0}tu6V@-flMxoQG{BHcz)7!Flk8omOE+n)wc68dTjWz2k=Sng=EqXv7?1ZCk_x zP=+FgfICw`O|C>h6z!i7nzHfO?5^Ir6aFciOal+M;8x?12F-)_%~}8ZEPj@n+Fnj@ z+60#``M_hSXQR%7YjPrs0Er^;S=fP>kd-i+Dl*VwaAJets;tWaSt=Y#pU&BD$$+`X=W}38~rU{ob?bYk$e2!?bz)Kv;%f@F@8f6a|=Yw|2Q2 z8tBD2qC9-*l#scudqMz3N1>AgmNA?`GFu{YCc%cU%J07JVsunybmx$5P@{}Rsc_FS zUS5M8c&We@XS4J0N6a@5l(xcZ_m{ z9FzikY`<8#;G-WhUn)(J!%pqAC(AJ2DTTAhHR!1H{VXG~@Ef6l8LQjNQuB0YICO!T zUp4OeyrJ%MfJ+lxmTfNyz$K5zTUXLlJfH4Yl-o%2Gq=|b%Xs-JvF1oQnUcVm`NX*{ zv%phki@fe12$Dey(4?>e!GL5#FADM z+ZHsDvFh^%eX0Qk>OThBi#Hsb&s#G&?B|yk&IdQ906c@*6?kt0ZSHd7uMO!y1Q^qh z@CHTTW*Z@PoJy8iO8U$9=7J(6#IHFiwYS6AUf!s;;KV$2cOHalxr{{g{W!(Cn^#n0 z>Z^`Bv}?Yg?MjSPW&#-y*;Pl&Dr_TyRK%3&^!np*b6|UyAA0fIsEL5K-1ogs=X0PC z?W@9F1XR`E_2spaM&^)W=G%!`Bm2>F7{d)pi?hl;)3x$nMj1C$dg{u}7rn&xBve7wFRQ`CSoH^y_9PD73*ywk z-UpD@6*Q4TBjxZ39Gp+8`X0Z=+-zGK3ZDY~ppM%*CquuU7-~<0bpT0q4Z{$71}BFF z>P((+mjhELjoEtiS^}?&GYA9wLIV^OVU%xs*HeDk`tJk!5YFq-q}pr$m5%SsmnrMC zIE8Gz%wOip^H083>+kOO1m|)$*Cgq|yA#P!u~YL+*mgcyz$3HP&Ud&);0=(Gdrv4G zYUnDZtRT+dFH0|N&D^r2$T9Wm00I8kt66?XYDWPJoLA%~->qn18^7tH7E=5PO~Cx6 zmN_)KvST%cGeNN#==wPup+r<~|*D;4)g&kG7x z=5U;d&Lg>p*!Y4l{fGuF8uCskou2WJ%>Y15bk7Sc&gzfp3m-2HnMTcl<5P`%I*j{4Bkkbf%(9r}<9jgJp*j6^|V3 z^@h-BS2xw6;+y2zaz_+UMz9U`Q^&Zbb<)=pdo#6GbF`X zJ&4?iO;uU2MEJt32oMF#5|pRmFv)OTF$l|8udP^~ZNImR7(^4GdtRRtxZY>LrQ0Y$ zl2oMOPFo>|w4h!uBO@DVq7D%o4_Opx>ebM@7++C7Mg^0GNFD1P?A>sL6pyI3T<@N{ z-({lxhd5~#@)sOPON>0;lSG<)(?f5L*Mm^}E3k<)kUYV~)^Bt}tL}R^_e>_mAQ^${ zGPZcr5J^!tFSQ6gcAEJ-gw7}g_WdZNM;EB_mGhH8TP$Or(`Rl8HX+8rIo^&cJI|IJPuxSQyYyS_xatoE>>a$m3R%G zu~Qz2xYoh-Qa+r{9KGzaq1YJ~0`De_9biTy8oM>+b^o2gtrDK2i|NpwgrH{7+*i+~ zjG~p;o40Zw*8D{jfWvQAj#SuH0i?a%le?b5ebJO?qyHP;Y@s(l1D>3^wUz3B3Dqy$ z2Xo-oxiaW?jwj0V2WVQE{pqZm?7Q>>MgJpB0u+mC z$r-|>&gStWh;3ES(kxS;G#yuEG)i9+V1{ShsLK#;_2}aWedNNulrHykEeKf~@Wl=u zUjU)m&Slvc1#yx|P$np+5nQ4lMHX6e!@<9@eFCxcf5nS?)xP%5@m^gMneCmYskUr> z0m{@trdY=OSHEyw{IBe6rVsLPO{>I3%TaTvk7(Q(g5Q#JQ)(HVi@(cJ*?{9jxZL z3zN9nK3r*Ld52pWRpMc84>`w9C65zaPuRz3=4)Q7JSmI@m^qE?ib;iM&$VS0$1Uzy ze58Olw@w9VG&5NCb3lFH9)^*dl3Ai2}lZ6u)4FqQ^)F`*?t`hajDApH} z>cM+x->HCF64EDXs@(0X57xj-0!k61DSRPFuaIXWdR+9XUMmJ_9k1^e|CF$#K zx4_C>UB(xe9IsZ?fkYPEzm?-^KrI?ZM>d}lmhDiy8OXrNM7*%a!N7f}({?#3$>5ko z8dHe88<(XvGEr?Z14DN6F5Q{qIP68L6Exx68}LwsG6%E6%r?Vylb})zyIKw=IUCbJ zx!?{>={*unLy+^VHX$w)4S+Bat}$k=kj>s&*d-A0n}sMSvYxZz2Rj}kt%W5CZb&r= znY;;SA1Rx%sZ2z0%D+9*(d=#+haXgsiD^tdC$Jvy0bo=ps%CRO**=;rzUte@wNuc4 zceYx(4zWJAX=GgkTRC@UI@X>}CvmsZI@CYekb|S)2zj8)nUNf%41&6uhR_2b8&{<5 zd4f5$ZhhbPynMd?gBd|PZ{_1~7eaZY-(^4>m(TPrssl#$TE=z6MrcMyWUj)vpiH7` z7;Rsp?2C>(2d9%qrNl?ofBIJr)c^d`KonV`=uE>gELU*>pPn!CmuUudn|_Se%q`&{v>*p{^Zz8EQuhY=1_{G>2K

B5#XBQzY(qWK0uk|zeU~Z_$y+HCIzh(zQnlW@sRsNGdOv^#4JMailKW% z_a}IohYkRk8p5WFpR$HQB~T6jX;UHnRKF zx<%jB^2?72RqyRNv&_u7{c!?}JY{rW z&+uc1e@UD@>LZs0NlGL$z={SVRpvLW9BrAjPma%^ZxEi|^yoJol<4Mp^cf3!1uT(F zRK>hYG${U}A^xJKJC}YLfFdHhWTd91x$dM>?_Zn~j-h*!Vz=&!4+MtPns{%l_d$>;^R z)IXCX$?xt>=oKR`|DrZ6hTq+@b_Q+weM#0A@oEpJ#h0DUQI17RrY!G@@jX`<)Tj9$xLtfxGGdK3A@7Sh`seuem;o&E9_M z=Gsu__fmT{&)Leu$r_COzVuGVSwX0r*`w|7ue=)@`*j`pZ2Fmjk98==yGH*q>!$VH zwd-ERLnEtg2_8wJVKX&jxWpZ=T>tx1wxfm>RA{a~i2HSyl??pf z6m`?7Uo(h}-owPtJPcl*x95x6pab>1_Z{_qeQ46;)PJ0N-mSxzPI2uy#A0faTWYwh z%6}q7ldDc|LT`OV&Oi1ZVsciuk4|T1by&X%d|pyEzpRQv73=t3kej&228`Fj*VI0r zVpLjcP#RfD$b6R=wkB0{P(mYB{n{a|-KR_;o#u{Tp=NEvcIMV>FT7F+63#S;Qp#+9 z;{}FW#b_HLc}08k3g4U-d?D}sz_#I!y{7MZQwOkqa%(D(Et#{l)tRN`RQeU`xXsa9 zX)l_1PGW`Su|vD6`%5L1k3~OX<3ao)rm6l_}n&f7b>TjP*{c49h}h6t0fDYv8J zXXO!0q+0}Cey^$E+qV&!)(FiT-aGW>F10QoGrY}XEGt#4!V3Q#!@h2N%gX}+}7bo}Kx2a_jzzohK(J3m9yMm-`GDAh_j- zFMydrSlEv)O~E9)Y`r|0`X-lC`Sc^^{;5+_DwwFk3!h#&zg#H}`+6}#xlgs(&3KUU zeM{bP$RPIDMQ4We96g2GH>+?+j+b7TJTgj&IN}kwiUt z1&UsssO2;G4!w{j$to+T25@;v9>>95{24wy8-OVGEI$5KKN_?Sf9Hfn#r}uuPT1tU z_rVFlLoe+5FPS}*(ompdIB}J*wPkeGN_lyJ#dDxv#aqmeg9rVt3Hzh0x|rHYqlxPG z$j{wPl24;UUf+)5YOoA(@Q%*w>Ef$Pd#H=7N=7g2%8RqFXSnqLe?9$0(sXUPUB5kl z-!yM|-epyp^GRp)#`*b(&rUytWVJ|v*3Ptu_`+2MWE0*Q;bep-aZ<<~@%@M>@jSVF zcVB;xB0{J$N`lS7EN0UTlwl?68J_Dkrgfu z>OKVd8tBr9AACg?94`g;{{iJd8ov(Vt2`EiWQ6^s(YSW|$ z%w$(b!*<(CPcD67nQY1viOgBgH2+L&AEC$X`Z2cn5I21vl^seiz?48msr@&I$QKIM z?iAcevR^O@qRg`FnC|A|=nTgNtVec=v_wX)@vD?2nh@JbuG7>w~~jgwm={=#>R`OGdnb-m@~u)#l= zj99ZNf4R5Cq%X|MhPDvIBb&p9jiOJViBst{o z?>p8@WP4FUP{E=j1x#m=>pKMpturcx`^F_de6-^Em#%SbW5g`>c>cze8&phi)&m@w zUSmB@DD@bKa-)W6Pnlp;0(YL+;M7s)*(ijvKwP=853?HR-I7guheB_8ysZrUB(NEb z|1r#XUZ#X9aHLdzVzb9z!5Ixw+o*S$j(>#}z9m?Zq${kj!dnA(VjIySaPZ=@T==E` zjhl}=LeC@pX-$u$2n`~viQ`RHMgk#6W?kub7ne9-7*U~UA{RgPDK32WbM$9>SPK@N z<3KSlZ?haUr{FHk6-W6HStu;KCptpV9V{Le_jGZ}q1Sf=q9`cjsrGiQOgg z_s}UhMDx_+DYnQ{Px08#{eABI5B~<+54{ftZ$%N*3M;ID)>t@51gYk7X>p1`DrwI* zc0)r?hHQABD6gXI(`Is1CD4k^g>9XZ-8`bw=AWx+OI+n8q3IFWC-?-FmR6@s zrBCY-i$*_`RM8o!QD&+xDKCwl!-n>l5|}arai%WZaDa6-I7)#qqh&g{n^z})K+FSP z6k|W^6S%@it|DF&eFO7tD(x}x-Av{&AKaG7NtRWg%Sy;j=iAic$gD> zkkrm^F^U%S+3-6#YLTh!VO(We>=C6+d&^|6c4hSGBo^nKkI!XEZ>xC@v}8dLiKr_| z+QzcCtKbL&7;uWCG&=oOetau@127_e0xw;;#{c};S9tVb1F!moQuy(Y zR{W(8kN7@wzGuhzA0BZYJ?OJHQYN%qKtU^Z;~LWT@TO)w=ut(7kggT;MRPGzC#o@V zXmLu6vaBeIG-!6NAY#xTZte^~@>2!tZ}qiqg*T)KIg?dgOn3(y3iMQEcF-RC}`3VA`e$gW0Nc!E06It#zleE0!!DPlUWxq5TybIKpZ+{3f; zuEQ6Nl+tUnBGn+OCRJ#s(#i5oGegY@0y9aSH6<^4455b9Nm`Qkok=Ry)9hR}A$6n| z(tAP|z%2jLb=T}k^5-90sN3|NPF{MAb3gZwm__Bge&%PX&fbpq z`$)OUVXv^lpBzFJk1%eJF_mX%;uLYG3{FqBA#PCH6(|nU%cBxv1=1kJ0f7dUmMrni z_i!qgPK{gIJUpkdWXOyXr9db!f;R+eR1Q!%K)fX~qY5x^rS_OKi~_=x!eG@g6F z&8Ue?#gpP6z>PiI1`2L!(9{Xi1N8Qu5yQH9ZHU||E<-n$C777I-n&-f!4C0@8bcqTwKdQORJ=+j; zmzyVB3K2)lvijC@1xQMiMh`>@$!;N&=^%>+jFS9H)w_PwigZ>z*)jr6>jU#hR7YJ| zpA0xVJk5v^1;%Et$9Hw`P2bcGe(#mGEfTIieMVNs0bO94`2 z!ki0hEH%XlhDcH*2TJkks|w zQ+BoQP_$0ti2#jcB9ugamRWr{Z)T+FmtcalP-9Hd&M-t?M61S^Id(ZJp(euK|^ z@r%6wKmQqy{?t!p70r_3W>wC&!V2F20-M~&gTn)!Y#-%-iz#4@k+B@3XzpascX7FZ zvQFQ}%%%miB6X}cQwj|fs>#cl&KI#o9SXOk&^MzHXM>uijkp`3Xc3Jdni4x02E<%) znacZHf;5;E1UX>rQ+91e%?Py5URx7*b0 zn8rtG%N?S7qH2AO9R>_US?319Uu9jk5IM?jdzr{A`HRLiK=E)Dmp0E04X%z@@>z9H zM1UyC=h4%MoCq#Y${RC~HjU=eM{NshD=fT1QCLnQS)SWEVpNfouFEq)gL?}k#ULK& zCM(f^dBX+yeTLenWkzd`N=+Gh?8S@h@fz#&DMFRr=ZaG>^bNLTi6S|qds6o2X- z;VXQzFvxZ&S~~+ZMpZ)$6+KZ#Nb0&C0x!M%BG-1tSm;w&gBhG$AM&GPXR|fD4ETdW z2^6%<04oY+)0U>*$0t{j1EUxgY*b_RF-ESaIkasqEi#BUSIR?5(j(v&i3aK|4aPKI zUOk1gL!q)MUOGs{bL|?x{;Kiblgb*xiS0E`9|wJ9l1im;3M*&@ra)0ZF*2kl5K3ki z`0eLGhVZvPBz)-Il8awD&+h)+R@lIEMMfHvD}B3+l`E|9&c%u(U15cH9XeS|ifB@| zR3QW(SJA(fzz*AGd6M45k&k`$F~`V;0|c{+0i zP|lGPavh6cbLD486i?j=7y+kbL6~-=XQB`w=10rw8OfxnEp2N~G-Fr9)AjH$yk3#MA2@UB=gy{F0ha(CKp+e^)zx)X68G+ z8^OCKauqjXdq80o2j^d9@BDe5|3818-ue-GAN(M_du{`-L8@*Gue<72SYd@XMj;iY z_b5V)N)W*%b+t`uPesTBgDIjFfk5;Ikp}TGrQe0y z9v)sw9nmuxmWGftKB@y=6I3azB}k%BH)Nj^ev$oHu&V>w&?DlMI%X^lH8mosgm|jL z^P%RHKgU&nf+$X{H8;yEw3f*y+7yg?pv{S>H2fP;oWLNTlVD!rIzhYy+X6kn^=9gJ z@1*YWp2k(^NVkHDHCl@pQvxmSHPC`sZh8|zZ=j)vsNkN;qD5kU%n2ju(rG@QSWGl| zGeUbT8@v5#V~p(>sP(DJ zHdk0m>bGX8%a;+Nz?HL){6v6h3vB>Dq`=K);ZhPn07>spzaE zNNQjWvmh? zJ(HjPIiHPct{g^PUxojZ>_Q2IaOX=H;m}aNK%)h+2{^5 z>JU0y0wRK;w5g~m^*`Ps9@D)sINbzxCe9QLG6G%}ikwi9{q_87PC-o|m5%Pq|iJp{6Au9rsW*`xuQH5@yP5Cb~ zSL{eiBR2DyLaZl?0}EyHew1hK+oLW7RW!yUs?kLvcM*&9rb|+wdhb!?o=S72B2&X*FfET0DRBuLwqv$q%Q01UtE9CYDVz-r|7ef$m_JO^MBWzCP|)O?jVzQ9^Z`qP zi*n$5`R?0f`ZR)0aBAqbk|JLsDiOD^P)_f&^QI^Rh8+5cex5Cw<8OQoArYC;FHwd8 zN}w}=Ot>a$Gew_>#~A^b&bc6-6u0hn84;N8q@qMKaG{oxiA@;$gczngD?4lzw{n7$ zoQ_ZPte;^bdq{MK-EnTOzn|5xO(oFE1p*!BEy0Ca8-_Nf)kq~1YHtW4m{}$?os%+P zomG^E#&;RX1jA{$#Ka$^2mk3!1yJCLs7S1n{`lp#UYfpa8mf@aX zNtzVD+28fMNJ-ka!uqj;$JyATKQ|@?og^YOk)$^JKu1N?f=(1mCkjzVJ(bFbzKmXk z${meHLBzaa&{W(SPw|S4SEZ^Pk8F1XZn0HP#tpELOQ((2TRMqH$5OK+nAz!B6_m{ zsi_b>(s_E%;^&W?>xFYJGB0_LcrM}3#BG*>_Jrk()Xm#l zJMUcF(pApR5=$&`HN?CO(wFY4E0q+u$4oxW@8h8;P}P|#9T!R;Fp(}1I-U*7Y#WI+ z!W3hIdjvg1C1TVVEk;Ageu=Fo9eSX^n2@sIWBT6HF_aNo(o)M!L~?0=5TtE+WqX{1 zIN=Mn%Vc0QJ^?%AlJ2od2PlO_f;0@uJvtXU)^JzwTWdBalfKn2@LnUD1IS48%C-cqJ#1S-mVkg4eMd@_HllB*!?jEDFEk=GC z3+EsPR-4zcQN9c9pv1fwUAVL6k*aH09n=T|j@QR{jlPWU<0c%TlRzkyH3W0RLmGJqN-gz^ zb`F;K_Ci8I>=dLzLxFaYA6hehbfx4Z!eJX}!zzg{n|CR|97bCtQrcL@7M7I;c3d5)e(+PA;1I4RH>~{X!4a25&Cl|J$GN#IU6E zz-aFfV}+a##h?z@ni*K7)fxJpAcT z^5mBv&%T`#aX zjm11!v0c66zXs2i1+M8hd`>LR&ud>^f0RV+=V^I*#-cCh>`e>rHTT30s^oIbbUYo< zNgmYo`|p3x1g`ZYq%X9KdAs`kEZPC|%GTrwnEoluLmZBr1DPpHdnJ~Tlw~GP^tnfz z^(B)1vHH>TanZ5g?=+hY(N|R0FYtsUP%%=zu^EBz#{$4KWZtYe86@}D!o89b& zuCACR{}j=*#1*|mR1sHNj42J1?rAi348omsazLlMh(fE6a}ZXU`ZgD*PcYW6(7NEh zO(DmbhG!{c3>349h2$xkY;zE}7*F#L@ncXLJMt7Q2MB55&uCH~j8leySWRGyNJGaY zUy?Fc#P)r0UO_WSRSHJ$0o#j$rN5kk6iygIz-*q{Zf0~{B2ep4roPn;%_$^30eU$h zDpwiLEWZA&;0i((W`FOFf=;UBNt=(~1tNhdH64mt_9YcSl$MGPO-fry*IWO((h{UW z3|4)OyX1Cm8{A0k1&*^Bwzw(W%7zcpw^)S6JBsZ8K6eW5&+=R`y2SSu`oCht*%>JJ zj{_G5$7nrLNkfe?ph7XG9qf((D)408@W%C$djhNi(+FKCh%&`|nw9p-+8_x4R&XAD zw&l0K_zZixN^s%Mm#y=!-?T=#x{BK+jO^v?Fq!5nOodg4cyY>lNY)zSLeK&2*wD@N zy}kM76WnoE&0l@FL54#xXJ_BoA1iF6@#J=4Y=s8Z0fdqm3&xGpx-bBWAiVxKO#Nxv z!I+5gx|7?Sq@*7OFR%0^mRRE3g_qn+_T0I1eD<@S<-rFZh;GTQ# z;Vo}@3qSaSKS&7QSqJG4edt4c{_~%oJr)r@@{y0csQdiPXFkJk{Kjt_dF~f};TL$* zo8I)I?)SPw7Zbg;e`%gxR1fib6_Km2lU^${cCl=2HleUozQ$~V0pbo8!6WA$d5p=K z)3oQGX8gnxJo(8_Q9t@sw%ReWzt5fHq?n1BPVLFW3MJ+ePbDToPhh&B=nPqnW0uNn zLO&h#Ir%49q1ey6eDRQdfv_Yi9+|5fd-Md~qOa-fwS{dg{+tg+W#(PlKi_+G_JnJH zJblx;?9&=;!S^(`pKJWI+&1xl9X#)Q;QAj+q~E=^W;S(6a+Jr4vGQi&OXa$e&aW|_4HHxz)$|?Y~FARkA{4Q z@0Cj|@jZd82%RhUlKL=a(nX{MDKg2{FYxrli{}#jeD9L9gd#484N-=f!0KS;vuUU| zbe4$0pd|sN^O(uXj%We%3Z(*#mbgpzh01T0cNM3;Q0+T@Wl9Zxe;4VpxCrTfTB-x-^y~3>^YJ=0#`6T&KOHC9@ zUYP{&dY06lIA}w(WhzgjRuiaj#`%Uf#HGf)NUBz^QpH7bg~mM~lEQc_Cdca4a!AVv zlXh0dAX$OcD<#w8bni@IeTl$Gev|>F0ZBfrr8?8_1gGs;YI`{?yEOJSrW&wtNF@y| zyWkx{fuXs#7EWO1TPRt&Ztq<=1*s-rt_2vIb>KYQN>PhRKhkASNZ+`$AB}F2<0l~Q!I9PSFt&ra4HM{f#5v8-}0&PI%lgBcndE-fVVWx z%|TOu+=9pTa476!$$BcluxzO7h%yKFQKY7HCl63xMYI;`XF4C;#i`p4hIf0e^PTX!_TFeFd^`O?4=ODwU(i;tHK zN&4`^4|DIm_wwL_4_;CF^L*Ib+vEQG@8|ye?`L~^oAXmbuwZ4SAS0X&|k9F?xw-`n|=h|@m|>2I`VPzq>8+9yPhVjBAFD-zCUIdN@zPg zmvVRe2gE0yVtW2*hT3rUkN%j)KlZ1bh#iBr;Z8HwW2D9iTHq@~V&}B6OA}yGT8m80 zXh}q(dhhW$Pm`b7mswJlnB`PlnTIKLne+_(xye6e;qyHq7)b=Gk(88$&j(0?5>oy< zQDZKnpNXPyzs%Qj;b$YpRG{_LrXywho)w`BZRqlZd{GfQJKn_+n;-qWE*xKDB;Jvd5+;tOQ&!X>!4U-fHyk}foBPWCcCrhujEf;gMx zcHNluQR%jVKL7wA07*naRKunF{(=Xe`5G(7R=D#mKg97n?`AGDx|Upci6xdmz-UPx z(Ovq6i6CAOy~He}ASO?Dq7YK7Tr?w^5hV2i1*t^bNz(7q3!-cCk#hqx#3KbtCmn?r z#J0q}Mx~+@q4Rx2jo_=)b~kOD(3VevL<%nx`KdzXkuKk8rVdX@!---Wm_lq3gw{aW zqOyXZdx%1GL9I+vUhRlEIozdS(ycQ#Axepbz68|L&5($?pcGhC2JNjVYwVVf(S?1~ zjUaj5g4KCw_YK0OgG4-sXqL)qL z-Vl>}Uhahr+=(73HBd>x)EWet5w%H?*ine%!D-mX!Wh#rfoba3#EDE0B3%fyA_QqE zWC!sP!A69TqC6T5^8!^ztN?>5mVgnoqg0{u08(N;!fZ-s5!adl+uUJ4#45M4~c<@~9tL1xOuq>_}G=XmllOg)EYvZe2ndd(y5s3=vD`h(WmBmKf` zp#Wxt;pL0Liv;TBHbVX9ju5HL+k7o7lC1Neqy+^8JclpMHjzgno(w4v!=*!V4_+ir zijolp4W&E50*Iqx47@<-7--9FoMeTX%RNJro;>@V;w(>#1oKoh+OgA2k|`6W ztgZ-m-%_z+o}G=H_FxKh5IQ7AN;4_|hiT)CyR2%Ll9d?wk(G{DxG;qDeUlEY1C)Uf zAXYF{VQQoRx6~*K7mlqbAARx_c-xw@!9Fk~%7C+@hKuEZ7N`LwP_&V%Ga9B~Mz8{> zCf$qShRuq9_2!#+~Y*8Wmdgt$cF81bT-8WEP$I4#A(F2 z#GHie(FY|#RwoK6aXmjbn;_-a`aqJtjJsET_CI^Isgq0Eja=53%8`1_gywV5`-4f| znfD}RCO_?RhLluxG-Vb*d?f4%=I{6Xdt77~7YWh+m=_t(UZKg+;}YhC>J^(>*q<+K zrf*xnA6a-FKT5bRzIOTcFKhA@r14eJ|NR!))sx#ZqSl?*tBHU?jGT0%IDMK2e)WIm zu^;_W{?#x2PsH^#%sYxAAlH9)v&0hL9DH5|FS2m&5CzwC@5~Dhf>RVFYJoO-B0p6S zUm>_)9x*=z?+6mWOT+}RfYE`Rr4(h9Lu8WQW=UWTd_eRDe3IJ21eFP70!T=~9xFcO zcsHd}O&*Kpj02P*a6?mZE{@qR98(y@vkq9;u2I496sbrR_A*=JNd1E2Vp4 zL{L^a$U&K=Pp$-CN2J7L zipiAL8)z$vFeJ)OQYNa?`3{{JNRH{` zDLS8Uu6vjrc?@?$Tq&hwtuENKAuF8X#sFvKDZXe2OxQ!k3D%;XTwhb4msb9gzpJP7 z;<FPnIqQK;`|U;3qA;)5UjAotvJ&kNo3C9VrN-U>3AaPA*I$N1}C zV)L1=5FYwV*5U*y3bads6E+^BE9*!lh)qFhtzG3o6}(wjW^?kIqW2WHB%Qec|!tWaZ-dI6`h-g{|y`N>`AwEVT0)yZ=U> zyC!<#*022B5mLI}c7CtAv%Pn~_={g+w_N2j|Hp4r+;Kavd)Hejj~$rD zB3ZFECqt1r0i?5=Lej=bU-sO4Hu^fmP4EVEls+pZc#Wfo7pc5GoJJTVq7ZPIB3j^V zVX*)Xa4e<1>sKg)(uOfcz&sGWvy2~2cAC6SP=0s0$`=NqHBq6&?lMKK2IC^b>REnwY{ z_2PC8{4vZAs6twBjM8D&;K72*Z>1fxU5X_@AJsKRsjpGfNYJZ=D+pwHkkLcPZA7$O7E2!4pr(aHH#9U>Ko z)8-lgCxry(il?}Ny~&umYzUgFLplN1`D*0MgH#r-!F(g9Jf>;$|~q#mo>rT88hJb)4S_u{i649TICBN!~#7 z9$X|+NK44>x~Y06eJAVKQdm#&d+sA6g$<~RRn`!KbQF^nhG8Qu=ss_omg>>#4p~VW zqj70>lmg9is%i98ftLJloyQ#hwpitGxCx!Iy|vC=H!D?(6p=gK+^Tv8I^|=3TGXq8D@fn$havPAanu+Lgx|b#?;e&R0~S$2wk1W?!q9z zd+scF!>L;su2qaj6Sh|2#4s#ew@wHhMM(XadosIHDQBnTTHeD;EV0BA-)>yDBABQw4~iW&fpENLsm99c=8Oz7d}UIc#-CCpTU3p45!XKMJ36=-9=JK zxO*zo6k#n-whI-iGT>cGBCbiwhY&~#2KQM)tr|$4goPyOpb%%soV@ISmN`k7?z zHV!*FL0WwBviCgK-+ke@W{|6sr;8$zt9`Clbk3f?>c+ouTyy*>^Vcum)vW!#@OhtE z@lm*QlL-5dJ^;a0&`Ep)+I-vCyp}?(1>~^GC!S!jR+QDf6 z2r?v4;;uw@OgfIyaxzZ%N(dkoE+H>KMYgCJdVzXOZB)girm>pVjR`fbfk1(avLXfj z9j2v3q@ZA&Jg$?3Hmiu!h)b)9uy!C`lfQSl6&mEaRve+rjF3LPL`VRFFK zBL$nOU5pXW{@T)_UZSFOaf*l#advrvQny%%x6s;oEF2)NnGh?$Q@ceC_X9c+B>!!& z0thq~Sxp9JHI2P`d$V7nhwxAZm+>QBu%KD(!c73NaK| zkrAa&P;*xNE?y>YU|mlT)Y)VUWdo?F!UV=sYMElRh$I4LpO$I;6pTO0L3@f5E3e`n zUe8+G=1h2;LoQ+3<^U>?tOE5M#>7H7eBUWtz5A5e&m#&@VHVmHV?+>2EfIw1aZZ$` zq^a2ky$@097u_5J0TY{L4Tz@21`2UL?%ukeyP;>)?MdnGG6z%hapjN*iqFeizwg(X3H{bDqp@bJS= z&~+!E67a}Mp=@fRI6ETs`Xyiqfu)unNB9DTn(U`hs`zb?$Qv}NkGYM5ypyNL9 zGgXmQB9sbvL+2H)L!5#ypLXs$CcH94?%W8J>w)*a`8Hm@6S#0V;`U<$?%5Vr@Yz`K z#_gI@+W?Mktz2=O=_{3#`)Ltg`X`rIVu>Zb>u_C?q-V~Y;n#lc*RD#C-f+VW{KQZE z1aE!oTc3B8>e#Vky!+kn=H2gpH_trt48QX`zjGuo2@+BI>%ac%{K~KV3T65H1DzKF z?|a|-c>CMmK6|W7(&4)kv+^xteP@@ovu8OzIiOfmx=_)0K~n^FzxXB2{JZ~!_=QK2 zC%%SQ#3PKhx9DE;3Z{cqMqho3jniLeBTm7cp$jXL9Iz~8vvo^kV(?_|KLkoV`GdAG zm&!?EA(ia8mX#Oz*C?ckoG`NrFoiO}APPxa-G>Ijk#YM>vC$uYemc)RdV;iFczKb8 zyF5MKa(iY$N(*)@%7@q7#&d4}Id*fc_sH{Y z`~}9M06hKRZ6NwV(WJKo`m6RA0vW6FvT|!tP#F{2AB&rm-SvBgLnCt<& z;Lus5)(Vx9DdXg)>Jioacl8#_!AT+qX?wnf_)0pjI!y{vPs4H(5F#ciIemy=GNC^s z14woWGNG^$K|0p7V3QkJbnJ03I7jSuSk(<~ z4!2R4$7$_RMloViq`yT^NSY-QF|U-WUg>jv?KQaU+&Lpjbw;wf_kmJ#rF(D%l*o_nPe&T4yV){iXnq0HQA+lUlGmjhITI^}|g@3`rhbe@9T+z>j7y1(w7C@mp)w#`c4mrxeC2sO^J zcEWlqj8&i}f1z)#;c;m+?r&Ml`_IeBcAcTHg`!rDMNQ9I>j*Y1@W^b5aB za@x(ma_zgs5=$(x#CIOo9ZA}&JICYk6|cSH9q-_0e&%Pcsv3Ph+<4=S{NgYEA|L(e zNBN^a`lBPSojG%cPkiDNy!XBD{ifUfjo?+UdeygOKTCXza0iKaH%dW4D5gT3z;4@e zu}O)=<1=5Q=^mqkG?^6vF;*_^FuMP52?CoARUUr0J6T_mNYV(QpQQk4;E^UZ?k!4E z9mQ+}ss>qTk;tu(iFR>X^_eQLXBtJ4*rh;lQqsHT_w?_xYb60)MpPQ9bbor;+vXFN zMBW;Sob5N;hY{(*zGuX$T$vbu`P%d%pPTuHC0-y13+mkbSR>SxQb@zad;b(W*yov7 z+zoY2Js2<;4xe9+yTlSN5zJD$%`r`0(EapRJePQ3mj{AQ#*4*CcZb|?unc1T+t;yR#l z(mo8HwJ|&8CZ*L>-5za`V)hEHv9N*4gy0iY+FXWQ5k={!5D`iNkuE6>NsE6y0wux# zX96-wUV08gIYuLg>{toqUb>~k0fpT~uyxFzPClUmjqgxOK@cYur9$*E?#>1qpi@Q? z5i2O&ao=Mk7tzq61l*GP729M*?q(`qrS%?*f6{Yl~XHQt>QvFnx+~ER2dm<)%H)d5RdEjt# zjF2B)HgHf$=0GNvl+p`irn{pilqN_EMW|S>juX75(2BKojT7-k?vXcAvq4I?5+Wm% zGLuD%`(NUv3=^T1kiCo3NLQs#B!Fhpaj?IORZc9|AO?nO#_CXWbwMh%Z#?ArLsCs^ zFAId~ZNdWMv(>dQ;eS4XAr^L7L6?+tYK^w zeTu4LSxwQ9#higu(%i)>gqunA0MTt$ex{^=gf26OeM-8uoOyCUZn#~4p&+X8|fRF=PpMGP&k@A-yg@~`+60qdh$?RJl5V7tS53^ zX7i8PHWq&_o-BbY!ml|unZwjb~d=E{kyeJ2# zl(WSxAres3*QxDBCUypw9l$W3qMDSJDWqnAQPHxC=^mobVi-b&>uG9LwivSOD;O1c zfm2|XzW*ZAM5t*^kdjT=W`#ozY)nG|Qc|i?2oywAlo*5qEr<*#36yk{G*k$!HIxk5 ziYut>U_NDqRo21*TGc$`b&A8Wq^8=}uTj|+tMLR8CziY5P8DxpMNYEABZ!WuV?k>M zrK3_280XH9M98{Q`c0TMxL;sEK^1GZift}5&(IYCkrq{DERI;DWCOG#Mx!+-QGyEU z9b&7Q054ecO(Y6<>XBP5Qm|DrPM|bnU=s#(IjG8Tayp{4m+<_oPTCm25MUmCpV+w@28?qj6 zV9QQ2i~}S>S=1aWPq3=%C?z+o-b^$>7!a`>3FZV=SoUg5^biq77=K%?a-ZMGVYQxy zrzV)Cz$QnqsnJf2po5eq8kM?GDoxfS5g2aO>`y0%Z-4~?!VRl6s}4w@@ByXQ;1y;H z9_V7E)Pk)Q=U=?3B-|PJ>(3l=*eO=PVFQOm<|FZb9DeO<`0BTS4@T?$Blvat))Sx+oVMdD1 zNYeaJB@v$5xAn@?bmVyYmFVDCCsSuZP%>AtK9{Xgzm1%Wa&%)$e9Q2x6qZs z;Sy;44C{q6v>P~xV_f$U6-pmc#C4=wN2)P_2_Bq%xr9=&#wsH@Am$SAL0Cb3fVmUg zC@>0{GKpu<4pzfWjQxDJCrCb}o4Uc+$4qog@IWa8N;QNr>TT}BA_Id`gy@H~Zn&)x zixTk;p`pMit)tc!C@4g8!H8hlH%GieS;c(9*w4_~c~myKK?oS@(lIQYFjS`d9ioCrmuy@X+Pxf=EwRKBFBM!@B{ z=m+Woxva|)!R=t`L;@luYbp$$KFc#7`uAM=tv}(efAc}M-}^4EC_Ho$LAo4`FY!`A zmf)v*S<CI3=eMSVcwEmce;_cY`&f=l*Jeg2zv zAK--dex7+z*LuIi6jo+{2Bo8=VVeAJX{e>9@|r{0ql<0w1`V2sTj7dy?7m(>%rOx< zDKV+hOl}5;KtV%G40&YZ$p_X1UMa8U?#UZi)irPL(7sb`^7FS#ipvA-Wush zQU9_-TVjsIQBRCOOlooWmLFK3@~@8<977n0vacNzKg4GXV##J|ln2vBWBpr{(+;`u7S3LiL z4}5^(aQK4n?`>~;8z1?|M>sq@oISU{zdujf{3bA&O!&eVzQEbDXDNz;TW-09yYIf6 zx~^ZSW*7*mhbIek9PO+OdH z3X+1fPkCP~OJDrgWA$h00RM zW|;VJtBBoz+ZqxAqAe~LaVZcAT&h&5 z;9#zZq>!PQOFE%LfkIXgtCAO{wsh>%$tZ>Ov>kO(<%PbMW3gsq8rUy8VrXfI95SW$ z0Vi~mpG$$7f5ZnaF?6ac@5mNF$ZBpyv6JCyzvNP{*+x-sKcp;08@Jonv&I z-~06&TNB&1ZQHhO8;zZb8ygK8+eu?Iw$a#0<7d9VXZ_#JTKBx0IrlkdUweP{ikY1U zDOsI{p8M|H?+m@k8Y;!NzmpeRfm|x6sw%T~YLwL${0RLCiP35ePNN-~SG!srgp|Lq zpL`tufpPIl{-Y|FmpAi>Ir;ugaiI*cStCx|Fs){|6w*8DewOHF_%zO=5$>wSL;VU| zNhMV*JB`P{Ttk|QDmsjlRkuN4lrjreZThqLP>7NiUjviF;O+mb@hiM__`nC}&tvC0 znWi0(Lk*;aR0{_R`j?XS=0rk)<8{wSdbQlYPx+1YJ!vVcQ! z;uq_-kN*sE?+3&up)f=y9C(J0g4D|Shk@7r#Mgc+T^aN-I~)XN6wnc(q6`oT{OLTG zVzS*i==c3WDHNPQ@4pHa$yQj=vlVi5VUJ}`2=OM(W3Z&f3a(E}Ypmw8rgU@1yt1b% zU=ToR{}i}-iP#z0h2BaAZm`L(*M8`fnh;Q|%q?wr$!O67$<5<7O_WNe-gS*psV%>0 zN(jBB^;cfdcJr^FCr)t!&qDe3JG1=G?@l8})w`2(#t?1~` ze~ZbR1)es(@C#o0K9zf~u|K7^pLRY1Ch*V)_?0bx@5G%rfku{a?IIlVaN7}PX1ijv zQ0m9yJ3X1^g(9dNli~BVb_w&&!;X|cZ}}9M$k z)b$9P%3S8bNi%XuOt#>;*R~eZE_|iUPi&TwzlnmU!->hui6u#N$W+8kAr%dZ4>iBR zA3RxVv<`~k>0M^2?UNC#Q_|(Qne&W5h0l=Kg+f`%rON%a44M1m8&&nEvtfj*mcZq2 zlrFhFBF}h6U!*DoW28@%l9mp>gUiaUQ*wstMxz!lb$brum+2;*f_?xh?=Nbe1*Ekm zLyZKIpUtgFKB6>{?L@_mvn2Igl$hFbZKH10p0o1Dn9{D&o)RY1v|*S6&}Ua~JenUg zmaegeS4RR#q)yTBhPf_PAMk25?6BgkM>uqCE`NHXCrOKHNZ{8U8&$jG`=gbZSZ)cY zq!qrik!_tI%+i}Vjf3yUDv{GmzCoE{X$!kQ#@o=v%!1GklmHv}I#lTu(x9v_v@(;O18efeC*ouyXr2Mp`k8-RYXU?+@Xrvzb+- z;rV{LYL=p&iAoywcmFEra7*iDz9rv}w2&sXX|4YY@qnl^U-qA%Cy%s(B>Orij$(Mb z392{K67#urx)gp?7k&(LINA2UK6(!Rdai$6w_w{#EqJGJ4!X~=ra0wB@IEOa{-F6! z>Wc~Ne&KZaeD@7HZwrcpA@T_+c6C0)vXjj)u@N94 zX+c6{P38cY=tdSGBCv3T5g|@}H$nt+no1=ZLVci+!CM6v_+@QjN)acfY;XQkn=8|3 zbzjY1%hK|A+Mj&pMMyX|+Mm2BcBE{CO1Jw(b@mh2<}!FK=bNUZa;dBqM9$`i@gH zs^@9vFD0`-R&D4WuPWHh%@%V^C0b`M)3 znp71lyuR1E7HoP*T-rXyqMi8FC`H(vF_eEsEaZjJNY^cUuCLJUbDN=6ZyM2OeV?sl z^6)$n8gK_O4!>C-&xd)9e-jLWQCLa#Kw0H{)lE7?>n?+*bdRlhRhMRT3+t~kn-Yes zfCH1TDQQSzrIVW4vbBMw2HkCs>dF;IK3f&o&rl^paZ+>GaZ* z9339_J%(}};wb)MbA*>}WWl)E-wl<`a{r#sC?*O(y&hUjZ*^!tR3^P(U(TQyBqgbm z_&~&)De4Y)PrgJEKnsa+aM2^S{O+$BqcI|T#Yk*Pkz{?>?$E`~UX;u}{0pXPL|vAV zTKC?aqhaQH!zBDnH(a939hDTw_Od4XNFE8*FQ}~Jr*xKC2omK!+xxx*YKP6DwEhk5#H(Fg29sZ z+Mn2tf^Q8}ErY`fKBd{Fs77fY^v?5=L{)8ywLdD-n=*?DCv5BB^pHIt&2z8zU>V zo}A6s$-Zdi<;$EtfP3A z!4(73MNRpuLM<~EkVD9oU1%KMn>`3^D?JaR^#PdcP5&Wqzg(n~OKB;4 z@6zixo8O~?{zh$wu6OeafD9||pP=ctR2?b?PX+A9W3DSv;_IwIVi6IR#osPeUbc1T3{qznLFC!#nBoH zFz{3x@7pCbwrnTE7&7qn8&?)s6pob%aI(6~(ccV#PqXqkkUq{8+EE$^eRqv3-86}> z>#N5^ess6nYg|Fj9|~2n{5+b-XoLzOwk_pz>7=WS^-!Efio(m_ef!LqR_bg+vyk+X zxOCFeN_bZ+e!cXJXW_Exl6Fq`nGa>dB{z}H`lD>*uEs$JnA<~d06ujG@AM+KO=n;C zv1NQ8{5jh; zgfL|tO_-3@lE+ML9QF}_ei=i#glAmbBHWg~Mj(@>WcC&hFR<&8O4;625(w;k3vnc@d}|9}T7=+GDy6*5^~{CbHp3$^fJCIl8-@rC5D1&E zcHJT)7nU#bzi2{n>yMw*;1jPQ^G%SE-BbGYLv5Laf^KKl&d|9kU`AGOB>R?pDhonN zRf%VS7m>1^T*8Wty5o;q-p7;VlhqDYM4(!O^pH1=2TFQ0dde^9JFF%6Q?_9kN0+7% z{&jw{In(N8XgBo3b1XO^R6uFpPHaKrLH4rS0W-|66NvuCuP!8Ije{Z8>Ju zNAx()7IzyEOx7QFO;9N9H=iydL=~r?!Pt);Woi}*fpnWKm3(a{fO%xo*GP7IP~bmi zcy{r2CAMy-E`VUh7Em4ReB=jF{{E2}?+J$HovS|~Ki!(4PgT+FUFa6kkpD^0O3Tw= zwS-WH!U9z1?XZcUma|*0A5vKR^un|%!~Fg@geVkkXYCO+>+$E3y0NT5Aq%iExZ4q= z>Tb-$j>|hL(Qj2t`CkE+{3aU3sXTL!hk9ioY-kjb-(SM&KltKuF*`4LJGwqJJy`#l zKZ93DulqhW`U2&{n(OR^K5vumLB8+ChK7Lzd~Tnsj+1};*nRCXVUK4&>+fKKZ(w$o zK6f(zLT7)g!f`!gS8jAK+57pmP~Q~vLDzCfAq(A1nyQ{KBsw8s2|zaGL5O7!!8_{(-;$}_xpwZ+sqoR}{ z3x`OikH18}XhT2V`-wr6OrarZp-5_de1vQ{}3j#wD74FjUcV-5PjIf{^s67GGMD(wK zJi{(lRl{Mba@jk~STRCYWY28!JJ4IAtnfc+3{_(c^W96*c%j~ESScHo=~v*GMC5H@ zG!%4Jx^&E?%D*#46-~yI#MnomW*)v1a>z3PMn*^Y{siHeFwTB<-6Xt2(N-9O8%!fNjNWa1geV zTF{b3a~X|mfUHcqT+g&v1B-v~cc;p~5EWFkC(Fc`qGN?_6Y|{sYWyf6DDOr5#ioX2 z|AbYX%#1>IIoZlq8aY(Tc@wU(#vjujC@71>2Nvx)8CclTOIUPUEHd2`V|lD9dV7Y^ zx!=-vqaWb3&{JK(Ff`QMe4PSb%m$Wxu${~$5+3JVw72>o;&uP9xtAm-FU?fPpVtH_ z1$xVxI6@|Ea++F0=F18FLbeyl#v~Nr2)pO}w`Rcaty9jU|6l2&Pw-x%&vPFr^vuoJ z^>)=&ReeTSIgLM>+4p`#ZhD<0a0iPiv0>2Tmu{W!8_687hw#1%8m)P^6#VDq zoDIBk=Vts`tPmPu{@iD7?C9`a@Ls7iJn#;F_I}yu`_K=8GVL79kyZ|q=QTUn_LtRE zB-iD|5VVfT17eboljtqOrO$o9e%zE$|8k4g|E#%!Jcp~=)7$#gt(L<6AutY?9eyEu z)&p3~gfyH2s!{E+J;~NMae~$J)RBk9w5pP@ zS|w_f{?J@E*{{(dN)n+5IdrX_c~q-wiE8NeVQ1q!x#wC7F)3%@`rzB`s8*L1;h<#fB}5=q}SE)~qOZ4EK?bA!7wtso7NU6IJ^VWZw$0 zU60#2NRaHv!&QT@@Y~a)9Z+>(XweGD&9WrIYE)xbGoueEdS<3R^BF&A&aqYtW{Uvp zyWM6{1kvsV&bJEg5v>!dD4Cq9=V170&FgGS5XE>CcmqYtc$|^~DPbuZ*)H6c8c)Sm zJ7zEy{g#5tu?H$ml^HJ`*GhXzZY3@ih%C?1F+d480GezXDcKY)h3Xqdmil=7 zuDYBX8G6~UIT#yR49kfn@;kGQC-qyTyq4wFtLAXG@Mleh(Cc)buh?2ru zhyh#X(+Zgk-{M$oT=IC1p{F7hWg)2!Pm>m=GEbN>ib#!Cmkpv(KlM~K3>p$^ie;D z;&rcLse!R&ZDT0IqaJlGb&`{jUNV&YFE`0kg-E`bE>*Xuu98|V^XvH>r41ht4Zhg= z{wdR(OKjN3ETeCKH8kbDAuwZq?>ULXY=$Z@+Q{t|vLJ#zbSu?Fl_c z%eN-zIFlK4%3^Oi=v@BjCT%r2;YQQob zzHaKUcEdWLSL1*x+dh@`BFr*>pF8hZ_eucU-mkEy0zfBL^^Y0PrI^4th@H&>&~|a> zMWa6^PkyqU_l{_7imjEUi^E4O*ORf4|HF}I2hOkRkbQ)G>1nee_`l5(Co)- zLc78wBc*m?qb?QE%q^OK`*lM~At=@yR_HsZIYJ{4RYVOQ(;0_KyY|TF^$zLos=&nCrIKp}CSXFc^Z! z&;C)p^*AN>>CQ%bCh&SN;4|Xp2Mv6`wx?O7ch_x(JvhM8IPf;k&08fa!BDA+1vny; zIO^xhLHP$4f$6bj)bx>0A-`uX;oZQb+DtYAV%q;!2Yt;qZ&+DB7Z;a>M*S-Co!WnE zpz(7K>^#v9k|_L5$82C?US1ygB$4kSTF})=(3NK!CR)&GW>5^aaX^Z7LEuwY_2?TR z9XKtZMm>SyAvv4FA@724r9maIqWl@obC%owT9J?95RhoQJ=TrVYz&AIpFfY5`=x%o zB*m2=Et6-)Oo@fdSk{D(&t?t6q>C&t(vKfWx;0kB8k~gH=v{6NmTz5u>fi)qaIYGl zui)!_dl+`!dHgO)w%a>%_~=At1*4OUBuuL(GkD0I@$#m_tXoOO&|2o8CoLY zB8sgxd)Hn5`KF&dCr)Xr-0T0GfJz%8SA-O1&_3AI_vq~Nd2hT={k2rj{_Mn*yVZTVh1!Bx?6U5|Fnn@;jxes`hpfUr z>k*sG6<9E3eSy0C$3sdtwFN{}z3@WVAJ}nz#-92Gor1Xb+0Lj+qe)gvdOa*X&_4{x(FsZD+>YGU#xM!@)55O5-Cd3qAX1%x+J^fC3cKJP3d2@Ob zy^ir@mPQ|1v@7VV*ty3I=YKujKIHA>GV?=2Lpd2so*x+#etQwv|3KRRZN|A9NKPd3 zzi8m@4${pKxE)4!_6@F&0-e&%$}RhD5c+N+#kC~EjX#f!kNVJl>g^}<@8XXJ zh!rx(8^Gh~f%6`2^Z%42PF7b!Ub|8Ul@VP5buLzHAp{zeeVVnn=!q~0Txz#4B)t2CVh6BU@nCQ(%H;zMZ1my!EfaULO_ULa- zg1=MWcyYO4gK){MVG5uQpmt6|3)hA;)J_WE%d~1X!c!2K7|R(|kt-h&2WA?qv26@d zf3muYu~LquEfX%_xl;Oylg5z1H3izSDrIgsfM|<8*rpVmS;=~P7M_WMAMQ`Ks)Q*F zfTM2>Xy`McixPGFY)4W7a1Df|tNj!vX`nw~xSWoO~5KovkQ5IHjHb;uFoP zC9E-Nc+D{qY`Tbj2D++mA|+b*JVIk&SaOYI78#%kZwY^sQ@QTdQsFc4Z+!?s;XH{@ zNg8w008y3ysZ>X(TgH#r?>Ozyi$a4ObCCpFYI?}J(ts3PDoRy51@H)Bwp-dLA{nB) z@bp!)V~-*nLZxOTq9>+x!wIRI8ZAf4WD1pJR9jjKHL#ZNg*^Be5(0#U5^|d0zq4XH zP9Bsx>e-4j?j2l!Y@u0uwu4$e;pj(Lp@CACqL$QEJl|y$6K_*S`aqYIu7k`y&EIym`OF)C#J&-ZBVHSb=szpIwW*HwQxx5#=bN zo@)Qc%FWg<5VIFVCkz@T6a}uExwyVrIzxgKJC5M@(ct%t^Sl3yx6ZK?fq#plbc~II zC*QgVkx@{5kF%{48M;8`j{kCP59JdbppU+w@A!PafI8)VKKF_o$9LYaqb;|#Vaq8m z)daxdm}NsU@|VwcBgkXJ5{jM?$O}nGtMN_+;zDnE2lxT&c4^j@QtP*COD!Hzj^hRt z>wjMe$|cdWCc(+Wl-3^+bqlo2(h?1MQqk7q~Qlo!%B!v&+cq z<=QPzPf!SAOPQmCCNIT?mUAhD1Ya(Mdp2DJ%qLoh4_(k~HqOQjdbvs4+#Vtuo38;7 zs&~qN@}ea7Ygfn$ackIZ^vUTHWoL9u0$$j@Zu&m11A2^3Hkm)&gPIPQ!Ix~rpTO-{GQwS!6td%&cRpD#8R>;vZfu8&$WBSATKv>C>`YrgH z5#Th~8+f_!-i^y9PLC%x=d=*?j<}@?xt}OtBjwHiY``OY(lagrMx*s+{P_>=nuQ zL8xm7giUp1G;f*XY@6kpRtG}lz|`MTyXIj#CJxFCMeb4~laLz~Pe`#Wq&nM4a*(Rw zXftpU;Gt--=ud&+yG|QyHpUKx zfhs~VwOA#nb*~MSNo@Ykg4K@)NJrp>wDu1cuH;fee_I|n%t}Mma2lxx%j&8&IR++J z0sU%%+MmG)@u6^QmP{*V9Z5CcPt%wU6L%egcX>%+)}%;0Fy{v@7dNmF;STcO)iWe6 zHe!m3v7E39NFny`#vff~I zII;U%oOm`s)M^Sa_DRVUcvPQK%bweQBDy@2JIc>y6@j_^Q)fFf(&h}fr9;JAHe)&~ z$ePji4W%8HG&zt^Qk0x23euK_GgJbR+_zO(H`Nn)2(JrL0el=Ue(cB2s2)F6#%wan zk6)wt-TfKCS+1|BZ>Eu$nW{+=Oe}O#;a0H~f?6Hf zkuJCKr{VST{Cg08h>90_MzPx#Fwh z#Y5hu5WO2}i`OuU*G}3mMC~I=ykDF@tjSaO+hO9zW*4Ujtq0)UwU=)PaMT>P@*1cJ++EQ;c?i&+*-;7b{?+Y*%` zTd$_pyU}R7R#o;`Ca`wF0dZvtTYzvV?%Mxw@Fob>3*f2T!aR9FP}12pjBK3C?XOT4 z*d$bN%)KrCypBP_=!oP2(`KVa*DM|yJSj4V0tOeb`*3-!m>?HL-Qzrj8aqOel75_$>M+t z<Cq8-1^~ z6`s6dzUo@JKrf;diLY-?xC!S>;J^7SE4_s>4exT4!Y+%m4o@m|;Oe3!4Aj~b^KV=k z=-;+z%8C&&8`~Fptx9wM;N8ChlW zHVs2rGB;T1AvWU)W;1OEP(c9?ftw3;x1L?GNq6X^9qN7~Yd(ov9A&k~5^)B%2oBgA z4sS5oZ7bQBFa(wN@Ndm-5#=`H6AR&$K!vOr)|J(iDKPI7lIadQbpeB@V@=?77#SXr2{R zEEzu}$YPG%3#F3fqp!)DX_PRLRX*Vdg~}9SC^X~%P~(J;;O^r=l|t9=)(NrVYA1cP ze`t6nMcZLA)d|+&o=U+5O%&wQaL1Rk(N{B(nAV~F9Y{z~X?acZwAaj5q$}xJamp-? zm>yDyGIq9$+v(4_%o!DV=UCs;6avM_SZTu*vrEQ#EyC?n7>PSiHLu04-FGOB1Ieux znK&9O6-R6A6V^#p-5RS^HMj=x60|wgzJWEMX|@+kKM6@q=RUeB7GXYP3io^cb9u(X zmRf|3MN^HY39T0RY%s(Ei3&o_E*MK3=3TI9lN7qTMdi8Z; z|4@rNUi-i0b7SQS8qiiK7xdb$MIc~r|F1WS{iqHoR(XHLXf`lmRq0z^NyqE zb`@ditMP33*3{T&? zg=)5M2>|vn7<oCB$JXgrR{c-mo48m%ej^ZUdkQZ-*>>ZZHWDb+fb@Xw z%wJihVHeDJY0G?kvUf->6gb18!~AT&e)o{2R+FMs=hcbeQnXAG=Q7Y{M(k919noyd z?i${qv-v~}hd@H16;H3GGP9;g>zHw8lwZ~zxTUD2iD5kAWdePXm`Cliq-S3F zMCJ7K!l?D|IBH#;{qt9QryluCBa#Igne=lNyxmNG`q*3*9f zj^EWgO4;$dGFl<`eNHO6iu4o=OHb{En}R8nhRnV_I8AJYc7#>y@HfZa)AiQ_}>B zysN-HAhv6ixQO8U8^Oq&LqLevLxtrB$KDLidW}m(an14#snn z{8hoeYapcxgX$p%X>$0lF6uBCO)Ou$35!bVJZkInX24d+ctFB4$W~8d&&^ zz+*A8H$RSrEF*RWmnEgFk+b7ypeV#=JCm6AUm4KLhXLWvXSMY^v%e=fL!k1OJ0UW^ zp}lgl->BJoVU0)-3G|Wz8x^?^vJzeAf$MczSH5N$Q?|@y8{?bTb<8AKXh-Fl$eM5N zVfRajvpCo5o%hZYzO@qTx{mdUJ~LBV%hhBj;^g(^x8h@S+_J>NTuy=K(Jxl&o2&)P z8KUHZ(XmtgQyM#lSO&gV8v<|jU)o0PUrB49*ads$%Af93 zB`q7*E}+w0?O!IJYb%XS2I?&qwou9!e)j9-adnHcP!sP^>>weouTRG3`#*^fv^-87C)wlq0-Y!_+)ytQV z-TxK?3ZpTt55#k6;p<+oc@ec~Fzo247A1D1o8`SU=>CB@=Av6j%y~-S--M@hj^|5+ z7Ru7rSSsq{?TiL^qph>di{FHdBbrLBP3QCW0E7zAQ)DKE<_;m1wo?d*VAHa1nsFnj z#3l}91{nJ4Io{f&IN`y~a}F+2(z9ZQ1Dm~2CNirYz#|k;!I|VVM#?D1ayzgt{?X>D zcN389yXzG+(AyJ?;SIde_A10e$A@8w$EeN60tHm)96A?%96CJn)Z!?@azwD9NB@X< ziZ0?ZmoO{FWDFH41wzLw^v8uFKuLubbLgZ*Zyz5TG>BMA6k%F{#gQweC%I*Qu>i;; zcn6kOqphpr0xqFXA3b_u`Ju5aPC@byHwg)ZoUwE8M;+`u=6`pYYeLY`>j6ZKGtL@( zj%K~PXqvtITawiKozp)s?P$XqYp3;6ak9GFPu?;?sw8LKCt@Y)fg%4W#XdLQmZ&{R zTiz6bW-5_pH?i{Gk2Qr^R@EAJdmCLAv6awG1EF|4vxpBK<5*!VKQ-=t{ck>^3sRsO|Ftzr;^O} z_P6yu2^i}#zkGhZvJ>j&Uc;W^TY?sc_>EFvl-)_~MWy}ods|{$Y9fUq?_Q$Qo+Hv( zG;J2sVrd--5h|KltWSta8n16YPCL3_RK?1AsuKyt6h7IEl`rsIXdjhYjsz{5t!SU4 z8XagY#{ELH&%a41)W0Uxp_ef=lAW^ZZkd?@6YHM4;K;Pbl)xR$^G499Pp3cP8!zbf z0WTWS<1yB$fRmncQ88%}sX|g!n#TCsa=PwlyyZ|uO~rO*V!MTaOey}2pcL5hOO|Bs zVi&l2U}+cbe&D}XiZ1s3jC6o3T?_VQiwtz+{@`fKkW*3_H!QWNG?H49;e+lVZac}Ej7B(u z;gP}Lyy5Kv%+13oxK?F1{Z>*#E%^l@)vTi$w%jgh0QH=UEA%&Q5XCl-Fcq!Vimi!l z)g_CHM`eTqK&d|;&*-L9QQBJOY7QWg5ho3G1*1fQa;MAL2guADCIM5WV#Lu=Qc#n{ zXlsrgZdpQ67ABZjY0eMcc<_l#ns`#*r~?<@Z^{O0g@zQF$3W5=%I-hSuFly1`s*>b zeg7L)f-I{;#Gf~cF%h5tIo%AEfxUU{m|zoeaV;j zOq-R`&LP3rjp>L_ql@dRN*Kr6^9joI>vw5hyniaCGX(iX&6Vvp;3ek@;!&)qDNMBd~gMbYevER)1VG@~2ZmWSSGxDA+_4|C)W!JB7r`DPVF3kOt?^9?cNnm5o-x2fic{jH^;mFV| z^N*(l*?u^ncAtq|fgzTOI>gQ~U3rpI>Y;tJwdS5OwY{vh}fhkMx`lbR?s@Ij4M}E3YUiSO9<>pX6MV&uowpW-3A^IO?DoST6N$_nW1LPio6HTovg<=a!YYl6+E?)a z4xQ3B)Z1=0EHW0qxi!&7F-^CX=-U~jqg(Sm4R^f?Rjypj!YSTB#ni}+n^>`l9EnME z^J44ls`H%R5@lGiz3~8JBbJmxY$|N1`>W|y%jnv?J5Efv`XW?B+R%pix6z*Q{MvY@ zhQTx5zCnK!X*e}%02~HRN?6#EC+JrLNy0t)>fV=TF&Ds~I z-?d_g&X{3eQa4&{{=p^GGL%t&DD?liIn_I=q*KmwA*j`&UlYP%UVn&S3nehD;NDmw z{M&8wrYG{d@=5PiFi0MgAahOfm`j)q${aHtmTB`WGfL`+9we>4ydsgE$(Bm!6 z0@HR{jn=0--oRRyM$nKlDuxeZnfm+RDx+&3{?n%`gpb67xT&Xs%r~9p1m^VWo~W~8 z#ssJSoW8#s!k$Nu1wGVQm}=4%{Jb89UH4T$xG`W3adS}Ij`-sdT28q6@Zn8}A7vFp z*NWGzeb+Yy1s1@T-%b3SF=8#lG!(;r}(`bzvzD z#%6qc*soTOPjD0{}4F*QqPozRA-TrBkz549Wx$bEq~Tx*@z^>63(L%1&GmQA0uhBQHaM z5dHU6j=UmEWhThr){gJ{f}rbkyKXrKNzQU z@Pl+|8rI~~)6+jt!j(PfwIcYHux5=v3gm0qYQ7kZK=?0A zXDH+CQbA_%5e`3&c$*`hgnc$GDJ%U&bYX_(rt}<$k;N|^tpdXk5_4>!G>&b^dU_bU zpG|R@o&=@qyZ%!TeMq5!7rXB0L1hbAW2^wdSpkF*9gX6aUn=t8^|ah;vpW=hy?yj+ z|Lthw`Mi<)&ZCRBCuXGzg$L#j=XcYKe}D`Bm4CGC*0(##yguuMhwnI>*6 zaeFZPlLeN{S2Sn)yF5-hRq8UuWMW#DGcyoJlWbMAQ%lC{UXMnF-*%~2I9;oaPTrrW z_=8`myWRHSSLzKdt0$_izi^ViPJ|@|@w~BrczHfuts8;n{P^J%Xb3N-XZyR9l-8j-)xogBgUz+N zjKnlX#1v~Qv@9pJxCbd}KTKZ7Zgiwuqiek|!@iPXYr~=_VOu#Qn46m9TEuIzVfIA=eSlM(w8vn{@EQ=7rvj8&jv6)NC_) zP-&BF0Ntl3ogmJX8*@Sssq zgi*%H2^si--{_Le-DLi;Lf0v~Fc{_rBDY`}xIH^mT3q}#meB)Ar8sj;?~+M$;y;xx zc{Tc;EF6fhnA|itbE4il1ohm>CX)lPED>UpLvXi!Tlgl23_gPe90Jk6gD-Ls&$EWH zw<|((QZ12^f^86X54|qFuG0HP;jYN#ruAu9-d=6Bjh6-*SX4|KyQ#1ay{~gjIvC%$ zszTg%)=FMxjM5d-gDm*2#c}-d?4D#V`yNLs? zFl7cNO`|eD*o4VYT%CI+SK8&^8D$3HFtB)Zw?}^7>X&kiLIUy7eM7pAzF&-EuPtSY z#2?Nm=+{jWu`5?cH>!6VE&iniFsopTyIofd4A8dAx2&2RUA$OyP>pvRixcgHA)!9nw?xVAmIurPr5O8!j`UzjE)~ z+7oM$H5)9I1&#YPvgZ(Sm{2L%m;ot~paUyzwzttwZ}*Aim?De%@N5aa59Dg8qw_Sg zN@@uJ-P&n426eQlnS}c=xliFuq)423JSFQN$L0N@nuw@zsS@cXZ{{7a`sW&=Ufll; z2(^6rOeBGIH$B6I;-KTyF?+$@eZiN2mHfIXU*6r?Y*5C|zl0s1oro>r_Zv_ct!s4C zt>7`J;N<1Q%BuEp`)S($t?}{_awC*N3A`v0h`vss8dLgmAfhL+SPUT+Ra`tzwg@Ys zjuBoB4;L!&B~q-W83Cw*jUoSQI}KMZhakxtg2V+$-GFYqkKpgWvpuP2ZxuAVARNSQ zKmB&q<2V{aXnfrDcxHHQ07~QSO#N89&%VAFcvis}DFRnQ5qvLZso(QfeT3s8#D$1J{xz?0b2-9oPLLE#1n@dX|^5GdV$7QH2tvNEUki`600 zZ+G!@zcEC$G7bs9yYP3oy|+Y^`aN5rz?(m-&-3E&!yHws@%i?pihp15P?{6Mw&!2{ z3Ml~&k)7mk&P&Huji`aCITIabfigO4li+DSUfMs1} zROYeQKRbW@FcH0iH)xMeSNAFO8*i$RH=kzFtG4Gf#H(IO1tLVhR|N1b_XID0*;Ljg70 zZ4D5-EilqH5-S73PBN%2xj(TFr`ORxe8QoXBH&WhEAzn2iUidlI3!j;Mb|v< z(hsHz(PG~l7Zb`6O??xhn@~+YziS|QAd~{Jh}fhr!$vMEOPCf%aL~`)p9@OTA40YI z0!`dEDX~p}09np5{A0&nm+~AE=(I4c!avv{eaBGVy?VjaFbxB67)04JLkO;^_il+8 zUeVAI^fHP7&>hN|6;1CCvITquL-e+q{Mr#6Hu&I_ol>*Ef$8@xGJquQ5>3GPBK}R_ z-+A__?jmrkV~lDN%5ci`s{=JRk{BsH6WP;Q7Du}bP}GUhNl6AtJ%iv`Py>Ckk^`7G z2{xX%G4rVFlhEp(7Cj2k?HLQ8d?_A{I#ex@O2Ff^Tm1Qx8i%p5av~U zfjIC%HRzr@7*s5{R!~-5?L5&6(u~JKqQkiU&kI2O@rO82eci7`0|V+B6a#ZVTXlzoI~^Y* z$`#!H`l5iL=b10VT+Pqi{>as=d`DG4-f9$#=j_~<{m>cPtG<+jiH4cg81jH7ux0;q z^xXX3ajlOcrJbz7msw|wKOqd68mO}SM+haa=i^RXW}SKC`?dI`_lA*Ulqd3{Q53uo zlGkDhGn2lE?B>iMfyFE7$QuPMxCj$PoR zf`^1yhi6Gcs(+EAk|tdgqC~nRUBTI1=PoF)*b|q+KDzpjiTiG#@^dvDKK?1+6a=jJ zYrnAz=_UCI%0a^g`};^}zvQMf0~)_CHrWFt*FreJl0r=LA+EnGpcU*B-E-^X>2*vf zT#>9^CilWeq{Q(uiXuKLF8)NsWCa@iw#XElExg1{6I8(a@$@Z~UL%(zoN*Z9I8k=m zp!c@~IJKfL9j%%THfy1QnbJAu=tfx12GF{=kp?^gFDXNtcGa{ZuQB;Y4~|Njpx0Vu zM($&VBK?}=fP6-$g*LMb*{0G04$P^onvJ_3wld_nt+ar4)5MiL^FSKOJeXyPi>QEE zqbQ^L510SP)H{aP8LVxfv9V$_wrw?b(%81K;-pDqyRps2ww*=|8{4+e>fZZ1=e*Z7 z|JM8dSu@Yf+|P|bXhlXBY<#b&xNFhBeX2%OUpfWVvUcEQL5_(b6j#!xE`wMy;5hrD zJ|SMZfGEa9+-k}T!yUX=E~2>2-vW~jL5uWc9Ytl0-7DD;>kBjWa!p8xi32&p^c%c^ z7+8o@^Q~|(^as3EvPcnCRs^NR3D~sJ<%{C0u$8opFyC;;SrzQGC)6?U(-YYfrqfSV z)0Uu8D6DDywcCa3J}Jzx((UD~kms@OCWyEha|gtJn{bhq&&d`g+uP9Iw9y7?387T9 z^W~15UYGrMt(@FffR+mM(?8=lF;v09Ki|IkTD=6J3XL*<-Z0<(v%y;PI?S$VecuO; zfm-#`#2?$l^;!(weH+~`F9F0)0b=o(pmyB{$3M%2G{sWp%9v@;HW;>6R%npE#t@`} zc9KSz7Gg$S`h=fzFML%@L=oFh4wD-f_{Z;HMq*_oGRhSz&WE}@$hEvqed+ylLJes< z<)?^wqAjTw<5tFDxrn_N@ozQ`H#P>wBhm47&1c2e+>It)q@Ot2VR;>HZR~D>?qZLY zmulz6)~Jf8F>)>03qr2H?{P**DLA!1?{>Y^x?CDiho)!PadPnaWa5~Ze~~((qP!M} zOVN+lY?)lL5E7mGeXU+P*m{F77VTv{C=$zim7J-+tlZJE(K6^B{P}rs*~(|=q-$^Y z<#a7KNT`O2u%M0GJ;8vz4f9od5%=u19J+4>^}@yxX7qxQX6Th zuJfmgy!+!F(_oDS*0w9}3w4y=b^N%gKMi$Fk zi3U7n{p^;K8DrAbn`M*_ru=d?7A-E4+qWu+F0PCv9XWvw>l`)WnNs@KKF}A3HmQt5 z{*Dc?#tLKx^xRsl*DrY-m_f#a439yLkhC!)8wI!#R3f-WlChlB_LOPFGogeU5Qn2A zaAYFyo>sAyWtWAYq!iPWLUWcqkoU#8#?W#?NNMd~c;IbLovz0qcj2sPH0xL?w0VTv zhe8vH3NC@>=t%mlo|J_6jWo>>j8by2XsC=}JR8H&r`)^YiNv)^WZsgRqHqN*bD zpMT=c}-O!e`AIgRX7h zNF4ExA>SXIcR7!pVIG~kgaR)|g_YKa)47MBwqwf^$lIVTRbJ%E^2dXvz*R3~jXU=y z`U!D>Iw@v7#Mdrz7dYaug-yd>RfV}e`lwm>qV#ip($h{ruv<)}OM#G`RtqP50kLsu zm<-<|pUuzlhRjCubwy&)i=fR3ySG9k{r&Fgd)j7qnPy1K{fbZElMCvmMzxYI4n+M% z*QmEZhyKa1F<9j5G{^;Sg&2eQ?e2B9rU8Gq&zXI3DE#QbJ|JFv28HQi?!F@ICL6() z+IAQ}XbRp2*A82C}l)Z;cHc)m!ytpUy6j=Wbs2ASUTS?*QO=Ml!FLszoT z*AMcw`*-4_wJI1D*YlVe*ZCGLlSaMbg~~K8|2%^NZzN-k?eFdgk-ODA(4y(L3EoFc zcF(J8vSL@rCUoV6?&_B~6e|+zH1?ub;okk)b5BfL^2-I%z8}gXde&=YY07mXY$9q- zE4#u(yGfn7$Q|kWvPdFj&OdVcA9%N^Y0Oe7kjX;xCR61eD)px{TAWtyywc7%LX!j6x(g>8AZiw^;&)%eR^4ZwC2spE?AUS$6_I1_=WxF!#^wv*w z(j9!|%9RIR%8o`N?NMyaJ|-(fx{5A?X&jk>R#lQGDJGYXoXl*s0MI6}CbkT)5@#U6rzHqHS5caY+y)Bo zbE@+8)j1(5hPcKN?JjuC|98RMd(UU0Btm5IxkVbj4H@qJqtmx~Uhm|4T}&McJ@WoT z0Guz@csD?)RL)EK9?lPE+RZI3I!3L$(x?9$5djHWpFBLK2-j6RF2CT0w zZ{0;?XO%Yi)Vhr2yGIg3h;jpeZdm=Db$TbdXfl&dAKhYyz?z!JQtqSZkRb2!X`nZl z7gV~RsW&;lIg6tEtu-)XJlg7t*~q*Ig;%mDd_+}*GPm<<;K>Kp0+y);@e&5IF)+K^ zo$q1S*_9z7pd*PB4C^a8-zMZJ`EI39*~`YjIB7UxtEdlLXRo%ae`8pVB9Z3tqP4%p z76R7dE;j7$q5ijDE@8+bK-93;I?n0*rvXv{Zz0BZYzNmI!i5=QoqG2*ChdWZNKT5& zffosij&*@tQoMr~(!)zR`<}4!NY%TG!#>=H!XC-fds-cnTHmR{@#{->R1tjezM7??szMb(vnEm`HcmF? zQ8;Y{MkSaj(rZRQsBW4}laJ}>)gy08q!mx5X-c1KBglu>5ug2uUjb4AL^ z?Sg2qEFh{esU{nZbS>1{qbAVrg+)lP`>W4(A=uZA{=yXC7x{bc-2lf#^24DD0=1yg zmy zi(}V+YghY)eh~kcI=-e3Ez37g9g-9PGQ*%JDQD*v<%E0Y?Y6xDgJs(pn#ll#hCDCH z3(;#9)Jjoua9v&=DJ5n8V0_K(0YD($E>uTho0C@2N}ZqBF0_lC7tHygy~RCPwtWj@KSf57*s5pmhCDvUTj1mk3WgRE>H-Fx8rItP^=hJcPB$y<8 zD!qt_Q7oaRr5HcC#R$HR3&$=4PD64{ZVj=32fCvbrxlURMfQQlzHiVyk7h9+nw*Ld zbRGG(c)C#TOMFE;cVqdV77X9j{oa>;WRHMUEA12i6f6J6=2i1W_p5{74fT&i{)^V# zFAk>*GoXFvDI)g?-tW-E?{MZ0^hUJdQ;6X|gDh?kDIe77BQzDtz5Pdd0r|elQy^~QxIOvfI#){a*6@)X|jr=wo$RdJtk7dGE4KWl6jmzvv#j{>D zXods=gy{r<93&%4)ckfXpVU*E=jwO$?%#cEV#u%UCzhyJ-aIF^rDW@ANU0qbhjB>p zNPoR&CEl+-2tHV}5(aix23m~=Dj#0CdHN5o;-3(HRgTx(2+2*kM37~_Zg#ZD@M1-h%;{HkFbBx>3+AJv zO_R_Wib2)}yl|cPl!2JZ4$zFEKpJyVB?;}FIiqdfM1h#`E^)?V!4m%w7ilRn`c{BtMod+2`3p!Z&H~)8|Ry!k_ zDsGxr@hMY-ZJ_~&ymgN&@HbJkCd9rATKTkOV80u(*hUl`XR(^Ou3{$FCyFMevFG)*{F!a zKqVf;bmclT)oS1Zy$w7A2WbHX)*yyV3QwS%oD+2|i4u9W{GNaRmn?w?_FPqOF-&rJ z67U3R`f_^QWJ7uAX}m0#BJm%S`16km5w%E~>ZHd5KCYp@%#Nflwmr&g>_+Wu~A` zQ8~JEQAT~dLP6jkv%`9tCO8%;>9UrzgSB51T!0QyQ*x63cM%xem-z7sxS!$XzRZ`l zg6u(`-#0(s9lcRzL3zQ~b#cDY|1ws7tRJ?&{!3IcsoVOer*}5oMe{h^4kJDQjqdIC zKgUVA&*{0_s-Umf&Mt7*6w$Yl25Lp5q5Yi0)!)t%vhu7t6_iEF_IN+!NL#8TJ%mGZP_i>j($w~*hk}n;H)lOmk{Sf`TA|4)t9fP^kLLHy4)dv{JE1ZS60w{m~< zdi!k6O?l;|kyU(aAT~PH-vsxM=%&abU%6z_%hMWWXa&CC=$uG)v7_OJlw!F(|XHK_(L@Jtfj$ z#f&UG=LtKFr~$YUtl9SNs`V1#E*M3yl_*kx!Z!#Bi5E>aD4UNc!Q^Fd7095<86m1u zAY6=`j4MNr&KNKJi#`-OFrcZmaSJ{bYA&~-=JJy{?jPs`s`49uy;a3jMoFhYOp>r? z5ZglNqUY1^eqG-+OcD$qtG(QW%!f zwZ8{9?9;WLXY`ZJ7Iv2erYh>(L`fj%)m-L>G1yDJSnDr;E5qZBSK0IRD30X#^&*JY zLoyiyNN75B556x#S=vYW^Ix(C`@B(Ih~$<+O|PjCiW%xD*7t^Z$*MRkI){&7+EI6V;TwbwZvpi z;yQGSujg6ShFdE;^b7^0CKOb-BWN9va)v`qFmbI*XD$iCxO;e9IvxiX@=eAk0lx5C zc^r-S&fJN3RR`mzAq%ZZ;n)-r0z>dj-X`OTyylOAtZ@QN6pT*5Yl>TR^7yqfN)r?e zZ9r3Bmq!T#6`<32JW$7$Byp`AjjVqVBV?(J18Ut|^tX7bTD=izf)yhfZP>(ak^y@{ zM%z;B;gWz12A!NNwm7i*Z(=Bkkmq}bekB>WhiN{tOeqbP4fHJXH4L{Dhi0KB8l8Q5 zXk{5x;DNw{x{iv;WHE_#gpMY2NPMFv|3}R6>QRc%{q?l|Ly>sCs-#jVo%*7 z=VxbE;d-)2zX0jNSxB>%>b*Ong>`xB{#z;ytG$A%a6rPs7i>t*+AcXi;m8t!$U z%Pvr)^cxH)z2HYbB&t9!h^y|gzF$$XBS!oJ`1&^Rb@JfgfO|dURU;|WEsl1I|6?KU zy0_&0DibBqh0bN}Jj>9ZYh<)w3~MK90S2S=XfpmP*b7t};e zgkO4I?>wHFQko#En99#>P0yPj8O|rKpMoDlKW^d2T|5dwTjo7u(w+LUT1Um1tI<5) zqrQ8HiT;pJXH@+oL1ay!S3wgcT|(KPDbAy`NtqjlDM~eN<+yPA1Na1(Tl^*A=t${x zUtSOiUU1+4zAngrdDz_vovH=#1VqG zbfL;=waGX*sOBMJaKhU?|N*W7zfxSp|;^9g%LG@BMq0krz)+-70lix+Q5oI^c zWup-0$#_#+gR9{%gD+svttTG7#hv6bBlp{_E@dAZ0l%lU{3YUmtkX5CobrTY7Cn!$3N_ zC6CX;nVd$z58fA$H|^BO*N+@Uf1law`hMF2n3+<9uXJ!lnkZl($5u@I# z0|+<1nZCKYH{SG?MZbvGzSq8U7kO_@G>zD)tBo&>14ZeyAch&8JLwqG*g$s*K8nE{hNDjHAO~DMEwx?^)i~oXmV>SF zYwEcV-}5>+7UlnRZPGX7m(&Eb5SuQ(=IB@9VFd37{;v6+o{7~QOS}4tGt1;bMq0hD zVajtX~1cQjY@|^zdY%5Y01w^>Zs%eB&1Hf^Ks784E&4R%;`k~DZio29~qKj#f z>A|G$+PT|PcG7ogHcZCKR^2?;FzzI@b0vNW30)W(XBgmE;$>1Q;aBzvC>BIbBoX?p zm$VCn<^N49>IFRrFX3KbkPr%)Rb?^m&c6Q)B&MkQ^6=#2&U@P8QoX#b)*+JlpjBp+ zXr(&A;Xsa_zPf)w8NIE+`g3);S)BcP@r^!0x@zmLI0^;O2vJsl3;U*SG3AIeAVWAP0%JXV1Mpqu7*R)E z2YE~O;mLx!+;}UpKpaY${I8Ie!c5@YW4Rf;>mxigJ867Ca~|*SApXRpc=Tchr4VdV z5W$-_XA zIz`EFeS`3?1acCgn!G0)gs7I6P`&q~o*`y=ZgsYKjk{&S%Z^Yxu(JQ}HV#&x49<9Z zDfC1LmpdVf01KL~`T}xo#RJiI!gj_zme+c6a|DLbg%j#^uERYOWqsC-vz$E^SKW9K zYZ)fRMj#x~2~Q^)?}D<&Ilvngk%%>IBdC)lIGsQUHdIk>^kQs-H$xMkhc93FwkQ1Q zvDnrICR}g2guuA~DD{s`d=B=X<8PmP4uj24D7(+Hq(*7mV>Gj2%U^a8I@vvSXZdVj5N zM{h`Ag>YcYu z$A5||f zFST7QrU2lBMDu|~0#l^8OvwG*4t%)(LseqDo99!+kn`W%) z@pL9954Lc-A|WGybM4^XH7WBEti@yJ0mhz~fg#A0ZH=^#7A@m8)obs^yI{`8?&r@P zv9G-&pRb>>wY;R`cKh`{LD?aN8%E>I^htY~(k~D*JBx>3VxX8=FtYU4M(U~&+Q`@> zR0kRJP1beGp=Duw`$QOmlu$t(7psKz!$yD7`n+pMz2Lk$#Gx9ia#no&T=s3Q@dKZ< zTO8?Yknzjy-8X{eTe}mFg61HbLCEmKtBXhlMfv8Hq?)=@NqXpEaGZB9rYGkOjjY`g zr$8gjR*!PAAJ~l&lWzira&?Ui3CcF4# zvYICR!O;3?_#NF!!DY%pK^!QQB+k@$$V743zYk7<4hQ8ij~E}WyHUCakzptV?MPEZ zRY6t(WgR}JG^gTSfHgp|`5q*Em$ljnl{7e+H5XjG=M&tHAzoHgatDpfDCJ8R@qb)^ z7})u2*=Sj$-{5aNj8w9ul4v&L7Y-&6`QfeHByNwQjg*mObhwn&@Uuvs)(+H+n<4Vl zykGDBi<5(9=cyJs1?Vo$ndr*91Ev;&YwBL&IVI6P#pQupU!~_YFrAox%7;Xx)i*o9 zOH@3eOC5Af*-hZ!j$(keyn#sm42~w zq?yy7L7s2G z@uNO-THRyl$lvcg15%#dQohnz&IOiFYMo?}$db$D*mX~~?ejlXuRLC58JbV$l+FfL zZgWUa;DG`dSuV*qzq`da(5Bf^JR!G2*_*8re98^h*T@jNQ)?ux6it-dMssuB0dW$DI5({*iC86JB0S<5hVj;jLQG6 z>k=lU%-L9U_jYLVc@_X@zRQrd#T!_2ei@_D3r}=Ocq~_>!$-))5D&*R!lH~|qZlMN zVJzDZOf(?pNFwvJaY9R?#nzE0i8Rs=Jda0`gVoQulP+&5-2W=oEF`JA`8WHrW~Jr- z+qO>^;bf#@UQ(oKA`9q?I0jQ~Q}gOku-vsZ*>QsBd8IUyXYu&X7t`!QX;KPVHMRr=5u3ScD1t6}22qTdRz5 z-`rq(m*U^O*YT^}Y0UlgR@a=q2+}M%oHf$3sB3L;(QaS%OfG$lY;H|(6P9*A8gyTN z{Y*`wrcU$J?A$|kp#rrvWZF~prwCFZ#WT(@IpOL9#-Y?Dq|5k<{Jmu+1Lnf{6|0*a zs9ICflEO8%+9670dOK0GP{ODEA+F~GRFryxW;%l~iA3B2Lj8{+5>k%9Nx>Nv2L%&p z!i~ot?x0}xt%VM>IDYpm<#s^im3KF(lmI#S*b9{m%UR&9bn`0$K7C> ze+N%cm~56|N`sP5?$0mCAC|$yg{I`BL}uTVVC7mVZcLFR3x@d{ro1DR~y>zg7QHUTBcf*LAC%FARM*D;Wx9Mhn3*Z z%~%mwk!UkQ))xO$(uzxZ0$axC`OQ|*bQ?1G&nLuT7v}cfM3+MB{~#_&-w6)UIpxA` zEcAQ_d;%IZ(qgfA>-~?@9Gd8?SM~&I9jTnqHrcrLdkv{*(tk}_!_Jsa zZe;rLz0GT>R=P5PA$q7=^oQ24Udh!jH^$T_vwpN;BG#9Ddb~2Ara~tul;sY`3%zsJ zj}RidKJ@#Ni*1B(E(9C0D)aXxphub$;$6@ypS>zMK9n9=AU}R^E-dLIOEU zE2Ht;2JEkVufAO$kG@`Q)Z_UxK8vOYIW)flet5^$yk}Z^1rC0of^2`DYW&bq=aL2R zj*2S`Ko>qY8XO#3XPIzZDtLiy74i)-hv)qixD)VeBpT?kUU{U1sjn9qg#P$S$l-|6 zF#2@7IwUOQPv_Oq_cBGcYMk# zDki$pd(bUGTMNZ!YvX@>^vF}f7^ir-AcnjId5WJ zI}y&HPy^%MpB5H#V@^7%5)h>)LljL@OUsx{J@pzq4DD7Zjr^tDBITeJM_Mh3$t)*> zMh>60teC7q)fKF%&pN!(z?IojXE4}*Um!nc8XU`bN0OFP)gBO+MkB(O$2i(1tIx5C zN^wZ(DB+^aLXx3W92%HH5?WqJQP31TFUn#fAI_167b8*$tsJ6d^GF;9Q-hJxekW|- zyDvz=Ui2Y=AJd*);Eqw(h8Kyk&hvjLs$^F;=f5dtAci~;^Nr}M3?6w3dOl*2e6}tI z86`1GO6>&!JGon-o<*`YQlLeJ(4ranPs1YZm z1U{TLG?C6AgY}5ZWs(uMPu+G~$wyInVNRdNp==GCTKJz%+uJ(Pg9UL^PBE`@t?r!hd$MjVRUi`kau!>sBj$iV<(FAamudeSlH`m5*q8N69Sqk>mP!}Uo&mZMl)|ZH)PeM@ zBE}iFk+1_=WOD$eUy4@ge^|qD#KZO&?K{ja7#l=q_KLbf8$a$A%HeIzuf3UP~YHWBlFY1m_8Z($kuyuvq>T z^Rs-!rb{p*Odv}IaW%Dc)8_R7rq_s&PoLif--E zn$+MJ{7gUR-LEuy3+>kgEswO|wVRzOv|$Hx1gh{?+*X%{yiC%eZW}sspx{@`^=8(Cfh#ZF%1CECZw@nZu@6@E@j(?;^aA@V^z9Z|8 zFJJcgY5xX4Qx?%kbKr8yVD4jc&9(gT4hoT@&~;J<@p7^b($>cn8zw?_*s5>?T^6wQ zwDfjT#(ocqr8n=sC=fgK%U$eHIcOL=yxL)oJUtwDSb650lg-9!$%@bqyBuq~AG%yb zcmP+;!UW$D8^yxhta#v7hT4ur16UKFF)C@T(_g^9bcelU6<_>xrN*&BpRjgN;_A$= z52eJg!5U1S%UWJ==T~Q5R)f`{8cPcf<dJdH(ZrKu=Jas#SL+^9RbeS5Lqsq!5U2Dp9T$5+a_V0S7G&(4#JM zKrbU!aO?B;X37#a=x)#bye4lQrDP|dAN=nDV*Los1(hB~%0rU4xX&7f;t5zP&jBQI) z(YSWB5G3{2laqHYHI9yqNe#s@?pK$2K>YX>SOZLmuT9`K56W~v7G-Uv(aXp zRx&|~53;XsogX3a!F@#6X#48n@||eobMr%B`ja_#JE6x1>KkXiZTqx!=1Xk%n*tHh z&z$!Lm{UA;0%z_C?<|8@@6<|yjNb94GamCyo(6vEb0!+GKK79oYY%2{#<|9;g_^l$ z`wzb%=?0hRo5|y9tEo)llem|I3I0jSgEFWWr~$>v+}{AXvO^X79Ztm<8d1-2zul5IIPIy}8JBo} zw>A>30FEm&>~=s@pYxv-UE=464{vyiq0l3H8eDe*%GD+)0g27vf0|ve5EPO1Ykimt zDZ`zn4|vraOoy>Mn)6Kh6Dc1HZCA+JGHbIKO<(wapD zjt!>`(1M`A8dUh+{8tJY31w)v;lW3XvExEd5$78 zC&LOYehVB^t0!N$Rp$&>C4=&i<+hk#0e#aV*Q&on1n*Hh(imMBxs&pVV1a6L1R5e` z{YnTn6VQs6EO@0qh~o71cjFV68quI{0(d(Ovi+eM^flw4;?IoCvP{N|;`+8*KbmfS z;^&>ufc*yHp!ry|h?L&a`C|(TJC#>>9YF=o4(M|SJxXfYagQKBDL)sT;A=A8|Er$s zw*Rf3zyvHP0lzccg205M)5ID%o+|oKktKU74)z2k}JJ<%dp}h4#O;Ho)Rh2$Q-7E|YtkxGP@t@5v$O_*r2O zBuETvgASaQOTO&RF!SRsK|%el-orZDV=?QRZ8%{;tv0IMPeu6ir!?GB5#T}RS}A@Y zX@!v!D*V&&3>W2L00v`i>AZ(Q>MSM`R;!dFz6lZ=b~d_<&JoT>)9b|X1KsDqx%u;g z*z@D@GydR&sjjRQc!sI_IrI&<6!&fkN2%=C`CGZrf#Ndqs%>wrux->p2oHMtR-)bM z<-0^UX1GR~WPMm8cj6(q#J0(0NZ7GeCYr@nHd&GK9vrglh z&1r_I4v1rkvn<;B5cSiyI6z^gqy#$7&L#kilDlD_dfB|cVdCrbb801}2=G^k=O7N2 z%4E4okP0Y;tl4_Sg!p@$_-{2FHI+gY_IwN4{%Wa79dT?p{d{`FvVC#Rg4?W8kW;#| z3?m~tI&5+SQfvY_T_WEO{7}T=CnJ;qj?7K4mskS6#pKFjC~`SG!4?p!E~UPs9N`Ot zZ>UF`C8U`X6EAF)x5OC&aOgmh?gwoC8!UrRpiBBZ3`O>E6r)ON&jLe_yA9zW6mkpt zb6j|5ZtXpai8D^QTcEu$K^{iX``01t!#?B$;f}0Yt(<`D&oq-8t`as%qE`co4fx+b z5cZM&(&u61jepYO!XN(+aydcHLraXszsHyL_9^Q9m-{s=n`r*%+v9Q(GrG@sZ*yL8 zaboYCS!KB$ZMltPIhb$RIFl%W4k4q&Wv@bj5pUdE0u343y_}cI41)w0Dg;-Hgce94 z%tZl?EjT5!E$BnH zCwc69$$t#0e*W3qNw*ylxZC{n7;W+;diVK}dzJiEQf4HjcAWh+l34f0S{$|jG!=k%7!VzY2r4s( zzn29i5F zfMBHD5{JwL?pRWZ%N|UJ9~DVRkbARXj5Vf&*B1JoMhP=zav|NiS4p_c5F%5=ldNG zhJYkJqNMkrD4C+<(~&i>%=?=-mPs{`Sb|j*KUl^c+=s8=o~BiAgO-_27-Q-T$CJv;iWbcLuZDj^!2@<=ZDLl-K$u)bHRK*9eO zAQT;%dUGd+irH~Fparb6d?>|Q#{>j>HpAurWn3c>u z^Flt%qV;<4XBAoKI6#a{bTT#(YE}`PT!#0m+EyKjU4$|O?xBs-k%e^so4y&hshEvR zA6?wZ??vVS6$N1iF_YixX7#elkM4JQYgVY(+$9)JD3Wlyc@t}yCV{x(KPiJ1`*O?u zH4*B6*E~Ne8-%0$-Mqs_{h`gr$X&7yUHx|8c)h>*#%S^5n)! zDFN(l_ZrG7)Q9cFG@ucd53Ai>7Bg-*M<#1mtS95aEpYC1vGgvkWFFN7S+|e9jZ3OV zpHiAm;ZLMgQNEP(6q*V8w~E=~B`5l&i)-3${insPk!ksJxEzbI0;gj%qXpnewl zT%i6SwuedK2pWp>)NENkHeOsw^m=eQPp{TsYU|wBG51$+#ba#Cru|6Wt-(L-p^zv% zwPFuu-eT0WMX#dXzrVy4%~C+;?-s4@=FCE7eaYU|ip8BkA>Ime%G#R0Bcnc}?6!_` z9!0W?-G$%>5-+un*7>ooXWGe{q5@@wVwSq$yBvTCew9+NBnYA zbFoRv8sf?X76Dd~6>O}RPHogCTu*A(cN zBW;XKPcCI}h)k?Dn?d8#rtV*hqX-PeGJRt^7(4ZPM+ghnV7!SA{V*?u5YE6>XZ!#= zT-YshLyO=hvk|08`|ZN$WkBYUn{foUTie0lEDnwc2A>n@?1U!f*38K9XKTQ(Lh;~qiYuMXyz1sBJpWL>x8HNxcpZo*u194Qhjc`EKi{sn)$ zTBE6juWyh{py-aN9r{htc{DhyHK&9PvoL!;9`02A#cK(0pTiEXqe9{lgYU7aAf94~ zLAUsBlF;B%($BknwY+MxOdAYHRpE$mjz-)n=y~sG=_pe)pQ7Ad2Q}@=iW7CZkUtG{ zG}x+jO?x}^7jps%jcWHfyrX8;m5M_d{demFENdi*-6 zZQsg+6K&bo;>o@LZB26peR@D1Z*_`3+O>#2QzA?}UWQlwGo&6Tgrim>_~`}fhqD&3&>DT$i`_3Ke>MW>2(*N?CmQZ}4L~g77tQ=3 zpiF3$ssdNE9RK~3c-Y7PiCs8s%)UtaXZR5fe4#u_ZBvI4$Qc*3Ezh30{4IlcuB)&HEnn_gaz~cg$TbIn{t1*QMM&;V42dfoZ&mk zK=>dC{YvRT$X2XXtWUQjj7DITgbnuW5(6${Q`GA8U*D43c{e7S4bt@^Yk~o-*+y)qJiVD6>d~XPvaUX9_ z+cVJ{R@(wm0^>J5-yG}j&r6-9mabxxVCot_5ngRQ<&p6019Dhv8qO}9uQ7-Z$#XxU z4W8zRZ_aQ&kTE6}5;sYNb^2eUg0zeFAY=1r<($HY84fM8Bd*>?T|lhft^Sd(l1Wq| zkP$1hnw=}^>degKI3UH;fvLjaRRNESI9fqTyf-Dds#GA*Cf16HF!{NN@j?kh>{tmq z+^wz5lkQ}12Z~vhEJqPj)zlb~Y=q}j3yd8%I z`C%`+(Ho&u)#NS>S`DHCjiUZbX_o%kRiaPIXx5^Hg}ZQk5W!OI3VEibn@}o652u8g zY%gvdWb^o#zC(=&h55_H7eL=OiGKqt|F-_}43bA8%3lWW(e}gk=#J-`Y~Pg>mcRp=?!mgs93!KwW7UleAZJ7^?q!7U(B{ zL=WordpBlk`bg?EhFFOjpo)httb$ex5T+2M5JQN<);^$4&J^G%lB&i$5DHGDv-Ts$ zI)`tzkAh01^XiO zfqD2#TgSaoZIegV+mqf&%`RT**8Yfs5oL8Qb;wQkg#rI=7N)mDON5a>79`zHU^;M~ zQM6|N8_66!`sy10&_^NS#W5>t3Wib$;0SVyf(jbmnrBZv&S{gsigcW-OW2a1H1Zf& z(OWC_8VVixg)BsaqB+6x(e2R_7WXl4XaZc7vGYr#o74rGY@W@2G|ApXrkQIRM&D7n z`cK1oCrmejO=ew*n`Zef@$)?Q2F*x?3wjpsrF6#nYpSmcLx{_@H&sXv;ARCHvO9#%YbR z!q)8q`l9@4+4-=Wr)7Ajb8`0ELIzrL@}!`=kaqE?vW7m`VFB@b9q1qzwCtd>PG_yL4}xQa4~36Dx=pELu)63Lej zRbn@gjmVzhgPfxK07Z7j%^{=qUS;Y4&FYW+9HF!J?W_ID+25j24iBm0G2IFwxz*gL zHT=qz|Jh>=VkRxh6uB?x5l;k*PhOQniqzE|OH%I8tfE7{Y4dk^K>gesMjV2r;ofJ6 z===4(pd1&&Qx)Ik2tAeZF*kma1cHYh6!GqqP7nw%g>gJmfF)cX!(b6-u@Z)MajYx0kD4eSD!BF!O^~G{43z;>WIsOKD7HCXn*5~L*dX`{j`JK@~WnJTm1zUKMtu1~n0Lrrb zN*Vtt@vNFF-k%LN7O*m0M6O;Ir!^UH2w_YZ5BGmufMGazYLYB4FL(+-`kz%!Ng9J@ z0AA2<=S2*P_}Dx6(X?;?R1zBOw)W)L&`~Bq#H>qrHdw?vJh1 z*fS7l7YD5G$`tI5T%n|ZLl2&^q@mh3(73Rv30`xUk2xMDO+@dCwn}#i^?8PmPP+*$ zh(5<0g&Kh$w8m#Cf<8VvLc{-ldfPQ83`vH8|4MSWrVo;OFQsANjH{IZKG8P1V`_!7 z^KAe~q%&K%fB|VOs!7O+nzuEtNBKqJKQv-EyBc+TQ-HGBU1-NdmWJ4dWy;Zu;$wdLl zH@0wbOSKQnW~^@SyRYAtgIWyx(WwvwE7AZZMZN_KHVJcj=Uz}GMt#gSndMeX0Qqu3{@H>O9u%9 z31%*A%-`EbZn$5*`H2w6KN3<(bT~r%J$!7XL7esvDtCRwiT6IlQF)$<(8mzctm{4} z`wQ-kaO%LX-?1-QK58649MYg?{AJ@LVY&KDAT#ueC8d&3)N6u6Q^ntLIkHVjPgG&q+U{4OG9%;)#q`qgf_IoUznll=I~OLTE6~V>4ch=BX!2 zMiWQf!EMvONdI67i$>$a#C3@*?<58_#n4uvOm^ds0Pkdo&QR@*n+&KX&{jCZOoSM` zCbM6Be-JOBFavEKISQ+ChtGam?*Z-kN6CYmuaA+L$TBtLjqTehJyS9jJ|zv(4CHhn zp89qsva5yWHU4dzT|`wE#gzKm-tFZT-tYgJPuOFBS&2WM4TVi|i9GptkAK|%xPI-q z{<3^M+gsO$5V;Cf4AZ!qg8CWqRq8b#l|47hh%fzSnY(A)@$+vD>+42CBUz)u#QI}* zP_}Am$}qX|kWGuIz^S}cYChp2Ci5@lJM9ox2T+qP}n*kjwa ztv$AFduET#JvQH*bMO7$pI)o~_3EsOjEc&Pq(hb*wsC=6LL!hI4p9;{0nJWyIvEz} zwmT%jwF9I;IQRQPU32f5JJ|jwm%d$Mxmvr z2greenCA`mxG$X_SNQlw(`W4)bQK1kJt$e6q4rb+mpjI|Oq-$O7X-LEqU)Fi5Z_~g z#00UXYIDUt!Czs5Apw;j3`RzpJRYjdD}ZA}Yle9qgkuFug-mZBmgsPeIOP5_jrwS~HF68w!gim|9yijvC8*2RU}Yz?x27Cwj8}L?E$ETgCG(k{$E;lw$TaB)4iQO? z=10P(9POIA?2`9`aw*F;eWnJKDU@5b@X$Tz2hwTz`hvj~ys3sv0yTi=12`QJRi)d* zjsU~mkOq&E`Im6E3WHt|l`|MytXVw$osG#B12r}V+)Du-dVyoCB;0Y z1+JU#3GjD)^j}2Ky~AT3biPM%?ss1DNO@j>VfCGzljQvGoN}ALu+wV0B!qWwq~m_z z>xT0Q{wad4L=DE8PCye-YkcgdP@_O2M2xB-*n3_{!U>`RF(swZ5#m@Xj55?-3K)^<1^Aj2vHlYCy~&03X4nTo-h^4@#xbxN&JcQRObEd zjZM7*;4;(}M)UN~N05&uR3It=jwIa*oP}d_1P9FENfBLs!$j-brv=1b7+8%gh0eD5 zB7P)e#K^1Y=t`0P$$Iano5j-%^Rw~QcSbMFbr-yCX6uoo_9GZ&9L6vPBxbCUV+y`H zOc@klp$kV2@xsx*U1IGd=2rrNCClK_feCiABv6J626W+HV$X2&xK-Ta;Ot)|g9WI^O|gaFFFha)=F~&#<$>5yLo(%mrr|i8Gv1 z!#J<#>oNEPH1n_F+b58tH+buk%2`Z$PcF_SO8V0QZ3DAJvYRGVFtq@F3tY$>-70r& z_(TK8Dp>p96L4FO&5oo8yL=<-W^fM++{K4s-0s@?7*IE29z1NKSeeC8J_wIXk&$7r!pyR#^==+rBoAG)O7lbiG*_lMC z|1p66@+s~c76In|1`4O|P1s+W?!Oe!M^{%uS*$m$gtw4QqJkh|Ob3;C#}0;G575v# znS=jH(9tN((&lo6r0;haH8e>4VeqMr@C#HbM0Krg5rsq%U`^|AZ{xD3^$aHV_nk8w zZqBf^@&{Yh+eL*lOKOX1?gvt}Nv&?cRF-Kt_AzhsrX4&DORFKx zR&j}f%Ai$y2(!(?tzkz1kdwLtubKMVNKNlNR1X|2ZVk+e`J6YWUd+<>Adv~sWhB%4 zNbAenYH!S(!*Wc7#C6H(PmK#j>NgKxcw-^sE9Y; zs7r>|f((PDl5nw3p;>GwVkK-&X~%g0u?(D|_K%lGn(bR#oJAZG99IL`XLNXDM&&{)m^g`MFSgfM6B?Af2#3O5lR=8<&QA&eipg>vW_#{KBdypv9%_YfbX9xXjUs=+Gr&)_mc9AG{T zr)f>N_f}s>T5Q>nkmJ4qP?El&ybr^xS9-p<9IhyrkyXEIx0lwPH@GVYu^`g?O!j;Z zTxmQh|6KwrAa5+?v2N_ZI_!0n9Wkv2VeRf~f6Oz%9p$IAU4+2m?2z!O@K{*S2xG(hw=nhOPt3#W)Qjkryvoaqb_rYAqlah!kUCSkJR%IWZgnk zyHiMtiDXNX_2T2fz-YKdn@1(ZseS>M(vngB)}awpGEBxPbI&hG2t@-vV?<}TV9X+P zDR(FFqzQBbtjCK=ut->m<3yZg$dzql1G9~$P|w&27{6BMmIG+Nmt9 z^8RREdbpx@HG9CMo|V=PeOTyv3o+uwA-6AP-tXD8HAC%01<$b}W%utQ_<8V`|Ce+~ zpuV876)h(lcs^e(%4~nb^}J6RUy2QnjsZ!BklP#`QqOQPg=4*v@q&%`w;i%?`rUH& z+#b<0LI$*BLL*^p86K@9^}m~jH$sqQ)|)|5)AeNTzbH==ED8k81588H->&U^kK%B} z4LaX!lFs0X9aF&iKn>#iQxJzaO-_`A1)yjb{cbzmNQs#ksbcj1^;>`(2Dc=2FQPPl zlSiK@zQR4cp;E*iQzzBCbkG!a)gsAnB8~K6t8qe;OXP9TNZFKklFM2z)p(1+Qy96f zx~12fzl+i~v;#hhOMKz>ek6Wj`Qj#9qYy^B|3Wq9tcj>p%ziE;S`s(NJ3SA{ zMkXGz6jw2t4g^7vs4ac2D16?%-�~!B_gE_@NJI3c->A{01OunBH*fUgHw-K9v$* zP`k>%>A!;VIk?V0^2!#JCQvaWorSP}5U@i3GxWf(!AZze9u|g?+4m_9J6T9G|6LH3BS+91yQ9&8GAP*(PZQGCO|H3F2)J zW5hTK0*U5BD#-#mTp-HfUrwlLH*n)~DIj|6gPD6V)urx`_K-AST0+GkKp#$~3qLAN0TJv_+1^)!QC&_|2?SC#FVa zLc7MX;TV4a^vBl z?_V*ycMBR1FT5?CD}Xr2azfvX+LqGaA^4}4bgD<-w)yXN6PUfg_@1EN)3?)Cf4$P? zD7~8u#)U)5Cb~7J-K08b%fxvjkiq0z1#(ApoHl)v@hI!{+RplZ?2pR_-$Ua!AX7%5 zn+)A%EbCtb_k(Kh2eqHi@JH}01d9%zE1ozr<6u_7Ei#ib<~zcNw48$?RM)o`#HOK2 zh@FYOVfq=F$T?b(xQ_qV0b!xhl1{iF^6a|Cy4s)30wZ(Fndy$3oTSuYUlG|RU_A2>F=$6KYs^RU;Cyd zk(e70aNaicjmLylv7R=$s6+KD6_8JZoPEiAXU~46^#*bkjJ7%4!X4|mKXl47d0l#i zS7(ooK;*`W2KWEL|iN%diDm)czBrd;GaL$_BDM%PTTi>sF zz6Ceu5k64cHoU??dI<39Xy%BtJHw z7V8fzG~DngXP7}qg&ClMO=8>F0~WJc$lEku9(7^A7s{lyaJHt!-Qyjsph9vO>{~V)+Qs5%%N2{47-wy8AmblL`uvnI=gqKwn|kt!8si&E%P%}3zY#nv zAe!XOzzP1SVBIO5`>+dEDr5_Y3bUMJ%AUTKRu^sj3_lhRbp4_nzGtd zWAM1KM4aDc$1OsETP5G2H!jG5TxvdiFoX29S{BAK24YUAR-;fPMw2e(EJ4?y48Pjo zjs}n31;6Ru6;omO9w+kwjX?>*I!)W+iXXHA%W4lvOj&cn=eW}|<}_vCw1T0pz5VY` z=p6_cz79t@UY+@){^l63@(f`ftCi@fWf<*L&a_ps3zG%rm%C?{4olE29P-JagEk&A zP4_4()y%v2A>2#g9DMNT0_>xRF1#9sYKD#T9MQFe%JJd`&JpPf!@y-5HW(n%EjorI za0ejAF$mG@7ME$eOt}PjV2F!j^H=~c6cO&b1iW#QKLFCP<@w)myg$Jf(xs0_;Sgl6 zJnt6e6Yk!Ivz2>liP3~NS*w4wQb{BqebYw%bgJnfA9heX{*MPO!zccS3Qsgg^yA1L zggeUBNko&9@TN$0WMDhKR8p;d@y&i-?3BJLF>W zRim@iN;@^^f#zD_RAYD%{@km8b_~Nbr{Be61-jU{sk1r*5V<`jspU%_H$DhU&A@iZNphX= zFiSwzs;MEDR!nlb3Lyg!R!sF|Gy)1GfT}9H8eTAz zPaI`>V|L_lL20^Jp$kI)kir?Hi_3~3P^`b!C=XuQy{m7G9g&D~HhLF@F8|;q)xH)@ z8Q*%U7YFM0c*^=U;veHB(b&zj_L095Yo!TfuuGP4b47m`+{Da@ffRe1Lv1NB2%a}E{0W2k`_b(-t>YRz;Pywt!M*M|_OXIml zrH^JsvYr8QP))1DO_W(s*!~i2x|TvPud`>xf)-=YUhEk@Qu1R9=zS}<|Hb-nXUa1N zZ(#2D%DE6?ilN63;tb=9A9{lBpsJH%v^rS3TD9-4! zLrVHjFc6EV+RXgYb7UqFR+?x8TU_gcTm0KkTYst#eULA1&$i7ftz!V~>md}|hQX`T zr}yB#iYXuVR4+)Y@Jab^fis7l=s$?gim|O_G;(pHGA~9#42IGX46l4h&uhHybL#c=IHa9Hm0e^^{ zKpFrPgW-y#J#upPZ$W}A5Sw$$i-qLa42|6CxqD)$?{JBD8((;j-%zyKieSsqpIRL^ zbp$_P=<()_^G}Mo;fp#sa=#G;xrE%tgr3g+0(gTXDFgNxaQyf>M_};EwQ?|frt8@k zB@nlKuvwuiu6t(a{f~A1%=5Ze`B(Tz1eD{o-6$pCL6(t$k$g`-DIRv+Fzq@za+?q?8h2-qA_i)+dISz0fZ}C zQ!`Abij5hCVk5~gMLA5|A=T;3_Bh|0xDp6Eh%HJw88F-!6e7*Q1pq80O~1@kqZ3vA z@5s}MM-YZ05?8ERUwO5l_#l!9DYqo}j;)XxscM2cvkpU{v8JmJCY*kBRnQ|1K6FDW zKS~>)s(@bm9$D>c0a&~;82{ko_7WCy3MvA=Rr^QGHQQDVXsBMRJ{U4u9}enUJWfj( z5H#?r8%`&qo9{7m*ZV#HtoH>-H^ews1BBUWvHK{ptA*NHbhPU^B4jQ!mhw zOBs3xiwzMocUO*}gxEF)ANG6eS!Yr{xHq24T#Vd-c4-Rp8!j-^Y;aU~+=u$nDr1?+ znNyI;lZXcnBIGBFjNK!e&MQ1L7k3@G6U9UqmH(lz>Xzp}Wecv*CX7UtEV9BIEz)7T zT5C_oJnXN$?QwlV{ym+9Dkz9X(Khz>_cw#^_ubt|5A-}y?7Do#KB_&~ z9VmvHpSrf)abc76DTmN3cxY8r_b3|ZG+`sP7*9xYWaP#T&}rT^FmL5u@Mh&0Geo|1 z(RY8p<`^ERp>Utj_a{&S=jJ&2E8n6Rdw9BUumZL*U` zu+Mt{D)8i3Etc%*cFXb^e-11G9USC*zs28@VJH4F_U$Ng?@3$bha$4|BwtU`ZaYq17I))ju3}z(MeMQvT?pVJ3 zKbo{%^Y2MVO-g{oONcZe4d`MeWAZUiqCYE<3cVJ`n?0R-vFOZYV&;iWc5zPf7Xhtt z4(SmpXomrf4Jd-BK%Ds)v%Isf8?RB(#Zi>X8^S$0bczVcud!WKP6Ctn*#g zznNa_UWWbu!1ce}RLL5AIcechmjv{~WcjF4jivGFI(Hny#>MCJ^Ojw;C3W(@8rocw zY@k{4zf=02(tnB?0SNZDy7ZLv&yR*j61IXn z3J*hm(A_RsSb?gT%Qp}KvP&@u;hIqR-`0B!%KuM36j6uER82nuxHJhnHh^REj->`K zg0Pyy#YL>q8{YD`eLI3Bm~pqBSh=DLn-vHjr>ku5M$*vf(?f{|C}qffl*#o>Ols9X z1f>riu1tKtVRTCmbB5TFdh=%uU1urh8ZZi2v&zzkEVo5d)0$y+h=N0Bb4i2~o}sOM zaOgCg1H)dNeES9a{@cb)9O{5hY;&)HO*d)qZ?wmj(ARInWw4;LiJpuT(-a~N+1L-f zVO4#a_i?qE1=Tly@2R6^Cbh>XyOrm`WZ=n^hQ}|hV`*KV?x(M#r;9&)n*jCJ_^<-! zX7BOYZPO+LD>H0=EvAT|%zZBxH*cxGAw745H;=S1ngxbfX^+&>od(6c9ot~T>tXc6 zxEls?Dp#qggW!Yi8Sp=d0A(1m_S^j%Kpnx$TFFPrprd_&W*u>QLeETj$Tf$&6g+8! z)rO66j2ZK>(oX8E?wkV!8K%&7(M6mZP%RlZ$o}9das%N`ByX3pWFO_uYu4NXMK09E zz;j!At%xZ?VdQZxLTLXD00i$t&v-fgq}QS^0gjizSgo7>#m{p|1_=a|_*NAx zJD6SN1HX#0p#sQ`r5+Grwvg0N(a#w0O>gU={#OfNDeR;I)RYQEBpPIlbjZcV z@%R;XTLek(v)9VG%JT4OG@atU_=U|O$qrK_B7HTH+a#N4JOwM*2wfMP_5yla2k6xBssUqd2B1yReGzv8DyjqJgaA{rkue#47}{)>Ok{0Uh__lw@vV3 zf!~LGXc_}cWaU)xQUg>u=CGm(ocpf?|B4v3-J*PB`qVS9I=c{%Vl+rxF_&?SPbsM> zLv`nbeKtjLvIwysXq`A4R-`*b?O!i@t&qZUwNviF#N@&BGxcvRhSg^bZ$O!eqnATR4il$=$K5y zjXXvK2Ny2R*^Rh~g{^e7elqzG)|G=DXQeTQ)~6l0IQjpdJ1aXLEB!KlbUrH4gTpIG zxje4ndw@j$MP0X@VIcS0Nqw{6lE_mGy@jCq!FZh%zJTg%bQUnQ#-ay;%NqLNg7t2$ zo=>2?8g5RTQ5#oi6(T})VfupM{$0^%2GZz z)Dlz74^06xmQz(H)zb&BG~+w;*U^bzKV}gK16=7eo!s0_Dy-lIPzA0!NdmP(=!Vwj zQGU;9U&aF#1L!{@h^+TV1&_KFW8|D>U=XpIzp5su0CaN5h4ABQGOoVSFk!n{c2@;d zAKj>AUK-{dkQj*@bIZgp?#tCQR|xoRaOqKrb@j-7L?bTXyC$$if?t6{6GT|IADnjI z6+a`HGu(q4>u=UmQ0u5)B|%-Bh|VQkpx0UTAThX7_&4CrZ=WX zFR)6U1i#=Y_Qo_sIkF1@;20_Ea73grTihT#g>#Xy;58?YkmjVrp%z?w9@m)D9Fok# zISLUooR5|_4Oxg>tXs)DkNAaFd55`(<~T*-gNYH$&GlsxyEqU2e~P;8`ESBZrQj8b zZ57{iz7~DL7JT=QoMWRkb38-CJ&_Wy6%%IUmRKyJ4=>FwPNVA{YsK?PcIJP}0Fh)5 zSFdo0gP7;^M9tdWeYiGZfDP9P$Qx_mNE@Z`P=(S`!_{Z;$HWRC9%pM+eN zF&pdtUB)+k8Rzwb+c7QF*8o#@!A516DH6CaAr6W)BrC9KHOCc2gwn^f}uRw z?r`tI4qP(atXXGUF|F$h!~oni-2ADVxiN+7$&8600p9`ROsABSF<#WwHbW_zc<_qn=R_ z#w-ISQAe4Q;f5V$l6)+Q(MSam4!=jLS(7$Rp7hj%a%zF*%|oI_RTIQV;)!&-Uj3(pPDd{E4oMvmnRK5{4a2 z#Ej^5TWuASY7O}*(NrQ}bV`LvSX?}u+kyL8#11%iyq%@y*5=0Ht>;7f0hD4{)cR!7sB3#nr)OQ786usN_FjOF=Ag%n)(B{a*a{ zm{;G_{NwDt_unKv4qYzpJtNyXz<~o)qt+AsX})nr!A9262rNFiPS22q73Q?+j!cpn z-)MtdEtxr{>0GHe-IWg>8Hazb7>1NG1ByEB%ug;ox+sVlpIWf^zSR99&xf3cd0q?mD1A7)=&x+c9iS zs|elEmf=$5rF=FMv`gVq4jM3P)T%or)XQ|EhwZ2nXg!t{?mJ#**m+&n6_GD!$Nh+SNET;P^QW5L zT{#Ho7Mp@D=<-n$$#eYDtN2J+#4_;toFj)!3BochjF$acB3wf-g@YtSP`QxkuZ`Kq zxJ?{gI|GgheQXE_I1D4qa;puVm+JqE>F2k=e{wD;WAK;-%Tbcw*ADT=xEm)gUZbCF zp4V3n{{C65PooGZvaANjfdnz10CF@LHwH9-v%pR4d^xCWtPC{ZZI!aOW|w3zvbkJ< zx~JscNlhD!Z3;d!2nWyADQ2H|NIpZ9kCPOaAs&p|yXD~xmeUau?cBI0oE%0UOPYXI z)y*Y(Z|HZQILG(b^Uc`zy|&D~(*#!+jYi|Lv?l*FG$Ke;XvXi#)uep$Ivo;`_EvG{V;06f6Q2D`{jWyvs}sLi zqu5I6`LqMT9_ zHfL+N$eNz^A*ug5R;!!>>^A>v)yD<3ibTiNFs^r%IH@>4dN`yUR#Xc9btsauetB$0u#I7fJ|>XQc41Vr*xMjD_*5GWG(*?gS(9I(t7{=QVlFIPGv8jD%XKnB+Vy^)Xj4U!o)adAE+mR*Jfsawoc5@R zg*i}La7|QVw;Cl|YHznCb&$E4{Uu)@$W+4<>fq`EfUL%aB)(aYyeo|5i>IrIawQR>pFS8?|svEybj~bHM0|2dyN{0wIMvhH%%ei zjY&n+JZAoB)=GhzPoMS_szm^G<~4#YoED4@ndZFAJ4h#oypnggoEzF1&HX;As^ z9StEf%P^`&(jdI$c3}+wd>1La36ErH{@1x zm5kiw5lR$$&+DeoY`6C%G5$f8JYNK&@|C!x>fhl8;>BHwT_xhC{x!G+u)ROV@{W5w zotE-B2kqo^jIIt$RLZI~Qu)l2@hZ;T2?SM@*K{NjCqo#(pUks;E@5XjVrH?EJPCuh z!-Qot3U(MudQ`pQ`K_vJU8!Ks7#|3`Pc3IKx&b1XP1ZrPP$Dvz-(zr62f3YBN8-Lu zWp&-QVnvj)%zHEP-ih2OEzKLd%wZ+_WZ@3StD+G1g2Lihw-2okPpT3;dj|>8BeX_ zw+>?yCILhcfuIEtj5(-3-(25or?aD@W2MvVm^05WyGxZds2|QLGyPt~Wp!bh-9ER= z^?sXu=h`Rb_n&*!0M{IaS21+ARr4&N6ypgk{$|T!94;5!q8KuC`COB)0UFnUp`a2Z zPHI4}Zs4|L1V96nXs8khxe$gYZC!*p1tYb}L>Bg&*t{dlNf_XV2a)&F1TchaRHr6xMYW7mzBnwU9{pv=IOn|0P?5X zt8MQ_V%-F_*ZLuMeTm!zeP~385G7m(-*}f(?KC{FFdbs&C==wW6R9IBlEjE?!>r`U z!Un!s`^n3*u zRoZOSM|ECz#2tL^jNXuNBoA<5B^@N^(6yuq15HAagPd0=-1qNmc6NnxdL#&*VFIwK zlGMvwt;z8@L+)HCBK_I6CPHzK6q%b4{bR*S`9`YgCIFS~ap*Xuo>$u5cJp{`SoPfe z>+j?$2M;Kq@hyiFK9yXk(b*hsg@nZ~wYYM^>dUAVj4t<01%;G&FG^Lf`I}!8l{cg6 zP!(!LFU|F^He1fLY|{z>KCN4QwD_N(Yp%41ya?ELkV^z$Hc$o$Cc3u~W9OeJG?i#U z4yMOM==vVHPX}?0n-@vO?XSGo#-ni`2<*KFIWqcQwA)~a9lXr}GkG6?#-b7I2BBBd zn$}(Ff!wW2thXvV0-(C6bYVot*bpUyHUk9)R<3_v9-vK+KS=4Y2k-8nqy;J&=msbV zw*!WZq(!^6yQc^G`oI8nr3Qccef7@N;&y0c*Bi{)W9AhjiHe%{-ErC$xrBbfYT@^boUrs=hG*_1NXXR1NKT%0z0&3MH^2 zbU?!)uT4}@6O&o0lQ4oP2eGxw2=9O9Bl#}>tyqR=h=*DlRyjzDbOR-;=(QB4F;Dd-Z_wIs&P22~fww9E5#X#hH?d zlUDDLk4`<~x$(J9QuF@bBM z8Gds#hyNL#5wfjV#9OF(aPax*SnQ_olT ztpW~i?0WCaSr)+b!hBYSG2ZFH8S==r^-8=4dUjdKs8>OGY!y{9Ty|Ncnk$5q?T+u} z$n?XK@iVz`u~Qh7tE5V^rzAy64C{*(}`W)P54fn8Tex(MPskr--u)1;sv^%r>v z#5?J$wTm~2rX)xaU8YWB;{mu?dmvy>M#$6`e4i2vY64HwU+*n||3 z2JJWw%to{dwf&)kjTTM8$KW37@$7V+_XkWC+!ihq@eTkW14D;3b#t}$X*PFQ{{e~V z97ajnvLvqw&EB?$<(6xZ2jI9H$zai_m`;>G0dCKgjJT>0HwW6@p$g% zy94;sL0Q?U#@fr(v%^0Br@0gyGijjeaMHd*a^;?@7-=8ua7O{MQ#y9XIa$hXJQgl~ zi6yexam}vq=WC@u4~iCSo&7bRN=j0h98iPZn6LnhSU*<539cwF;VcuBt)h&~?Y90G z>8~A6;t=|AmV$amX64mOaz?^sWLP;B^;B!(ubmpH6Vmc+ImD`H6UeVk&P1l@pRuGi zV5Meb^x2}^xRFo(p2o?tlTn*Ki?S?fX&kP{I5~C*)hW%c$*Vpz0ZJ%>k}CT5EzhjR z&s8f6&3>zfp8Z;pf)0CXK+aT{oC8BWwlbG%LiKY;cL~HO9_(E(ObYI&>c&sy@nw)( znI%nV*$y{zu$!MdpHNSIkB5*J#HI)R-6k=NQeb;mFG!5SVQUWHMK_4Aok4{fKTfqW zM`qx0Wgt97zi@CnQ;T&3Ot@Jwi^d<9)&oZqCDe3LEPS_Y#VM`FZj=l}y(7baQpT8D zOdVAoMD6Df6!;p16IqftsTLR{(?0LWI9i}b(c_sffRa}bRps(m2Qs$WZ%A3el+EOp zf~3l4m-t+IJ0SkCcQU18l-YJeeyX|9$mSiiC~!AMxHe?yvp`tzbRCT4t~C~Jjq*D8 zSeRJQjNc_=XDrVvI_AL>j5aJ@HrmArvO^e>(PXN32Iu}N(;wdS6F=STx= z{PP>{N!;X=%%mAd0#f-RJwL>w)$UR+|0dT?(MZ(6umhL+r_g1)ocR>K&r8IBVXUed zn)qQwBij?|5hmM^08Mdr?Szzj6cO@q@pu*~=5x$UMsEW^Sinq8Y_MlaMZ zEX7IS>TWlO)%s8Avo#Rq4-*uSCq$PQi`NJhmA)W`HIUWN#n;uyU|$6@bKzhh=18uA z!&v7TU#eywtj9do^GQLi_|PFj5j*u1wdIiOyy{81*tv)EcE+ifebR9b$9>)m%E0m2 z5=#z-sjdMC&If@vQgF?G;?{naIQ;2Zi!$tDlk4P`GGfc8FqT=!S45p=wVWVaFd^S- zr3ST1W|5TGx#ayP$P$ONGuVepqC^S3_aX@_NbQjdkKyAOI~^f^9za4M8_E@f!t)E$ zU6EGSUN|C}lg;IU<2?u!v2}h~4=(=ZkMO!?kQ^Y8y@|n^306GPQe0?ri4ZO_)=7+S zQ+~qzWtbp)U`*4Pie)UJuqY&pEON7*WP*wPd|9|<=lnHfNl>sjtC^Ws=6l8zrSA#D z+zW8N9w&a`s?)0<4r&xQ2R0a3dgE$df~>V%wW<6V zk1?1!t=-1qoM2ZQX29Wh%Tp;u)DLF4RJ2`x+b4L~*9=pcnD@!9GpdXK3DF#5>|U`K zLu$K(@z&S{YrI7&CB-_S#i?Oy)O)`wy-&r;6ul{J9UReVPs+_6l-=#08hViT1!S(z zIT7XesQEFBDHcu03^swJ%;~fmm2K3ccZ0)3(}o3ARx5v^{XK@+;UW8optVe6D$9<$ z9Sc-~Xp`u0JVu?(?U!1g0yIA8s7Cx70%e1Jeytw3f|WvcU>@Cy_J3=Q1L!aDP8*>&v*a;E=>oI4|CNdd@J~kLj zD3lP8b!U!7mz4Vck$53N;s?1!zRbc;HY5(g6DSgYz#6vWN+*k8#=v`QPDL>qte(aF zq-h}>XM60NqrJb;=@w}pC9B2_Yy7PmAe5vkVI?y^P*g%^JjFckXm^`;Dhmr3ch1G& z1Z{qV;Ix+estzc_5lexL|kh2qyE69yOv1=871y9w>_+P%>4VU(cz6o zFW)ejg}!QOjzNImM!#%g0VX3;sA}1$B5iRM=s;t#fdnE&FJ-Dr6lqRgFtS zHQRG0k3Y_hv;uNPstj_wm`1xirup=t14Xo-oA1ML`)6eEgj51E1+-0(91~+m`KVSM znK0$;IdxbSJW;hf65)oW_ z;};4uZ{(JBA>D{pG-5o*G zqcFI5*6eY9Wb9r|xIflp;!!^xVT;-Dj@58LKmRbHF+a%nYWh!3G(X2QRg5nW)5FhO zp+koB&C8mswUjr$c$fr@bR?j;3GFo$7+;}O7^G@%oNvWl+iJC3@H?54eP&QAY)1ztNubSDS4SGvmiG z=i*rrQ6UOhSgC4W0@>;l&Qj9=5v*@tW8xUx&cwxq`Go)3^zA+>I;>b&2zMc~Z49x7iQPJ?og5x0D9 zrz=O>?*mu{cP&J{zYMlz>lgIKbqD+~kr@YBYpUvyqi@jB%ZIfEy&H&)4gtvtEn#s?tBdH*`gTv_Mx z$~1g5X(FJAs?e?`W^V<2bcs_f*#5TCvv{^k-ML?vfs2LeV^N0FQe4|o zQu~R^r~N)t>3++5Yyfo;j8vWZM>ep$pmm{CR&XDhtFQTaXVPo?n-A`L``USLIL$&5 z39ahF<27NBgsdbxqYRAWu?m!~9Tuq3H9nOzsPV*t-sL80a&ETXAM& zj4nW@GQs;1#fTC?1cnqYZ+Q&Pu1Md0ZyaN*J1NWeJV@uh#Ver+PS0UvKiWXn6oJ)x z)bO+Z2?@%UXV55%eZm(>=66NJN6zshBjSLyAMt;;;15sQ0sA*rMk=Vp3Qx|bCm%N( zJN;?$pM+-1@|EFOG+>W-;uhj=rm?T3*R?_H^v|&^XfO)rL>#IgB0(|Fn?o7$`bJIY zLv_DOS(MSSuBovL6iKD6(qpp5XLI{2g&HM|Ps}>d%^V^Kh804W=2mr%%+OeaF4u*; zj-b~4m!T3I`!d(YfoZ)^P z_P(LZ@ZYd`8&YHsMh%jZTEwqZ;*k$|6Qi%}I8k_|+*(BwvJcQ+dxE3O;go6G3li_; z>c46}ecf=o-$}Hhn`C#-uR$+Z9XZ9lZ9;wR|FI(f590m&?qvb*R?G+;QJAf$5scr}Qr;lN z*Bb73s#kCG&$p(;58epax<(ip!r;=fRfX8o?M}BWS$1t`iM93uD^#;As)kkvWNh2N zaG^)_p^EPO%^;O#Ps@bn!K(~dnpWYZy?cYWwyri&|eI52H zpu{E^Eh9_OPN)BAN=QmGJ4*pQbIR*aqGwD%Fa8Z1frb2M)~DG|IH(jA!Fs$~xT|5| zY!?zJS5X300vT@Gi+kg`H)v!VxOkdUi&$A^#{sx>duVA8IkyU@6)mW?(l^?>F<_7{~Iqz**q|5f!m}Z0*ROq7y?Wocz)+srGo&(84m-v#g$SH)&)AiAu{3l3r z0;P^(gYmZ=+qN5ib@c`!K8oE5t`T##8_7xyntyizW0TS8{bOxK0+bi#=sEHKA|OF> z_emC6oG_+3q(CB@7|bFWxT72lQj%irU{pJ0bhLrR6}!XiV-C5Kho#?m$lQ-6WGZREUExj$zSV# zwE((kH1y4q*BkP++e0Wmzf(#6;#eym%L?sHP9T=M>&L5Pq*_*_H;9+%6~!=Y(_3nc z;a0&ORlz<7m%a({&IlV7xYYTKqSdtDn&tZ4F+i)=#6xtsylDPOD)PQD|JD|3`8y*0 zmYK}Q@6vCifTEv*SFPHl&%2)$PC!h{6Mwbde17!+weXifyJazJyU(dHqx0^35sE=p?GWsB(=ok;d(H( zssvM3wV{UFfcMwA+HYnOYk`yiDk=-j&@MF?l2oMDb1Ymq^vQE_`?_yo^oq=?v%3FF z3O{TeJo#TXhp2U=NTwNh-{YhLwmzpBWZ5z{WVB4M?{T!o2)E^kJ>HK?qt7KREu`PY zh@eu(z9~V`g(xaYIi#GvJK+MSWZZ5y%cquUywu^WVQ{sal&q|cY2P#!&?GfKwM5`k za(RM6_X0m$YSVe`yBWefg~uI6OBHUI*xZRRjM>;bw?F3 zTlwcy5v^nu(Ok#S+E-teSJb*7Xd@JAdh|isF^fCe>{aeQbrC5eQoJC{8Xg0rM3pF^ zy8h+Eo4vyvdd?_F;YM{I*zSzZ;r4)$b=4E+w(U;L*W5HRvX;%ld3QVObT|8z-Hx7X zb~CV8+y`N~99fM*RF3gms4#M065Dk_4OtQ-r_o8br6uk65?D@a& z?h6p{&%qaUZz(|nNbT&Q!`+nttv^7KMNtK3rIbT`j-Ge2rkDXt(ZPtaskoB?oa_kp zp2c)6HObH>z*0^j6DH**I3Jz9zEgdn~Hgw?dh*XMEhb$S&1DF-x zr7@7eN()9VWq!lH*p?>^-!Bz0K+msl_zMQFKS{|w3YAcj*+xlR64A8^_Eg1B8vrp{ zr79^{eyMBRc+=jYyo<`LSzsb@f++9Ht#{bi?}f2csl*U@h&qO3uS>GL_F-MMr6Q`t za6qB+-Y`UnGbJBF4+hsjajzxs%hK+1SRaH(|1<78g8BOzKmIk_gPP`YWBO_1%A{$T z$U4^W9IYe7UtIYq{n}k&fqv`hk)i)0H$O zk8o1!e?aCn7eh}MKUcqJ7<&AlSGfPgz>rF?LbKNK1lR561-&O+-;UV-7SEEN@cb5! zC$OB45T;nzFQb36TQpSbU140Tu&5@Wpe*Hnk(rB6(s&RBT|TcrjTDmMC)w-qZlb#uEN-Sp zH_Yefm_5h{)mB}uam0{e{#;F?vH_|DdOgeLwD|e7yACt>7HHGlOr7uzhK%BwAJx-0 z+S;We!d|2T(yD4LpV+;O282Vm*YJ7I7QIx8RHb1Y; zBF6U5THm3*>xldL^LL-5|KfUZzdxFZ@Uz z?JJw&O4N068gJa)p@S13xVu{j?hxGF-Q7KS65NBkyF0<%J;?2ub7uBFKj89#Dw--- z>(%FVDYIU@wwh>ck&BijmQC@Ga~*G-eNzJmL0Qh;UlG}&xZ*RYl257NwC#)_!X%Lf zqiEym9=2RxUI63Z(Vw}gU-sx7uIbMO(8$q!A*HALpYvJ05N1zioOyHu zety-kYb2P%zP9Zg`GOt!t;^Xf9nTqvq6Z=C1#wJ>DrqrsnHJfgW=$y)TQ;t zuYl*>zNXh1OZD0$uB-k9`&oiF0_5jpQ&KC8NVZZz!QQ&}2U5rVxVPjOs4UQDv;m}Y zA)4+Q#@_0chAa_|-LZQVXM~KB4R=RnI2SsyuKS5u-In(FEKxbr6Z3BbS%O* znX!VRAUzn1TiuZQL!9cbf#0>59;RILVCa0Lzsby+dDr2hfA_~z>*j%8r(he$4bkcM(Kj&yYY?8&@$xBYVR8AYhoqa!~^S|M{%b2{@?0mhz zccE56W$A}d&^1Zpkg6BThDNDWDkabC0^p(R+_f)Ss~40`L0<~fjpqagXp;J-OOn1K zVm_>oGQVAPc2~YG{$|)L@1{uK!kKrGvBeVn2VnS}AWL>uR`$$;1u{q!OPVs_2O#15 z@G5o4j2n&=I&jC!qlOv9#M^doia!ASp3MJ!=>L4}cq?44Cl8sm> z>MI5rICMmWrL8=nn*^Lm^WKvL#aE){vd!;z=_3`;J`jC{X){Xv!TF#7)Z!(fP>Co} z52uAw?+1OTyL^(gXd&7m4q@Pg07a59oG!Ho)o9ywr^SYp<{AC&q5esi+fYvGg}Cqp8G(jys^*&Pi8g3NF1JUrAjcVfvrFZ8B1tiB4T&%PN9?M7?IB1uD##ED%0A zuw|zB^^kE+XJ`(&yeK!~gZ8rXjot(if2<&D7`5rqqveZ!BYu|t0Df^5bXi)FWdvT_ z64ogf;L#gX=?;JaW64_P3BJvz9_FfNZ6uY5HSajzuzdbuwv7Hxr$#T3?hJc=>k5Q$ zu5A9{YqBpzJ%X)@u8lZi*3@^v4=Y21z}ZDWGNP_JvhX7)r&JD0B}!$RUTSDzv`vs#Fg3ot;6EkD5j{1&= zQz&gV?*b}!czoXs_)P8`BnDGVh4>C-!Zxlb*P0EXhA~FI^?f&}A%nAQsHW+M)=FSs zwn#Wz>Afnf%J;y(R)zgkr>PXu7raW0ZjlKiA#qp*3edzleE4rD4L#e{Nd9iPMZPfsmukhj4$G`KsaWhrT ze^i6RhG_^mpuibQ`8Pt7ZP{Q%~rO9M03u|ZJ z(WTb<+f=@q&+8dvu9$~HK`Y#;MtW{&S@84PuswKE7V-jCjUK}0W7*k?|77OU8r!c6 zh?oI7J<;VPYUqUzo0pif>MzBcy`Loh6>TXhM;CPQ8L3@)i2y3nE=I|rTt9Se(Q)RZrVX(f(|Bgb_w`9De3qMx@sNOU|NO{y||P#Kjy4RMOzbY#D|gE^5= zLCUz{_`|qVOl_?U7e*%&Sb7;-S;-@Y!Xi$G`Gx$@Hl*jUkIu`sH3qlymhSZpf^kYq z=i6r;3d(SwMuJz{n8xOJn}^G#x=E+|ZPU{|SbU_QSKQ}0o^$wwmkH5l* zo`>|%8zK8pp8hfu^t;%6v3snM*3qIRCNy81fZl>hqC$rK&1L-!_nQ#d*Zs=}Qo6q~ zkZln#=EfEbb_pun2pQjaOb92=1XjG8a`8}eM-^h7bUdG?Zv@F;VN*a@SAGXy4v zvvk(?)hY7#uKL|d_E_^ zF+7Yi#{3}>$|Y$_UP3`e)X7mZ5fK^O{(pZzP8Fd$PNu7;XRtx{SvkLONLwov^r z0L~QcO2g$aQCH8LvAMm_O|&fH;b1blmnOsT1M?3LK)PD_DP~mu$+7(z`1=P3bfba7 zowAe-Wls6=(a{(`<4|w-aZn?;gtI>)1X93h>>nI`U^c)E;v!M(8Timj*Q(p`*!mt& zEJE+`I933 zyU=jNpjzQ=&R6dZjN?=|hTVxB7H%R9c3by%(W1o*NqHF~wvt9$<4tHZVH-!6cMfKB zW95{kajgGhKoi#AT^ul26}1vUj8nz*{R@^Wyp2lxu%=E#UiQrLsYm?xrgR)bCIY)Q zo}_*1Sk(v>Csn4iGZ?fJdHLldDsB;_XnrwG2h<(81}J5K?Se7370M5v03XmN^tdOH z%qOR~oAd4q6=%Oi-Vr%Zw@Lo)QXkF~*Hc+-&N%IYgk$DYRKWr3zu!H}nYLZm;tWvB z5_yA;6DCf@0_dpTMPT?|(PVFXj+m3elqs}KXn*~fV+51*9qCjitOtp(QgGh>?dA6EWb~gHRA6yY$x3wY9;99lSs&tW=S>G~uAW)hCvSU-*|5 zt%!__^miEs>Ld4{1e?{27W>pOwDfk4(b-ak*|ipI{%4G&W0sKK?~)3+TaK+!*uCkT z`MI8j!iCEQww58?20~_J^eJx%m?mdTpj2vw)*mX6Q2})BIO`xwEss9zLFho@h!Tfow+wx@3MTY@;cvSh zxtU9aLzWrzcJt3kFCoGz^OXCVP+O!y8j^Kk^qVn`eL-6|d(edQ3$Gi?B>u~(e`Z)F z?mlW~R~aD-!xTA3Wn65m<9l3tR?=j9*YCkxGIV>>VI)QG6l{3olu9m+sq@Y~AX2N_ z^^iHKnTcsvd8cRk4l|MIO~oJlD_F|o>hE*W1)FFh-#x?d{yg_W`g@{L{5V&}2CsH) zD2PTJ?62aRxOioLhe>m@44-n2Z{R(Z1;x~g$#zFnbNgj%j}XmjH*I@cG;k5r8magC zx`)j9-=P9x?w}zF6Vd7X*Mu}VOa>9%(fb&UU=%-x@0XxhcbvG6?9)wXm2q-kvXgF2 z#dW4}>R0xvZhObhV=-t}ace}SheldpN&Fw(q54~Q#A4uL$$TTK*l2U0YYdy)K|!Nv z&;$c#e_oj=DN$%jXwzX;kR!pyV|`7T%>Am&^ICyWEB)ZGRA87fj!z^f8jjO-{+OGX z%m^L9NV{EQCl{V{D`Buh;(gZv#PZO?s=$AZ4cF?XG^cv1!U?5s6|eb#0BOfp+_P6K z-q?OZZl>=YT3aW?5I@Om|2D!mDl{sx9sCK7-Z2x701=urHyp>@%wu~}AU3jF&G@NO zO{Y-Ucn6CemwB3wh!CboP2!`q$;s;Z{^f64!9=8DumJ4B`;ae_K~Xhah!m}^kjJ{+!;to;FSX06qA$+%@%?z{+LdC^S&U6P9pc5Pr(xFkTJwJIDJ;eo=hZq!a zP;yeabMSW8X|g+2!7_BjE7{Hy$$T?!0jVBW!?|$L0VMgNe%|{`jqr{)Kl5LJw=Lvv zyjucHE;9r#1xu%vuFcd~Sz4l4W)sfvuTZP?ZRxqbrq0Gv_ca&U{-9-({k)IU{v}AS zG>iH&6^ksmm=O@8!ZTrY3BoS6A?cT~5D_(7$b{*Echn?PB(1|9ABx zB&D$n4#_(P^ZP(&5A(P(Cb?!YLUcHF0#*temU4|b zSQwerDt0XH-qgt&*IbCZc-eS;bo>|gFr^1wNc^~B+OPuyADw35Hzyw}xRRPwR@O;c z@6U_ZsxetCzLe?_A}$Sozl=hipLR)AUhsML6y^XY%>Kh1kEs8_!37xNi{;7$_0{u% zWL2^C%lC1+5?$h;Am6+?^9feh9r78^pc!~BlZ`W0i>4zN__7BRiL1&k zt`AA8O)3kRYl$lGOaeEEll(8-BtgKHxg2IzIGU2urFz3m>wPx*o)M?X1ma(@12#<# zZzITry!;pe!@k|AQBhcTI91Osp?yDxZ*|=qug364lFTnBlE^vG3FvrIl2nj0iyw(s zFG-$DCk>SoZHJ{+owj@~eqS#;wLLyDvoKV1bB)fdfe16@nW$phKxKEW)?cHm_j*Z7 z>gs!XDC4?D*l0T*S#qj~_d^cQZjiuD#2mD=!!uYT80Lry?T;AxFKF**IZ3p`X;uE? z9;>nII)$*s!G&`*fz$;l4Ro@_sz0~-!=mS|XqNBCb)IB~xs@b`;&O_eo+&D3{6hoW zDnMBzhnSJAd?MsDKLe09ouKqooJVOA%ayZP%YydrefVyt_0480xOSqq+Q20mPB@k! zB_!7rv|91bNn$8kyCC}h)^4AV3pcRODe<<{Joi$=-dJkp&-c(-`#EaDfB2&n>h^uG=i*|&+@Clgj?i(reum-Iq{*Je&^f2D-DhNbE8 z$$f=Ht6VQ|JLii)6cM2bJxa+AK((hSG$)F9CQD#&56;Dl+$x~P9o!v|zl}`XOW7k+ zS|nWi6Y$_PD)>l$Y7y0@Z}*|;@dnBlSKq0mYrj}0|AE|dA6S4tFL`{VJ)9g1=vgit zT=JSFxBd-;wd-~-YZ_R36SX_2F()Z)s1|7t-kB5}4K>d-o$D_8%!bWJa#UG8MKU!D za}{5hkBR0moe&`nu^cqkB)dj55<kpktg4H9Gz7PL4MCIm7&Csc*^_ary4gvRuwn@8m3_45(n)7gkuhrU+!2MR?ws zG|&yr=XcAkm72gwVC^*secH08kf?#_4OD{^bGdV%5HF?T4v{m^keysQQt$^$g--f-XT$mxVu^~X{A{~xvfLXVVz@rv9IaRfK;An zKm>zv1^P!h`9fSXdd}#ihe}ZOdqER>qaph^BV)8jy3ZY8^nj^$m{DGtjS~y6k8mad zhiUXO*zsErq>75gMC}z7_fPl4Z<9Tmd1M(`!r0H>=6)(A=SJ|aww#|m+#DWs3>C8< z4E5Q+F~0}Ou9hCnW2Mp2Fb9!k6G+g|)Z8gY`jU!@*m;B;yg$a#o0$)T@Q65(GE{4) z(SM2O`RY*+I3j1tj;5RI8=2f=%!*4R^=G#ajUC-2`=b{mD_yI(FSWVRE_xsOfS4=o zZ+G$x_pYfG+HaAgf|zJvX=UK%a!M~gMQ?f|ZSd~vd!uJ}Kk#!NEY*3@-Y^qUGp~H6 z#QIpAom*sgLY1k4g@5#->57t#6yhn6zbvo55ZOBti@XA}!C-0AASJVS){``=xg zDdZ<3E^62nnPe~!<55du|^FnyDZuv zHR!MqS$DUOCMKu7uC$oIOE~zxk}-N(xAXNbE#cjqQNz(-5%T1(aSxPu*%jQ))iuwW zTb7$|Z^Pcsz+n?Pr4? zW=3229u6^C>`kD+&b$RlGyM{^#vm%5{tH1tgCP`ab#1lOH<2U0%GBE5-CoO0KDY;Y z-Vy!F_&8=vO77iShRVSj<;fHvg8uVW#CDQ(++Rg;N`#xTY z2Vg5cj6kuE#%5ZQn-caF>fzhXExX^0kMTRw?Ay; zy_7U_00Ybq~ zm!z3cWFVV<4+jR^cPdmBwDnBGhgMP(W2a=v_pMH$R!O6+wJS{T^F_a;u($3>qard| zF(PjDvD_fJO-J5-NBBY|H)_?U&X^3ar4$E63?F(G6esyY0i#Y-j8Jm!|_EvNm0H zz6W~4-7oC0C{igZGW5mCDl+AHG$_(3zocOukWo=Igj9&?4Y9YzR1juWNbnae%&m}2$Xv`Y$5>1 zx--ZX2hYcpd3_+BdvK4@81$J7&`m}z7&ib*03XLv_s-&wD)crP?^)nV5{S>xSzU z|$!w=k7DNwTTU%D#}E=R@6H7=4CiTCdQ~C z(dpPPDUNQq!d)JURIHPomweiTrJq|o7zaGUk?WxVc$mhK#PQ=o5RwMg)`=5e&?K(q zH$o(W_OIB3bstz898k_w2g@P~GTmj&Con$fi~NW;te};+%!t2#nDW}x9+(8}F0nW;e%tK|^=D0$#Y~Eh)-fw~Cqf9N=r+M)1htqG z>blwPAG1%YQpfWQMz9||hDZtyOjCwA%(ANie}$K&ehqev(Eug_?IFd8T!$$L7&U&Q zk$l^R!qzr8-NWV4jvV$Tqt4^ShItN<(L^&`W+-9S`(|eyocWNPZ94qCD&3Q%!-}5p z(0t{f;C;r(ZFSSY@&xB>wS2z?j~@yBCpH_R3)B5(*}TRf`tn|U++)z7Aqa)kBmP40 z9VB0-j(yym512t_B*bWVIe4 zSRCN%o= z#WK^5sK{j-5W^L#^20?%uO$#Bj9kdSdyf%ssTzTmHP^ozGc5W%mLcUUd_X*!4u;gs zM-5QFyqgjiZ1iWjp~F0)V&~t;nzLFZ#?TaE8g%fV+dYu91^#ID^!R#9p`$HeRW}AE zqz6WX=M;#75~;A@aB6=C@T+}QC(2zipF<2~(*ppqA%FFd)c&pjz@^G(7} z}sq0w(YjZTu--56oRFp$gvftj_L&rBXBGx7H?qlL|ej9cbs zOFg1~3D&y052!?+M7&<%R+NJ$*`gnuA#&!^M@sIHCu3RN9U_hVk@NA;znf-CNI?e0 zD~X9!(`;(kRrgJ>96>XZ`X;ZsZS)RZyfB&_t0rf$6Fo7%XCyFEVpZ(gK(Z;C@vpnt znXVR+?oXw?@h;b3I!78d&Tnn~?xh;VWq~ddzCNDXvV6E#S@R~G{d2FJnM;nYNXU}H zRxXVXE0?Uf_X#r~jgd)&I%CN zC9nENi;MTuLW^Y9O)68|yzHup)n!DH9E6V9V7Q$hf$gP=s-RSh@o^z|01fbiu9%N~ z_~EhoCsz&JqYL(WYff|6$z{3FC?dP zZuWZb#m#;zh(|&~?MiaMKg(X1%-d>_31vjI!QB?-%4#&+8wZ|uKv?Nj#i9`1=gZ*E zFE$$+*H-eM6}i8rk9UI zejN}pFgvSm+K86~$;1s}ak=GwJH}33_#}0LLP2FmzM^k@CyHioVjX-HG#JiW*2^F-V3J( z4guR=7>eH-Mci8r9WQ}ex63$SDfBbj(rlk(?j%?FsO=VI$q82Of($VgOd5@>XJnz zQEPne2ojf!FeRySV}Z@jeQxnb_&wIpNa+y#Ay5x*+ojDb+B+kogMc05KFERl^BtC+ zu|qoic;F@6wr3J?mR)JJ4}zlKO_qse5{FPwaBhL`f^BCKbeJNUk!6<9>cE&7exVSS zK_nCs{ms>bpioT{`y^%ji!dTtfK_Mvj&in_?y0_)wS4uHPw8%&-Z*EnieQ3O8Xj5^ zWY3y7XKg$z-C@5Neev98Kwhh^JaM1Hn;Vl*(WYjyN)yeQ^!GV=iT!iwQ=J$iF-S2M z!}C#2p<*4gyYK2^Mh@M3ew!9b7EKXIuuzbg*UXn7s~r&uMj-+y2{LZU8WqFIUbH&r zWj2g1xWSf#Ji{VZ;l)zF+yoi?ZdKCGk$}!;CRO9KgxD1w10)lMbGkr>$SN8*j$ za^U7Z;@mOzKE2EOUyWU@L?o#_!yReYBueS-nGwbCvl#;>l;V}dmd-xO+$gZg0WW>vCb>UX>R`aR)Nm4tO{YaSs1$J%WmMGU2zEhlv6UeOd)%EZVJ}`W zDl+Te>J!zr$qbDp&-tqjEK3t8eb!* z3w|;fbP)(inTHYbR6cvIs@Erd6_`q$j**+qCz1yo1~H@kP=H5dM+7q-!RzZ-YE-a9 z5LE8*E%@Mc-HT`|Ps=;?%#XAhiFAAtv&TElLwo`gD7w$WBK~7Zx;b5gtV!TA5HzLq zUX#U)g`l6VHPv-_^nTfqpFfEVbj?w*dB>WS3n5(F2ttDJ8=Jz8NBXk`-P2?H3@_X6 z&HW}KC?%_Vac`!jDa5*kDw4cN{Gyi`HJ2Xxn)Wx~n9o-S=W-tsTwPdXC3Y!mmAXQp z?#}f}G=7pr5>;dbJ3pz|f)9+>wI~VKwlQ1kaU7!~lkb`{RspcZ9w_OH_oFnP>57w| z|0I%Lsn8eO3KJwUa88O0c}41-m`32Wjl#2}Ab`LJYeH5v*y=7=+J!E2wH3aW>2@I&KC5J{@}K$XoigNR4HEr#|(!H znmF(pHV!@=QqG*@mwbR1l=8WPV$ft(#TJE?T-<^(!(rZ&(aDEa42X86ByVv~F}>LA zPx-^la?_XOJpPd$HYl59Kqs?{;&uh2;b#b8OV1o(m{z9`FMAy`g=&)fRWO958+-_F zqq3kwJAlSud_T@A4!jDf=T24q+ul@A7X+G4LLqM8hNr07w_%ax+3h9Vv9d^s7W z$75PW83{`i)Ixzk=z5~43qOC{_m|Zk_R|z_ zg7@gLFI&`K;5YKkPz<-(Xgl9fQh(|}3l9;&Bx#o5{K)ya<|9~K3ArtjF|{hbxv~e+ z?My8;LvgLFW5g4w4&RMAxtS%2kJnt20rvfAYf}@;v(fyYn32AC1Nv{&O-3OXr+9tF z{O)#Ks%TJ15wjdT?sjHyG!P@jf@chv*jqi6Cu795R2zB3m&GEAaB5z%-wbNyxf=8v zI~?9gwizq-fzRM`Ma&}T!>58_yO0*mH=ZWbCh-YQ%k_lwqu*?N-*%d;xfgBKYO-WM z55bK%_~cE)1muaM-GbzOsO4YIZ*!(MTmQ5Izd?lwFHp?FFPiK=BLiReajJd`MUF_Y zJ9g7EIAk>S`u5^gyS9-QqTf}f6o9#hktB3_GvsLP9jNrP+Nd9~l0+~z??>~Q7R%58 znxM>V3b)Il{ILKvjHKn)KsjX0dD}0Q(%O+@B{t8Rm3syH&m8PKvueCv_A~~J;$8Zy zyo!K8H-wMhC-~V&L^mR^hI!*Wdsao&ILOrhB^oA}Xcs(~n3zP|_7MIqCkw0`92}F9 zw>!gYRCyY8!?K%?aCfC0ifLkFRQS4ax&~JxrtX*kHZF1jm_W{3yLGXH*fV579vRIa z!{tr~9(%>OOYW2HFvdVWlMl5N+-cLgCxumRK=zL!-MnkgNk4xdo@yyjnMV3Xa@4z< zUi`53ec3^_UKtt2)g!|J2#4>ae>E4=*M~<1Y@kz~`n~adWfmALA?D?N!Bw2KZIFsF zAW%g{>m2?(%}P-04EYgL2OtLhI=4_s!AMXW{}2(!j9mAw_$G)N8=VNzE^H5DW+m?W zvTY1vaJ_DSKM_o9AOP6Ey?AKoHIJ=uTJdNxvCUimjxN^v_;al$#zqz=p*eU+jAIqy zn!Z+S~Dk9B40dT<%J`WE17zrRJbE-hw$O$4qKZ7pwJH&UNKnh_Sqk~szUy=sP}p`-bgGNi%v|uWRQ0G{aMem$*!bs zL6pq_meJ5Q$~P!u0aPb21u%#yP|hR&o?K?FJvdjRT3;1yi2f;2NT2Ze+=tZg^~=D+ zMd??AHa&CaQ?}Ou{MzR0#M&)8r0WVl*5O!TD3cNUUv`)A08R(|XtMpg zJA9j;jIUj54te!ek3E;`%+bhU1g;_!FXyX#T{_St+ear~*Cttcc!q<}1cs6n1$Z{Y z3c>hk0k`84w&Oab3Suj}7ms~XvS{NdO8T?B3T& zc`#dw@3)FibEN{DlakIpmQr9~)feKAWN1qTY#y7QT^FzTk#x0%P8og^jjUgyl_$La zY??_XCWM8&_cf#&G-q|1 zViQI+%fiWJ`Kvmg5mg)5#?>t1A5`zU?pxh1r|jO0->y4f5i~oWKTsSyg-d1VO(B?YeO|Jn@U=h z2=d}4Ud>;OFC<0Od9x|zIm%D`!ChuX!Tl)&7jMl&aDX6tHzn&M+vCve`erYG-XpiG zBax^~nagy8Gx_qHLN;st&=0{v*Qou3c8)*a-Lv)}zY4%bs)2z)suBZkxHKKNWVErX zBeEu=>Qk2j6S07hjR}F(R#(F7srzp4&(-Ff40B)q6l6>y)g+e{h0oQ7{B|07l_nMLOiDsWJs(jl#q6r4@{v4|`$+tgtEG3b z`db9VOhEHrV}?E>KkeIJK>|2*2a=KGvV@L_%ViILs%tg5BS=CoZPAm->9&pCrm#{( z#FIU?be~DUsM535`+gwgvd*U>8D{$>Yf2G(9uhSiNSTNj4<;b~%KYtAJNndJFbJ(J&m7!2Rh9#!#2Ofgn21iie_%~8 zNr#9)r!mi5`jXO*wyAg>^PZPrUNuF}!lrF5{zF`|I+}}}0@N)u3*aBcz1n(hCHovt z6F}1gb%{U$spC6yEi;WLE1<(L23wdvU+@pZlb?V84K~mr^5Cc%#GEqph4L+yU$&Uc z%xI2A_!fA-zhWOtqHgDUrlyPsQv~2c1>PT-1Fs>hG{igqaW)>363~+g)jpo}Q5H&`kb8pkNH| z0Djl6xx+esa;!M|XGI&UvUTXw3aj;AUI~sd#Ykxm^*P;-c#p|Hs@nSIRWg43(JR0}OCji2!KQ^fxSn#|y*5P^c!z37I~|Z@h3G!OO&k~lIVf_;vla=3ZoxKtM(jnU z)?Vwcp>=Pei(nm=X_S#}#8up}^0N2?S*@Vdc$d64nHtyM?Ki?Wr8d59RbawhNQwE4 zdAwQ*{^$KXt7gDP>?W=q8rB-ITTBJ8hJ=IyESUL66alv=MJEdeWfr-tjh}N{GN$6Zs-1Gfs)~3)#OU_>SYyQgdeuW zIcNu~HL3-wACAn+y|1yf8`lDy@Ds*hvlR}{^hV6z;x=iXN^RsUrteWS)*Fb)2Y4k- zYy@HiAO>Czoyz_xxZRHWdSMgF70juiNk& zgz^}s{vS5Qmp4BHOUV#~O|!e#*2kegf?XRIOxwr9g>x+R{!1musCP45&HngZ_yE+< z$-MoJZb*T*NxvAo*L^#5s9<2a)R(!W+lrmuu@v`DhhO-Hbdml5#CDf05!2h+%UFRz z97O+O)j5}vqaYP7NY+p!@ZFln<%4j=JoDd6R7f->M|tVrjLi~Nq=4w&Kn#OVkr8lk z$MY;yXB$0Op~ zzYVvOXsb&nl+!cw8x1+xqi|Ues4%34{}gHbc|KhA<-N;QFzcViaetcE}vrat&nji z@(%g}devs5eUWp7w1h+?dW)ms4Jke!t9J4MVCv`dV8iGfnG?0ns6~6QPIJ@1~ni$|0(@FFx1A~O^ zm0>jYOU4QNhIH&So=z|id)NH_HGV3K3ARm|Ur9oMKy)aB3i8-sIw5PL%!%1+lCPZ4 zu4^d#L0H+vT#eRGA^Q1^zduUkdBjExf8y7xhWXS#iywSM6>lP7w@k zXp6`!INGPG2yUD-!H=1hEKnZ&B;_rkeJy|SnB0t2<9=f{fx=|AKPL_Id*+81&(#_2 z=cgJ;OWerdc)`^~Em<4{M%RnotM^Ag%8wL@;XjqW9mLw;Ap=at_<1oO(Nn%%xCi~E z3IDu9B`>(bm?>!|-#Gd1kA|;DbY>7SqK;Gf8GKol@NF1<8P{F_H6hHpoQjW~J`#+ET z%XY_x1H3s%@qM0stb{$iXgHzJ&R~N(@{WFQ07T3&w9OV$6oOvhH4RJ&&|5JttrnIV zDD^nk-ZZ`3$dPNva=(U@-vb`X6cACUFxN+ur>74!SWYzJw|*KnxDeS`bBph-YLih8 zMi!m?H4efhKRcn&Y6}M;QgzRsUlegn^}`E1-8^l0Py)NW(73NXmDg$iqn>#v;OBHn zDpUJ`4APe_a$)-q`UjS0p{lbp)vCP3${@{Vp8B<3b6-*FcZfNDMw%9e3GAA zj86sqLSa#9bn;m~#@;|4@Z~o&NkTxt$&B-@K*wb@CiT`r;{BtixRC?`PSKuCt>cElqZ?(*E(q4Fm_eiG1vnA2cNh@2Ga2Mjs)&wRal3f4tb9@3kIEM z^GydaNUIs*y#VcMW<#^(_OfFmkjG zL<&PwBFGT)kNtwXT1xm>sYh@Jb3i5*kDs1f?sT_HpSn>O6fpk-?``8jI^vST-HLwh z>(5p<+!zfJYI*4u1ku$d(SmTSs0;2)H{$hH&uGMJu1)FxqCxy$G@zQHGTeN~+n-9> z3|Ih3XVy5MeIj`)?G%|71LKuwz=Tj)GFj~{6VZ08q+pL#FKs!RejnW9gsS57FFRbc zwWgp(Y>A&!${-~-`nx5iMob_gBzB#a51syxPouxfE&U5)e1HLV zo8xQVpYM&Oy`^8@!dUvB!#@Dudld~UM!kYESpy#)U8A`4y;HFX7izE4NOq16-V$q~ z(mopmb2G(DcYXfd_{VLlP>3@&VW`&nM572x_;L&K4;R;v{trAKx4p7|t@oVQ-@FDv zIl~wZAz`yp!926UN0?9V+x+}9M(cho_>TMa4o=!D^x}PQami_rCbV&Fz#S+3UIe?0 z7D203x&U}{X&hH`kbp)B3G5zV4RORJ!^^5dIBfLzmxt>!f5G04adm4rC}|);KSo8p z)HWMVDuYnOTLa_g>qE-yr>b|f(NZYoeQBD??IbOkVno8GO;HBZ=RT#T(D|%JrJv41 z;1U67SN|9?j*`qtG;L#Al_PJY=wI5o$bto>{U96=h4Xr4p~{P#B18|69cqZx9XQ#;Ox3$gB@htdtRsXnnJZdX2IMlk^?*> zG^B{V-5o*yV<$;`AY75mcwIpOIRtoT@BWk292z?}w^Xr8K~F|)7$po63N@rU0!ZUl+nAHa81OH0FmP@NB6 zor4$eZx{NDcfJp9erbw+&$E69acEBb(nt3m@+zS^Zy?R&>StlLrD1JRN`5FZ3Q`_Jm;{!QNdi;I3~X(_xha=+2luPV+> zFt0Co_8c>M!_YRX?`UXf-tL;R&&igD4X>wp{a1B`Y;Fh91?_r^X%sE^{qG8!@g>qF1zSktv1>$`k)lgy)4&TVipz_F8UB# zeE_#ZFS+PTzMj2aGrzNyD&!bBI$nqV#2vgs(UPQh*+D@@UIUL=X;gga&*k^B9r^-Z zYTl}f`>zIo?aHqZi&BgK`e5#ZJQ%?KE5615|9?L7gDk#jk2+lpF^2$uNsB9pRf-q{ F{yzd+$I<`* diff --git a/examples/async_sac_state_sim/async_sac_state_sim.py b/examples/async_sac_state_sim/async_sac_state_sim.py index 56e5d69a..90a1acf8 100644 --- a/examples/async_sac_state_sim/async_sac_state_sim.py +++ b/examples/async_sac_state_sim/async_sac_state_sim.py @@ -107,8 +107,7 @@ def update_params(params): with timer.context("sample_actions"): if step < FLAGS.random_steps: - # actions = env.action_space.sample() - actions = np.zeros((7,)) + actions = env.action_space.sample() else: sampling_rng, key = jax.random.split(sampling_rng) actions = agent.sample_actions( @@ -120,6 +119,7 @@ def update_params(params): # Step environment with timer.context("step_env"): + next_obs, reward, done, truncated, info = env.step(actions) next_obs = np.asarray(next_obs, dtype=np.float32) reward = np.asarray(reward, dtype=np.float32) diff --git a/examples/box_picking_bc/bc_policy.py b/examples/box_picking_bc/bc_policy.py deleted file mode 100644 index 207031d4..00000000 --- a/examples/box_picking_bc/bc_policy.py +++ /dev/null @@ -1,251 +0,0 @@ -from tqdm import tqdm -from absl import app, flags -from flax.training import checkpoints -import jax -from jax import numpy as jnp -import pickle as pkl -import numpy as np -from copy import deepcopy -import time -from datetime import datetime - -import gymnasium as gym -from gymnasium.wrappers import RecordEpisodeStatistics - -from serl_launcher.utils.timer_utils import Timer -from serl_launcher.wrappers.chunking import ChunkingWrapper -from serl_launcher.agents.continuous.bc_noimg import BCAgentNoImg - -from serl_launcher.utils.launcher import ( - make_bc_agent_no_img, - make_wandb_logger, - make_replay_buffer, -) -from serl_launcher.data.data_store import ( - MemoryEfficientReplayBufferDataStore, - populate_data_store, - populate_data_store_with_z_axis_only, -) -from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from serl_launcher.networks.reward_classifier import load_classifier_func -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper -from ur_env.envs.relative_env import RelativeFrame -from serl_launcher.utils.sampling_utils import TemporalActionEnsemble - - -import ur_env - -FLAGS = flags.FLAGS - -flags.DEFINE_string("env", "box_picking_basic_env", "Name of environment.") -flags.DEFINE_string("agent", "bc_noimg", "Name of agent.") -flags.DEFINE_string("exp_name", None, "Name of the experiment for wandb logging.") -flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_integer("seed", 42, "Random seed.") -flags.DEFINE_bool("save_model", True, "Whether to save model.") -flags.DEFINE_integer("batch_size", 256, "Batch size.") - -flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 100000, "Replay buffer capacity.") - -flags.DEFINE_multi_string("demo_paths", None, "paths to demos") -flags.DEFINE_string("checkpoint_path", None, "Path to save checkpoints.") -flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") - -flags.DEFINE_integer( - "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" -) -flags.DEFINE_integer("eval_n_trajs", 100, "Number of trajectories for evaluation.") - -flags.DEFINE_boolean( - "debug", False, "Debug mode." -) # debug mode will disable wandb logging -flags.DEFINE_string( - "reward_classifier_ckpt_path", - None, - "Path to reward classifier checkpoint. Default: None", -) - -devices = jax.local_devices() -num_devices = len(devices) -sharding = jax.sharding.PositionalSharding(devices) - - -def main(_): - assert FLAGS.batch_size % num_devices == 0 - rng = jax.random.PRNGKey(FLAGS.seed) - - # create env and load dataset - env = gym.make( - FLAGS.env, - fake_env=not FLAGS.eval_checkpoint_step, - camera_mode="none", - max_episode_length=100, - ) - # env = SpacemouseIntervention(env) - env = RelativeFrame(env) - env = Quat2MrpWrapper(env) - env = SerlObsWrapperNoImages(env) - # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - env = RecordEpisodeStatistics(env) - - rng, sampling_rng = jax.random.split(rng) - agent: BCAgentNoImg = make_bc_agent_no_img( # replace with no img one - FLAGS.seed, - env.observation_space.sample(), - env.action_space.sample(), - ) - - wandb_logger = make_wandb_logger( - project="paper_experiments", # TODO only temporary - description=FLAGS.exp_name or FLAGS.env, - debug=FLAGS.debug, - ) - - if not FLAGS.eval_checkpoint_step: - """ - Training Mode - """ - sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) - # load demos and populate to current replay buffer - replay_buffer = make_replay_buffer( - env, - capacity=FLAGS.replay_buffer_capacity, - type="replay_buffer", - # rlds_logger_path=FLAGS.log_rlds_path, # can be added to log - # preload_rlds_path=FLAGS.preload_rlds_path, - ) - - print(f"loaded demos from {FLAGS.demo_paths}") - replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths) - - replay_iterator = replay_buffer.get_iterator( - sample_args={ - "batch_size": FLAGS.batch_size, - }, - device=sharding.replicate(), - ) - try: - for step in tqdm(range(FLAGS.max_steps)): - batch = next(replay_iterator) - agent, info = agent.update(batch) - wandb_logger.log(info, step=step) - - if step and step % FLAGS.checkpoint_period == 0 and FLAGS.save_model: - checkpoints.save_checkpoint( - FLAGS.checkpoint_path, - agent.state, - step=step, - keep=100, - overwrite=True, - ) - except KeyboardInterrupt: - print("interrupted by user") - - else: - """ - Evaluation Mode - """ - from pynput import keyboard - - is_failure = False - is_success = False - - def esc_on_press(key): - nonlocal is_failure - if key == keyboard.Key.esc: - is_failure = True - - def space_on_press(key): - nonlocal is_success - if key == keyboard.Key.space and not is_success: - is_success = True - - esc_listener = keyboard.Listener(on_press=esc_on_press) - esc_listener.start() - space_listener = keyboard.Listener(on_press=space_on_press) - space_listener.start() - - ckpt = checkpoints.restore_checkpoint( - FLAGS.checkpoint_path, - agent.state, - step=FLAGS.eval_checkpoint_step, - ) - agent = agent.replace(state=ckpt) - - wandb_logger = make_wandb_logger( - project="paper_evaluation_unseen", - description=FLAGS.exp_name or FLAGS.env, - debug=False, - ) - action_ensemble = TemporalActionEnsemble(activated=False) - success_counter = 0 - - trajectories = [] - traj_infos = [] - for episode in range(FLAGS.eval_n_trajs): - trajectory = [] - obs, _ = env.reset() - done = False - action_ensemble.reset() - - if len(trajectories) == 0: - input("ready? record robot view as well!") - - start_time = time.time() - - while not done: - actions = agent.sample_actions( - observations=jax.device_put(obs), - argmax=True, - # seed=rng, - ) - actions = np.asarray(actions) - - ensembled_action = action_ensemble.sample(actions) # will return actions if not activated - next_obs, reward, done, truncated, info = env.step(ensembled_action) - transition = dict( - observations=obs.copy(), # do not save voxel grid or images - actions=ensembled_action, - next_observations=next_obs.copy(), - rewards=reward, - masks=1.0 - done, - dones=done, - ) - trajectory.append(transition) - obs = next_obs - - if done or truncated: - success_counter += (reward > 50.) - dt = time.time() - start_time - running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) - running_reward = max(running_reward, -100.) - - print(f"{success_counter}/{episode + 1} ", end=' ') - print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - - trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) - infos = { - "running_reward": running_reward, - "time": dt, - "success_rate": float(reward > 50.), - "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() - } - traj_infos.append(infos) - wandb_logger.log(infos, step=episode) - - traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists - mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} - wandb_logger.log(mean_infos) - for key, value in mean_infos.items(): - print(f"{key}: {value:.3f}") - - with open(f"trajectories {datetime.now().strftime('%m-%d %H%M')}.pkl", "wb") as f: - import pickle - pickle.dump(trajectories, f) - - env.close() - - -if __name__ == "__main__": - app.run(main) diff --git a/examples/box_picking_bc/record_demo.py b/examples/box_picking_bc/record_demo.py deleted file mode 100644 index 66e26a1d..00000000 --- a/examples/box_picking_bc/record_demo.py +++ /dev/null @@ -1,108 +0,0 @@ -import os -import datetime -import threading -import numpy as np -import copy -import pickle as pkl -from tqdm import tqdm -import gymnasium as gym -from pynput import keyboard - -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from serl_launcher.wrappers.chunking import ChunkingWrapper - -from gymnasium.wrappers import TransformReward -from ur_env.envs.relative_env import RelativeFrame - -exit_program = threading.Event() - - -def on_space(key, info_dict): - if key == keyboard.Key.space: - for key, item in info_dict.items(): - print(f'{key}: {item}', end=' ') - print() - - -def on_esc(key): - if key == keyboard.Key.esc: - exit_program.set() - - -if __name__ == "__main__": - env = gym.make("box_picking_basic_env") - env = SpacemouseIntervention(env) - env = RelativeFrame(env) - env = Quat2MrpWrapper(env) - env = SerlObsWrapperNoImages(env) - # env = TransformReward(env, lambda r: 10. * r) - # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - - obs, _ = env.reset() - - transitions = [] - success_count = 0 - success_needed = 20 - total_count = 0 - pbar = tqdm(total=success_needed) - - info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, - 'force': env.unwrapped.curr_force} - listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) - listener_1.start() - - listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) - listener_2.start() - - uuid = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") - file_name = f"ur5_test_{success_needed}_demos_{uuid}.pkl" - file_dir = os.path.dirname(os.path.realpath(__file__)) # same dir as this script - file_path = os.path.join(file_dir, file_name) - - if not os.access(file_dir, os.W_OK): - raise PermissionError(f"No permission to write to {file_dir}") - - try: - while success_count < success_needed: - if exit_program.is_set(): - raise KeyboardInterrupt # stop program, but clean up before - - next_obs, rew, done, truncated, info = env.step(action=np.zeros((7,))) - actions = info["intervene_action"] - - transition = copy.deepcopy( - dict( - observations=obs, - actions=actions, - next_observations=next_obs, - rewards=rew, - masks=1.0 - done, - dones=done, - ) - ) - transitions.append(transition) - - obs = next_obs - - if done: - success_count += int(rew > 0.99) - total_count += 1 - print( - f"{rew}\tGot {success_count} successes of {total_count} trials. {success_needed} successes needed." - ) - pbar.update(int(rew > 0.99)) - obs, _ = env.reset() - - with open(file_path, "wb") as f: - pkl.dump(transitions, f) - print(f"saved {success_needed} demos to {file_path}") - - except KeyboardInterrupt as e: - print(f'\nProgram was interrupted, cleaning up... ', e.__str__()) - - finally: - pbar.close() - env.close() - listener_1.stop() - listener_2.stop() diff --git a/examples/box_picking_bc/run_rbc_actor.sh b/examples/box_picking_bc/run_rbc_actor.sh deleted file mode 100644 index 5862c8cd..00000000 --- a/examples/box_picking_bc/run_rbc_actor.sh +++ /dev/null @@ -1,10 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -which python && \ -python bc_policy.py "$@" \ - --env box_picking_basic_env \ - --exp_name=bc_drq_policy \ - --seed 42 \ - --batch_size 256 \ - --eval_checkpoint_step 50000 \ -# --debug # wandb is disabled when debug diff --git a/examples/box_picking_bc/run_rbc_learner.sh b/examples/box_picking_bc/run_rbc_learner.sh deleted file mode 100644 index 79b64cbc..00000000 --- a/examples/box_picking_bc/run_rbc_learner.sh +++ /dev/null @@ -1,10 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python bc_policy.py "$@" \ - --env box_picking_basic_env \ - --exp_name=bc_drq_policy \ - --seed 42 \ - --batch_size 256 \ - --demo_paths "" \ - --eval_checkpoint_step 0 -# --debug # wandb is disabled when debug diff --git a/examples/box_picking_bc/test_demo.py b/examples/box_picking_bc/test_demo.py deleted file mode 100644 index ee15a307..00000000 --- a/examples/box_picking_bc/test_demo.py +++ /dev/null @@ -1,72 +0,0 @@ -import numpy as np -import threading -import pickle as pkl -import gymnasium as gym -from pynput import keyboard - -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper -from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages - -exit_program = threading.Event() - -""" -Script to test the demos recorded --> they can be repeated easily (if the box is in the same position) -""" - - -def on_space(key, info_dict): - if key == keyboard.Key.space: - for key, item in info_dict.items(): - print(f'{key}: {item}', end=' ') - print() - - -def on_esc(key): - if key == keyboard.Key.esc: - exit_program.set() - - -if __name__ == "__main__": - env = gym.make("box_picking_basic_env") - env = SpacemouseIntervention(env) - # env = RelativeFrame(env) - env = Quat2MrpWrapper(env) - env = SerlObsWrapperNoImages(env) - # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - - obs, _ = env.reset() - - info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, - 'force': env.unwrapped.curr_force} - listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) - listener_1.start() - - listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) - listener_2.start() - - file_path = "robotiq_test_20_demos_mar26_rew1.pkl.old" - - with open(file_path, "rb") as f: - transitions = pkl.load(f) - - try: - for transition in transitions: - if exit_program.is_set(): - raise KeyboardInterrupt # stop program, but clean up before - - action = transition["actions"] - next_obs, rew, done, truncated, info = env.step(action=action) - - print(next_obs - transition["next_observations"]) - - if transition["dones"] or done: - print(f"done with {transition['dones']} {done}") - env.reset() - - except KeyboardInterrupt: - print(f'\nProgram was interrupted, cleaning up...') - - finally: - env.close() - listener_1.stop() - listener_2.stop() diff --git a/examples/box_picking_drq/drq_policy.py b/examples/box_picking_drq/drq_policy.py index f1c54698..7b9a7219 100644 --- a/examples/box_picking_drq/drq_policy.py +++ b/examples/box_picking_drq/drq_policy.py @@ -12,8 +12,8 @@ from flax.training import checkpoints from datetime import datetime -import gymnasium as gym -from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics +import gym +from gym.wrappers.record_episode_statistics import RecordEpisodeStatistics from serl_launcher.agents.continuous.drq import DrQAgent from serl_launcher.common.evaluation import evaluate @@ -34,10 +34,19 @@ make_wandb_logger, ) from serl_launcher.data.data_store import MemoryEfficientReplayBufferDataStore -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper -from serl_launcher.wrappers.observation_statistics_wrapper import ObservationStatisticsWrapper +from serl_launcher.wrappers.serl_obs_wrappers import ( + SERLObsWrapper, + ScaleObservationWrapper, +) +from serl_launcher.wrappers.observation_statistics_wrapper import ( + ObservationStatisticsWrapper, +) from ur_env.envs.relative_env import RelativeFrame -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper +from ur_env.envs.wrappers import ( + SpacemouseIntervention, + Quat2MrpWrapper, + ObservationRotationWrapper, +) import ur_env @@ -52,28 +61,46 @@ flags.DEFINE_string("env", "box_picking_camera_env", "Name of environment.") flags.DEFINE_string("agent", "drq", "Name of agent.") -flags.DEFINE_string("exp_name", "box picking drq", "Name of the experiment for wandb logging.") +flags.DEFINE_string( + "exp_name", "box picking drq", "Name of the experiment for wandb logging." +) flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_string("camera_mode", "rgb", "Camera mode, one of (rgb, depth, both, pointcloud)") +flags.DEFINE_string( + "camera_mode", "rgb", "Camera mode, one of (rgb, depth, both, pointcloud)" +) flags.DEFINE_integer("seed", 1, "Random seed.") flags.DEFINE_bool("save_model", False, "Whether to save model.") flags.DEFINE_integer("batch_size", 256, "Batch size.") flags.DEFINE_integer("utd_ratio", 4, "UTD ratio.") -flags.DEFINE_string("state_mask", "all", - "if all the states should be considered, see serl_launcher/common/encoding for more info") +flags.DEFINE_string( + "state_mask", + "all", + "if all the states should be considered, see serl_launcher/common/encoding for more info", +) flags.DEFINE_string("encoder_type", "voxnet-pretrained", "Encoder type.") -flags.DEFINE_integer("encoder_bottleneck_dim", 128, "bottleneck dimension of the encoder") -flags.DEFINE_multi_string("encoder_kwargs", None, "Encoder kwargs in the form ['dict key', 'dict value']") -flags.DEFINE_bool("enable_obs_rotation_wrapper", False, - "Whether to enable observation rotation wrapper (train in one quaternion)") -flags.DEFINE_bool("enable_temporal_ensemble_sampling", False, - "Whether to enable sampling the action from a temporal ensemble: action = 0.5*a0 + 0.3*a-1 + 0.2*a-2 + 0.1*a-3") +flags.DEFINE_integer( + "encoder_bottleneck_dim", 128, "bottleneck dimension of the encoder" +) +flags.DEFINE_multi_string( + "encoder_kwargs", None, "Encoder kwargs in the form ['dict key', 'dict value']" +) +flags.DEFINE_bool( + "enable_obs_rotation_wrapper", + False, + "Whether to enable observation rotation wrapper (train in one quaternion)", +) +flags.DEFINE_bool( + "enable_temporal_ensemble_sampling", + False, + "Whether to enable sampling the action from a temporal ensemble: action = 0.5*a0 + 0.3*a-1 + 0.2*a-2 + 0.1*a-3", +) flags.DEFINE_integer("max_steps", 1000000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 10000, - "Replay buffer capacity.") # quite low to forget demo trajectories +flags.DEFINE_integer( + "replay_buffer_capacity", 10000, "Replay buffer capacity." +) # quite low to forget demo trajectories flags.DEFINE_integer("random_steps", 0, "Sample random actions for this many steps.") flags.DEFINE_integer("training_starts", 0, "Training starts after this step.") @@ -89,12 +116,20 @@ flags.DEFINE_string("ip", "localhost", "IP address of the learner.") flags.DEFINE_string("demo_path", None, "Path to the demo data.") flags.DEFINE_integer("checkpoint_period", 0, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints', - "Path to save checkpoints.") +flags.DEFINE_string( + "checkpoint_path", + "/home/nico/real-world-rl/serl/examples/box_picking_drq/checkpoints", + "Path to save checkpoints.", +) -flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_drq/rlds', - "Path to save RLDS logs.") +flags.DEFINE_integer( + "eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step" +) +flags.DEFINE_string( + "log_rlds_path", + "/home/nico/real-world-rl/serl/examples/box_picking_drq/rlds", + "Path to save RLDS logs.", +) flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") flags.DEFINE_boolean( @@ -141,7 +176,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): if FLAGS.eval_checkpoint_step: wandb_logger = make_wandb_logger( - project="paper_evaluation_unseen" if "eval" in FLAGS.env else "paper_evaluation", + project="paper_evaluation_unseen" + if "eval" in FLAGS.env + else "paper_evaluation", description=FLAGS.exp_name or FLAGS.env, debug=FLAGS.debug, ) @@ -153,7 +190,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): step=FLAGS.eval_checkpoint_step, ) agent = agent.replace(state=ckpt) - action_ensemble = TemporalActionEnsemble(activated=FLAGS.enable_temporal_ensemble_sampling) + action_ensemble = TemporalActionEnsemble( + activated=FLAGS.enable_temporal_ensemble_sampling + ) trajectories = [] traj_infos = [] @@ -171,10 +210,14 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): ) actions = np.asarray(jax.device_get(actions)) - ensembled_action = action_ensemble.sample(actions) # will return actions if not activated + ensembled_action = action_ensemble.sample( + actions + ) # will return actions if not activated next_obs, reward, done, truncated, info = env.step(ensembled_action) transition = dict( - observations=obs["state"].copy(), # do not save voxel grid or images + observations=obs[ + "state" + ].copy(), # do not save voxel grid or images actions=ensembled_action, next_observations=next_obs["state"].copy(), rewards=reward, @@ -185,20 +228,28 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): obs = next_obs if done or truncated: - success_counter += (reward > 50.) + success_counter += reward > 50.0 dt = time.time() - start_time - running_reward = np.sum(np.asarray([t["rewards"] for t in trajectory])) - running_reward = max(running_reward, -100.) # -100 min value + running_reward = np.sum( + np.asarray([t["rewards"] for t in trajectory]) + ) + running_reward = max(running_reward, -100.0) # -100 min value - print(f"{success_counter}/{episode + 1} ", end=' ') + print(f"{success_counter}/{episode + 1} ", end=" ") print(f"time: {dt:.3f}s running_rew: {running_reward:.2f}") - trajectories.append({"traj": trajectory, "time": dt, "success": (reward > 50.)}) + trajectories.append( + {"traj": trajectory, "time": dt, "success": (reward > 50.0)} + ) infos = { "running_reward": running_reward, "time": dt, - "success_rate": float(reward > 50.), - "action_cost": np.linalg.norm(np.asarray([t["actions"] for t in trajectory]), axis=1, ord=2).mean() + "success_rate": float(reward > 50.0), + "action_cost": np.linalg.norm( + np.asarray([t["actions"] for t in trajectory]), + axis=1, + ord=2, + ).mean(), } traj_infos.append(infos) wandb_logger.log(infos, step=episode) @@ -215,7 +266,9 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): print("Stopping actor eval") break - traj_infos = {k: [d[k] for d in traj_infos] for k in traj_infos[0]} # list of dicts to dict of lists + traj_infos = { + k: [d[k] for d in traj_infos] for k in traj_infos[0] + } # list of dicts to dict of lists mean_infos = {"mean_" + key: np.mean(val) for key, val in traj_infos.items()} wandb_logger.log(mean_infos) for key, value in mean_infos.items(): @@ -224,6 +277,7 @@ def actor(agent: DrQAgent, data_store, env, sampling_rng): filename = f"trajectories {'temp_ens' if action_ensemble.is_activated() else ''} {datetime.now().strftime('%m-%d %H%M')}.pkl" with open(filename, "wb") as f: import pickle + pickle.dump(trajectories, f) return # after done eval, return and exit @@ -393,7 +447,9 @@ def stats_callback(type: str, payload: dict) -> dict: batch = next(replay_iterator) with timer.context("train_critics"): - agent, critics_info = agent.update_critics(batch, ) + agent, critics_info = agent.update_critics( + batch, + ) with timer.context("train"): batch = next(replay_iterator) @@ -451,9 +507,14 @@ def stats_callback(type: str, payload: dict) -> dict: def main(_): assert FLAGS.batch_size % num_devices == 0 - if FLAGS.checkpoint_path.split('/')[-1] == "checkpoints": - FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + FLAGS.exp_name + " " + datetime.now().strftime( - "%m%d-%H:%M") + if FLAGS.checkpoint_path.split("/")[-1] == "checkpoints": + FLAGS.checkpoint_path = ( + FLAGS.checkpoint_path + + " " + + FLAGS.exp_name + + " " + + datetime.now().strftime("%m%d-%H:%M") + ) # seed rng = jax.random.PRNGKey(FLAGS.seed) @@ -469,7 +530,9 @@ def main(_): # env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) - env = ScaleObservationWrapper(env) # scale obs space (after quat2mrp, but before serlobs) + env = ScaleObservationWrapper( + env + ) # scale obs space (after quat2mrp, but before serlobs) env = ObservationStatisticsWrapper(env) if FLAGS.enable_obs_rotation_wrapper: env = ObservationRotationWrapper(env) @@ -485,9 +548,13 @@ def main(_): # assert FLAGS.encoder_kwargs is None or len(FLAGS.encoder_kwargs) % 2 == 0 encoder_kwargs = { "bottleneck_dim": FLAGS.encoder_bottleneck_dim, - **(dict(zip(*[iter(FLAGS.encoder_kwargs)] * 2)) if FLAGS.encoder_kwargs else {}), + **( + dict(zip(*[iter(FLAGS.encoder_kwargs)] * 2)) if FLAGS.encoder_kwargs else {} + ), + } + encoder_kwargs = { + k: (int(v) if str(v).isdigit() else v) for k, v in encoder_kwargs.items() } - encoder_kwargs = {k: (int(v) if str(v).isdigit() else v) for k, v in encoder_kwargs.items()} agent: DrQAgent = make_voxel_drq_agent( seed=FLAGS.seed, @@ -496,7 +563,7 @@ def main(_): image_keys=image_keys, encoder_type=FLAGS.encoder_type, state_mask=FLAGS.state_mask, - encoder_kwargs=encoder_kwargs + encoder_kwargs=encoder_kwargs, ) # replicate agent across devices @@ -511,7 +578,10 @@ def main(_): if FLAGS.enable_obs_rotation_augmentation: print("Batch Observation Rotation enabled!") - assert not FLAGS.enable_obs_rotation_augmentation or not FLAGS.enable_obs_rotation_wrapper # both is pointless + assert ( + not FLAGS.enable_obs_rotation_augmentation + or not FLAGS.enable_obs_rotation_wrapper + ) # both is pointless def create_replay_buffer_and_wandb_logger(): replay_buffer = MemoryEfficientReplayBufferDataStore( @@ -533,6 +603,7 @@ def create_replay_buffer_and_wandb_logger(): replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() import pickle as pkl + with open(FLAGS.demo_path, "rb") as f: trajs = pkl.load(f) diff --git a/examples/box_picking_drq/record_demo.py b/examples/box_picking_drq/record_demo.py index 6e1da63b..e9d8afac 100644 --- a/examples/box_picking_drq/record_demo.py +++ b/examples/box_picking_drq/record_demo.py @@ -1,4 +1,4 @@ -import gymnasium as gym +import gym from tqdm import tqdm import numpy as np import copy @@ -9,9 +9,16 @@ from pynput import keyboard from ur_env.envs.relative_env import RelativeFrame -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper, ObservationRotationWrapper - -from serl_launcher.wrappers.serl_obs_wrappers import SERLObsWrapper, ScaleObservationWrapper +from ur_env.envs.wrappers import ( + SpacemouseIntervention, + Quat2MrpWrapper, + ObservationRotationWrapper, +) + +from serl_launcher.wrappers.serl_obs_wrappers import ( + SERLObsWrapper, + ScaleObservationWrapper, +) from serl_launcher.wrappers.chunking import ChunkingWrapper import ur_env @@ -22,7 +29,7 @@ def on_space(key, info_dict): if key == keyboard.Key.space: for key, item in info_dict.items(): - print(f'{key}: {item}', end=' ') + print(f"{key}: {item}", end=" ") print() @@ -32,10 +39,11 @@ def on_esc(key): if __name__ == "__main__": - env = gym.make("box_picking_camera_env", - camera_mode="pointcloud", - max_episode_length=100, - ) + env = gym.make( + "box_picking_camera_env", + camera_mode="pointcloud", + max_episode_length=100, + ) env = SpacemouseIntervention(env) env = RelativeFrame(env) env = Quat2MrpWrapper(env) @@ -52,9 +60,15 @@ def on_esc(key): total_count = 0 pbar = tqdm(total=success_needed) - info_dict = {'state': env.unwrapped.curr_pos, 'gripper_state': env.unwrapped.gripper_state, - 'force': env.unwrapped.curr_force, 'reset_pose': env.unwrapped.curr_reset_pose} - listener_1 = keyboard.Listener(daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict)) + info_dict = { + "state": env.unwrapped.curr_pos, + "gripper_state": env.unwrapped.gripper_state, + "force": env.unwrapped.curr_force, + "reset_pose": env.unwrapped.curr_reset_pose, + } + listener_1 = keyboard.Listener( + daemon=True, on_press=lambda event: on_space(event, info_dict=info_dict) + ) listener_1.start() listener_2 = keyboard.Listener(on_press=on_esc, daemon=True) @@ -69,7 +83,7 @@ def on_esc(key): raise PermissionError(f"No permission to write to {file_dir}") try: - running_reward = 0. + running_reward = 0.0 while success_count < success_needed: if exit_program.is_set(): raise KeyboardInterrupt # stop program, but clean up before @@ -101,14 +115,14 @@ def on_esc(key): pbar.update(int(rew > 0.99)) obs, _ = env.reset() print("Reward total:", running_reward) - running_reward = 0. + running_reward = 0.0 with open(file_path, "wb") as f: pkl.dump(transitions, f) print(f"saved {success_needed} demos to {file_path}") except KeyboardInterrupt as e: - print(f'\nProgram was interrupted, cleaning up... ', e.__str__()) + print(f"\nProgram was interrupted, cleaning up... ", e.__str__()) finally: pbar.close() diff --git a/examples/box_picking_sac/run_actor.sh b/examples/box_picking_sac/run_actor.sh deleted file mode 100644 index fac4186b..00000000 --- a/examples/box_picking_sac/run_actor.sh +++ /dev/null @@ -1,15 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy.py "$@" \ - --actor \ - --env box_picking_basic_env \ - --exp_name=sac_drq_policy \ - --max_traj_length 300 \ - --seed 42 \ - --max_steps 10000 \ - --random_steps 0 \ - --utd_ratio 8 \ - --batch_size 2048 \ - --eval_period 1000 \ - --reward_scale 1 \ -# --debug \ No newline at end of file diff --git a/examples/box_picking_sac/run_evaluation.sh b/examples/box_picking_sac/run_evaluation.sh deleted file mode 100644 index 40eb31e5..00000000 --- a/examples/box_picking_sac/run_evaluation.sh +++ /dev/null @@ -1,10 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy.py "$@" \ - --actor \ - --env box_picking_basic_env \ - --exp_name=sac_drq_policy_evaluation \ - --eval_checkpoint_path "/home/nico/real-world-rl/serl/examples/box_picking_sac/checkpoints 0411-16:46"\ - --eval_checkpoint_step 100000 \ - --eval_n_trajs 10 \ - --debug diff --git a/examples/box_picking_sac/run_learner.sh b/examples/box_picking_sac/run_learner.sh deleted file mode 100644 index 5027e9d2..00000000 --- a/examples/box_picking_sac/run_learner.sh +++ /dev/null @@ -1,16 +0,0 @@ -export XLA_PYTHON_CLIENT_PREALLOCATE=false && \ -export XLA_PYTHON_CLIENT_MEM_FRACTION=.3 && \ -python sac_policy.py "$@" \ - --learner \ - --env box_picking_basic_env \ - --exp_name=sac_drq_policy \ - --max_traj_length 300 \ - --seed 42 \ - --training_starts 900 \ - --utd_ratio 8 \ - --batch_size 2048 \ - --max_steps 50000 \ - --reward_scale 1 \ - --demo_paths "/home/nico/real-world-rl/serl/examples/box_picking_sac/robotiq_test_20_demos_apr11_random_boxes.pkl" \ -# --preload_rlds_path "/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds" \ -# --debug diff --git a/examples/box_picking_sac/sac_policy.py b/examples/box_picking_sac/sac_policy.py deleted file mode 100644 index 2acf8d8a..00000000 --- a/examples/box_picking_sac/sac_policy.py +++ /dev/null @@ -1,398 +0,0 @@ -#!/usr/bin/env python3 - -import time -from functools import partial -import jax -import jax.numpy as jnp -import numpy as np -import tqdm -from absl import app, flags -from flax.training import checkpoints -from datetime import datetime - -import gymnasium as gym -from gymnasium.wrappers.record_episode_statistics import RecordEpisodeStatistics -from gymnasium.wrappers import TransformReward - -from serl_launcher.agents.continuous.sac import SACAgent -from serl_launcher.common.evaluation import evaluate -from serl_launcher.utils.timer_utils import Timer -from serl_launcher.data.data_store import populate_data_store - -from serl_launcher.wrappers.chunking import ChunkingWrapper -from ur_env.envs.relative_env import RelativeFrame - -from agentlace.trainer import TrainerServer, TrainerClient -from agentlace.data.data_store import QueuedDataStore - -from serl_launcher.utils.launcher import ( - make_sac_agent, - make_trainer_config, - make_wandb_logger, - make_replay_buffer, -) - -from serl_launcher.wrappers.serl_obs_wrappers import SerlObsWrapperNoImages -from ur_env.envs.wrappers import SpacemouseIntervention, Quat2MrpWrapper - -import ur_env - -FLAGS = flags.FLAGS - -flags.DEFINE_string("env", "box_picking_basic_env", "Name of environment.") -flags.DEFINE_string("agent", "sac", "Name of agent.") -flags.DEFINE_string("exp_name", "sac_drq_policy", "Name of the experiment for wandb logging.") -flags.DEFINE_integer("max_traj_length", 100, "Maximum length of trajectory.") -flags.DEFINE_integer("seed", 42, "Random seed.") -flags.DEFINE_bool("save_model", True, "Whether to save model.") -flags.DEFINE_integer("batch_size", 256, "Batch size.") -flags.DEFINE_integer("utd_ratio", 8, "UTD ratio.") -flags.DEFINE_integer("reward_scale", 1, "Reward Scale to help out SAC algorithm") - -flags.DEFINE_integer("max_steps", 100000, "Maximum number of training steps.") -flags.DEFINE_integer("replay_buffer_capacity", 1000000, "Replay buffer capacity.") -flags.DEFINE_multi_string("demo_paths", None, - "paths to demos") - -flags.DEFINE_integer("random_steps", 1000, "Sample random actions for this many steps.") -flags.DEFINE_integer("training_starts", 1000, "Training starts after this step.") -flags.DEFINE_integer("steps_per_update", 10, "Number of steps per update the server.") - -flags.DEFINE_integer("log_period", 10, "Logging period.") -flags.DEFINE_integer("eval_period", 2000, "Evaluation period.") -flags.DEFINE_integer("eval_n_trajs", 3, "Number of trajectories for evaluation.") - -# flag to indicate if this is a leaner or a actor -flags.DEFINE_boolean("learner", False, "Is this a learner or a trainer.") -flags.DEFINE_boolean("actor", False, "Is this a learner or a trainer.") -flags.DEFINE_string("ip", "localhost", "IP address of the learner.") -flags.DEFINE_integer("checkpoint_period", 10000, "Period to save checkpoints.") -flags.DEFINE_string("checkpoint_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/checkpoints', - "Path to save checkpoints.") - -flags.DEFINE_integer("eval_checkpoint_step", 0, "evaluate the policy from ckpt at this step") -flags.DEFINE_string("eval_checkpoint_path", None, "evaluate the policy from ckpt from this path") - -flags.DEFINE_string("log_rlds_path", '/home/nico/real-world-rl/serl/examples/box_picking_sac/rlds', - "Path to save RLDS logs.") -flags.DEFINE_string("preload_rlds_path", None, "Path to preload RLDS data.") - -flags.DEFINE_boolean( - "debug", False, "Debug mode." -) # debug mode will disable wandb logging - - -def print_green(x): - return print("\033[92m {}\033[00m".format(x)) - - -############################################################################## - - -def actor(agent: SACAgent, data_store, env, sampling_rng): - """ - This is the actor loop, which runs when "--actor" is set to True. - """ - if FLAGS.eval_checkpoint_step: - success_counter = 0 - time_list = [] - - ckpt = checkpoints.restore_checkpoint( - FLAGS.eval_checkpoint_path, - agent.state, - step=FLAGS.eval_checkpoint_step, - ) - agent = agent.replace(state=ckpt) - - for episode in range(FLAGS.eval_n_trajs): - obs, _ = env.reset() - done = False - start_time = time.time() - while not done: - actions = agent.sample_actions( - observations=jax.device_put(obs), - argmax=True, - ) - actions = np.asarray(jax.device_get(actions)) - # print(actions) - - next_obs, reward, done, truncated, info = env.step(actions) - obs = next_obs - - if done: - if reward: - dt = time.time() - start_time - time_list.append(dt) - print(dt) - - success_counter += int(reward > 0.99) - print(reward) - print(f"{success_counter}/{episode + 1}") - - print(f"success rate: {success_counter / FLAGS.eval_n_trajs}") - print(f"average time: {np.mean(time_list)}") - return # after done eval, return and exit - - client = TrainerClient( - "actor_env", - FLAGS.ip, - make_trainer_config(), - data_store, - wait_for_server=True, - ) - - # Function to update the agent with new params - def update_params(params): - nonlocal agent - agent = agent.replace(state=agent.state.replace(params=params)) - - client.recv_network_callback(update_params) - - obs, _ = env.reset() - print(f"obs: {obs}") - done = False - - # training loop - timer = Timer() - running_return = 0.0 - for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True): - timer.tick("total") - - with timer.context("sample_actions"): - if step < FLAGS.random_steps: - # print("sampling randomly!") - actions = env.action_space.sample() - else: - sampling_rng, key = jax.random.split(sampling_rng) - actions = agent.sample_actions( - observations=jax.device_put(obs), - seed=key, - argmax=False, - # deterministic=False, # sample without argmax for more diverse actions - ) - actions = np.asarray(jax.device_get(actions)) - - # Step environment - with timer.context("step_env"): - next_obs, reward, done, truncated, info = env.step(actions) - next_obs = np.asarray(next_obs, dtype=np.float32) - reward = np.asarray(reward, dtype=np.float32) - - running_return += reward - - data_store.insert( - dict( - observations=obs, - actions=actions, - next_observations=next_obs, - rewards=reward, - masks=1.0 - done, - dones=done or truncated, - ) - ) - - obs = next_obs - if done or truncated: - # print(f"running return: {running_return} done:{done} truncated:{truncated}") - running_return = 0.0 - obs, _ = env.reset() - - if step % FLAGS.steps_per_update == 0: - client.update() - - if step % FLAGS.eval_period == 0 and step: - with timer.context("eval"): - evaluate_info = evaluate( - policy_fn=partial(agent.sample_actions, argmax=True), - env=env, - num_episodes=FLAGS.eval_n_trajs, - ) - stats = {"eval": evaluate_info} - client.request("send-stats", stats) - - timer.tock("total") - - if step % FLAGS.log_period == 0: - stats = {"timer": timer.get_average_times()} - client.request("send-stats", stats) - - -############################################################################## - - -def learner(rng, agent: SACAgent, replay_buffer, replay_iterator, wandb_logger=None): - """ - The learner loop, which runs when "--learner" is set to True. - """ - # To track the step in the training loop - update_steps = 0 - - def stats_callback(type: str, payload: dict) -> dict: - """Callback for when server receives stats request.""" - assert type == "send-stats", f"Invalid request type: {type}" - if wandb_logger is not None: - wandb_logger.log(payload, step=update_steps) - return {} # not expecting a response - - # Create server - server = TrainerServer(make_trainer_config(), request_callback=stats_callback) - server.register_data_store("actor_env", replay_buffer) - server.start(threaded=True) - - # Loop to wait until replay_buffer is filled - pbar = tqdm.tqdm( - total=FLAGS.training_starts, - initial=len(replay_buffer), - desc="Filling up replay buffer", - position=0, - leave=True, - ) - while len(replay_buffer) < FLAGS.training_starts: - pbar.update(len(replay_buffer) - pbar.n) # Update progress bar - time.sleep(1) - pbar.update(len(replay_buffer) - pbar.n) # Update progress bar - pbar.close() - - # send the initial network to the actor - server.publish_network(agent.state.params) - print_green("sent initial network to actor") - - # wait till the replay buffer is filled with enough data - timer = Timer() - try: - for step in tqdm.tqdm(range(FLAGS.max_steps), dynamic_ncols=True, desc="learner"): - # Train the networks - with timer.context("sample_replay_buffer"): - batch = next(replay_iterator) - - with timer.context("train"): - if FLAGS.utd_ratio == 1: - agent, update_info = agent.update(batch=batch) # try it without utd - else: - agent, update_info = agent.update_high_utd(batch, utd_ratio=FLAGS.utd_ratio) - agent = jax.block_until_ready(agent) - - # publish the updated network - server.publish_network(agent.state.params) - - if update_steps % FLAGS.log_period == 0 and wandb_logger: - wandb_logger.log(update_info, step=update_steps) - wandb_logger.log({"timer": timer.get_average_times()}, step=update_steps) - wandb_logger.log({"replay_buffer_size": len(replay_buffer)}) - - if FLAGS.checkpoint_period and (update_steps + 1) % FLAGS.checkpoint_period == 0: - assert FLAGS.checkpoint_path is not None - checkpoints.save_checkpoint( - FLAGS.checkpoint_path, agent.state, step=update_steps + 1, keep=20 - ) - - update_steps += 1 - finally: - print("closing learner, clearning up...") - del replay_buffer - - -############################################################################## - - -def main(_): - devices = jax.local_devices() - num_devices = len(devices) - sharding = jax.sharding.PositionalSharding(devices) - assert FLAGS.batch_size % num_devices == 0 - FLAGS.checkpoint_path = FLAGS.checkpoint_path + " " + datetime.now().strftime("%m%d-%H:%M") - - # seed - rng = jax.random.PRNGKey(FLAGS.seed) - - # create env and load dataset - env = gym.make( - FLAGS.env, - fake_env=FLAGS.learner, - max_episode_length=FLAGS.max_traj_length, - camera_mode="none", - ) - if FLAGS.actor: - env = SpacemouseIntervention(env) - env = RelativeFrame(env) - env = Quat2MrpWrapper(env) - env = SerlObsWrapperNoImages(env) - # env = ChunkingWrapper(env, obs_horizon=1, act_exec_horizon=None) - # env = TransformReward(env, lambda r: FLAGS.reward_scale * r) - env = RecordEpisodeStatistics(env) - - rng, sampling_rng = jax.random.split(rng) - print(f"obs shape: {env.observation_space.sample().shape}") - agent: SACAgent = make_sac_agent( - seed=FLAGS.seed, - sample_obs=env.observation_space.sample(), - sample_action=env.action_space.sample(), - ) - - # replicate agent across devices - # need the jnp.array to avoid a bug where device_put doesn't recognize primitives - agent: SACAgent = jax.device_put( - jax.tree_map(jnp.array, agent), sharding.replicate() - ) - - def create_replay_buffer_and_wandb_logger(): - replay_buffer = make_replay_buffer( - env, - capacity=FLAGS.replay_buffer_capacity, - type="replay_buffer", - rlds_logger_path=FLAGS.log_rlds_path, - preload_rlds_path=FLAGS.preload_rlds_path, - ) - - # set up wandb and logging - wandb_logger = make_wandb_logger( - project="serl_dev", - description=FLAGS.exp_name or FLAGS.env, - debug=FLAGS.debug, - ) - return replay_buffer, wandb_logger - - if FLAGS.learner: - sampling_rng = jax.device_put(sampling_rng, device=sharding.replicate()) - replay_buffer, wandb_logger = create_replay_buffer_and_wandb_logger() - - if FLAGS.preload_rlds_path is None and FLAGS.demo_paths is not None: - print(f"loaded demos from {FLAGS.demo_paths}") # load demo trajectories the old way - replay_buffer = populate_data_store(replay_buffer, FLAGS.demo_paths, reward_scaling=FLAGS.reward_scale) - - replay_iterator = replay_buffer.get_iterator( - sample_args={ - "batch_size": FLAGS.batch_size * FLAGS.utd_ratio, - }, - device=sharding.replicate(), - ) - # learner loop - print_green("starting learner loop") - learner( - sampling_rng, - agent, - replay_buffer, - replay_iterator=replay_iterator, - wandb_logger=wandb_logger, - ) - - elif FLAGS.actor: - sampling_rng = jax.device_put(sampling_rng, sharding.replicate()) - data_store = QueuedDataStore(50000) # the queue size on the actor - - # actor loop - print_green("starting actor loop") - try: - actor(agent, data_store, env, sampling_rng) - print_green("actor loop finished") - except KeyboardInterrupt: - print_green("actor loop interrupted") - finally: - env.close() - - else: - raise NotImplementedError("Must be either a learner or an actor") - - -if __name__ == "__main__": - app.run(main) diff --git a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py b/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py deleted file mode 100644 index a5a2f6b4..00000000 --- a/serl_launcher/serl_launcher/agents/continuous/bc_noimg.py +++ /dev/null @@ -1,146 +0,0 @@ -from functools import partial -from typing import Any, Iterable, Optional - -import flax -import jax -import jax.numpy as jnp -import numpy as np -import optax - -from serl_launcher.common.common import JaxRLTrainState, ModuleDict -from serl_launcher.common.typing import Batch, PRNGKey, Data -from serl_launcher.networks.actor_critic_nets import Policy -from serl_launcher.networks.mlp import MLP -from serl_launcher.utils.train_utils import _unpack -from serl_launcher.vision.data_augmentations import batched_random_crop - -""" -Behavioral cloning without using image data as observation, only state data -""" - - -class BCAgentNoImg(flax.struct.PyTreeNode): - state: JaxRLTrainState - - @partial(jax.jit, static_argnames="pmap_axis") - def update(self, batch: Batch, pmap_axis: str = None): - # rng = self.state.rng - # rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) - # obs = self.data_augmentation_fn(obs_rng, batch["observations"]) - # batch = batch.copy(add_or_replace={"observations": obs}) - - def loss_fn(params, rng): - rng, key = jax.random.split(rng) - dist = self.state.apply_fn( - {"params": params}, - batch["observations"], - temperature=1.0, - train=True, - rngs={"dropout": key}, - name="actor", - ) - pi_actions = dist.mode() - log_probs = dist.log_prob(batch["actions"]) - mse = ((pi_actions - batch["actions"]) ** 2).sum(-1) - actor_loss = -(log_probs).mean() - actor_std = dist.stddev().mean(axis=1) - - return actor_loss, { - "actor_loss": actor_loss, - "mse": mse.mean(), - "log_probs": log_probs, - "pi_actions": pi_actions, - "mean_std": actor_std.mean(), - "max_std": actor_std.max(), - } - - # compute gradients and update params - new_state, info = self.state.apply_loss_fns( - loss_fn, pmap_axis=pmap_axis, has_aux=True - ) - - return self.replace(state=new_state), info - - @partial(jax.jit, static_argnames="argmax") # no img data present - def sample_actions( - self, - observations: np.ndarray, - *, - seed: Optional[PRNGKey] = None, - temperature: float = 1.0, - argmax=False, - ) -> jnp.ndarray: - dist = self.state.apply_fn( - {"params": self.state.params}, - observations, - temperature=temperature, - name="actor", - ) - if argmax: - actions = dist.mode() - else: - actions = dist.sample(seed=seed) - return actions - - @jax.jit - def get_debug_metrics(self, batch, **kwargs): - dist = self.state.apply_fn( - {"params": self.state.params}, - batch["observations"], - temperature=1.0, - name="actor", - ) - pi_actions = dist.mode() - log_probs = dist.log_prob(batch["actions"]) - mse = ((pi_actions - batch["actions"]) ** 2).sum(-1) - - return { - "mse": mse, - "log_probs": log_probs, - "pi_actions": pi_actions, - } - - @classmethod - def create( - cls, - rng: PRNGKey, - observations: Data, - actions: jnp.ndarray, - # Model architecture - network_kwargs: dict = dict(hidden_dims=[256, 256]), - policy_kwargs: dict = dict(tanh_squash_distribution=False), - # Optimizer - learning_rate: float = 3e-4, - ): - """ - create agent with no encoders - """ - - network_kwargs["activate_final"] = True - networks = { - "actor": Policy( - None, - MLP(**network_kwargs), - action_dim=actions.shape[-1], - **policy_kwargs, - ) - } - - model_def = ModuleDict(networks) - - tx = optax.adam(learning_rate) - - rng, init_rng = jax.random.split(rng) - params = model_def.init(init_rng, actor=[observations])["params"] - - rng, create_rng = jax.random.split(rng) - state = JaxRLTrainState.create( - apply_fn=model_def.apply, - params=params, - txs=tx, - target_params=params, - rng=create_rng, - ) - - agent = cls(state) - return agent diff --git a/serl_launcher/serl_launcher/agents/continuous/drq.py b/serl_launcher/serl_launcher/agents/continuous/drq.py index e1c6177d..518f17ed 100644 --- a/serl_launcher/serl_launcher/agents/continuous/drq.py +++ b/serl_launcher/serl_launcher/agents/continuous/drq.py @@ -10,7 +10,11 @@ from serl_launcher.agents.continuous.sac import SACAgent from serl_launcher.common.common import JaxRLTrainState, ModuleDict, nonpytree_field -from serl_launcher.common.encoding import MaskedEncodingWrapper, create_state_mask +from serl_launcher.common.encoding import ( + EncodingWrapper, + MaskedEncodingWrapper, + create_state_mask, +) from serl_launcher.common.optimizers import make_optimizer from serl_launcher.common.typing import Batch, Data, Params, PRNGKey from serl_launcher.networks.actor_critic_nets import Critic, Policy, ensemblize @@ -18,39 +22,42 @@ from serl_launcher.networks.mlp import MLP from serl_launcher.vision.voxel_grid_encoders import VoxNet from serl_launcher.utils.train_utils import _unpack, concat_batches -from serl_launcher.vision.data_augmentations import batched_random_crop, batched_random_shift_voxel +from serl_launcher.vision.data_augmentations import ( + batched_random_crop, + batched_random_shift_voxel, +) class DrQAgent(SACAgent): @classmethod def create( - cls, - rng: PRNGKey, - observations: Data, - actions: jnp.ndarray, - # Models - actor_def: nn.Module, - critic_def: nn.Module, - temperature_def: nn.Module, - # Optimizer - actor_optimizer_kwargs={ - "learning_rate": 3e-4, - }, - critic_optimizer_kwargs={ - "learning_rate": 3e-4, - }, - temperature_optimizer_kwargs={ - "learning_rate": 3e-4, - }, - # Algorithm config - discount: float = 0.95, - soft_target_update_rate: float = 0.005, - target_entropy: Optional[float] = None, - entropy_per_dim: bool = False, - backup_entropy: bool = False, - critic_ensemble_size: int = 2, - critic_subsample_size: Optional[int] = None, - image_keys: Iterable[str] = ("image",), + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Models + actor_def: nn.Module, + critic_def: nn.Module, + temperature_def: nn.Module, + # Optimizer + actor_optimizer_kwargs={ + "learning_rate": 3e-4, + }, + critic_optimizer_kwargs={ + "learning_rate": 3e-4, + }, + temperature_optimizer_kwargs={ + "learning_rate": 3e-4, + }, + # Algorithm config + discount: float = 0.95, + soft_target_update_rate: float = 0.005, + target_entropy: Optional[float] = None, + entropy_per_dim: bool = False, + backup_entropy: bool = False, + critic_ensemble_size: int = 2, + critic_subsample_size: Optional[int] = None, + image_keys: Iterable[str] = ("image",), ): networks = { "actor": actor_def, @@ -87,11 +94,7 @@ def create( # Config assert not entropy_per_dim, "Not implemented" if target_entropy is None: - # target_entropy = -actions.shape[-1] / 2 - from numpy import prod - target_entropy = -prod(actions.shape) - - print(f"config: discount: {discount}, target_entropy: {target_entropy}") + target_entropy = -actions.shape[-1] return cls( state=state, @@ -107,34 +110,33 @@ def create( ) @classmethod - def create_voxel_drq( - cls, - rng: PRNGKey, - observations: Data, - actions: jnp.ndarray, - # Model architecture - encoder_type: str = "resnet", - use_proprio: bool = False, - state_mask: str = "all", - critic_network_kwargs: dict = { - "hidden_dims": [256, 256], - }, - policy_network_kwargs: dict = { - "hidden_dims": [256, 256], - }, - policy_kwargs: dict = { - "tanh_squash_distribution": True, - "std_parameterization": "uniform", - }, - encoder_kwargs: dict = {}, - critic_ensemble_size: int = 2, - critic_subsample_size: Optional[int] = None, - temperature_init: float = 1.0, - image_keys: Iterable[str] = ("image",), - **kwargs, + def create_drq( + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Model architecture + encoder_type: str = "small", + shared_encoder: bool = True, + use_proprio: bool = False, + critic_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_kwargs: dict = { + "tanh_squash_distribution": True, + "std_parameterization": "uniform", + }, + critic_ensemble_size: int = 2, + critic_subsample_size: Optional[int] = None, + temperature_init: float = 1.0, + image_keys: Iterable[str] = ("image",), + **kwargs, ): """ - Create a new voxel-based agent. + Create a new pixel-based agent, with no encoders. """ policy_network_kwargs["activate_final"] = True @@ -142,19 +144,18 @@ def create_voxel_drq( if encoder_type == "small": from serl_launcher.vision.small_encoders import SmallEncoder - small_encoder = SmallEncoder( - features=(64, 64, 32, 32), + + encoders = { + image_key: SmallEncoder( + features=(32, 64, 128, 256), kernel_sizes=(3, 3, 3, 3), - strides=(2, 2, 1, 1), + strides=(2, 2, 2, 2), padding="VALID", - pool_method="spatial_learned_embeddings", - bottleneck_dim=128, + pool_method="avg", + bottleneck_dim=256, spatial_block_size=8, - name=f"small_encoder", + name=f"encoder_{image_key}", ) - # use the same encoder - encoders = { - image_key: small_encoder for image_key in image_keys } elif encoder_type == "resnet": @@ -162,8 +163,146 @@ def create_voxel_drq( encoders = { image_key: resnetv1_configs["resnetv1-10"]( + pooling_method="spatial_learned_embeddings", + num_spatial_blocks=8, + bottleneck_dim=256, name=f"encoder_{image_key}", - **encoder_kwargs + ) + for image_key in image_keys + } + elif encoder_type == "resnet-pretrained": + from serl_launcher.vision.resnet_v1 import ( + PreTrainedResNetEncoder, + resnetv1_configs, + ) + + pretrained_encoder = resnetv1_configs["resnetv1-10-frozen"]( + pre_pooling=True, + name="pretrained_encoder", + ) + encoders = { + image_key: PreTrainedResNetEncoder( + pooling_method="spatial_learned_embeddings", + num_spatial_blocks=8, + bottleneck_dim=256, + pretrained_encoder=pretrained_encoder, + name=f"encoder_{image_key}", + ) + for image_key in image_keys + } + else: + raise NotImplementedError(f"Unknown encoder type: {encoder_type}") + + encoder_def = EncodingWrapper( + encoder=encoders, + use_proprio=use_proprio, + enable_stacking=True, + image_keys=image_keys, + ) + + encoders = { + "critic": encoder_def, + "actor": encoder_def, + } + + # Define networks + critic_backbone = partial(MLP, **critic_network_kwargs) + critic_backbone = ensemblize(critic_backbone, critic_ensemble_size)( + name="critic_ensemble" + ) + critic_def = partial( + Critic, encoder=encoders["critic"], network=critic_backbone + )(name="critic") + + policy_def = Policy( + encoder=encoders["actor"], + network=MLP(**policy_network_kwargs), + action_dim=actions.shape[-1], + **policy_kwargs, + name="actor", + ) + + temperature_def = GeqLagrangeMultiplier( + init_value=temperature_init, + constraint_shape=(), + constraint_type="geq", + name="temperature", + ) + + agent = cls.create( + rng, + observations, + actions, + actor_def=policy_def, + critic_def=critic_def, + temperature_def=temperature_def, + critic_ensemble_size=critic_ensemble_size, + critic_subsample_size=critic_subsample_size, + image_keys=image_keys, + **kwargs, + ) + + if encoder_type == "resnet-pretrained": # load pretrained weights for ResNet-10 + from serl_launcher.utils.train_utils import load_resnet10_params + + agent = load_resnet10_params(agent, image_keys) + + return agent + + @classmethod + def create_voxel_drq( + cls, + rng: PRNGKey, + observations: Data, + actions: jnp.ndarray, + # Model architecture + encoder_type: str = "resnet", + use_proprio: bool = False, + state_mask: str = "all", + critic_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_network_kwargs: dict = { + "hidden_dims": [256, 256], + }, + policy_kwargs: dict = { + "tanh_squash_distribution": True, + "std_parameterization": "uniform", + }, + encoder_kwargs: dict = {}, + critic_ensemble_size: int = 2, + critic_subsample_size: Optional[int] = None, + temperature_init: float = 1.0, + image_keys: Iterable[str] = ("image",), + **kwargs, + ): + """ + Create a new voxel-based agent. + """ + + policy_network_kwargs["activate_final"] = True + critic_network_kwargs["activate_final"] = True + + if encoder_type == "small": + from serl_launcher.vision.small_encoders import SmallEncoder + + small_encoder = SmallEncoder( + features=(64, 64, 32, 32), + kernel_sizes=(3, 3, 3, 3), + strides=(2, 2, 1, 1), + padding="VALID", + pool_method="spatial_learned_embeddings", + bottleneck_dim=128, + spatial_block_size=8, + name=f"small_encoder", + ) + encoders = {image_key: small_encoder for image_key in image_keys} + elif encoder_type == "resnet": + from serl_launcher.vision.resnet_v1 import resnetv1_configs + + encoders = { + image_key: resnetv1_configs["resnetv1-10"]( + name=f"encoder_{image_key}", **encoder_kwargs ) for image_key in image_keys } @@ -183,7 +322,7 @@ def create_voxel_drq( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - **encoder_kwargs + **encoder_kwargs, ) for image_key in image_keys } @@ -201,7 +340,7 @@ def create_voxel_drq( rng=rng, pretrained_encoder=pretrained_encoder, name=f"encoder_{image_key}", - **encoder_kwargs + **encoder_kwargs, ) for image_key in image_keys } @@ -227,7 +366,7 @@ def create_voxel_drq( use_proprio=use_proprio, enable_stacking=True, image_keys=image_keys, - state_mask=state_mask_arr + state_mask=state_mask_arr, ) encoders = { @@ -311,11 +450,11 @@ def data_augmentation_fn(self, rng, observations): @partial(jax.jit, static_argnames=("utd_ratio", "pmap_axis")) def update_high_utd( - self, - batch: Batch, - *, - utd_ratio: int, - pmap_axis: Optional[str] = None, + self, + batch: Batch, + *, + utd_ratio: int, + pmap_axis: Optional[str] = None, ) -> Tuple["DrQAgent", dict]: """ Fast JITted high-UTD version of `.update`. @@ -329,7 +468,7 @@ def update_high_utd( before updating the network. """ new_agent = self - if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: + if self.config["image_keys"][0] not in batch["next_observations"]: batch = _unpack(batch) rng = new_agent.state.rng @@ -343,8 +482,6 @@ def update_high_utd( } ) - # TODO implement K=2 and M=2 - new_state = self.state.replace(rng=rng) new_agent = self.replace(state=new_state) @@ -354,17 +491,15 @@ def update_high_utd( @partial(jax.jit, static_argnames=("pmap_axis",)) def update_critics( - self, - batch: Batch, - *, - pmap_axis: Optional[str] = None, + self, + batch: Batch, + *, + pmap_axis: Optional[str] = None, ) -> Tuple["DrQAgent", dict]: new_agent = self - if len(self.config["image_keys"]) and self.config["image_keys"][0] not in batch["next_observations"]: + if self.config["image_keys"][0] not in batch["next_observations"]: batch = _unpack(batch) - # TODO implement K=2 and M=2 - rng = new_agent.state.rng rng, obs_rng, next_obs_rng = jax.random.split(rng, 3) obs = self.data_augmentation_fn(obs_rng, batch["observations"]) @@ -386,4 +521,4 @@ def update_critics( del critic_infos["actor"] del critic_infos["temperature"] - return new_agent, critic_infos \ No newline at end of file + return new_agent, critic_infos diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index 6160aaba..33476580 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -162,15 +162,23 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): chex.assert_shape(target_next_min_q, (batch_size,)) target_q = ( - batch["rewards"] - + self.config["discount"] * batch["masks"] * target_next_min_q + batch["rewards"] + + self.config["discount"] * batch["masks"] * target_next_min_q ) chex.assert_shape(target_q, (batch_size,)) - temperature = self.forward_temperature() - if self.config["backup_entropy"]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py + if self.config[ + "backup_entropy" + ]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py + temperature = self.forward_temperature() # target_q = target_q - temperature * next_actions_log_probs # serl original - target_q = target_q - self.config["discount"] * batch["masks"] * next_actions_log_probs * temperature # as in jaxrl_m + target_q = ( + target_q + - self.config["discount"] + * batch["masks"] + * next_actions_log_probs + * temperature + ) # as in jaxrl_m predicted_qs = self.forward_critic( batch["observations"], batch["actions"], rng=rng, grad_params=params @@ -181,14 +189,12 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): ) target_qs = target_q[None].repeat(self.config["critic_ensemble_size"], axis=0) chex.assert_equal_shape([predicted_qs, target_qs]) - critic_loss = jnp.mean(jnp.sum((predicted_qs - target_qs) ** 2, axis=0)) + critic_loss = jnp.mean((predicted_qs - target_qs) ** 2) info = { "critic_loss": critic_loss, "predicted_qs": jnp.mean(predicted_qs), "target_qs": jnp.mean(target_qs), - # "log_probs": jnp.mean(next_actions_log_probs), - # "temp_log_probs": jnp.mean(next_actions_log_probs * temperature * batch["masks"] * self.config["discount"]), } return critic_loss, info @@ -388,14 +394,7 @@ def create( # Config assert not entropy_per_dim, "Not implemented" if target_entropy is None: - # target_entropy = -actions.shape[-1] / 2 - print(f"actions shape: {actions.shape}") - - # from https://github.com/NickKaparinos/OpenAI-Gym-Projects/blob/master/Classic%20Control/MountainCarContinuous/main.py: - # target_entropy = -np.prod(env.action_space.shape) - from numpy import prod - target_entropy = -prod(actions.shape) - print(f"target_entropy: {target_entropy}") + target_entropy = -actions.shape[-1] return cls( state=state, diff --git a/serl_launcher/serl_launcher/common/encoding.py b/serl_launcher/serl_launcher/common/encoding.py index adf4c321..c54915b7 100644 --- a/serl_launcher/serl_launcher/common/encoding.py +++ b/serl_launcher/serl_launcher/common/encoding.py @@ -11,8 +11,8 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: all = jnp.ones((27,), dtype=jnp.bool) none = jnp.zeros_like(all) no_action = all.at[:7].set(False) - gripper = none.at[0+7:2+7].set(True) - no_ForceTorque = all.at[7+2:7+5].set(False).at[7+11:7+14].set(False) + gripper = none.at[0 + 7 : 2 + 7].set(True) + no_ForceTorque = all.at[7 + 2 : 7 + 5].set(False).at[7 + 11 : 7 + 14].set(False) action_only = none.at[:7].set(True) masks = dict( all=all, @@ -21,13 +21,78 @@ def create_state_mask(mask_str: str) -> jnp.ndarray: position_gripper=gripper.at[5:11].set(True), no_ForceTorque=no_ForceTorque, no_ForceTorqueAction=jnp.bitwise_and(no_ForceTorque, no_action), - gripper_Zinfo=gripper.at[7+7].set(True), + gripper_Zinfo=gripper.at[7 + 7].set(True), action_only=action_only, ) assert mask_str in masks return masks[mask_str] +class EncodingWrapper(nn.Module): + """ + Encodes observations into a single flat encoding, adding additional + functionality for adding proprioception and stopping the gradient. + + Args: + encoder: The encoder network. + use_proprio: Whether to concatenate proprioception (after encoding). + """ + + encoder: nn.Module + use_proprio: bool + proprio_latent_dim: int = 64 + enable_stacking: bool = False + image_keys: Iterable[str] = ("image",) + + @nn.compact + def __call__( + self, + observations: Dict[str, jnp.ndarray], + train=False, + stop_gradient=False, + is_encoded=False, + ) -> jnp.ndarray: + # encode images with encoder + encoded = [] + for image_key in self.image_keys: + image = observations[image_key] + if not is_encoded: + if self.enable_stacking: + # Combine stacking and channels into a single dimension + if len(image.shape) == 4: + image = rearrange(image, "T H W C -> H W (T C)") + if len(image.shape) == 5: + image = rearrange(image, "B T H W C -> B H W (T C)") + + image = self.encoder[image_key](image, train=train, encode=not is_encoded) + + if stop_gradient: + image = jax.lax.stop_gradient(image) + + encoded.append(image) + + encoded = jnp.concatenate(encoded, axis=-1) + + if self.use_proprio: + # project state to embeddings as well + state = observations["state"] + if self.enable_stacking: + # Combine stacking and channels into a single dimension + if len(state.shape) == 2: + state = rearrange(state, "T C -> (T C)") + encoded = encoded.reshape(-1) + if len(state.shape) == 3: + state = rearrange(state, "B T C -> B (T C)") + state = nn.Dense( + self.proprio_latent_dim, kernel_init=nn.initializers.xavier_uniform() + )(state) + state = nn.LayerNorm()(state) + state = nn.tanh(state) + encoded = jnp.concatenate([encoded, state], axis=-1) + + return encoded + + class MaskedEncodingWrapper(nn.Module): """ Encodes observations into a single flat encoding, adding additional @@ -36,6 +101,7 @@ class MaskedEncodingWrapper(nn.Module): Args: encoder: The encoder network. use_proprio: Whether to concatenate proprioception (after encoding). + state_mask: Which proprioceptive states to propagate, and which to ignore """ encoder: nn.Module @@ -46,11 +112,11 @@ class MaskedEncodingWrapper(nn.Module): @nn.compact def __call__( - self, - observations: Dict[str, jnp.ndarray], - train=False, - stop_gradient=False, - is_encoded=False, + self, + observations: Dict[str, jnp.ndarray], + train=False, + stop_gradient=False, + is_encoded=False, ) -> jnp.ndarray: # encode images with encoder if self.encoder is None: @@ -88,7 +154,7 @@ def __call__( if self.use_proprio: # project state to embeddings as well state = observations["state"] - state = state[..., self.state_mask] # only propagate non-zero mask entries + state = state[..., self.state_mask] # only propagate non-zero mask entries if state.shape[-1] != 0: if self.enable_stacking: # Combine stacking and channels into a single dimension @@ -103,7 +169,7 @@ def __call__( return encoded -class GCEncodingWrapper(nn.Module): # never used +class GCEncodingWrapper(nn.Module): """ Encodes observations and goals into a single flat encoding. Handles all the logic about when/how to combine observations and goals. @@ -125,8 +191,8 @@ class GCEncodingWrapper(nn.Module): # never used stop_gradient: bool def __call__( - self, - observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], + self, + observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], ) -> jnp.ndarray: observations, goals = observations_and_goals @@ -185,8 +251,8 @@ class LCEncodingWrapper(nn.Module): stop_gradient: bool def __call__( - self, - observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], + self, + observations_and_goals: Tuple[Dict[str, jnp.ndarray], Dict[str, jnp.ndarray]], ) -> jnp.ndarray: observations, goals = observations_and_goals diff --git a/serl_launcher/serl_launcher/common/evaluation.py b/serl_launcher/serl_launcher/common/evaluation.py index de7ac137..5065a5b1 100644 --- a/serl_launcher/serl_launcher/common/evaluation.py +++ b/serl_launcher/serl_launcher/common/evaluation.py @@ -54,7 +54,6 @@ def evaluate(policy_fn, env: gym.Env, num_episodes: int) -> Dict[str, float]: done = False while not done: action = policy_fn(observation) - action = np.asarray(jax.device_get(action)) observation, _, terminated, truncated, info = env.step(action) done = terminated or truncated add_to(stats, flatten(info)) diff --git a/serl_launcher/serl_launcher/data/data_store.py b/serl_launcher/serl_launcher/data/data_store.py index 5bd3e985..20e65813 100644 --- a/serl_launcher/serl_launcher/data/data_store.py +++ b/serl_launcher/serl_launcher/data/data_store.py @@ -25,11 +25,11 @@ class ReplayBufferDataStore(ReplayBuffer, DataStoreBase): def __init__( - self, - observation_space: gym.Space, - action_space: gym.Space, - capacity: int, - rlds_logger: Optional[RLDSLogger] = None, + self, + observation_space: gym.Space, + action_space: gym.Space, + capacity: int, + rlds_logger: Optional[RLDSLogger] = None, ): ReplayBuffer.__init__(self, observation_space, action_space, capacity) DataStoreBase.__init__(self, capacity) @@ -79,20 +79,15 @@ def latest_data_id(self): def get_latest_data(self, from_id: int): raise NotImplementedError # TODO - def __del__(self): - if self._logger: - self._logger.close() - print("[ReplayBufferDataStore] RLDS logger closed successfully") - class MemoryEfficientReplayBufferDataStore(MemoryEfficientReplayBuffer, DataStoreBase): def __init__( - self, - observation_space: gym.Space, - action_space: gym.Space, - capacity: int, - image_keys: Iterable[str] = ("image",), - rlds_logger: Optional[RLDSLogger] = None, + self, + observation_space: gym.Space, + action_space: gym.Space, + capacity: int, + image_keys: Iterable[str] = ("image",), + rlds_logger: Optional[RLDSLogger] = None, ): MemoryEfficientReplayBuffer.__init__( self, observation_space, action_space, capacity, pixel_keys=image_keys @@ -150,9 +145,8 @@ def get_latest_data(self, from_id: int): def populate_data_store( - data_store: DataStoreBase, - demos_path: str, - reward_scaling: int = 1, + data_store: DataStoreBase, + demos_path: str, ): """ Utility function to populate demonstrations data into data_store. @@ -164,15 +158,14 @@ def populate_data_store( with open(demo_path, "rb") as f: demo = pkl.load(f) for transition in demo: - transition["rewards"] *= reward_scaling # apply reward scaling data_store.insert(transition) print(f"Loaded {len(data_store)} transitions.") return data_store def populate_data_store_with_z_axis_only( - data_store: DataStoreBase, - demos_path: str, + data_store: DataStoreBase, + demos_path: str, ): """ Utility function to populate demonstrations data into data_store. diff --git a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py index f6102bdf..d94f1143 100644 --- a/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py +++ b/serl_launcher/serl_launcher/data/memory_efficient_replay_buffer.py @@ -121,12 +121,7 @@ def sample( else: indx[i] = self.np_random.randint(len(self)) else: - # raise NotImplementedError() - # print(f"indx is {indx}") - for i in range(batch_size): - if not self._is_correct_index[indx[i]]: - print(f"index {indx[i]} is not correct!") - assert type(indx) == np.ndarray + raise NotImplementedError() if keys is None: keys = self.dataset_dict.keys() @@ -167,14 +162,3 @@ def sample( batch["next_observations"][pixel_key] = obs_pixels[:, 1:, ...] return frozen_dict.freeze(batch) - - def save_to_file(self, path): - import pickle as pkl - obj = {} - for attr, value in self.__dict__.items(): - print(attr, type(value)) - if "lock" not in attr: - obj[attr] = value - - with open(path, "wb") as f: - pkl.dump(obj, f) \ No newline at end of file diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index b7b4b66a..b288998b 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -186,10 +186,6 @@ def __call__( else: obs_enc = self.encoder(observations, train=train, stop_gradient=True) - # output the encoded obs, returning is not possible due to jax (on gpu) - # for i in range(obs_enc.shape[0]): - # jax.debug.print("{}\n\n", obs_enc[i, ...]) - outputs = self.network(obs_enc, train=train) means = nn.Dense(self.action_dim, kernel_init=default_init())(outputs) diff --git a/serl_launcher/serl_launcher/utils/launcher.py b/serl_launcher/serl_launcher/utils/launcher.py index 56c7635f..c37a2620 100644 --- a/serl_launcher/serl_launcher/utils/launcher.py +++ b/serl_launcher/serl_launcher/utils/launcher.py @@ -117,13 +117,13 @@ def make_drq_agent( def make_voxel_drq_agent( - seed, - sample_obs, - sample_action, - image_keys=("image",), - encoder_type="voxnet", - state_mask="all", - encoder_kwargs=None + seed, + sample_obs, + sample_action, + image_keys=("image",), + encoder_type="voxnet", + state_mask="all", + encoder_kwargs=None, ): if encoder_kwargs is None: encoder_kwargs = dict(bottleneck_dim=128) @@ -146,13 +146,13 @@ def make_voxel_drq_agent( activations=nn.tanh, use_layer_norm=True, hidden_dims=[256, 256], - dropout_rate=0.1 + dropout_rate=0.1, ), policy_network_kwargs=dict( activations=nn.tanh, use_layer_norm=True, hidden_dims=[256, 256], - dropout_rate=0.1 + dropout_rate=0.1, ), temperature_init=1e-2, discount=0.99, # 0.99 diff --git a/serl_launcher/serl_launcher/utils/sampling_utils.py b/serl_launcher/serl_launcher/utils/sampling_utils.py index dcb3fde4..9827b2de 100644 --- a/serl_launcher/serl_launcher/utils/sampling_utils.py +++ b/serl_launcher/serl_launcher/utils/sampling_utils.py @@ -13,7 +13,7 @@ def __init__(self, activated=True, action_shape=(7,), ensemble=None): print(f"Temporal Action Ensemble enabled: {self.ensemble}") def reset(self): - self.buffer[...] = 0. + self.buffer[...] = 0.0 def sample(self, curr_action: np.ndarray): if not self.activated: diff --git a/serl_launcher/serl_launcher/utils/train_utils.py b/serl_launcher/serl_launcher/utils/train_utils.py index 4301f96c..200e1798 100644 --- a/serl_launcher/serl_launcher/utils/train_utils.py +++ b/serl_launcher/serl_launcher/utils/train_utils.py @@ -32,7 +32,7 @@ def concat_batches(offline_batch, online_batch, axis=1): def load_recorded_video( - video_path: str, + video_path: str, ): with tf.io.gfile.GFile(video_path, "rb") as f: video = np.array(imageio.mimread(f, "MP4")).transpose((0, 3, 1, 2)) @@ -110,7 +110,7 @@ def load_resnet10_params(agent, image_keys=("image",), public=True): param_count = sum(x.size for x in jax.tree_leaves(encoder_params)) print( - f"Loaded {param_count / 1e6}M parameters from ResNet-10 pretrained on ImageNet-1K" + f"Loaded {param_count/1e6}M parameters from ResNet-10 pretrained on ImageNet-1K" ) new_params = agent.state.params @@ -142,30 +142,48 @@ def load_pretrained_VoxNet_params(agent, image_keys=("pointcloud",)): to_replace = { "conv_5x5x5": "voxnet/conv1/conv3d/", "conv_3x3x3": "voxnet/conv2/conv3d/", - "conv_2x2x2": "voxnet/conv3/conv3d/" + "conv_2x2x2": "voxnet/conv3/conv3d/", } replaced = [] for key, weights in to_replace.items(): if key in new_encoder_params: shape = new_encoder_params[key]["kernel"].shape - new_encoder_params[key]["kernel"] = new_encoder_params[key]["kernel"].at[:].set( - ckpt[weights + "kernel:0"][..., :shape[-1]]) - new_encoder_params[key]["bias"] = new_encoder_params[key]["bias"].at[:].set( - ckpt[weights + "bias:0"][:shape[-1]]) + new_encoder_params[key]["kernel"] = ( + new_encoder_params[key]["kernel"] + .at[:] + .set(ckpt[weights + "kernel:0"][..., : shape[-1]]) + ) + new_encoder_params[key]["bias"] = ( + new_encoder_params[key]["bias"] + .at[:] + .set(ckpt[weights + "bias:0"][: shape[-1]]) + ) replaced.append(f"{key}:{shape}") print(f"replaced {replaced} in {image_key}") # replace LayerNorm params with pretrained BN ones - new_encoder_params["LayerNorm_0"]["bias"] = new_encoder_params["LayerNorm_0"]["bias"].at[:].set( - ckpt["voxnet/conv1/batch_normalization/beta:0"]) - new_encoder_params["LayerNorm_0"]["scale"] = new_encoder_params["LayerNorm_0"]["scale"].at[:].set( - ckpt["voxnet/conv1/batch_normalization/gamma:0"]) - - new_encoder_params["LayerNorm_1"]["bias"] = new_encoder_params["LayerNorm_0"]["bias"].at[:].set( - ckpt["voxnet/conv2/batch_normalization/beta:0"]) - new_encoder_params["LayerNorm_1"]["scale"] = new_encoder_params["LayerNorm_0"]["scale"].at[:].set( - ckpt["voxnet/conv2/batch_normalization/gamma:0"]) + new_encoder_params["LayerNorm_0"]["bias"] = ( + new_encoder_params["LayerNorm_0"]["bias"] + .at[:] + .set(ckpt["voxnet/conv1/batch_normalization/beta:0"]) + ) + new_encoder_params["LayerNorm_0"]["scale"] = ( + new_encoder_params["LayerNorm_0"]["scale"] + .at[:] + .set(ckpt["voxnet/conv1/batch_normalization/gamma:0"]) + ) + + new_encoder_params["LayerNorm_1"]["bias"] = ( + new_encoder_params["LayerNorm_0"]["bias"] + .at[:] + .set(ckpt["voxnet/conv2/batch_normalization/beta:0"]) + ) + new_encoder_params["LayerNorm_1"]["scale"] = ( + new_encoder_params["LayerNorm_0"]["scale"] + .at[:] + .set(ckpt["voxnet/conv2/batch_normalization/gamma:0"]) + ) agent = agent.replace(state=agent.state.replace(params=new_params)) return agent @@ -180,11 +198,16 @@ def get_size(params): return sum(x.size for x in jax.tree.leaves(params)) total_param_count = get_size(agent.state.params) - actor, critic = agent.state.params["modules_actor"], agent.state.params["modules_critic"] + actor, critic = ( + agent.state.params["modules_actor"], + agent.state.params["modules_critic"], + ) # calculate encoder params try: - pretrained_encoder_count = get_size(actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"]) + pretrained_encoder_count = get_size( + actor["encoder"][f"encoder_{image_keys[0]}"]["pretrained_encoder"] + ) except Exception as e: pretrained_encoder_count = 0 @@ -198,11 +221,17 @@ def get_size(params): print(f"\ntotal params: {total_param_count / 1e6:.3f}M") print( - f"encoder params: {(encoder_count - pretrained_encoder_count) / 1e6:.3f}M pretrained encoder params: {pretrained_encoder_count / 1e6:.3f}M") - print(f"actor params: {(actor_count - encoder_count) / 1e6:.3f}M critic_params: {critic_count / 1e6:.3f}M") - print(f"total parameters to train: {(total_param_count - pretrained_encoder_count) / 1e6:.3f}M\n") + f"encoder params: {(encoder_count - pretrained_encoder_count) / 1e6:.3f}M pretrained encoder params: {pretrained_encoder_count / 1e6:.3f}M" + ) + print( + f"actor params: {(actor_count - encoder_count) / 1e6:.3f}M critic_params: {critic_count / 1e6:.3f}M" + ) + print( + f"total parameters to train: {(total_param_count - pretrained_encoder_count) / 1e6:.3f}M\n" + ) def parameter_overview(agent): from clu import parameter_overview - print(parameter_overview.get_parameter_overview(agent.state.params)) \ No newline at end of file + + print(parameter_overview.get_parameter_overview(agent.state.params)) diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index e308a41f..d0a760d2 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -115,7 +115,7 @@ def _gaussian_blur_single_image(image, kernel_size, padding, sigma): def _random_gaussian_blur( - image, rng, *, kernel_size, padding, sigma_min, sigma_max, apply_prob + image, rng, *, kernel_size, padding, sigma_min, sigma_max, apply_prob ): """Applies a random gaussian blur.""" apply_rng, transform_rng = jax.random.split(rng) @@ -180,22 +180,22 @@ def hsv_to_rgb(h, s, v): x = c * (1 - jnp.abs(fmodu - 1)) hcat = jnp.floor(dh).astype(jnp.int32) rr = ( - jnp.where( - (hcat == 0) | (hcat == 5), c, jnp.where((hcat == 1) | (hcat == 4), x, 0) - ) - + m + jnp.where( + (hcat == 0) | (hcat == 5), c, jnp.where((hcat == 1) | (hcat == 4), x, 0) + ) + + m ) gg = ( - jnp.where( - (hcat == 1) | (hcat == 2), c, jnp.where((hcat == 0) | (hcat == 3), x, 0) - ) - + m + jnp.where( + (hcat == 1) | (hcat == 2), c, jnp.where((hcat == 0) | (hcat == 3), x, 0) + ) + + m ) bb = ( - jnp.where( - (hcat == 3) | (hcat == 4), c, jnp.where((hcat == 2) | (hcat == 5), x, 0) - ) - + m + jnp.where( + (hcat == 3) | (hcat == 4), c, jnp.where((hcat == 2) | (hcat == 5), x, 0) + ) + + m ) return rr, gg, bb @@ -256,17 +256,17 @@ def _to_grayscale(image): def color_transform( - image, - rng, - *, - brightness, - contrast, - saturation, - hue, - to_grayscale_prob, - color_jitter_prob, - apply_prob, - shuffle + image, + rng, + *, + brightness, + contrast, + saturation, + hue, + to_grayscale_prob, + color_jitter_prob, + apply_prob, + shuffle ): """Applies color jittering to a single image.""" apply_rng, transform_rng = jax.random.split(rng) @@ -338,7 +338,7 @@ def random_flip(image, rng): def gaussian_blur( - image, rng, *, blur_divider=10.0, sigma_min=0.1, sigma_max=2.0, apply_prob=1.0 + image, rng, *, blur_divider=10.0, sigma_min=0.1, sigma_max=2.0, apply_prob=1.0 ): """Applies gaussian blur to a batch of images. Args: diff --git a/serl_launcher/serl_launcher/vision/mobilenet.py b/serl_launcher/serl_launcher/vision/mobilenet.py index b9b54e83..33d5ab02 100644 --- a/serl_launcher/serl_launcher/vision/mobilenet.py +++ b/serl_launcher/serl_launcher/vision/mobilenet.py @@ -38,11 +38,6 @@ def __call__(self, x: jnp.ndarray, train=False) -> jnp.ndarray: # normalize inputs using imagenet mean and std mean = jnp.array((0.485, 0.456, 0.406))[None, ...] std = jnp.array((0.229, 0.224, 0.225))[None, ...] - - # normalization constants calculated from the demo trajectories ...demos_mai3_streamlined.pkl - # mean = jnp.array((0.68992649, 0.66665285, 0.57000176))[None, ...] - # std = jnp.array((0.35203312, 0.29289631, 0.29029032))[None, ...] - x = x.astype(jnp.float32) / 255.0 x = (x - mean) / std diff --git a/serl_launcher/serl_launcher/vision/pointcloud_encoders.py b/serl_launcher/serl_launcher/vision/pointcloud_encoders.py deleted file mode 100644 index f8a8ad17..00000000 --- a/serl_launcher/serl_launcher/vision/pointcloud_encoders.py +++ /dev/null @@ -1,88 +0,0 @@ -from functools import partial -from typing import Any, Callable, Optional, Sequence, Tuple - -import flax.linen as nn -import jax.numpy as jnp -import jax.lax as lax - -import jax - - -class PointNetBasic(nn.Module): - """ Basic PointNet, input is BxNx3, output Bx40 """ - @nn.compact - def __call__( - self, - observations: jnp.ndarray, - train: bool = True, - ): - x = observations - - num_points = observations.shape[-2] - - conv = partial( - nn.Conv, - use_bias=True, - kernel_init=nn.initializers.kaiming_normal(), - bias_init=nn.initializers.zeros_init(), - padding="VALID" - ) - batchnorm = partial( - nn.BatchNorm, - momentum=0.9, - epsilon=1e-5, - use_running_average=not train, - ) - dense = partial( - nn.Dense, - use_bias=True, - kernel_init=nn.initializers.kaiming_normal(), - ) - - x = x[..., None] # expand dims - # shape (B, N, 3, 1) - - x = conv( - features=64, - kernel_size=(1, 3), - strides=(1, 1), - name="conv1" - )(x) - # shape (B, N, 1, 64) - - x = batchnorm( - name="bn1" - )(x) - - # conv2, conv3, conv4, conv5 - for i in range(2, 6): - features = {2: 64, 3: 64, 4: 128, 5: 1024} - x = conv( - features=features[i], - kernel_size=(1, 1), - strides=(1, 1), - name=f"conv{i}" - )(x) - - x = batchnorm( - name=f"bn{i}" - )(x) - - # shape (B, N, 1, 1024) - x = nn.max_pool(x, (num_points, 1)) - - # shape (B, 1, 1, 1024) - x = dense(features=512, name="fc1")(x) - x = nn.relu(x) - - x = dense(features=256, name="fc2")(x) - x = nn.relu(x) - - x = nn.Dropout(rate=0.3, name="dp1", deterministic=not train)(x) - x = nn.relu(x) - - x = dense(features=40, name="fn3")(x) - # TODO original has no activation, for me it would me sense - return x - - diff --git a/serl_launcher/serl_launcher/vision/range_sensor.py b/serl_launcher/serl_launcher/vision/range_sensor.py deleted file mode 100644 index 7e908cce..00000000 --- a/serl_launcher/serl_launcher/vision/range_sensor.py +++ /dev/null @@ -1,38 +0,0 @@ -from typing import Any, Callable, Optional, Sequence, Tuple, Optional - -import flax.linen as nn -import jax.numpy as jnp -import jax - - -class RangeSensorEncoder(nn.Module): - """ - Takes depth-images as input with shape (B, H, W, 1) and returns range values for each keypoint tuple provided. The - values are pooled with 'func_pool' over a size of 'keypoint_size'. The output is scaled to [0., 1.] - """ - keypoints: Tuple[Tuple[int, int], ...] # (x, y) coordinates in depth image - keypoint_size: Tuple[int, int] = (3, 3) - pool_func: Callable = jnp.median - - @nn.compact - def __call__(self, observations: jnp.ndarray, train: bool = False, encode: bool = True): - x = observations / 255. # convert to float and within [0, 1] - - assert x.shape[-1] == 1 - assert self.keypoint_size[0] % 2 == 1 and self.keypoint_size[1] % 2 == 1 - - # add batch dim if missing - if len(x.shape) < 4: - x = x[None] - - points = [] - for i, keypoint in enumerate(self.keypoints): - k_x, k_y = keypoint - s_x, s_y = self.keypoint_size[0] // 2, self.keypoint_size[1] // 2 - points.append(self.pool_func(x[:, k_x - s_x:k_x + s_x + 1, k_y - s_y:k_y + s_y + 1, 0], axis=(1, 2))) - points = jnp.stack(points, axis=-1) - - if points.shape[0] == 1: - points = points[0] - - return points diff --git a/serl_launcher/serl_launcher/vision/resnet_v1.py b/serl_launcher/serl_launcher/vision/resnet_v1.py index d7c8985e..e89a6f42 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1.py @@ -63,7 +63,7 @@ def __call__(self, features): batch_size, num_featuremaps, self.height * self.width ) - softmax_attention = nn.softmax(features / temperature, axis=-1) + softmax_attention = nn.softmax(features / temperature) expected_x = jnp.sum( self.pos_x * softmax_attention, axis=2, keepdims=True ).reshape(batch_size, num_featuremaps) @@ -138,8 +138,8 @@ class ResNetBlock(nn.Module): @nn.compact def __call__( - self, - x, + self, + x, ): residual = x y = self.conv(self.filters, (3, 3), self.strides)(x) @@ -208,17 +208,15 @@ class ResNetEncoder(nn.Module): @nn.compact def __call__( - self, - observations: jnp.ndarray, - train: bool = True, - cond_var=None, - stop_gradient=False, + self, + observations: jnp.ndarray, + train: bool = True, + cond_var=None, + stop_gradient=False, ): # put inputs in [-1, 1] # x = observations.astype(jnp.float32) / 127.5 - 1.0 - assert observations.shape[-3:] == (128, 128, 3) # check for shape - # imagenet mean and std mean = jnp.array([0.485, 0.456, 0.406]) std = jnp.array([0.229, 0.224, 0.225]) @@ -263,7 +261,7 @@ def __call__( for j in range(block_size): stride = (2, 2) if i > 0 and j == 0 else (1, 1) x = self.block_cls( - self.num_filters * 2 ** i, + self.num_filters * 2**i, strides=stride, conv=conv, norm=norm, @@ -271,12 +269,12 @@ def __call__( )(x) if self.use_film: assert ( - cond_var is not None + cond_var is not None ), "Cond var is None, nothing to condition on" x = FilmConditioning()(x, cond_var) if self.use_multiplicative_cond: assert ( - cond_var is not None + cond_var is not None ), "Cond var is None, nothing to condition on" cond_out = nn.Dense( x.shape[-1], kernel_init=nn.initializers.xavier_normal() @@ -328,24 +326,22 @@ class PreTrainedResNetEncoder(nn.Module): pooling_method: str = "avg" softmax_temperature: float = 1.0 num_spatial_blocks: int = 8 - num_kp: int = 64 # for Spatial Softmax + num_kp: Optional[int] = None # for Spatial Softmax bottleneck_dim: Optional[int] = None pretrained_encoder: nn.module = None @nn.compact def __call__( - self, - observations: jnp.ndarray, - encode: bool = True, - train: bool = True, + self, + observations: jnp.ndarray, + encode: bool = True, + train: bool = True, ): x = observations - if encode: x = self.pretrained_encoder(x, train=train) if self.pooling_method == "spatial_learned_embeddings": - # TODO maybe make the same as in spatial softmax height, width, channel = x.shape[-3:] x = SpatialLearnedEmbeddings( height=height, @@ -355,20 +351,20 @@ def __call__( )(x) x = nn.Dropout(0.1, deterministic=not train)(x, rng=self.rng) elif self.pooling_method == "spatial_softmax": - """ - implemented as in https://github.com/huggingface/lerobot/blob/ff8f6aa6cde2957f08547eb081aac12ca4669b6a/lerobot/common/policies/diffusion/modeling_diffusion.py#L316 - In this case it would result in 512 keypoints (corresponding to the 512 input channels). We can optionally - provide num_kp != None to control the number of keypoints. This is achieved by a first applying a learnable - linear mapping (in_channels, H, W) -> (num_kp, H, W). - """ - x = nn.Conv( - features=self.num_kp, - kernel_size=1, - use_bias=False, - dtype=jnp.float32, - kernel_init=nn.initializers.kaiming_normal(), - name="spatial_softmax_conv", - )(x) + if self.num_kp is not None: + """ + implemented as in https://github.com/huggingface/lerobot/blob/ff8f6aa6cde2957f08547eb081aac12ca4669b6a/lerobot/common/policies/diffusion/modeling_diffusion.py#L316 + In this case it would result in 512 keypoints (corresponding to the 512 input channels). We can optionally + provide num_kp != None to control the number of keypoints. + """ + x = nn.Conv( + features=self.num_kp, + kernel_size=1, + use_bias=False, + dtype=jnp.float32, + kernel_init=nn.initializers.kaiming_normal(), + name="spatial_softmax_conv", + )(x) height, width, channel = x.shape[-3:] pos_x, pos_y = jnp.meshgrid( jnp.linspace(-1.0, 1.0, height), jnp.linspace(-1.0, 1.0, width) diff --git a/serl_launcher/serl_launcher/vision/resnet_v1_18.py b/serl_launcher/serl_launcher/vision/resnet_v1_18.py index 1c867ca3..cc8bbe0d 100644 --- a/serl_launcher/serl_launcher/vision/resnet_v1_18.py +++ b/serl_launcher/serl_launcher/vision/resnet_v1_18.py @@ -2,7 +2,7 @@ import jax.numpy as jnp import flax.linen as nn import functools -from typing import (Any, Callable, Iterable, Optional, Tuple, Union) +from typing import Any, Callable, Iterable, Optional, Tuple, Union import h5py import warnings @@ -21,22 +21,26 @@ # ---------------------------------------------------------------# # Normalization # ---------------------------------------------------------------# -def batch_norm(x, train, epsilon=1e-05, momentum=0.99, params=None, dtype='float32'): +def batch_norm(x, train, epsilon=1e-05, momentum=0.99, params=None, dtype="float32"): # we do not use running average in the implementation (set to False) if params is None: - x = BatchNorm(epsilon=epsilon, - momentum=momentum, - use_running_average=False, # was not train - dtype=dtype)(x) + x = BatchNorm( + epsilon=epsilon, + momentum=momentum, + use_running_average=False, # was not train + dtype=dtype, + )(x) else: - x = BatchNorm(epsilon=epsilon, - momentum=momentum, - bias_init=lambda *_: jnp.array(params['bias']), - scale_init=lambda *_: jnp.array(params['scale']), - mean_init=lambda *_: jnp.array(params['mean']), - var_init=lambda *_: jnp.array(params['var']), - use_running_average=False, # was not train - dtype=dtype)(x) + x = BatchNorm( + epsilon=epsilon, + momentum=momentum, + bias_init=lambda *_: jnp.array(params["bias"]), + scale_init=lambda *_: jnp.array(params["scale"]), + mean_init=lambda *_: jnp.array(params["mean"]), + var_init=lambda *_: jnp.array(params["var"]), + use_running_average=False, # was not train + dtype=dtype, + )(x) return x @@ -70,6 +74,7 @@ class BatchNorm(nn.Module): the examples on the first two and last two devices. See `jax.lax.psum` for more details. """ + use_running_average: Optional[bool] = None axis: int = -1 momentum: float = 0.99 @@ -102,7 +107,8 @@ def __call__(self, x, use_running_average: Optional[bool] = None): Normalized inputs (the same shape as inputs). """ use_running_average = merge_param( - 'use_running_average', self.use_running_average, use_running_average) + "use_running_average", self.use_running_average, use_running_average + ) x = jnp.asarray(x, jnp.float32) axis = self.axis if isinstance(self.axis, tuple) else (self.axis,) axis = _absolute_dims(x.ndim, axis) @@ -111,15 +117,15 @@ def __call__(self, x, use_running_average: Optional[bool] = None): reduction_axis = tuple(i for i in range(x.ndim) if i not in axis) # see NOTE above on initialization behavior - initializing = self.is_mutable_collection('params') + initializing = self.is_mutable_collection("params") if use_running_average: - ra_mean = self.variable('batch_stats', 'mean', - self.mean_init, - reduced_feature_shape) - ra_var = self.variable('batch_stats', 'var', - self.var_init, - reduced_feature_shape) + ra_mean = self.variable( + "batch_stats", "mean", self.mean_init, reduced_feature_shape + ) + ra_var = self.variable( + "batch_stats", "var", self.var_init, reduced_feature_shape + ) mean, var = ra_mean.value, ra_var.value else: mean = jnp.mean(x, axis=reduction_axis, keepdims=False) @@ -130,26 +136,29 @@ def __call__(self, x, use_running_average: Optional[bool] = None): lax.pmean( concatenated_mean, axis_name=self.axis_name, - axis_index_groups=self.axis_index_groups), 2) + axis_index_groups=self.axis_index_groups, + ), + 2, + ) var = mean2 - lax.square(mean) y = x - mean.reshape(feature_shape) mul = lax.rsqrt(var + self.epsilon) if self.use_scale: - scale = self.param('scale', - self.scale_init, - reduced_feature_shape).reshape(feature_shape) + scale = self.param("scale", self.scale_init, reduced_feature_shape).reshape( + feature_shape + ) mul = mul * scale y = y * mul if self.use_bias: - bias = self.param('bias', - self.bias_init, - reduced_feature_shape).reshape(feature_shape) + bias = self.param("bias", self.bias_init, reduced_feature_shape).reshape( + feature_shape + ) y = y + bias return jnp.asarray(y, self.dtype) -LAYERS = {'resnet18': [2, 2, 2, 2]} +LAYERS = {"resnet18": [2, 2, 2, 2]} class BasicBlock(nn.Module): @@ -168,6 +177,7 @@ class BasicBlock(nn.Module): block_name (str): Name of block. dtype (str): Data type. """ + features: int kernel_size: Union[int, Iterable[int]] = (3, 3) downsample: bool = False @@ -176,7 +186,7 @@ class BasicBlock(nn.Module): kernel_init: functools.partial = nn.initializers.lecun_normal() bias_init: functools.partial = nn.initializers.zeros block_name: str = None - dtype: str = 'float32' + dtype: str = "float32" @nn.compact def __call__(self, x, act, train=True): @@ -193,54 +203,73 @@ def __call__(self, x, act, train=True): """ residual = x - x = nn.Conv(features=self.features, - kernel_size=self.kernel_size, - strides=(2, 2) if self.downsample else (1, 1), - padding=((1, 1), (1, 1)), - kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['conv1']['weight']), - use_bias=False, - dtype=self.dtype)(x) - - x = batch_norm(x, - train=train, - epsilon=1e-05, - momentum=0.1, - params=None if self.param_dict is None else self.param_dict['bn1'], - dtype=self.dtype) + x = nn.Conv( + features=self.features, + kernel_size=self.kernel_size, + strides=(2, 2) if self.downsample else (1, 1), + padding=((1, 1), (1, 1)), + kernel_init=self.kernel_init + if self.param_dict is None + else lambda *_: jnp.array(self.param_dict["conv1"]["weight"]), + use_bias=False, + dtype=self.dtype, + )(x) + + x = batch_norm( + x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict["bn1"], + dtype=self.dtype, + ) x = nn.relu(x) - x = nn.Conv(features=self.features, - kernel_size=self.kernel_size, - strides=(1, 1), - padding=((1, 1), (1, 1)), - kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['conv2']['weight']), - use_bias=False, - dtype=self.dtype)(x) - - x = batch_norm(x, - train=train, - epsilon=1e-05, - momentum=0.1, - params=None if self.param_dict is None else self.param_dict['bn2'], - dtype=self.dtype) + x = nn.Conv( + features=self.features, + kernel_size=self.kernel_size, + strides=(1, 1), + padding=((1, 1), (1, 1)), + kernel_init=self.kernel_init + if self.param_dict is None + else lambda *_: jnp.array(self.param_dict["conv2"]["weight"]), + use_bias=False, + dtype=self.dtype, + )(x) + + x = batch_norm( + x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict["bn2"], + dtype=self.dtype, + ) if self.downsample: - residual = nn.Conv(features=self.features, - kernel_size=(1, 1), - strides=(2, 2), - kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['downsample']['conv']['weight']), - use_bias=False, - dtype=self.dtype)(residual) - - residual = batch_norm(residual, - train=train, - epsilon=1e-05, - momentum=0.1, - params=None if self.param_dict is None else self.param_dict['downsample']['bn'], - dtype=self.dtype) + residual = nn.Conv( + features=self.features, + kernel_size=(1, 1), + strides=(2, 2), + kernel_init=self.kernel_init + if self.param_dict is None + else lambda *_: jnp.array( + self.param_dict["downsample"]["conv"]["weight"] + ), + use_bias=False, + dtype=self.dtype, + )(residual) + + residual = batch_norm( + residual, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None + if self.param_dict is None + else self.param_dict["downsample"]["bn"], + dtype=self.dtype, + ) x += residual x = nn.relu(x) @@ -283,23 +312,24 @@ class ResNet(nn.Module): If this argument is None, the weights will be saved to a temp directory. dtype (str): Data type. """ - output: str = 'softmax' - pretrained: str = 'imagenet' + + output: str = "softmax" + pretrained: str = "imagenet" normalize: bool = True - architecture: str = 'resnet18' + architecture: str = "resnet18" num_classes: int = 1000 block: nn.Module = BasicBlock kernel_init: functools.partial = nn.initializers.lecun_normal() bias_init: functools.partial = nn.initializers.zeros ckpt_dir: str = None - dtype: str = 'float32' + dtype: str = "float32" pre_pooling: bool = True # skip pooling def setup(self): # self.param_dict = None - if self.pretrained == 'imagenet': + if self.pretrained == "imagenet": # ckpt_file = utils.download(self.ckpt_dir, URLS[self.architecture]) - self.param_dict = h5py.File(self.ckpt_dir, 'r') + self.param_dict = h5py.File(self.ckpt_dir, "r") # print(f"loaded pretrained weights from {self.ckpt_dir}") @nn.compact @@ -320,77 +350,110 @@ def __call__(self, observations, train=False): std = jnp.array([0.229, 0.224, 0.225]).reshape(1, 1, 1, -1) x = (observations.astype(jnp.float32) / 255.0 - mean) / std - if self.pretrained == 'imagenet': + if self.pretrained == "imagenet": if self.num_classes != 1000: - warnings.warn(f'The user specified parameter \'num_classes\' was set to {self.num_classes} ' - 'but will be overwritten with 1000 to match the specified pretrained checkpoint \'imagenet\', if ', - UserWarning) + warnings.warn( + f"The user specified parameter 'num_classes' was set to {self.num_classes} " + "but will be overwritten with 1000 to match the specified pretrained checkpoint 'imagenet', if ", + UserWarning, + ) num_classes = 1000 else: num_classes = self.num_classes act = {} - x = nn.Conv(features=64, - kernel_size=(7, 7), - kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['conv1']['weight']), - strides=(2, 2), - padding=((3, 3), (3, 3)), - use_bias=False, - dtype=self.dtype)(x) - act['conv1'] = x - - x = batch_norm(x, - train=train, - epsilon=1e-05, - momentum=0.1, - params=None if self.param_dict is None else self.param_dict['bn1'], - dtype=self.dtype) + x = nn.Conv( + features=64, + kernel_size=(7, 7), + kernel_init=self.kernel_init + if self.param_dict is None + else lambda *_: jnp.array(self.param_dict["conv1"]["weight"]), + strides=(2, 2), + padding=((3, 3), (3, 3)), + use_bias=False, + dtype=self.dtype, + )(x) + act["conv1"] = x + + x = batch_norm( + x, + train=train, + epsilon=1e-05, + momentum=0.1, + params=None if self.param_dict is None else self.param_dict["bn1"], + dtype=self.dtype, + ) x = nn.relu(x) - x = nn.max_pool(x, window_shape=(3, 3), strides=(2, 2), padding=((1, 1), (1, 1))) + x = nn.max_pool( + x, window_shape=(3, 3), strides=(2, 2), padding=((1, 1), (1, 1)) + ) # Layer 1 - down = self.block.__name__ == 'Bottleneck' + down = self.block.__name__ == "Bottleneck" for i in range(LAYERS[self.architecture][0]): - params = None if self.param_dict is None else self.param_dict['layer1'][f'block{i}'] - x = self.block(features=64, - kernel_size=(3, 3), - downsample=i == 0 and down, - stride=i != 0, - param_dict=params, - block_name=f'block1_{i}', - dtype=self.dtype)(x, act, train) + params = ( + None + if self.param_dict is None + else self.param_dict["layer1"][f"block{i}"] + ) + x = self.block( + features=64, + kernel_size=(3, 3), + downsample=i == 0 and down, + stride=i != 0, + param_dict=params, + block_name=f"block1_{i}", + dtype=self.dtype, + )(x, act, train) # Layer 2 for i in range(LAYERS[self.architecture][1]): - params = None if self.param_dict is None else self.param_dict['layer2'][f'block{i}'] - x = self.block(features=128, - kernel_size=(3, 3), - downsample=i == 0, - param_dict=params, - block_name=f'block2_{i}', - dtype=self.dtype)(x, act, train) + params = ( + None + if self.param_dict is None + else self.param_dict["layer2"][f"block{i}"] + ) + x = self.block( + features=128, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f"block2_{i}", + dtype=self.dtype, + )(x, act, train) # Layer 3 for i in range(LAYERS[self.architecture][2]): - params = None if self.param_dict is None else self.param_dict['layer3'][f'block{i}'] - x = self.block(features=256, - kernel_size=(3, 3), - downsample=i == 0, - param_dict=params, - block_name=f'block3_{i}', - dtype=self.dtype)(x, act, train) + params = ( + None + if self.param_dict is None + else self.param_dict["layer3"][f"block{i}"] + ) + x = self.block( + features=256, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f"block3_{i}", + dtype=self.dtype, + )(x, act, train) # Layer 4 for i in range(LAYERS[self.architecture][3]): - params = None if self.param_dict is None else self.param_dict['layer4'][f'block{i}'] - x = self.block(features=512, - kernel_size=(3, 3), - downsample=i == 0, - param_dict=params, - block_name=f'block4_{i}', - dtype=self.dtype)(x, act, train) + params = ( + None + if self.param_dict is None + else self.param_dict["layer4"][f"block{i}"] + ) + x = self.block( + features=512, + kernel_size=(3, 3), + downsample=i == 0, + param_dict=params, + block_name=f"block4_{i}", + dtype=self.dtype, + )(x, act, train) # if we want the pre_pooling output, return here if self.pre_pooling: @@ -398,27 +461,32 @@ def __call__(self, observations, train=False): # Classifier x = jnp.mean(x, axis=(1, 2)) - x = nn.Dense(features=num_classes, - kernel_init=self.kernel_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['fc']['weight']), - bias_init=self.bias_init if self.param_dict is None else lambda *_: jnp.array( - self.param_dict['fc']['bias']), - dtype=self.dtype)(x) - act['fc'] = x - - if self.output == 'softmax': + x = nn.Dense( + features=num_classes, + kernel_init=self.kernel_init + if self.param_dict is None + else lambda *_: jnp.array(self.param_dict["fc"]["weight"]), + bias_init=self.bias_init + if self.param_dict is None + else lambda *_: jnp.array(self.param_dict["fc"]["bias"]), + dtype=self.dtype, + )(x) + act["fc"] = x + + if self.output == "softmax": return nn.softmax(x) - if self.output == 'log_softmax': + if self.output == "log_softmax": return nn.log_softmax(x) - if self.output == 'activations': + if self.output == "activations": return act return x resnetv1_18_configs = { "resnetv1-18-frozen": functools.partial( - ResNet, architecture='resnet18', - ckpt_dir="/examples/box_picking_drq/resnet18_weights.h5", # download from #TODO - pre_pooling=True + ResNet, + architecture="resnet18", + ckpt_dir="/examples/box_picking_drq/resnet18_weights.h5", # download from #TODO + pre_pooling=True, ) } diff --git a/serl_launcher/serl_launcher/vision/small_encoders.py b/serl_launcher/serl_launcher/vision/small_encoders.py index b120d451..d0e37969 100644 --- a/serl_launcher/serl_launcher/vision/small_encoders.py +++ b/serl_launcher/serl_launcher/vision/small_encoders.py @@ -7,7 +7,7 @@ class SmallEncoder(nn.Module): - features: Sequence[int] = (32, 32, 32) + features: Sequence[int] = (16, 16, 16) kernel_sizes: Sequence[int] = (3, 3, 3) strides: Sequence[int] = (1, 1, 1) padding: Union[Sequence[int], str] = (1, 1, 1) @@ -17,7 +17,9 @@ class SmallEncoder(nn.Module): num_kp: Optional[int] = 32 @nn.compact - def __call__(self, observations: jnp.ndarray, train=False, encode=True) -> jnp.ndarray: + def __call__( + self, observations: jnp.ndarray, train=False, encode=True + ) -> jnp.ndarray: assert len(self.features) == len(self.strides) x = observations.astype(jnp.float32) / 255.0 @@ -45,13 +47,12 @@ def __call__(self, observations: jnp.ndarray, train=False, encode=True) -> jnp.n raise ValueError( "spatial_block_size must be set when using spatial_learned_embeddings" ) - x = nn.Conv( # 512 to num_kp features (less complexity) + x = nn.Conv( # 512 to num_kp features (less complexity) features=self.num_kp, kernel_size=1, use_bias=False, dtype=jnp.float32, kernel_init=nn.initializers.kaiming_normal(), - name="SLE_1xconv", )(x) x = SpatialLearnedEmbeddings(*(x.shape[-3:]), self.spatial_block_size)(x) x = nn.Dropout(0.1, deterministic=not train)(x) diff --git a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py index dc8b8e2f..45fabc33 100644 --- a/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py +++ b/serl_launcher/serl_launcher/vision/voxel_grid_encoders.py @@ -13,18 +13,19 @@ class SpatialSoftArgmax3D(nn.Module): 3D Implementation of Spatial Soft Argmax why arg-max and not max: see https://github.com/tensorflow/tensorflow/issues/6271#issuecomment-266893850 """ + x_len: int y_len: int z_len: int channel: int - temperature: float = 1. + temperature: float = 1.0 def setup(self): pos_x, pos_y, pos_z = jnp.meshgrid( jnp.linspace(-1.0, 1.0, self.x_len), jnp.linspace(-1.0, 1.0, self.y_len), jnp.linspace(-1.0, 1.0, self.z_len), - indexing='ij' + indexing="ij", ) self.pos_x = pos_x.reshape(-1) # shape (x*y*z) self.pos_y = pos_y.reshape(-1) @@ -65,24 +66,31 @@ class VoxNet(nn.Module): bottleneck_dim: Optional[int] = None final_activation: Callable[[jnp.ndarray], jnp.ndarray] | str = nn.tanh pretrained: bool = False - scale_factor: float = 1. + scale_factor: float = 1.0 @nn.compact def __call__( - self, - observations: jnp.ndarray, - encode: bool = True, - train: bool = True, + self, + observations: jnp.ndarray, + encode: bool = True, + train: bool = True, ): # observations has shape (B, X, Y, Z) no_batch_dim = len(observations.shape) < 4 if no_batch_dim: observations = observations[None] - observations = observations.astype(jnp.float32)[..., None] / self.scale_factor # add conv channel + observations = ( + observations.astype(jnp.float32)[..., None] / self.scale_factor + ) # add conv channel - conv3d = partial(nn.Conv, kernel_init=nn.initializers.xavier_normal(), use_bias=self.use_conv_bias, - padding="valid", bias_init=nn.zeros_init()) + conv3d = partial( + nn.Conv, + kernel_init=nn.initializers.xavier_normal(), + use_bias=self.use_conv_bias, + padding="valid", + bias_init=nn.zeros_init(), + ) l_relu = partial(nn.leaky_relu, negative_slope=0.1) max_pool = partial(nn.max_pool, window_shape=(2, 2, 2), strides=(2, 2, 2)) @@ -105,21 +113,25 @@ def __call__( features=feature_dimensions[1], kernel_size=(3, 3, 3), strides=(1, 1, 1), - name="conv_3x3x3" + name="conv_3x3x3", )(x) x = max_pool(x) if self.pretrained: - x = jax.lax.stop_gradient(x) # unfortunately also cuts gradients of the LayerNorm above + x = jax.lax.stop_gradient( + x + ) # unfortunately also cuts gradients of the LayerNorm above x = nn.LayerNorm()(x) x = l_relu(x) x = conv3d( - features=feature_dimensions[2], # if pretrained, uses [..] out of 128 pretrained params as initial weights + features=feature_dimensions[ + 2 + ], # if pretrained, uses [..] out of 128 pretrained params as initial weights kernel_size=(2, 2, 2), strides=(2, 2, 2), - name="conv_2x2x2" + name="conv_2x2x2", )(x) x = nn.LayerNorm()(x) x = l_relu(x) diff --git a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py index f40c52de..90c4836a 100644 --- a/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py +++ b/serl_launcher/serl_launcher/wrappers/observation_statistics_wrapper.py @@ -1,6 +1,6 @@ import numpy as np from collections import deque -import gymnasium as gym +import gym class ObservationStatisticsWrapper(gym.Wrapper, gym.utils.RecordConstructorArgs): @@ -19,7 +19,9 @@ def __init__(self, env: gym.Env, deque_size: int = 100): # make buffer for name, space in self.env.observation_space["state"].items(): - self.buffer[name] = np.zeros(shape=(self.max_episode_length, space.shape[0])) + self.buffer[name] = np.zeros( + shape=(self.max_episode_length, space.shape[0]) + ) # may not be used self.num_envs = getattr(env, "num_envs", 1) @@ -51,16 +53,24 @@ def step(self, action): num_dones = np.sum(dones) if num_dones: calc_buffs = {} - calc_buffs.update({ - name + "_mean": np.mean(obs[:self.curr_path_length], axis=0) for name, obs in self.buffer.items() - }) - calc_buffs.update({ - name + "_std": np.std(obs[:self.curr_path_length], axis=0) for name, obs in self.buffer.items() - }) + calc_buffs.update( + { + name + "_mean": np.mean(obs[: self.curr_path_length], axis=0) + for name, obs in self.buffer.items() + } + ) + calc_buffs.update( + { + name + "_std": np.std(obs[: self.curr_path_length], axis=0) + for name, obs in self.buffer.items() + } + ) buff = {} for name, value in calc_buffs.items(): for i in range(value.shape[0]): - buff[name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz', 'grip'][i]}"] = value[i] + buff[ + name + f"_{['x', 'y', 'z', 'rx', 'ry', 'rz', 'grip'][i]}" + ] = value[i] infos["obsStat"] = buff # print(buff) diff --git a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py index ac9cadaf..4bfbb721 100644 --- a/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py +++ b/serl_launcher/serl_launcher/wrappers/serl_obs_wrappers.py @@ -31,13 +31,14 @@ class ScaleObservationWrapper(gym.ObservationWrapper): (to somewhat normalize the observations space) """ - def __init__(self, - env, - translation_scale=100., - rotation_scale=10., - force_scale=1., - torque_scale=10. - ): + def __init__( + self, + env, + translation_scale=100.0, + rotation_scale=10.0, + force_scale=1.0, + torque_scale=10.0, + ): super().__init__(env) self.translation_scale = translation_scale self.rotation_scale = rotation_scale @@ -49,7 +50,7 @@ def scale_wrapper_get_scales(self): translation_scale=self.translation_scale, rotation_scale=self.rotation_scale, force_scale=self.force_scale, - torque_scale=self.torque_scale + torque_scale=self.torque_scale, ) def observation(self, obs): diff --git a/serl_robot_infra/franka_env/camera/rs_capture.py b/serl_robot_infra/franka_env/camera/rs_capture.py index 8d3ee534..249135f8 100644 --- a/serl_robot_infra/franka_env/camera/rs_capture.py +++ b/serl_robot_infra/franka_env/camera/rs_capture.py @@ -9,14 +9,12 @@ def get_device_serial_numbers(self): def __init__(self, name, serial_number, dim=(640, 480), fps=15, depth=False): self.name = name - print(self.get_device_serial_numbers()) assert serial_number in self.get_device_serial_numbers() self.serial_number = serial_number self.depth = depth self.pipe = rs.pipeline() self.cfg = rs.config() self.cfg.enable_device(self.serial_number) - self.cfg.enable_stream(rs.stream.color, dim[0], dim[1], rs.format.bgr8, fps) if self.depth: self.cfg.enable_stream(rs.stream.depth, dim[0], dim[1], rs.format.z16, fps) diff --git a/serl_robot_infra/robot_controllers/ur5_controller.py b/serl_robot_infra/robot_controllers/ur5_controller.py index 9b00075f..b0f04a7d 100644 --- a/serl_robot_infra/robot_controllers/ur5_controller.py +++ b/serl_robot_infra/robot_controllers/ur5_controller.py @@ -18,21 +18,23 @@ def pos_difference(quat_pose_1: np.ndarray, quat_pose_2: np.ndarray): assert quat_pose_2.shape == (7,) p_diff = np.sum(np.abs(quat_pose_1[:3] - quat_pose_2[:3])) - r_diff = (R.from_quat(quat_pose_1[3:]) * R.from_quat(quat_pose_2[3:]).inv()).magnitude() + r_diff = ( + R.from_quat(quat_pose_1[3:]) * R.from_quat(quat_pose_2[3:]).inv() + ).magnitude() return p_diff + r_diff class UrImpedanceController(threading.Thread): def __init__( - self, - robot_ip, - frequency=100, - kp=10000, - kd=2200, - config=None, - verbose=False, - *args, - **kwargs + self, + robot_ip, + frequency=100, + kp=10000, + kd=2200, + config=None, + verbose=False, + *args, + **kwargs, ): super(UrImpedanceController, self).__init__(*args, **kwargs) self._stop = threading.Event() @@ -45,10 +47,15 @@ def __init__( self.frequency = frequency self.kp = kp self.kd = kd - self.gripper_timeout = {"timeout": config.GRIPPER_TIMEOUT, "last_grip": time.monotonic() - 1e6} + self.gripper_timeout = { + "timeout": config.GRIPPER_TIMEOUT, + "last_grip": time.monotonic() - 1e6, + } self.verbose = verbose - self.target_pos = np.zeros((7,), dtype=np.float32) # new as quat to avoid +- problems with axis angle repr. + self.target_pos = np.zeros( + (7,), dtype=np.float32 + ) # new as quat to avoid +- problems with axis angle repr. self.target_grip = np.zeros((1,), dtype=np.float32) self.curr_pos = np.zeros((7,), dtype=np.float32) self.curr_vel = np.zeros((6,), dtype=np.float32) @@ -58,7 +65,10 @@ def __init__( self.curr_force_lowpass = np.zeros((6,), dtype=np.float32) # force of tool tip self.curr_force = np.zeros((6,), dtype=np.float32) - self.reset_Q = np.array([np.pi / 2., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.], dtype=np.float32) # reset state in Joint Space + self.reset_Q = np.array( + [np.pi / 2.0, -np.pi / 2.0, np.pi / 2.0, -np.pi / 2.0, -np.pi / 2.0, 0.0], + dtype=np.float32, + ) # reset state in Joint Space self.reset_Pose = np.zeros_like(self.reset_Q) self.reset_height = np.array([0.1], dtype=np.float32) # TODO make customizable @@ -79,9 +89,9 @@ def __init__( self.noerr = 0 # log to file (reset every new run) - with open("/tmp/console2.txt", 'w') as f: + with open("/tmp/console2.txt", "w") as f: f.write("reset\n") - self.second_console = open("/tmp/console2.txt", 'a') + self.second_console = open("/tmp/console2.txt", "a") def start(self): super().start() @@ -89,7 +99,7 @@ def start(self): print(f"[RIC] Controller process spawned at {self.native_id}") def print(self, msg, both=False): - self.second_console.write(f'{datetime.datetime.now()} --> {msg}\n') + self.second_console.write(f"{datetime.datetime.now()} --> {msg}\n") if both: print(msg) @@ -179,12 +189,14 @@ async def _update_robot_state(self): obj_status = await self.robotiq_gripper.get_object_status() # 3-> no object detected, 0-> sucking empty, [1, 2] obj detected - grip_status = [-1., 1., 1., 0.][obj_status.value] + grip_status = [-1.0, 1.0, 1.0, 0.0][obj_status.value] - pressure = pressure if pressure < 99 else 0 # 100 no obj, 99 sucking empty, so they are ignored + pressure = ( + pressure if pressure < 99 else 0 + ) # 100 no obj, 99 sucking empty, so they are ignored # grip status, 0->neutral, -1->bad (sucking but no obj), 1-> good (sucking and obj) - grip_status = 1. if pressure > 0 else grip_status - pressure /= 98. # pressure between [0, 1] + grip_status = 1.0 if pressure > 0 else grip_status + pressure /= 98.0 # pressure between [0, 1] with self.lock: self.curr_pos[:] = pose2quat(pos) self.curr_vel[:] = vel @@ -192,7 +204,9 @@ async def _update_robot_state(self): self.curr_Qd[:] = Qd self.curr_force[:] = np.array(force) # use moving average (5), since the force fluctuates heavily - self.curr_force_lowpass[:] = 0.1 * np.array(force) + 0.9 * self.curr_force_lowpass[:] + self.curr_force_lowpass[:] = ( + 0.1 * np.array(force) + 0.9 * self.curr_force_lowpass[:] + ) self.gripper_state[:] = [pressure, grip_status] def get_state(self): @@ -204,7 +218,7 @@ def get_state(self): "Qd": self.curr_Qd, "force": self.curr_force_lowpass[:3], "torque": self.curr_force_lowpass[3:], - "gripper": self.gripper_state + "gripper": self.gripper_state, } return state @@ -222,19 +236,26 @@ def _calculate_force(self): # calc position for kp, kd = self.kp, self.kd - diff_p = np.clip(target_pos[:3] - curr_pos[:3], a_min=-self.delta, a_max=self.delta) + diff_p = np.clip( + target_pos[:3] - curr_pos[:3], a_min=-self.delta, a_max=self.delta + ) vel_delta = 2 * self.delta * self.frequency - diff_d = np.clip(- curr_vel[:3], a_min=-vel_delta, a_max=vel_delta) + diff_d = np.clip(-curr_vel[:3], a_min=-vel_delta, a_max=vel_delta) force_pos = kp * diff_p + kd * diff_d # calc torque rot_diff = R.from_quat(target_pos[3:]) * R.from_quat(curr_pos[3:]).inv() vel_rot_diff = R.from_rotvec(curr_vel[3:]).inv() - torque = rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 # TODO make customizable + torque = ( + rot_diff.as_rotvec() * 100 + vel_rot_diff.as_rotvec() * 22 + ) # TODO make customizable # check for big downward tcp force and adapt accordingly - if self.curr_force[2] > 3.5 and force_pos[2] < 0.: - force_pos[2] = max((1.5 - self.curr_force_lowpass[2]), 0.) * force_pos[2] + min(self.curr_force_lowpass[2] - 0.5, 1.) * 20. + if self.curr_force[2] > 3.5 and force_pos[2] < 0.0: + force_pos[2] = ( + max((1.5 - self.curr_force_lowpass[2]), 0.0) * force_pos[2] + + min(self.curr_force_lowpass[2] - 0.5, 1.0) * 20.0 + ) return np.concatenate((force_pos, torque)) @@ -244,10 +265,15 @@ async def send_gripper_command(self, force_release=False): self.target_grip[0] = 0.0 return - timeout_exceeded = (time.monotonic() - self.gripper_timeout["last_grip"]) * 1000 > self.gripper_timeout[ - "timeout"] + timeout_exceeded = ( + time.monotonic() - self.gripper_timeout["last_grip"] + ) * 1000 > self.gripper_timeout["timeout"] # target grip above threshold and timeout exceeded and not gripping something already - if self.target_grip[0] > 0.5 and timeout_exceeded and self.gripper_state[1] < 0.5: + if ( + self.target_grip[0] > 0.5 + and timeout_exceeded + and self.gripper_state[1] < 0.5 + ): await self.robotiq_gripper.automatic_grip() self.target_grip[0] = 0.0 self.gripper_timeout["last_grip"] = time.monotonic() @@ -260,7 +286,7 @@ async def send_gripper_command(self, force_release=False): # print("release") def _truncate_check(self): - downward_force = self.curr_force_lowpass[2] > 20. + downward_force = self.curr_force_lowpass[2] > 20.0 if downward_force: # TODO add better criteria self._is_truncated.set() else: @@ -271,7 +297,9 @@ def is_truncated(self): def run(self): try: - asyncio.run(self.run_async()) # gripper has to be awaited, both init and commands + asyncio.run( + self.run_async() + ) # gripper has to be awaited, both init and commands finally: self.stop() @@ -286,24 +314,40 @@ async def _go_to_reset_pose(self): # then move up (so no boxes are moved) success = True while self.curr_pos[2] < self.reset_height: - if self.curr_Q[2] < 0.5: # if the shoulder joint is near 180deg --> do not move into singularity - success = success and self.ur_control.speedJ([0., -1., 1., 0., 0., 0.], acceleration=0.8) + if ( + self.curr_Q[2] < 0.5 + ): # if the shoulder joint is near 180deg --> do not move into singularity + success = success and self.ur_control.speedJ( + [0.0, -1.0, 1.0, 0.0, 0.0, 0.0], acceleration=0.8 + ) else: - success = success and self.ur_control.speedL([0., 0., 0.25, 0., 0., 0.], acceleration=0.8) + success = success and self.ur_control.speedL( + [0.0, 0.0, 0.25, 0.0, 0.0, 0.0], acceleration=0.8 + ) await self._update_robot_state() time.sleep(0.01) - self.ur_control.speedStop(a=1.) + self.ur_control.speedStop(a=1.0) if self.reset_Pose.std() > 0.001: - success = success and self.ur_control.moveL(self.reset_Pose, speed=0.5, acceleration=0.3) - self.print(f"[RIC] moving to {self.reset_Pose} with moveL (task space)", both=self.verbose) - self.reset_Pose[:] = 0. + success = success and self.ur_control.moveL( + self.reset_Pose, speed=0.5, acceleration=0.3 + ) + self.print( + f"[RIC] moving to {self.reset_Pose} with moveL (task space)", + both=self.verbose, + ) + self.reset_Pose[:] = 0.0 else: # then move to desired Jointspace position - success = success and self.ur_control.moveJ(self.reset_Q, speed=1., acceleration=0.8) - self.print(f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", both=self.verbose) - - time.sleep(0.1) # wait for 100ms + success = success and self.ur_control.moveJ( + self.reset_Q, speed=1.0, acceleration=0.8 + ) + self.print( + f"[RIC] moving to {self.reset_Q} with moveJ (joint space)", + both=self.verbose, + ) + + time.sleep(0.1) # wait for 100ms await self._update_robot_state() with self.lock: self.target_pos = self.curr_pos.copy() @@ -311,7 +355,7 @@ async def _go_to_reset_pose(self): self.ur_control.forceModeSetDamping(self.fm_damping) # less damping = Faster self.ur_control.zeroFtSensor() - if not success: # restart if not successful + if not success: # restart if not successful await self.restart_ur_interface() else: self._reset.clear() @@ -322,7 +366,7 @@ async def run_async(self): self.ur_control.forceModeSetDamping(self.fm_damping) # less damping = Faster try: - dt = 1. / self.frequency + dt = 1.0 / self.frequency self.ur_control.zeroFtSensor() await self._update_robot_state() self.target_pos = self.curr_pos.copy() @@ -344,7 +388,9 @@ async def run_async(self): # calculate force force = self._calculate_force() # print(self.target_pos, self.curr_pos, force) - self.print(f" p:{self.curr_pos} f:{self.curr_force_lowpass} gr:{self.gripper_state}") # log to file + self.print( + f" p:{self.curr_pos} f:{self.curr_force_lowpass} gr:{self.gripper_state}" + ) # log to file # send command to robot t_start = self.ur_control.initPeriod() @@ -353,7 +399,7 @@ async def run_async(self): self.fm_selection_vector, force, 2, - self.fm_limits + self.fm_limits, ) if not fm_successful: # truncate if the robot ends up in a singularity await self.restart_ur_interface() @@ -365,14 +411,20 @@ async def run_async(self): self.ur_control.waitPeriod(t_start) a = dt - (time.monotonic() - t_now) - time.sleep(max(0., a)) - self.err, self.noerr = self.err + int(a < 0.), self.noerr + int(a >= 0.) # some logging - if a < -0.04: # log if delay more than 50ms - self.print(f"Controller Thread stopped for {(time.monotonic() - t_now)*1e3:.1f} ms") + time.sleep(max(0.0, a)) + self.err, self.noerr = self.err + int(a < 0.0), self.noerr + int( + a >= 0.0 + ) # some logging + if a < -0.04: # log if delay more than 50ms + self.print( + f"Controller Thread stopped for {(time.monotonic() - t_now)*1e3:.1f} ms" + ) finally: if self.verbose: - print(f"[RTDEPositionalController] >dt: {self.err}

9D+7#ATtcxj%;moqsSoMHL~l)NXRt8mJgNH^Y- zGet}%fC3VxSN9!PmX;ftSX7&S^R`uVr4mDd#c}KNzPIZW-0wpH&({W6Ults}kQ#}v z8OhzqHdNR=c7rS9{8-bLz|dCRG-wo!A7xBsn*FTH)WV!qQ<}(PxL*Ag!F+T0=b8yA zLVN7|16J5v7=xq^=7x1qrH6|iByB};HUQI_b>`ZTygBG4JwQsTG-aQ7@a3)!5yh!SEo z{jhYIouWf=CL=IJ9i3;oLytpL7*~xtmUT-tXFB3z2u;z4zlx^UsLElUkPF~>CH zn%2$zzB!|uXv6@uSy0@ukGu)@_w4^%QyX=7w7vXVgDaQ`aG*4MK9q&(Xy^1RMU>&A zO$2s$bf31w$ImeutZI9APB7{h9Y55h51wGC$HNbHuqQnb9ooEX;gTdEX(q$nSVk6D zF4Cy8=vnTie$%*0qk>4i?BrF*=Bg{OaroQgag@{?gDjRY2^!BuFdRHuHxZ(hiaNCW z-00YiP-bURHC;KK=>SX z?)YgfS~a7YSGVAJgiHXRq;7M6@rO57MceyXa=>H0Y}I1;ii;7`fIm-OGL?Z)ShNnB zkt|hUMP`% z-ItBI*I=pjm+XGolwJNazK}UD@`-=%IfEIY9DP0)vMkN+K>M|c(`*fULP>?GOBS)S zIR#i`6)f%pd_RwIlJhT7P0yu8BkPTGw7+|Hpkm2U=a6|Hdw_@4E zLz(cOB?Xf)y)^U%Wr~zlq~n`TS7vWt-@kt+NqkH}fQ?8+_jHcsA{|D)XGhU)QZXFX z;C36^Iodg`RQBJs>}!;LryU)v82M27B$*78tVuZ-orBwsTHw<0wGNGx0CBnicb$5p z8a4Q1KSy`mNKyX*wZP;|$rVDi1}a6PMlFxLAbCS4P_!m4BHQo&Ct+}x!mEpKUa+mK zGyMJf=izmOVO_l%p1x5pI&{;gNaIb_!mr0LYA7K!(?`|bWJtiJutk8{#HUL5xNAlS zpIJvl{};IlIU~7MXmRz}!LIyScia z;j+AdPj6vnYq!zF-tQmL>Nrf-XBTp3mXdM+T4fY_p{TkoBuPeHTL3=_B_uqp9 z?Eph`q-j?15|NLu5tUPaAlTuHrWD7IBjlg9hc>55)bUKy&D+Oty;cb~m?)8Uw2#?O z9#z&!XmNMck(@oJup-dG*8K{5EsmPe6nw7S`kiA^Bv@nqLE`CFqHs0Y+yCh?V0s_- zOf>9RA;;WUSv3i9e+Dhb(}>{nea%IV5Ax>gq0ew@QLM+FB5q;c7F+`4n5Sx&7+3c% ztHF&DIM--CF5R&#m1!fAJ@4#wvq>e#K5I=d(f=v-Ykpr$ z<^ptRJ*%65%#uoR@Nz2!nAA@AlR?K9vszzIk8mm{!!T72fq%CyaZ3cpuPk_kcyVk*N!6hXR(ZsA_Hc|TsR zIOf5yGoznA%;=c~Nk>1=$m-#F@uiVDU% zWC)?$oj^%LkBOfz^+}$Rn6zGUQ~UR|zr`nb@2dk+XXoJrb}!lrrr;M4yG)DLWCgRa zVo|8p_yp^#kn1_mjsYkST)H)ZE=G4-xiq=PBMVw;WlGbQG<74?;V)e91vL?xcIQMW z-Q!ImMSdZoe2aIv{JI7KGfxJG?=bZR!opSbuYtJZ2afUyt2E3jw(M~)kCRr#pM|^9 z*i!%G!$a)BPA2B&vMwmr?BTB-kWAfdM03^~x+kjr$r`evH7AiR;9ZW($!E&PQZvq$Fw;@CUhw#)=iFYdYsY8l5 z9{@Yir?HD=sLC)RVO=^C)y*#DI|F4f+owX&q}}$v*j=V|@1+?G42yos zTb*K?)N_-ruKnFeRV);`g`HD`P*G3t2E;=jwXoy$)rb=@rR|0$Hwi$F* zb$1X#%S0nv3^5HdUoQC}@>eb{?DIER%(vT28%Fy!g|JQXtt2f#B#&bO{A#eHYjh{a zx8Ja8F*TW93J002E&wK-TT091(yDkJ@6D6sKTR`gVl`biS!#i5>Lk_JT3MtgbTY2Y70ZrZQ(6fLB9g{@-krzNMo(etE4|R|0f3mOR~XkPDOm zL@E6!Yt_>=M=NuGl1+5U@oY8|jC666~x=GA<$SN3cBwh-$+&*UvJ#=qRoKa;*?pE{d%tI_W-=*|dfT3<<1OQoZZ@`7s)>7!ys`SB6fAU7_v9{W1&)+l4c`*}I+No|bIozLjUD0Bv@s%sc#x2_Td? z=G`!;I2<oiRLJFX4j+>dksAk{xJdR~(*y*X8{u3f*VbI) z*ZA0_N%9n^4Qh0KSMk4YN~X_Rx>3CP0n0N(vL#Jd*vglMhgkP$Mkrr#9T(ZNm3#_C zfDfJdbxrc`78W$jlouE}G2uW@dZ>kbILgas)!moX@!)|nZ>WN(D@%NsW|+Dh%abcF?nw*_Dx zXeo+uHSjUo`CDyl>8T~j$k#_XeI$R{gdjW754fpcqlY#mg;PsWt0%Jq-b~%z94G7& zbyG3R8xjyzye_-wA;OD(pYK@P*7rH7O@W8h>c5$*(dz)vV^5+})L!_CA!#mDxpG%> z@2uS{2sY|faI9>qN1DPKJ@Vt8C3$P4w|=H|QorWvjsr-oPW}#gh~Dowv<8pO{o%9b zg;0=xpQ8PM#7OQ-RHIDUWvYgMW7*IV4LBBW(3 z?o3i;W{EcevidFpFZv;NwCJ=iVt}AF^`Snb?k+tEb#%wMXAv$}s%j>pC7j4$(nbs2 zDA$39SZJBiYQ!+wu&We_D9o*f5nm&eg{}GPg65WCYrNZDMGgN~} zB#J*Z2!WNl;&J)*DIY3F7(9N_LWba~|2qXkZCu4%h7tjtK=`$jZSuAcGIB10DK_~o z-bqRr8zlehKxa*G{>~anrD^d|yhBV0T$;xdRp1%bN&M4Iy!Yi_!pCj1MkWFbObJI&q=C z8~;HgvmsvFD7+yQF^PU-ksr%vunWTGJz9M-VGJQAJWHEGfQ&d}lgft7qhFjj2%HccqI5aLnhp%!0A_3D&&&1mQf}&#Hkihks9(Ky>_X23_>wu8tLfcJF(3 zzr)y0Za5c%zoREvEHc>Z?`M$%Qnr&jYD%OMKM_iDRo%D*{hwCS$oQztaZG zL>aCaq!`QFt^*D~(ic8uko67y{F^n4E>k*~J4OUTK+nvo*<~cd$>=sW)R|DW;Pf+u zr;BN5w5Q~(amnOOqxXM$7g~6un?wu#-qh?@qH1}(zMZTj>UNkfJE1x9X)53amSHBrnYqsP2}=Q zJz#8|?r(UEz2_8MywBZD^P*5Z8sL)LL*fee?%c`vXF@>cg3+S;#wIBZxXMFcE(b z)6G>tINi*02x~Otn1&^+oOkApnr@zd_ZW^pXY+Xcs|!~{{er+1n$2|HG+tPc_g2SF zGH(|c4;LIuSFU5_q-zS8pFxp#yn8-M^{FsiLJ>qER35y1I_YFhr?y>isv_HO0=CRW z8!dUfE_MHo3o~8X8u_Nx`^1;4RkL1%RQ@~;e`F`O{i=P&B%v_{2ic~%7aRXXq0gp2HRkPN`aCWvNMPqCPgHQrl zT%vPffqi~~MRsK8ihbWM4M;o`hbJr}2o-}%wMh?m_)M_|j)cipqVGQ9SOYnf#ogg& z`&5;>r5cf4%g#o?panzU;NO!3pYUr!h_%l-Szcb=W_-{M0$9O@@J+1WQvSwXQ?mu}3RzYRjiX}MZEzWTnZ0e4Z^l}TBp zH$D<;HR`+48bt}OPswwGHkT;xqPxcriUaT69Iu2yp5nr%dnk`w(@&YIg~8#FTg2}- zY((L*NokZvvm#uxMDBGy;-U3R2#KXUAGY&5iDrJ5&m}HU+z0rN7&0TOuK@}zAPoI8 zh&+_SSp($rJPAW|(70S79dKss`}pVT&0-BFI#rqn`5gH?P4qemWNqHv5rGfAyPNL& zz0EcuY@m>t!YH6FPc4a{g-i#vVK`zr4t*7Ei1q_22ZqCJeLtlN2%P|J9-tW+KP;&m zhp>Uk_cL{!3xiO}B5>z@(Ir}X4PIDVTjFm=kf{X1;~@kiaIX21Hs7qet(~M!fTQTS zsPL6|{D0HUukD?^(Qnnl6@EF=diLrU{nVD5^B0g#Dg~Di`A9?sksO9;v64%x(M|Vp z8fJ_y*Dih3|bLWvxhd(Y%nY|xlmdN z7DSl`_XRxpTCmFIYvG_I`tq6mkJ$$!=Q5wf0l!;pJkN|H1ofTBH(I4WxYajcN9h?I zvA8jOjUt(4N_35wbkku#t;@9HcqB+}Cus{&vHQq331TI`G|m7E5Cq3IY2$36Y4>I; zSuGou6`yG&(!bj0H%`Li%A+UmmBS{1fG?Xtttc4_fyY?~(_AQVdp(f68EMtJ#P*Yy9|b1L&4OA`=rcF=>Cxp0^Lzm#)&?P$ zo3*T(Cue@il`N0G!OHOXdFFb4eja91ZkV#1DunYHyaIxNqwx5zjfXcr4*BT%KYZTk z%o+O<%tp~7@{!+*d->0Y-}9s8C(zotTa{!d&N)m1pwg*{so`Prm&bsnIzg@<{E;Fk z%+qMgw>i(;|D&;%CcHMkb!VAfVK`s1I4s@2J4O#$eX_(OM{1Sby1G6B;<+}pW)_pH zop`){AAaFrtKi7y8K&_54ySIz4kr@&OX3~+>E#TAsb~XK+b`^Bo1~9me=Lqgd?O%0qFUvxxbn5EN<4{ zUHHiCPbC*Iv97?!DrejvVGj1}2wQNB+l86!J*4akKb!7Ey58P%2rz|Q%b)G^Lv=|5h0%%qVi^gPah3Y3w#!K41o21ePCM;%r zxgp0tpC)hHZ&%>tffA#TOJ?o$J*I<&hhX_Q50ucrEX}Y1r@j$t(XCHArU`8eXRjs? zPn|%Xq93{hfgIHDlnojJ05Yg)$U}TiPGAuqr)1>iIi#*3m%A!2zfn)%qe{o5zbKt?Eh&;*Dq90x9@T2%b(Pujh;IQAtvAJK|?R(t3p4; z?4}4IsB?V`CS0hc<^B$?toK&@k+#r{)|{>6FS4>U7?wN}pLr{D^MNKVV2-(ChnI&0 zqhXclHxO&;bTJD%7BV0^u!rW0?&|DddZ3<@#D`<|t^cPw|vux5kyP7cq`;5qZeW*p=*1jmpspw`M&v&oR`*g48eLlqcZ z4QlybIZt-wIL^**`nW`+Dtpc=)&oJnbOkF6wksve`Tu+?($0(H>~VGX`LEpAT4)qq z6MOO?h&ndfeXgjKkglVWp|E53SmP$=R`jezgne#2wmpRj-@WH|h1g;$HNVNwsjWR& zIQVareRt;4%EmdT_=sN6E!z1IniPS^OxEsS%c!E<`;{(o#Pi!iF#@ai?@vr;seTzz z$d733oos_d%bvTLx|6272jvIzkxlN$lSqktX0)0CN{PT2&_kG6;oY;Y;CGqo88lOT zZ|r_CfYV0EuaRp_@{+0}fYgBmMqN4M>f;j*Y9kHQuMQRF)+K3`@UaJWp9-~y`%=V9 zT#r`>RFhm7)O->;t(3!uKH|AP)XsTT{H_cbTZZkw|4DW0#6^S?@9Y!(EerZ1ZH@~z zH1M>tAO>R8xGHna7S}NQmI&rHYi&ug0Rz19mlxon*QpEhCck7wEdlDw;Acw{C zueU+b;WA9Bi@O&Xjvp`0p2|1`OC)xI!Cyy8l0R$rp5dKZ@brnMF5AX8i@2KJ-w9QJ zbi~tOyBQdgWmBY}4+UFux8s!n2!M=BACiu4r1`!J^Xx!y@JL6Ij-6;R+_D@~bwk}r z5#mUv&{TzOFFbVX@790cX_Of@n|15vl-B+|n{es_NT`zao90>9YBN|dmGPB4QSTY^ zG$55JYirT=C3B01W<8IsVEOhnN7?mt8}95Uhfn&&WOSuV%g)4hX_S2TItxf;xE9P4 zTDEMk;&J%TNE}rE5z(;q&YPe589d~|?0QC!(>p%HVqWS~vBo~6{A3(tqKt?)C;oPZsErT? z-iE)aUSPQU0~HN$tb#;i52*gHcLplIMTM(ha6? z^M_w>#&SVu`?h8Vov55@b`kSnmWy~l;5!3Ti2Ku&9B zj7|aFcEa8iCHJ+l(3HZY3Q_o+@Ot@@9d}1%Emgq*#W!|7_4;h!=lKaRn}8>T{7scLM=T!2T5Bt447tKiVJfrx zwC(;Jtk|-O8*C50utXbD!$~4=-8h%E-u$iVvFFXTCS3{m$Fbsj&wg-igv5U)I&gT% z4!lofu_8p#+fqkq!v@tBpF74j#9qG+JHFMgO>=j#3ryVKXp@z5kLN)3$wmQGYDn-&hOf-u<| zX4#N_=@5&Pd$ZTP$n1!W9c~B*p^PDhoS2(n;XWOp;eWhV%N-zUtK{8UNPb%i4C+8) zHG$Wg24R-sn|*1Q2|t{F6rt+l3~cAn`R?UCcoHnHn+{ZUH~ry#Qe6lw?3@+mUi_Xg zo@N5d%b^3;xjUA!Wq#%CXkjvuH)Je{Q>$B55y`n=6Vn0SnXD-Q^ad79Yv*6Qljow= zYYI6VEWHCmJ{BZ@8~>Xv0s>wLq*x?Gl0MI(@d=py8qwO^a=`l5E6o~=o6wkfuz8&u zoS|4XJA^w?m1Xa0bO%751-wcOe&fxLx%2P8FF^l+a@oK7?Nu^&X{(i^fRPw7{0VgE z+^}Kct)q1=O+B;tANDRUgQt3|^_DWc&;f+i2QdY_>Q`NgcHA0scO|RGbgFpOf)3LZ zF$)06r{VmTSU4$q`Tz-LApysx?4J>Q@T6+ zE%%;1^L_t0^Nz2GH_yG+b)DyN%&w`X8&)BC&1xMGtQ^eh%3E@bF=bJjXtX>{e27YK6vIISk(|Em-UW-4}4H;+fOP4L8{&DE-*Z;XRR<+%iK>_}N z3d|-&4?4jN+_O+$X_VsiYR*_^$ybCpkHFQ@8VgJ-i28#O=jXTMuh@n;!QYJl{|4f% zoaI!k>g&cgpT95f^K796|3J<-`lBPG6s{B5XW&)wPuU&*078s#=_$@4^)$vBEtA7i z);SAkfdE*D*v3-Ge4VlFBsi0_R9rue{D!h)+~>X1{{M&mcdHCH9=Fj<;E!+SkK}?s z5s;t4v3P}+q~z~qO5kO}EA3u1(O%dlvPFv19iqQt{#LrGq#Pog&P>Ap)!^f-!1~Tf zZgkoUXRsjegG6D{(vRKLOPh(kI}Jby9OaF|#lwU*uVog2IEJQ}EuTH;rVk^|wQ@## z2-Q=Na|P8hUwt0pgg5!z=?EE<7Tx+5I`Ui9mV`+!d^a=609K|eQMO)shvVaSLGCOT z8QHct#iA(YVS~C2hPtcAN8IP5RsT5fErmBh*6U!=(DjW%#Y~oCjQ$ssh3hu?w+Vn+ zjayI8v>#%vG5NBudL6Jl9s*D6-X25WW`vo}Z8h)I!*>B4OU`kI(ueIw?<;r5ASN|U zB{7wtO3_|34CPpB3Uft*#?KNRibm~~?Bh~10^TrVHFaz0RkI4=3-4Ba_ojbfvDY&z zmnKcL%~Nv)Z5rL4ZUZ~}PG>WpGh-XcL3EQHv3krv?lgKgOX14(LP)7o0;)&!g^RXsfbO)woVNOZ zSpX>;lCkwNttzbk8VoUls3!U#r!@BDnDdXVSE+^)oQ=R8$k@JUlB&Y9&yb*wJ|`QNIyq#BmfUTG?sd@?^j6RxdfzyEa2hSP6Gjl# z3yVM=g@YQUTXFoYtOHDdPLQk{^?qbTpQW|?AlT7JS?GklA#08BzB&H7vmeE`lD~>? zb7NWqPLnF_PI&jAL-_QJ1$=gZZ8j6e-iUW|BGNIqSL5|f?vNFyh4yzoJwZEx_p;~+ zhr3VQ?;}h?&a&4>I%-cu1wQ@ur=yL^?V9rYwuclWGc?n?KVHzadx^!W2~r zkZaA1K_se-FrSi8rWtdt*ZTkx*1wM`%VCzurN4Q8g*`NHpAhaO&|w_(iqBwty2NbM{wc};*6nLmO25x{~mhnT7i+dA%| zc25oTb*tt;HWXEW(+@;+?PrN`zKd2EI{588n75gK=mdrLx9246ai>u87C=39fry-l zEKB z(nfOf7~GBIc;8WY?p0U0b)k{S6e8650L0)MInR4Jr&AyRk(;x5_4IV&UnK!2+F~Q} zd~23Aj7>TV<{uRg($6599(po7X;Ax#e@$T$K0z(Y6BT>%YPI3fUAjqWE>G-yWVlIAH{JF}}>i#$S*oj}?F>IcD=PskiP#Za4vmsm! z<5YLDyJI8W+R0!oI_9d!XTbCTX*J@HErImt356&^tMC6nxq^&IYRl&~h8-^SQ$_EE zXNPf%V{1HF<&K3g1KH%*lei_nAe#ZGA7EP;v%jmLeak?8cAWLGt?%zG+22xE8x`pf zZwSy;s^*f_0Tt)lSiS4bS18%0O$?K0iJD{XxK|J#B0isPRx?F8GZhof9jE!JkPi3V z{tOe44*Us-e}_7oHj-5yJm^!fJ>t|f3w`g63%O|0_CK>qdG7P3j@Wt&5%@+mphs#u z=@cHdU%JKb$7aT6hK}^Le2*|3tnRzXsEfV`j&-6+Z{tG}8X1|QL(f1Z(?)70KTeoHzpqC;!!Q7V zfa#+-JU#H8#A@wi_Zp+(&sKDRX3`qzvTZ5)#l{eYT+K-@1ZH-&z1CH00}t0>Q&dSTuh+6iRP%JU?@m+^*YUV&l7D)E~Y zHC1k+nA0euM_3T}89M_R){VnMphM?yaG(Vbw0<7Kn%+oS@Hf9*=UZqykh;sRO{Yr) zsMGmCUzeG@gu^sck%^RKxLLoJk!8Jm9f%6?MiQFNF~Fgj-HQ!;!5oz%E=M)j@iQo7 zrHX#Yra?%qAUO)%sH5v-n8Gnh>Z z?Z0jKW0+*Ef5xsxpY?R37Y%T)R150Nf3Qo%KMe%sIJxi!fRq^i1@Ni32yDbj6B1>S z!CFFy%8{HK zl160(aOQOZ>b~5bu)8+6yVe;mI zMUogx?6?&V$k>I-eBQaC4*^>MkJQ$6fSL|F;wu7HVnv$})DJ53 zm#h>d@gmS^blIVwf?0z*9oOdBDQcPLv`5o>wBM6Q#E|EBuBc7zsUuD3ABu);`UubI ziv>(OH!z=gW3ZH#!p+9DotW@unQ;@5PFDipuTCn{Z)k&q#@o)ql$8PVXLh=H1Tsm} zJ5^5PK>EbOxbF-jOy(9BR#U-gwgLNHxeo-x&FCpUaYg2ycb1 zTXQxm8;4XmYr58-UL}6|6PQxzKNmxO-%yFPXo}%6=BIEV_Ox!8yu(+IFL8EG)d>H} zG?{}2(pSwrjr1Gyj5)&-Y}gHWB!X3f@H%G6)NQZF=v8xNxUOTmm%(r0PcV1+yK??~C2EG`)0u20W^=q81CZI6v_J52M=>!@Hw11WK3wS4R5!>EIc)sly`FVleapChNJA1uI zXe(9 zA}ah&eN?hWi0+rVoN09?cCs&0y1(eG)Lx*0jqXxzmD9#2ZGZo{oPGYkm2oG+QSj%; zAx@nvGnwiZI2wb#2-G}%Yk;jKwycAn@U-{vT7Xm~V!SWr?lXsEDk=(g?XvBGuOyxg zG__fs_ctl9>$b8EsbGYpmEk%SA(}n`p5XJ`-}@W~n^!30eKWWT#EXcsUOma?{;a?%cv%}Oj?JNW+Ab$#vQp?k+T3{v55{=jdqG3VaFz!c>X)*X84Yl@|NSL<7be(MQF%V>673868Wp%=g<) zq3p?TZCYcq{i{H+*onIG9hh8%{Nc_T)i@p_0X3pyv5PyB8CzUHyhH7RW@kr`<`0u* zjncBRu{GR@5XFpJbB}}mjGJ57p3BeeO?iBf(epr zY9|LcrAfNEA}KAfz1jj4mlfTkWbnf%G>2)JbJa33jESi%Z}2*3T@7DX>b1zc3Q-9G zFq*?$P*SS@%?TgOJTofQ0gH!piNA3LjE~M8l>>MG=JrQjY~Ky5zG_x=c7d&lg*s2x zi!IMEU{56Szq@54hTqVYpv#^d(~bv zUag!Os|>JTwUV;S#;Ye0;Y3h~X@fLQ?D^tgYx z&K=rF&p4`|V5Fm9-UDnNpyL0V_d5bUVXx`l&&=BI#4(6q*;w7)jOrS{NrP_G;Q^JLK5u7^J>2P z)P%S10vhHHC=?{Wm!Y%SH8{)KD3r~(cxOs9vQtDH>1LLm|dyU!RLWG!Sms=6KL5}oTo%*e8Iuy9n$^%d7-X9kp zJ_}dc|2Q*r{%iIL4u_Y4S#$4`tkhKu@tgYGov{L&Fx`sMWe-?Fi#WZYB3;PO25~ph zsyT_4NDiZs#^hI?sVI7rOofPb`AW*c@-#tH=8=hkim3-cM!86Z<6R-G!$4E;D%e{g ze?s}X8x)0Rox#S0ZHDu6M-cm%GfcEDOE!rdFR#MG`}~BVQe;|3)bFnL5_T-MGnru zWaOW%Ms+AD3;JQS;@aXzme_br$JxWZB;JDFi{)$Vd7R@t9?WCP2v?bh-3Oz(S#+(2 z_<+S`lgY=&T5b zxD(Q9hzU}Nhllck`av=vXsKN__YW$ynOo3xc2;x0_J%0t@#b^mmtE>PH^7ezeV|MM% zny#rcMgT9K%+^1#$C$Bmf++t7#{DaSU%$pqAHb>J=Wg4#Y1S{m^xP)_Y2Smqc9$f} zuR+&@Guv7%X2kw(`Gdx*3rOL#YLU)Tn=e}XZSQ-Jn`L(}w8r^!eB~ve(X3ms4g}={ zbaYDV4}m+c8$Yi0Ex%b2ZPk2_qgk!XQWHB@tYLTh7V{wH(5gO`94&cNcM%673V3BM zoRS5a07bv;NN;@U6+@?_=(5Vd1>gZ~s%ehd#C%Hje5MG>K6`bh^*aH-bM8)@o<3a> zZsb&%X0^Rrq<_+(6|&#G+NMzMmc&V55i-BK}`fji74xSOav&DphZ=!eGh~d_>-5;^BqY zCxQQgYfK|@gRTZ{OAm4CFhU-ENCQ9EV?d(349fL?xYrE6x5F%D0OYFc>uVhUAD=c6 z%NzD1-V&g53%~V$CIPsVvjW+IydR(l*mOKWjZ>{@g7Nsl6xHZIdCiYLAg_72poY%I z=CTPvm7(98JuI$OHt!@1`|8zSBO19mUn8`H^Ib|}-Zem2`jWszOzt#qX~xRRi!-BG z1Sc-xkeX9y(>1ySpB4v3{XX0}VINiA&kbsUY;fK=8WhU0EfLi#o>ZYhVz#j*rGi5- zm+QcuGy3wULS*jQ%F1hyfa^0ep@`>E{}l07DEQ7amd}vssfF2lJ8bs>D*HOa9$Yd0 z32rqlxE{f7ZQb$Dt3LyG_0-7Sk+t8;8>ExobsmF(f^9=&=QhprW6|Hv-5meerR5y% zVUpjLh4Mx#b>{*@=sqP@BLfskZ&Sw)q6Gy`-rW4Wk=CgyPsMb zLj7&;Jgj>Z)%?sN*Ix-C`Vo}}2F7)z8&Z=TJGywJd`*3INq@B^Z6Jo3)O?VdnrNW} zXG_xm!|jOZc~j&W4!E8&r>C+iMm9jB^`C=sx!L_Cd>~WMD+Il&%3!VKq_p{#W4RT$ ze|NvjKMBI_;OqlFwo+tqr}l6J1qJo6{rfj-6g{jsk}L>WSy|)LAfL0dNm;hEb89`t z9E(O?lTUqt+XQz4PJSK7PfF!;2gUDjWkzC{eoW#p^_Sb$69t$p5t=0@yn{sdO9UK% zaSxE>S#Tx`$x_zkhYG+-0nbRTX(4iFLpJP!EMP;Ig1 z&GUONg#IPe{<^r&5(L*xamn|?P20MfV{D;yW1ZQC4j7mj%Jn61I;R^vN#%c)r*k_T zB%-A!tTMBJtBx|TgioP~y9~@$q#GLf#+_~pR|-TbW-y8!ndJrK$i^2W!@aO|uc&5j ze5dyl>n|SZ)3)DQz=2ec89*&n>$G9OhnA*9awY*qT+M%%h}epOrtGM5`%XWu3=#7b=R_`2hSv|KyGoKqx@H9#}<=_EfpR{GwYqV~M$T9f#l&lMd?( zElNwr`?BRe7e)@CmaoD^-)(CD`+Q>%tW5M4z9FnT!R)O$(HI*mb z$~dxnogD&4X+N!b(c-Zj^J$h5$YhF%PLfpf56GOy5Ib25b?p3cS@d|QIO%wU=n3uM z`&dU_-f#Aj&I5O2vomX%bEQh$C& zyT%H~8+kk08c-AONtJb=L)&c$RQBxIinu;`_y!Bl7IiY*Zt)H8H-Rq(s-p+s775;6{oARW%HmDo5y!;lBcbW0z$~C)mmlhUO+(gDAB&7au zjEQM2nbGrXtz;FJz?r=xRW4DVE=v!CEZOR2GI(q=gY0aAjp1Pq)%BTh~BpbN@ zfCLK__77X{MJR1xJlEI$)#4|lL?}u*>VNEfNwV!l1*d5*I6HLAhf3NTfIF9_gu|GiMHG88_O$A@)+=MKPG{T?1x z4}K;~!uL~TX4cc8r}~&EtoAYvjo~&jP;3!zWbd*j(oZvF4Eop^t;_=D!C!6 zL7DugW|@i5>&^DR519A*r(V7%-mBP!%eFKS9r_o%V+6M*0i|X6))tl(x2lmJq@oQQ z;Wi0JionF3h1v#n6;rwF&A5x<8Fv45lvWLQ&k|P#KMjhQLXh7hG!PwQ>n3z8LCv^u zE_f`2W8?i$=4V$ae!~?1)GDVZb;P?$VdpBZs&j8F0wjF}b+3<4bw1GJm6aAxY%m(9 zWi|W)C@CiH?n>%ZB_3(caTPPA_daz^_R+4W^44$>{zDwQpEr4g42^gcYBeR2?W0gv26&WN97nFX@0bfVD&_DK{v`GPIq5d#2F=<1C|n-h>r2rnA>H5Xgr?DFQsFAKId2!PM?i^^+2myTF-UJa4Ih8C1gEq|Lvsr6yusJk z<@(12{ngyln)-*ai*b8ytdNZp*-dZGaqZ8}bx66pZW_OMvVVO?MGcZR-}}Hzyf*>^ z8cE<)^YY)=WW(v-B>*vQFjWry_O1$+PG>3EsOz&VJ4q}%fj*Gxp&cpOn84)|yR@%r zU6*qtR_A;X>fP+8BcGBBK2G7$M-($UjuQx|ysWE&by5*j|KEN8{N+7s)2@x_#UnAi00Ot9mmZsauG)4uTX+5yab+kA8UeaL zC!lp2SZa6SBE7pgPoyRU49LHDdc!hh#V*jHXE;4*-PXfWAtU&B<`VtW zL@?^MF;ZY6*ZAG7$8_rtT8L!#J$`EI9y>@2?ZqrT`&t zpEkx42>&|&lPH;vZStGlCi(82=Y~i#Z6v8vp~sFnF$lQtKyb8a$A4%uk6ZI{I3I$j zXxO@Sh(aRY$qWX7YaOq)#}zO+OmX)%*!BPL+(hKfYPeT{=|Tn_wLdNb#dE};^OWb% z(T?a*UrORGwf{}QQ#ECvm~2z16-(Vk!0z{}qls+bU!$E*l0p6aIL=lhy+^gf&^_JZ zv0*}lNEvMOaaMQh!a239AZjj_XCoZB3%RcM)q#R)53$v=rLlhZuW+ju%ptDN$AUNG z2j8*6U?*qxUEir7=vXG`FhwHk-5L?sz3mBJW2p)Z)##%>8Jw8-x~QCtB+YI`>6~?L z3M(hJX10g;23UBn;J%?ocq3*ZfT0ypT>8UpTjRE?)QJkLrUfrW#^j|Ol`?!sppSyD zL)lDe(0hCBajPVS&;|QaNiak2aS>37kG;cv`#WD+d)oeW{JL7%Omad`E3^h2Pw`Q^ z5^?p)G;jx)hxeOKCM2}gF9RFJ$1N!L<((%lwx9%Q8K-XmauF zF|DIb2P>V$^S1{bs~X= zjbl%MGA=g|m9(;y_vf#uEJR3>N7@IKgaP1^&gSxIzpXTMjU@%$ftuYR|*M-CS3$rf~X z1fOU&1Uq>FLZE*J-fdJ0bxc=j^qV0A;#bJTg?K6i>wr$skuCVK!*cRZviL+-_=vyF zEb;vEa_8}{%EPiVRGCccXx1P6B#+c^sk~Y6K#&Zs<{Sk2rdCB&wwbm(UB>J^Uaft< zehHroO`%*x^Y;;aD3ytA(R34rT(uX%id_@`X&WGkKg()B)d8T~K@yg_wuMvk{G78K zZ;~uI2zMcSY7ODf_Vzg0f*?Wn;})li=l1^=13&t_r1rgjBrNC9X2vJrFa3!xZ6cDP zxPB+BdxWPtmypI#pU911NZwHbM{=Q0Jp=9^FcKI(){Va%>KJH$RspbbZ(ZH$o(ooT zA#t6APT5R#b8{3}WK4;GHujL{E%~G#+ouR&8b(!nt(TG%r40h*qZ}mY#y;)wob!44 zITl^=Dw;~Ig~3TZZn=>f%p=pTEuBscJ)O^O4omXJ)HOy?%-FSqG&Vs}b%8>|?5rQO zXK5_ViByQBlrxt@Ng96yYh{|yERbNrwA%SXZI zmi;77(%CzkOLJ~nQk}%~eB=(Tg{;T+QQA)1hH>vfYTpLk&I^mr;~+yvI~jvW7pn;d z+ktdSuRjhx$f*qC7Gs3CtTI&{v5=?rA3guNnTJ(ezPW7GSKRQFq?_LK&q&irnAQE} z@By2AdB1eAD=z@=rBEtm4OWR&$wzbu<0c!O`1i{@`Qj;Rl@kIH`WAV90!rln!2fSc%Z>m$KModWc`{ipWDndVGw+z7&Y2tKVz zG(H>a7bBa5X*p-gsgk2)(pSth#WZXCvG)P92e2K;WkTSD1vCXzk(9u?42UvmB-GN0 z(=Zis+GybJw_Fx-#)7`*&{(!&0Ony)cj9PsLSq`4l7x;}@Os_ELF65PaDqE9QY*h5 zY2Ko3cXgAo_VO{$Wt1QvfhFVA90xc)z;R2xOalyP*8oTqW*E%atUE^;2H-6g>T72= z{w+IzlDUtdg-@{e!b<6CsYweP+4AM`u}gfD!y7bZuj+}N5N`$xC_M6okXGHb(^sRa zxf%RejsoWQ_?qGqU)H>_aA-Qjcj&VC)ETPh%|DHVB%tHLHbHRo;X^7!@dz@i%*#`f zl<;7p6D%}|iT&Uub}sk?9VXkU~x~UPO+t!8n^wPa43@{+{*xF6l55TnV0wdZ|bpemVYpM2C|rpuhVKjrJ@7DSNa~h6@E3{AChzC#-FKHXo{G2HvJcr+{Z9fb|1idVT`Ms8!k; zXGGhRzwmDPh0su){DQtr;^&VIa0k&GsHu~} zhv(<25tsq&vPDySnp`nG;lN?hKI|bjTR#6~q^7y~fVw_0Ny-EsZSc+Y%?%HJ)Fweu zQ4yc_r^?(A1|AKe&6fu-PjpRjSUn_yWvm|Xp3!YcCu}qi@cy^2s&Q`Df=@R6pQ?-~ z$D*2WRf)G8kUttAIRReCgi<*KQK`Vs zZBH3ZG)x}5_!<%_Nm0h(lnT8!blRF&$p4xo>xu}9G>1+#(XA0!Sj@y-7{6zNDw@nt zmqMulKOg=6c+sYzW0m3QY2R7>*RT=7=hTzInbqb+p`}VB-;z&D$_NPU2Fseio-i>m z9DR-mc6Y5lcVWG8Sm_an<;WSM4lkBMmcVGojZ;LUOLe@O>f-2ZUOtxNm8*Zr)o0wK zZQ82CR7M8*2OIs5krvPpubR>tQti|Z{`|pmKUtX|(j_wCdOZ4=V=9on=Q-s+O`xP6 zP*^RN#HLf#Eco_ui%vu;U-Nw`8rAHDka{WZo7)Kijj(Ag(4w$z5Ukb-Gp9Ouk01Os zDE@-Xr`m>#=tX1tI2dj@{A`5)L^KkJ>D8Z;dkpf)DSL8epqLEZWveRmklZac958;R zQ;B-Pu#;b&AvC6j=UX<@6@_nFA%y_6dL7%_1sibc!j7Z*&29=aFM(+`;zRV6`BmG^ ziuYd^`Sk-H>HGVu7!V|4W&H*6#yM2Ta4y~k%sXgWE|!a)Bod3 zj2p0dRj7nQSYodB7Jv^xfdd7cOuvm^OE7QpNMWlk4%-hOb$F$4c<{{2MmG*{?v1oP z95>&dcIT`=tb%Rs$7ONoHYZ7s2Xa0ZI9G#A8iH|kU0pB;*#c7W=0tutnd#`^QA|!wL!^~dt<}0kln_JX>(bG20o!O< z@Y~yyf4mSujJoz$42Q106IKwqi|r3r`dS>=cP(r(i4-#5iY;m;?0F~lTyUm$>lDYM z4FxS`r;OR-Z$>LPyZGljF@2U-wdc=u$GbBQ#e(3#LaBTGw7{83=`~{R3+h_>QgE%P z22bxI#m<9MR{@7qxPEmmU3GtJi*7~U>Ph~DwU1rX)7m*KX4_B9P0v39b~tW-QU3fB zX373Kz~URmg3HiX%1uS5FrnbBALPtd0NKX401)yv7^J-)wsk6*P0JP>ziiYw(3@x9)G(w_p5OntCfdAUqpBOkRUnX=EUJA zEVfw7#+HRJqx)j!)%fy}8&B-af$NpbH~iNpb~}%)Kk%`7HiSF)-d)24M%4CXlKQU# zSe6U!ZRy;>+L}lZRv!*_16a8;8aAWsGJq_I+S_(e*Y$Au-28E+*Qq9my@?7bo@aco z-sHn^$2aB9*Fhc8aA4mCcIf}%jlV(g7K~RnepURT z$Fgo#N>-CDJOFA;oXtQ1K4Yu&`F0zTbk_J=Q)Un7yc=LJS6w68);)-|@S{yFp`&?H{96h*4MGbCv@VA&6DX&?VeN%;5*r zUdwo_@oeP&00aIH9tofH5OL^|P{7f~&CSiY0-c^(x_@l{%FDVzcU6{%VYCq>vSxf6 z*w%Tdr3b{^NY25Y0&hn@_zS;i1n*6*WnCbBsqx;{nq3-`@==0Ch9Xbg(z7Irh%+ju zRs}ADHAz38kPvfuk3LtJtIQ4}YbSw)^e49DD}n=ju`#FMWP9xuyV|e7_l+U1S2aiE z&p!nT=*x`#ou4&Yh@k-hequQ53w2hvhZkd~Gg_FZeg)VGcpav?-xor_Z{7}? z@oEHA@`4zNPZM!|(d4Hu?=B6c^Gm5vqU6zUx)rclI`x7d8l+8Q#ChU`!h73{D&&H9Kr#Im+9x}uiiCakw`gmK@Q&`09opid|kg&MYl!wLccxnUnL%;Fi^h%WMeK6-eaDyK3B zg+gr=);(XdvW274PyGr`habe=7IS{ZRl{=_*JPC{qtIFCwNML~sSlJFpG@D`pT8k` z0VeFNN<9Yi^^kXGnz0P(ZyZIUDOGZKvPM5@{LcZ=2OJQaXIMpJIVQZ>rv4v|7>-N` zY>V8$KsI{JiYvq+am2JQKfFHJBidEZf%3r+(^QlKJx*%dDp*bxPB zA@%Vrb;b~o_cFn)sxRxQEXT1YMo?gAeB+RxPo1)CRoiYmL!^0zs?v~$@-oi3ZbAB{ zeL`IhMzqBpgn7Iij3ZAT2I|mj;Id0+7-!Fj^4GC!7>zkPwk+W6vg3@vgv8lm`~xp1 zq2@@kmNhSpNm`Ic@Re==<(>oG=S^IQeGMmYfd2as1L>^4j`jCgI+-Q{MxX;hsbEds zPD))>naydfm5K{dT`RDO1Z_T$*fu(y7!&Dg*tBDhe{nO~?5&Wq=#}=0gS%P^- zE=A`})(5bx{OA2?OaOEN`|rsm?8v(X-!?TmzI<9p3o52h&#+jVlipJ0autPbS9IXs z*rxq>z`rp5U4(JYW8vE}h4 z;!X#=DR`6ts5z$&^mJ&rJv0IuH<|JN*bUuSPPFQ?f(O)L`DcN|*XIROH}2Q# zmkVkm*_h;S*OBuc+Ty^zH2a-`l=R_a9!oAqC`UjCdDZBzU$K2S5Y$6mJJ)zDw6$~P z9L}kjn;#tbBprVnhn&cU`OY-xCT6h3^jNw3{BxD|&&1;TQ`*OCCSdPwujF`d7Pjxg!~~QvU-oBh5Hf3Y&Ejzi*@f!d zwVwErfwhKBCWQ3qHncG?=9F`w}n1bvH@g*n#asioTbX;>L2-_!isF2*DU7BJI{UpVb8U)EQ59S`O zj+i@*p7)?(4U6xTF6g9P$ki=jP#$}VW<*=PQ7+@*t~`zE*ThnUZP+pS(B1G}59XH# zx$;>WNVEbXTI5un8hRLb;WgZr7cmGNVU#uyC33r#7JYE!9#t*hzy;7^UI$3FRrEP( z^w-PZ`-VflY4)nToo@l=8R7PBOr!_Q-5usLJyM)cb%Dmtsmal4gH*`p7OVZ~=%ZK} zcI|i2fF%2uEr{xUHQd`WeTkXSoXLtVF_)Vt)T~+7Y{enALF>hJT__X8JUX4|z>xzE z&j+r|&=@PLbj4liIvgEMEJAL#I)^o`Q&mO%fJChWc*7}{)5+FwEm-+GVGHBb)n?tl z$$zUJZ_ZCrJMDP)zflywaesJ{J<&k4;d;OG!}oyp=W^<8f@KNZpImRAo1eA&paBTh zw4(?=L=t9{^kL(@aY86GKShf??J3>n{JkRse+A`?uk}09iS_EkUI1GSf*o&MPDybg zMm}euW-NHjs$)!Hcau3SKKGuis5LqMmoGsgZUd%l26Ze)q<=FUGr@}RIvX`*j%|$8 zO{FY<>LBm;!LZ*6L6)RJ0MkLpoA=3T$&F+rBovXQ1TkUYkC-Jex+dLTp~zutFegA< zEZ=H_>F5Tm=-8k4ZgMiE2yrLF>P z9xi5%#tuEUNNppC`#2*QN4=#*u>6)Ad-8y6fZwiK@>yMYIajxWVpwtrz$J0w$@3$k z5nz^kh^gh&2*$c?N#!V#_z)HH!$?AVf@R1oaBIwpH1&}RRZDUgtjX)}^3MoVBqJ}# zBe6mP0Yk76ZOmgx)tV=>Se=qOLVC$pWIV#FjqC@dD6P!w0m9T6-_#{Ja!p+wNa8et zJ}nC&Rdg+wQg0?HJx7B4Bnt%Zm$gqrUgI~&x7GTI)^>1Q2W8vaZ8rai zn-yOr!U*|fy$U>sl@^8$apqcFxM1c+a0~1Qn^~Z{8QGmm`fmH9l(VkInjqt4>H;_piH#?KI&As_cQDypJYg;e^s*-m~H;Gutcu7Lzyl| z?HY$M$Bg0#!tA7-WkY`Li|NT4I@EgNhfntWDB%&SU;-m!N;;fayXh1hWEX*sop7l+ z^F|?P1r@x#038>M8#<4VF<^}fl`1z1+yp#Zs$iE)(3vyrbPB(NT@p`11D*q9n7?l` zL6%9!!-y326+A@{xp?#P1iaj<)l$4}=+-BX65!j!_Y4|+3V*U`e<^rg2}^5MN=%i6c!u$cC~J%Z!L$+eOI-V znuNxB@hhg;sq|7qDYqp+?d-yrnIssUowbJPQGVE%41&Pn`GmcjF~}+qzNsNAN)@HL zs1Bj@4-1uNavwVZYx+#55v!=SSWnjH5(~2TX3>4s_`AEgMI3)~)~o=ZZ!Oan^sW6n})J_zb0IumT?zaHIvCNZV zVwGv6t+>tOFm_Fno}T~N*-*xS+|*qyaTXWd3)06^EP9Q(b|*Zql)S+#MpBjHid!{z z+S1XBi1C6O9ON}?*kx!mI|o?}685i^wVV1*S|2LQ=cvUpttfRGDr>ZfzECSfP-1vN zzkJBF09nDVKc9jN&e3HuMZ@HJ=c(<$+y?zU)jywTn~XOlUX}f4=h3=^dRAPeCB0u` zW4I&v7Rdf_ef{WiwYkFO!qmU~V_>F3CD2L;N#k5a%JS#_9YUShaV01X@ zdA>GQRNpb#{_S}Spq+oLoRKMg-`+KC|Bx8}D3C3{u<@!w6G=rq7}B?~s{0+&nCcse z*6k9KSZ*-)ykmZS;`8&ir7lPbYx*oOr7@!S;W8H9`a--E1`@3(hPyJnt)aWIC9V&8 zy(##+MFavogoI`F;tWXw)+jx$Jzv@nvt@Z;JNto`{&iZYLPTSOQmW3r(8s@8$q z7}aW?e|M$K?eF4QirMYFVCeUEg<@2@IVM`%_^GNv1OJ8?jnBO97oYk2$Mtk$ZKrLMc&niVP@ug_eL-|3uz!WvxA_v>^~y&REHDVJQC~@A{Gd4N z*&e9W(YG{n;86Y)>KUoJd>;98C#%imA{=x;E;jWW0WL84cBm5JNt9D&v`q=XBOzdkB_0lT4+2oUR3b;vIV8GqrfHJ z?(@j;JO(J)w}*9OIA#!3!O!H#pN%3*TQt>2NGx$+e3bmN za@8C+{?hWYTEyFnfjghd2c`>KUHHViF|%!9Q2E0#-d1)n#THWJ>}yJ^p>3Eg%|^4s zHC*+-{;%-w-(_zMWFCU6+Im1EFZE>EgHxp=YB_*D5`4e9$VJzvV?*b(*Iuot!^k=O ztXq&TSOHk$HaRIEjj1KhkWL}P;;j86*r3lk(;mbOw$}Nx_7JIW6(%^5Bt6>G`uM4} zglGMyHM%S+Wf~N1<|V4F7ee7=_oosv%pk#P+X|LBmo(JY-Ffp|ug}ZldC=yC07tyj zlqSL(D@Fj#5a--!Du_-k{>&0h|&v|Ygm zE&gAYh@b7-Eb5BF(G0)d!`79T2yLpHz-$3{=fD2YuzIf)oDOTiq$P_g`B`ChC!b?5 zoR7yCGJ2vyzZGw+mUb2Br@4Z)Hb{NU%D!|1Q#pW?P%nFFS=SV#q%WwI#BFDhE1hW} zJ!m>)5mdJV$3%W*S_8sx{7_-vFrb^4qvlQ`P}_p>4NJ$L3C-*BO;L1M@yDcolkjSWx&LJWDm3~I zK&&Pp^4t>-YCe#5#GAf$)=ICpO~g{il@UTZ4=Rlz_kS_KPucTaE+>AdW&(E05TD{fZ!Q7y6)lY9h zk9VxbkWJ&706z3D6X8qyc<{w&mQ_3i$p;ybqf;Fo9qk9y>)#lz27dj*D$h%^M?oW1 z!i#iwl4pE5AVB$f-;+JIl@bEUC~`#iV+hHUMjY@IgY?Z`S;lPJYWyEhXBkyx*G6k% zlL8`L(%s!D-Q7qxNTYOzbVws1-6=2KuxUY*?iNtG^DMqI&iSbhhXT)D&%Ne7=QYDH z9AKH?3u5>5m}P>NK^@blHQ(10I-0#}%e!>~;+wSoTbBIahH2y2%B13#>+?A0jjo~w z{o;ZA1oAx)K!z9!MKamy4ZZieIH3Tv=J*%bANUghBI*UpU{{dzdO_@h##|6S2RpOi zY~jf_{7@V3waxr7&R1O>WLzqB6kuwBefoQTIO4T1ujIU* zd6x>JNUt34trU^rFM^SlJ`11wf6bQycQ%`&jisumm%7(8@51-`7ei*zh3Srd3CI6? z%-4pqez#HxSSBhhyLaSE72|h%kK_bBogl`;Z75y+?wxp=)n{Ff1DfMicC>nV|{xIz2y1hGfru7@+x z-57)r`XDmMiC@%h^+#f{8}QEYy=LvB9~c}A*V89}7dru(0&q;tM(djFd_7LRZ9DzG zVB$1R0AFMmva<4)gp8~eij@i%%50|@vUY%Sk8ju3Ysoo7i^ZIIFRe`OSv2PAJ+a;AII_oJXG2bZ_S}b^{Tx6;xG@Tl zy<8n)(*4K8xvJH$?_d3_X0fQ|tzBuiM-M#TRW|AlczfJ&&l;bQ5G0I$+tI|DoI-ct z7h`S2Ej0uG`EO^j6MxwnMn4}jn60d3%DijOKYz5vv(S+y&y%d&y1)yYv3*bU{Z$zo z6Rg+c;3)Y|+G|snZ}()d*0YSuOZvLNL_i@%m>Jv`f%YLMBOz5=dmx)Y^E2#E(g6aq zhu4vk6ZoSoeV@ATR|4Bkq5ro(kQnp_eg$ImP(rs%)@M6@ayQS9JbmQz$y|Hh5yE42 zF4(L3rr?y(!|Bb0?VdZ_w|-Yg;Wly%NCNxu5M!9KuyA?GOpU*IC!ZF+SvB-QMy~y( z%%~d(a=&DMRY`ze`V^9u{H=mW1Suyw)xVx~jUDIky}@kcr%U`&#aA{LW5%pbU{-Gw z?HtdQSE8$s?5M?=SWK99lz~F;eph=cT&1H3qPjRE5uL_E1PQOmBz)>D^&{AkQ{wu< z#FVj>Xf^$wZt+!U>!y^IV~=TE`dy}}LsviI*FSvPzrgwq8K$&KzWO0_yk3|P5TDKG zYzI4VMDWTTZ87mQhcXBP^U-j;Lc5CSMZ+^tLxs6w=Cl*XQOb9Zlw{;%S^T1IvXBk(31QXt5^aVw;44 zi-_%hkMm=?zuBI9>yH#FXV6rv8q@=pQi3@zYr*B@C6o4#=%0?3-{^aGZuFEiajt_B zK`0KXP-fP5alrU$_iYEKZkNvqjM+NK^G$LnebG4mvEgp*K#p>#saJ||(lJfm-IuOK zEC%i2uf$%v)>2nvFImoReO-??+;nYgDoh5=8DccH5H&$vwd~ZlqqbydFha}(0#|GVJac+qh0-)czYVtP+}d*-J0$DN z$N-1ckJFo<7Q+5lIN${d-J(-Xbi^VdApr*`J|1OyI&=^*Woi0HP;O7M5KSAMo7_)p zDsoxxmQ1B8XQspK$v3crg@uJI;)(Y3M}$@pAHnC&Lr@z5jo7Gh0S)YxZES2n_t9ha zty0~eZEDX3RzrXWzDcJ3xuI$mK`C+tHsA1$@c3}amU!-xxrF_(O+{KS#KhUGZY zdmCVRptkB9`x2);Dz+SU_mXL47`Cyuv5~!|38`K7B}kY@HYZIfDaRXycmm>8H89)c z<_Pz0MVcH6xV^SE+ORpJIehIFZyyc(aLVj`2GR2h_Iu zmm}{b;fZiL8-G|zoIWQ$6YDBwK5zS zl+d(4inx>za6z@);wo7cYgCw%+t^_vpKM;bCVO;5c8Is@CZF8n?roSmwq7$Kv#C(J zB=N`ER!TjLc`xxlm^hiYb2ab#kB(Sj3X3Q!io8A$IR96Z&cQw_SQ&x^V{P}m!~9-P zvtv_$F*NtV_tw}5LE=_qH*W31k*HaezwEQvp*N}U(D%7OUqsMBvDW$N^>N_yeILeO z54CbB_PR1HIFaWGnUoLeI2G?nuZ?`B0E`r2x`A1;eI{fNDX8fr6y^n_5%@S4Sbj|J z{`N?JoB|N}-~W$L2IO=MQ|#v@5ik)5RdU$z2Hx$L@{5Uu!gTE*+LXf{WK6!(JLPu1 z2e<6H_Qp`pj@7oVWp}|GjEYoLFca9NQH*FPm0*u7Ji@5sfI4Q=))ZmQ8s{K|rjj_R zn##&1=Ue{k>uc?L9qTx^6;9PnQc)5N&q)*3^p=3fEYg_Y0s?7c1djo#+MlR9>UF-| z1sPw12##2KlXzCi0iVK0HsbSGhUH%^too9`nOW`K_3r`FWgJ>mYqAE&0ATV2#FQWE zmCN5q6^DFElOSDB$I((f2~3+X0% z?H9Mgp4Rs>85JM?SEV|Y;mZb9b67Vc7X>(j2K&kJLsTH|WnUbUd9Fc23`<|~sZr87 z#}1GZCD*qjxm9eYws$qFbia zE&%b2no)SbK^RuXy|Jtx?}gu?AXb_h3GuqRAbinDI59^Iq*75W?~WmjtsW721cdBC zoZha}ebq-PKiBmJ{u%KNnminKZ_~7o=rm8|QeWq2HR8-Nsxx6jt zrNbW&17NEVRGz1lZPFREX2DV&%^Ql}(X&o}Q@0sJ0v85p_g?$6KWHrtVy=Wfm@aaX z#2^z1ATgs(40L9QA7g?Itx+5b{yhCyOFCpQIrIzxj#L*PpLlX)U;>T=-?5)^)VC>~ z*biSPtPflz^P}GyHHeLgW5p1YVn3cC=eo{o64JA9r3@=v~s_Q>A|ID=k5m* z|9-%6vQbraaSbRrq@LhpQOKx!6SUVjHc8VnNL}t2BTmSCES8W%8gAuWI}U z&1L>Z)m8W-w%k32&qNUvcw;mbO{fQPL@Fw|J#h0YOEdShlP0jDZh5I*lP&b7^yHzZ zev*M2w@P`3OD;sUu50eTImawfx|MuTZQ zwV-vs710_;`lU8t>fhxu*ZQWe&P|~8e`*rjH56s1Gr?n-UzTm`qCH708sj&RL@QFW zgsgjBquvu*#BRsYAd)G>{Z>vk6(-ym1VvG-Y--gg{h6-eJqde+rCKhU-8ud!?&D6) zFS58pb;s5IkU*x=e~4ACjK{XzVI1bo5+B8`TA!MM7f>0>?%VrxDk%OE}u)Yeiu zRTuBmcM|H1QlnKr8-_?t6Rpa9*wbradq48Fj@I*yam6vE6uRXQYQnt#F2>+1c)ob{ z37Pa)7R5+(1e1iYcvTnHr_R>qA2#kyKid?TO)(VME6~)w8?Yb{c>NRA&&$-HR=fH17uhqUYtKS7 zn?f1ucTO>ab~KF91pSvmc{Ikkyp9A*Duu%7(0T;-ALj#1T&`SiTOvS|9fWjGp~TMl zGxl4cHod*w_j5rs{Jns1ncBOlv>4qJ`}gKby(B#JL`GH0wW2~kx-~(+ck))?9&3cZ zR54_J!pV1vLf*Xpyezm)N_RLnwE9H4_@O?(jl`(nmlMi*4mC_Pkr*2Mws(bnIta|o zFv`@01T$>u!)m#SkGD$C1EU}j_=4#2gmrF(@<`(T- z@Gkgu3<=m=bBE;uGST9VtYBb~slB{jN%{GiRRX8&g|XJ9FDTI-72 z+S;myog4qq+MPoDDYm{^=M^Bxc{@qG5>IBjp__XR15jX{*Ouw50LJq7Z<$8@iqoMu z?NiQ#Jl6F5a#2{Gn;&nTUV6RGzK7sih0f2WMiU`p1xr6wJ>XyEIW@OwBlnY*P z>t|**vY9!*eF}qh+QTOd5OGc^w)>UYe-jWoHp*jPMw&~EL?-1^)1)b(Ns}@Mm7WTR znFZ}zMsts;RqB|TaSK#yF@iXUEw7>6Ci;U~Nhm9xVwgH|3pEQGRk|Dw77d~WZ40D` z!PTk!5=;iF2sSx_it8y){! zT6<&_z57E&LiVbNyB7+JJ;81Z>1Z!Ny#UEXN+4w+6ID56q(nwOw@nvLfkqCYR`7I@ITrrr7Th zeG*#`&dtVS_^r)1UY-)RIR2PDlt!hfc_R@7Zld{f9~>gpk8;8%21kQ5O?8=Iy&)Oj z5(?^aN15M<9`?oRnRVhtoxAW49336a5?S_9psW*BYR7_Pssc?P7$9?`+}aCs_H;V( zmu;Nh>*9WCT`b^K$y=d-a+nASW|p8Xwa~qv92}(<)*7Ap<4$02=Y) zYTx(JS~RJScCOm<9z~-eju|)M)Z5n_vH-RlEjwf2X9fYJr~M;l2~Z;F)2=P8KD7HvRw5rgdgm%?(oaf*sJ-*YCRp3) z41tAu(e#=|WgV>R3(ofBaf^^XOFk!F;wD+MSd@NDpit>Eq62V9g)eb06|W&Zwsr8R zdE#MaxL2ChORQS{yo2;XB;-nhfZsFNs2SvcVpa9YC<`s&flJ}NdypQt*HP}z_U}d{ zNv`5k1SdGZF>9H;o!ruk&P9MQ)(!ZVK)JR;YaA}x_Wa_QNb5kyW(@KGS8CfLbaihd zk{h>mt}?*F8df{!w{PRZXRS$?y025O=D%|6Moazf@eanTVn|&qq&E^-W11I*hB`y! zE`=vK#NFqVK8`n!mt!}O;33)}TDE#E{=k1Vzx-}_T}u+Czg!t(7`+ekxa%H65Q7@Q zwo=WjwQQ`SX}D?tpI2I+yVx#-TAylxTCdt1mXM@9W#Z3_Ld0-2-^vA z^dBtcwoUna78Y7@rhMD=n0NE7py2&Z;pK?hjhX?U--Am`)o~2Tj(ziS*OnV>n`eVD zA@eQxnuu~_@^Dms0l-XpC#@MJE>F=dyUTPT5!=7>s9|*adgUeVJ z|KV+VRriRV!|vkR3&E0uW3`xYmY7gO-@3*vpZeOcf}rJzRM_t`_-Q+5{P?pn@}Q46 zH4-$PJos4%Nz@rKPneKNhC{wQ7LYDosIGUud40@)$z*cYJ{}ha%Ve4x)ChZZ{TfqR z!$LGLAX@BUqZ_;`=X{>^EC3~MEB*Pd7MVmn*jIknT==|&dZEQe}{<|S(OZ;{wh^ALpS8Bt}W*Y9fb$mA^jFYiHhllB66A)iNYh~-Y zfeXCp2fcBVqM9z>zZzmMce(Fj1f0g0fLojBRQX>=S`KRtT?W3tU=&(i6%|&Ezy#;C zNc@@S>36~dyT5Ipjz6f6C#HVIFXGtshUkZ4jYK)r>>>Vzo{la|PyI(9u{ZXZqXY%j z^8-FP9Suk5aD-KgGek(3oXzGc(wj&ygLtE>V;yrq%F<6e6dh@cRG_NCuSoRi%neut zKp2_AH$cS$zrxTL5fhWektWj25UUFw5&6myo+kt@geK0sFW>HVmCFd*XZH>pDp+L9t&( zk)GT}x?ZhrN>$nvrwWZ8if1wlnoSzG-nW(q@c=E$L5$%0>Z;t)*lOwk#FAbLXHRbT z@?Iz!;C=pb!45@w4XHZwhkWx$AJRO%QEKSG5noC*E12mJYyu+?cI4 z1lE{<;P~@hln3zzL`eQHH~FvN)&JC`k8Cno(yR!5KmDSahIvbskJ|&etQfrT!p9^Ml%|@3&LV`E0(j6b@ZS{j*P4h)}0WtGw@ShW4OQ zXVws!%$LOU{{3ks{-XktUdJ|xuDrx_e?L6f7J;zTOD7jRwou6IyW%>~oVeg(si64H zY=$ast#Zb`4liTUM({T0Z71M_|GR4tFL=-wJVngKUw?QY>3)7ZUa3nP&uRCRud`s@ z3BUe3GoVycT^rs(J;(M*dBMu^r>p=wZ0i|h?o6$uVLZ2oH`te!c?Xh-#&eVj_|{hc zXCWW>_FxlQ`1sp*j7;v(>Rk_I6v1<7wfjbNepxB-G7%OKDRtG1G4otANCa^^u^$&?(;lJBk7EIp%jFKUps~bKteLIA~tKH zgs3^0dbaIHM#YBBU-P#E!8*y*0N)1jztnf<+~vY!CxubNtErVC<T{AP;J-+8xwb zO^0L;Uv1nQ>+7rU3mlWNeku&Cd|n-%HaGq@16?62SK}A-3r%MW&>L;{^X~!`*qsA+ zg*H4QN23MeD@nv&0e1C?)F_Ki8NdjbB#22=7I79Jd>u?+tQsWUKJ$)6Uaf_n>B^+O z62K4sR9bxA3Qt(47KJv++Q~uChL`5(tbFzqKm9^|zcjXrm>n8(; zKT_>$9CCBC%AzCI|MbG=E>_{{Ae4{Q=X9sl$-&t4j?IQ(%93nm8qH>Aqc--bPmzcd zQ5d``iu;9^ToeJSBT&KX;}|4eYxY9s){lN*Jk5zc6>7?A$G(Hhv9d$xIQ+;#aFJxC zfiG(oX59&-qbauv)LaJ)yYiN3lFEQCz5Jh5m8l^W<5dz_KT?(Y-(pWI;+N5(95g}b zN=wUT4(8VYnxonfU^`(H_{wO-4c^XW^Bi+Fo?EX;&erI|bv!OEKJ%UE7H#vvOw&g% z!I4HA6 z*gX&DoD}fjkV$*<-o#`Jta5tsP5eL*JNIQreL-oRGjzZIuXznx8*s@a9PmH@d@pz2 zwz7R$dB^EZ&S}N*v06h12aEs&M+_DUFLm>#n?c{;ZYsYGKRuDI`W}nm*DB1v`>1+@ zN>%=^NHiq4fsGjb7F)Kyg4mBTqs|sPgS-cHG6J)UXU6*V2{<(T{ojIuk-pvC5>}*+ zwl+8z?IeA}59Qa9@X$e;UF~E-FV)5f8#0Ny%u#f#wLhuKmze*m<`1W2eu}*&sryMA zk(a}d5}BsuaOKlU#^bfMMVEL{I<)3TU;(PLf`5InxLCpSQBguDs$}7K2ewmpCa%#F zF>}ss0+}=!vTWk3YLE|S!m>;9Zf?yj`73x9?hQzKw)L*W0Pi&gE1tVk#&=+_d=C9d zX_s5T>^7ht+edQ^)-J-P8yR~72Q_t>Y`dr_;9~o-B8W3!wuD9R1z83YT)ITsvNSEj zWL;fdGqa|89bQLu^AG;$G2Ge$T%`il)|ysNaB3rcumt4qi}=0#gKE3)h}iPF2X1c( z0X-UUi=Dh!s-+2H_V4^ehfMhgmOntPHYmn2{p=pkppvHg@#-{cc8FF7_?x|tk@IUy z{U9@)yF(<`&;A>M*isfEK~v9CP0hi}jy4YSU82SFkat!`_rhqAQx;RfoORSqo;47g z{Id2mJMTl3giqmm-7H~3JKXE30K&9!X>6?}w9dIo0?9E=V}Ii=GXFKix+hBJ%JA}f zn%MA=V88A&S#k9M)ePe|AmD*LL{4mBQ5Y%AM#4nl1|yTNk)N81+c_z~PhO{NNAU%( zIGjX>ofHT`0G-=8yKkr9qRwt@m-q}CK3~F3^r&`Su$5?h4*Qa*NQ}ekd{F+^4CH9Y zYUf`^ClgmTLWhOf0AUq8qqWAJec;>iZ>c#oydRpJk4cQz@Si^|+AGSyh6#ruXO|IS z8)nNsxiP9x44oQ{yh$$+C% zv7cI@eSuwrv-Q9KA`0jOE;dVgFL_i{rtORZSwBa)}_GClzIW1hPD3#Lp%GWuc zup|8~qkz>huRM8p*8sV3xY#m7ARN6kNT4r~2n~_Z{VX$QTr&vwAi^0w zgIw*SdbP1^;{xE%Ou;I~by(70Rj1>I_C5%+YYtc1h`Hs}0QH zahAzq4f_^74V&#ZrZeOK>Q6hb*ZOyN5nHyYCtszW9PYVs)OiR*j?p3)oOb=au66bE z2rDT2O$NqE>D&?TQdWHNWGPm>9dqeI+Dg8nT#R_uXs|rC`Exxel+_gqrYAviGb3~O zVc&?DK0g7P1#fkncE5CnFRWvnBG-`V*||BM5-b85%pL;OG{OZXuwY(1`Dq-=>BpO6 zSvO`goFmoIW6JK<Fv1EQPkz$;zmt9N%{51{v)uo4j*TCEC=t- z{1)L(vdE_fD3FofUho)$IL_+oECosLAs_-7*EWAooJ{BDsy*@ItYx=(&^;U786*Uc z*UV}dj6mkSI<+H}SS_Yf(=6(*RrI$D%_lyziTs{T_5gVLyFPj3Zj)!g0y?M@PzyKA zxj>(W&|rkY6q-O1#WzfmZx<`UlD63G(gY{M20%kzoHAdjk^96S&->ZM)juaNXv@cr z#oj&`0fZuN-q!xFk6Ek*_Kc*(DT=&6P52eALVV@OLgh&%SPt;Oo%r%}#R;k|- zP(`Eb#XL4&felO^C<*}^uJ%y&SQk(4jTt+$YD}8#1-SRhWj^M~h3#e3&~i zp$zz>zJD%xK?O>EQ)l=}&RdEMNJA*4{JWImLBB2+&|F?rMqU0*=S$n4yE|0pRg%pY zGTRGW6O>x$;KRwNdx~&Hbc2@V|MA?~*B&v*{7zs2Wpegt`pbV8=k;r5f4|J@kjGOM zF+}3ieEj4LU~%|{hK9g44ctFDh4U+7I<6@o*llK2e0Ub4{V&qTe3Kee=P|Y4b;p&;hLT_*tI_78MMAeb{MO zYtm_Qg(;LZ03&&qf9m>QK?u3tS%;1Cn8YT?;)6UFXvVYvT@yZ?t0wfgElVL%yf77M zz9;LwCWEj~jYF#B`>F}ux9rgMzkea2W@NNzZ?a%w290R=(WV_S7vviBHdBHcwBb-_ z*?k%@mA{e_41l~Qkk}AVO7S~3Xb49KbW6}En5#krAY!*fm;A1IcEOiT zJdh)Qcs1+FyWJgu0)Cn5GJ4?F?s;R)uk7CT-OhIVrWj1NLb7V8rwLIl@5SuF+|xZJ=I|Vk-)oH69jR5MkGBTPxsD&A_@g}Txzq}D z6vY!N$Ui4q4JJQCkMrYYzPx^5;bPEfX&QKtr!faGI`5;<{s1cHTXslr&^r_VOP+w| z`!ykU?f;VgGhhL4P8$NyyqBIol)JIL#4~NSUQ|y12GW4=8*(Blrsi$Rl4lVT3c6UE zC%XJ@v1Ui1j%yB4>)6NYf#Pnzeqkq;1dq|rf7LADB*B<*PyV9CaU99}UAShM{>MHe zu_fhXs*7Wx=chuctn92-k1$0!@VlHCtzSbBZozAJa1eo)kME}~x6AX> zV|T~VGqj%|H0E3r4aq;}09$>(U1Ail?yOH0;QDPRy$`xW8aB4p|2un+0_P}LKlz^=q8i&(AE%PLIkG@9+Ek7x+jlMjp?T3%Re!|AuU`mZ37iywIif)91s zbv?|JHC0F2y9{QXo9Zt8ijzR>?QxuRL7B+ZXOtToD85CA`zCQB9>o}!Tyh^I=a z13VGE<7zMkB^5KfO_3>xvX~{|(-cT$T zcn(0M{_{fQwgA?rN5$G?7({}2na@V5skrfGxi)nXe>*XYS=61mmrvu~ge8%l8zkp5 zTlTt^u1LreCs6nLvBuyN-ou0f9TdkqqJf@0Czgj4o5b7+5AW>E3C_45cPqt2_ZEsI zw?lF&EI)p=CEAVAU)K;zp+`gjyD4Wnb&egB?5i-9X$Z2lp|8cBFo{(d#Cf!mspX8` z)A7oC4!DLiq`2qp(Wt1Zo`QNHVed1DNx-d*-|1lb%~3m@*W(@LuYJp?k@q+=@79fL zBf%yM@`6GEE52&i*m)Rv6ny-2A4e1dFh|*=j|*nP7c`8k<6tqp{DS~>T~%A#-iiKL ztmk>WDze;ut&@8GCzD)^-1{6+ZInpw>0d-S-oYDt5*5=}iRSi@D(3%{6!~1DdKF9m=u7WR)ow$hr4*+0|<`);IeO63s8yEtK^=bS*|ECY4w_|GQ2G9)g2zt5C8- z)GPd_3o?x0Ewy4)Hid56drNPOE!qjNlH#+3o03T|EmI&`Id>r%>lsL;gLz=`AR~DH_7qy zZ4(C`ESk@u$Z~g}2_c!K`ORMwJaQ|2U`>~LeBdvpT zf-hTnm)us;p6yIKPzvnHFJa_NYAWN{6XKajFV{4hMw-VoUPWgsX?0PJ{@ZwLXXGA+ zb#we3)bqCYop+}K6uw!0p@lYIym6tY{kRJt?Lw-nl|2MM;7IR_*AcE$(sx}Wa@*Dnv}@&`dNVDHt{e@@&a z7?GPz_;>%o;}w_xXF(K}uce(ENj_v^BYrO~Akh!jT!5&Szjkc#;R8DGw07aqf;MPT z+v7LVZ~kj;_Uxy6h0MFV?6VB0dys}3J21TgKqO{ znTFTi6JV;$dBPHRY%*XZrp<;TZS}EhF}(_DURqij#o9TqHwBAnR6$Jf<;BH5@U`9- zW-V+L^6?9M?ToK75vKsphEHcrKf_{<7FJ;dlrR^bw zi@`y;U8)cl#|miSn|O@Zr;nf3wkCQdnyAeL2R(ST*DIM7^sIsjt7>XY!9$@=%@}H+ zF|@No^T+w`p0QV)Q1-x2+aU14t*-u1eM^77Tlduy?*on3YHQu+ATn5O&Q~L0W=a&q zp!5-BHZRR~$>(fnT+5^*jC1!Y;OcaK<32u#AL@jZK|Zpw)lMCvR5pX|Gf&T#>K_#v zEmQ8~mdTqxY};e!a1IV4psT6EnfR(=$FVh%>_)`hJbI55%I?=`PiEapX?zObFrEJtRT9)w;(XZ4=`9P85 zBG?&&?Ij2-L|~gxNp?;m11ro@9^!*?%m@zarjX?0-Xs`R<~NVMXJ=Pj`pcBB+cVq4 zAz!I{1{6|oCS7S5SuvY+@)Ds$ZCqU7ykzeiZN&JQ!o}8?ob%S#*LlEG(P8E_Lv>pb z`S0Hczq1j#n+fNDLc<^4$F6dcIzlLhRTG8u6+cvsSsV*HqtWJLF(k_beL?Za3qBqO z{Es!PcZbLV!>k*_r)`XgPi-&Dg;F*(7bh(YaavjD(BK71J!Ne_7a*JAY@QvUt_42- zUVw|n&0Kp`UlMq8LIGy{#r)VI3rA;Xhgtxp2U(;NMx$f}WCb?@Da)oWNK>OfQ^7D^5dWmDs5pVOuc3sH|xj?zPwht7v&C&&Bxbkv=|Yx^RZaR9-`p zMZQPb6NvDj662n)BjB7!oj?G!E4!snD_okK+%5^f<;Y~~;9wNC9ns2eL)Cg`!`pmx z#${_w?c^NPn)QMJ_RBn!UR0E{+};=o?)9wlV_r4hetLR|k5Z;)78a5V?_HU(6!9d` zYJkD>u9JBTM7U_rP#r2GChr)AaABdU+kp(Fb9t{Uh3d-#^aEFs^(M0$bdQtKMR zyLAdlPsazAy!rWgHM>w|hYT~}+@1{a9hawuhM%^`KBTjU(}^g=;{OGouURTiO%U(g58deu0xT!PV0<9B{Q#cTN_m)+J>I4-P7v9(ML@V0%L{>cfLb^}oj2 zIXE~l-db^u@Q>Swh_YI2VI3Z0$u+svS9OcH5w|^deWd4K=@0HQ@J!QGOz%CFs z#nxt_h#L6EdP?_r=tk@Bpu$MrmMs-4pEV7D%>UAuRh09*=G1H@@Yw-QWAFaAN0k<5 zHY~lSH>i$SwIv_p8bbVj_hjEh1ZUwP*xlGzs00^s0K+&2gY?x}#d=s`;qsCvx}XON zjld8^2_mqlYi%u$MT6DGvdp~Uv-WOMPpvQbX`8=Mb1qXE3=}sHuP}Tz<358V!ns3q z63|*W^2HfEc8W$uU#Zw29%Xz)pT8i}rfjifZ@3rf(-KEZj&AyYRQ`i{0oNcU3o~%* z7kt}swpl?vCu(Y-ANnVR=CDKQ?Rg`!)wVVcB_CTfR$bqG!!o+nVCe5%9g+XeI|e90 z+#BIcNlVBs_Z#zIq(3_W<2(&f_zua|P!E{b9i5L&MOA0Gs_0Q6H4FCKVd_>e%+qLq z5GCu3aeA?TeRFkKd%Ah67>oEg8aTx<0lTN4g}t4=VNMWk+bmS~pIX!o5PN^9OnOdj z4{cAU4UhRn4URc%^}iN-SNdzVWekcMhK%KYw_5xQNLms!6MIEd3;!eg%sM0z@w(zl7)^4qTg-PJKLkaxu6;z%5aA~*Is#EXYm^+Y!E}_vOywZiMUPmb^-xARum}H~qsXw2{kehX z?)K|8vqV4o)G}nsKVc4$=5{uXAb}25G|a4Mlmog&k0rJw-8S_NkKAzT)|-gubjh+7 zcc{KGmZPPk1=x5~FI>KGJU#4*6}qf`6*ViMl!ocT9ReQ&TW+W&K!372p!6*GtjpxQ zg#A`%(We%W;%A52c8}(!rWsdT?_6R~{q5pp1L~~re|jxHP{D39;zz9;7^YnI za?+fSDt^xifF2W`Smqf!UPFWH`X8H9Uz&28@aX7<t z4x`}axVoAJ!ML?QWE<(pIL&I2ue!Dtyp~YEyDqJ)%=Butue|7NcXxs?^qC=}^}s3A zDy{X3rW|%kG`tfY$)dfz-5&qa!UtD008T#8=V2m}qk-eBozA2%?KhA98}isK0-hn4 zqLfHj_@D;g8zZ9=P*i#0j7SFe4eh4hAy#07mb}0GBaSr4zUW%)fZZO;Utr3_lulw- zE=0~OO#CI8;8yQZFAkFrE~;Z1d`-a?W{4Rr%Kaew(`P<)TsT|RZoWjrGK3Xffa&Xd zk2;GrpD#ugYy?MTRqq#zoIEmMQlxw-^NU4@zAj_(jR5>%78k~I!sIhNkV0*gY&65v znV(YVImr)Kl zH*}S2uDhzU&)h?t#;21j4zB&uDkQR^CTF2g#7+K}ZAh`NWhpSiD=N1)GXFyV1CB1a zZW!o_qBd5Z?t_q}_V}|X7yy1mq z-sHdB{hcC>(oiv=1;8mAk7*^40;h>^W}0{0%U*aafBhv3@|0QptC zo_gjfCF$tJsZ?iyo0~^HESBC89n5AVk{r=g zO4gcEQF_W@u3?~cqebV7A6K?{(g>dCtIY5hdJZxiS_J&IbZ}oP1SiBS zsA@QA2awEh&6FZI*^%GAqEyzb|HzSA%XRKfAXCT6hY{IN^UPwhBc7k3gmO5TJ2RtQ zpA7r`c3Ul0L)&-@43}FX`c9pfp0RXr7~nbEf7euQVUL3S0T=A2q33&I{MHH~`yLn$ z=%BXFz6o;K#_U)`XOfgIh=~@GfA*70yK$YZO8%Dss06ic6aXYZRvA+&ZqLveZe{gt z0X){)bE3;^&qFQ3SyXa+TsfBCP+7~Pc$O@D`ZFwj9ddUV7QQFeX%f3Evs^1VE?Ade z+_G6V7%iEs@`K)_58bydz~Km_wMHDSl()RufO$gVyxQ@C893b*I(78FJ)i+UK+u<} zj??gAUe}hrcBEcur9i~YP2W&3LKQ$bKZ2PgIOpF7V5$aL2s6PP+b;N^g7JF2@%oHO zvk-AuJDB;E&Yh#%dJOh?lAncMfAG|4vk(0S0cPPc=s?dwJCr7TMHzR!$XImpmL$Wc0C7axR0*P<2o49Kz^vN zuivQ3I*3pDrH+SzfBwd$(3!&>k}CY2bt7@WChk{r^1<7{UTlX`@bj_CaytQVS=aNE z6SZ^HL*^XqA0dB>g|H)cm}};5thkuU%1VMb#xeNabozK#*MRu?LpmKD-INW*Ix}~7 zO_&h305J{p0$0^Qm;qe`AWRCTiVq8-^M$u+Z#d03u*3sgp5Y%3bi4ajKp&noMKtByJqD)p zEc<31vF-OPf)nR zS9ksmpla$V$?dT`^y=nT%EI3tABGMW({Hi#+B!O${EE6W z7Tk~scH#FF%4%7oQi*kDzdspDd}Mm0tEJO7*BU7eh5>gGeqp~*Fm{0m%{pi^k0dNl z*F{;a&ut$e-{s&ztT<`~@4cs?=NmGwhZ~L;W@Tq3N1qfVzshk|60-G~2eZYAH~U9! zP3>uFsQ*<1Wc^%t2+YsW7=!8vur*um^u>R1nF4PT2qdZFeD`HY{qW(#OtZGP_rkm2 zeij%v;ZT?u=0VCawG^7OhMu3N47s9@5+jyRjc49EIyx>dx^tJmVRd4V{U=Cd`Z$9y z-Et`i3H&xj?@89Jsl}i@S+nK7`1H^gHk8@Vx2wLZAw~+k(dAen2Yie;Wkkp!Fu%%~ zCI4REgS)Aop`m2+(%}7Zcee-H6H`K-_;em=;5oPt&+N1+)$hGZMd2YrpKtgLO_EPC zwii5g`=w8d1jpG$Q5P;v5az>G7le@iqzXPFKIbUEn824>vO1j7(qNYR!+NuFCukJp zQKZ|(Ng1Qzq6$4~1=)C23`d?SP=yyXkSx^jXbM^uoj!z!Th%hBAV1Zkz~!I$!yN2O z1tthjia)0pV8T!p97}M$?NBn*MPDZ7!M@ez`N2w4KW&(pJc*b zK}}7bb|07PcYdcyB<^L2W7%E7d|y9#^~!0>QrxBbR%x%smn@Mee(J;0I^A2|e83P*mPHmzAgABGM>6U47n7c(}-t=PZ3 zjY@=bX0O6kaC+3NC!L5?4k`i`T zBcjuHA^nAQ*Khj=!DDJe`z=wN>u;rhyYm270!Zwj;jFmyh$}h}5S^)`)Y2RIoxxcP zoI;ivuclP~46`F(GV&q+!X*xDpwZOo08d!_4*gYRU0lLymQV2af=_~;$aXP{eIO~V zrxnjKA{`dULqh>ekC;D4oVrB9O#f2r_rY$*^Z8bxSi2ddbeu zol!{rW7K$S?oz?!#C$jUZ(mw&SlqT|t=MsG!gzFlpY~+q-f8`~u8!5o-#wa3KN2G& zW%K5OZZjs87c^+_MH@k(z81wCVGj?13TBfW2|{f4GiC%{96&nV98quWO%Q}NtLkL)^aL{npE{3+)`W(6~;+G`3Odt+QE`!D^r$x0C3 zh!i!vP`u0VWk&M$?2$(LulPnutbe^}5Dz~%u;FXl4x!Z1#$YuuzxTl~=Z^S9+N*_7 zcm8{iDO0psGMHSli6LZ)SwXF%Y^?7WB`Ue3QK*n@x9OYfwTr&b(RTwos_yjtDz-_b zjbDK+*yxYo2-5FM2QQ5G_HJ2F=Ef9cLmiH$fAimrs}r=?C#mPZ0wk80=04Y+J|Hxu zTV%db2Nzar#^fVV9G<1n+JotoYxP=GHAcdN;|z4OXd3E_|Fh!|Beab!0x2n;Ij(o> z=+L!!$}%)-v2=PGU#}$~$<@6;f!^IU{pNRYzyT>4Le-Je(7|+Vvkx4n$o(2Skc3pm zCe8EKWl#_T7lCBJ!O97LJ8_CQoVX#OfcM$$p`WFoNwbP!WkhcsQ0a$N8x?Kwd&+XDI}hvGq*g3}GH9iMxu8^4x^w>E_ub^Y|x0mfhz zQG?E86p0!*NJVyB9R)vy%W0*FJbV5~7i$q>(;+VRvR2q9$mcr4UU%+1=A;lLBef3i zcQ(a`cF|+5!BW{p%rP|hpF~PBg4#5UJ`wv9o4%AJyl}=6NJZQYa{2c!vzmM|spL!` z@PkQzi&o*R33q9bnnj(jQZp$&R`!*+{taBCyddn(k~q}4(} zjo7xO$bFW-Jw)K)GObULOmFu#hmYG+@(ZZvQWWa7eXyD3 z>hx&gFriMd(#554QfjHPHYWM62|}W5(Jz??CvVM$otTCB>VZ*HqI))wMSda2?J7KX z`jr(oG3z$*Rid#djl{w=-cM}Q;A%npD{nM8b)}O*wgE~7_Pi-P*w^S0zy$Cd3AT00 zkR(2LxZqr399Tru6cUCz)&@ANMy`2SbY>qrXU2U84l}300}Ar9%YtWUfFyEgXrh|0 zuj_px0@M;66S>V!z@zBC?)lJ2DI9D@?C4BaC|aFTkp+YM3q_j8qr(Mg-EjKWFX}!vs?_+t%M73i|Q&-tH6oUM*@(U3_wdOYr??;DClfwkcEB zc9Q=AKRP$Bz*sPw&o&5q9Qm^E=yww`i5f1UKn?!WNk+ks^IaJLARqqs51)s}8~7RM zk&|Y}8(fy7m|*oSPYEn3-|&Mq;)`UDbcekg#irAK@z7 z+?#|y42`mfDRR=-gd(woW?qT<;t-&o0NItEDL;l2IJi0F59a~pER}Gu;NZY)e$1M~ zk2~N`a9mT0X_wcdI;58E>!=^TcMn!1?QXsl5iusd#<3;}Q2Wzk+>o+L(ag~YF+#2c7#*W7hq370$1Lg#2W@iK*g59wHXBQY#x81Q%&-d=*qk_ag@X<8 zlQ{6n7;y%_E0h(KVEUs&yRopFGwUW(ocHTxEv?K+i$?Y@^uXScRG!7`-~@3qa8xse z#(@RKic?2t?^@w3xnv`ryaD{MSB5a>N-ozelQHs8Ke{N20#m{!8s5Y9w(sR7djyxD zPQZ>U(9Q0VaimE>^9+~?4w`WcnF$Qq{eGI3vplelUIjX^Nzg)&3Qn7!canLgCI7y4 z{JCAwp>L2>c6)(JlE7^@syVHI=np!JU4PDAki7;@yKS(x{_oiH^o#`S^S=mw=Xh>T zYIrCH;hmM?+YORxqv`e|Ych7krZ8NeaHBZ|b4hg8q{+%}-1idSgWkO=HXyXRTYtt~|r6tNI>AwdG_bo1#UjEop zEpU(*IkIexz2h3?|7VZbjW-2dZ9OJL@c{GeskJXJ1#npfcG zjP@$tRToEDNu%5tW~AtuQw~%KKrA#!ZsDi`SI-sv2imY z44)S_RAmt`_e`Ki6w&vEWigkekr<`3#Kq#Besynp=|=?QX>&F72!^1b55L}jf#TV1 zd0*IRP&GIJ;2tIoqfY+*hluch!_Y}auQSr+LDmjPh;8=AM%``kf-Y_`N4>CxI#QUS zHpJpb#0^PFra2Zn_k>cP(1T>RDMrVH6Oic}4}n}!L@${fX;u(xNC6eeO{lY@;dW;0 z{RkE|uCCO5`NZkYD=g~ zl;Krrk3V+iIK;P(xMsXF4&)XJsMNfjtRl_N@($9@{egnKzWxEkV+M<55`gCr!4oV! z&t_%Fj2%>3n{fhn&ys{_PR&iQgh748(J;Xk)yb8&{OG5P@w!><-g7@^*&#id83$nE zfH*ok?`U5xE4L>Xbv9DM7`+SXgTIOSeq^}yz?MAjK}Bi z6HTRjdik&dO3#hMXL8TlM}x52-y@(`W?>3A($!5@!t3uUN5}#gq|8jl%3j?11 zV-)sGA=WasxyZTLu*Jy(+V0nn)wPR>Wjk-@?OIe*cY@xnU>}O(Q}#jBNcb6oARR5# zVg|SZag=={CfR}dHR*l2^cDSb^{2~{Dqq=>ufIZ`e=jnJPE>gh!~{bJ;wUBLFV%X4%OAX z%_wK$`!E}^va#yMtV17|SeD8W>!z#d_&PA3t})M|Nv9=f9uEUG7)-iBCG^pbuCAfr zE)PZhky~jA9!vFEx!&t%Z^NWE;_F|N(I!aRk4#ZV`(%*#78|I%#-cUZQ;`CnGeLUC z-;gNLfHFqPuL19fJZz!qj{a`q@J(`q1;>@Qz8~PA@z`%|N~xK#@=sBydoZ*PpKO}W zQ(xQA7P-h6QN+JtMi2K9JUh?EO9QSxq}u6i>ZQI!s}mdMJQo z5c~Le4ca{?_+wx{Ps( z<(JF88zJD$r%Pmdq8z!HxcuIo!8<+&yi`Nu_%|15JUGg7dLGfa+@EgO1Lu z&#Z2zMqzyg`Poo#%y}@NE5@P0?T`L6|6@)e21)P3sKNV^mm-B9gJ@3OQI`EqH@M7P z$Hd%RO6lym>f4{3<+}5Sh;rSPGrsd@q}HSs?mT5I8TRa&GW=D!Wb!NITIO$zV^%fc z1Kd5#CP?r%IR#ppnyEV9#Ir=lfQAA@F1CCn_JSB>3XkdcwhN%>nJq^d>gY{*g$Ysu zub3|WM`k;(e6O0uzFm#{WR1oT4{!{y1JOmQg^Rt)H=M&ts=iB{daOHFBiFiBa{UDv zaC5E{Pnw!Mm9Ok`1bA~N`b?wwloJK^E!x)8d~r1SMU=4ts>fAJ6BbgpoVf7&%gMEr zg?QQ%l+?G75YuOn5R1JTfMG`~g`Gp{T7x_=Ry#5CYqey>+AXU3dz-Bk1`< zSn%syUZRYxZnG^J`S_sN+8(W}t`0msy-pixtmTjnzXCe#?1SVRZ)k$*s?j?vX~z@i zEHRRa;Uis^eiL@BB|gY&XCU7$k)_^2%@`x@^80zT7beC%-raRTC;K{n=(@@HH*3@K z{yiIMg6k|wguy_Ml3JZs2qC&OevIAW!`z#+Z*NTbKWcgQYBS~cnw6jY`9p6cTj$BD zV4mXT<<$FUbOwL|~P+Wec6c-UV?oE3Fk_aOEG#8gzj$TyoGXi>0&!-Bl# zIz^pxa7IZMgo>D8h5&Jj>c()6;f-?6ZY>)0GmGVD?GxWuBo*Uhmn2ZA|LnK=Eerg^ z5im|B_{UJ7Y#hE)8l)H#K!W<$en&I@3MO|fG>QU%@pH54^C;^0UU*XW5hBxiAKOJ*` zcVKFY#Cr6UrplPd!$jkDIsW|5DyL%EB~4;ld*;3%oYDce*9OC{iu-1AC>3O81T>-TVPZfxQ|&*{e9&a2Ffd+ zD$3OF4G{Z-I2+(|02~8@09{6a2A+{kHr_mH&Y6=%W6cuE+)ysK4*4C!Of0Pm2lMA4 zUU+jI0D9Wy?Y%|w2ffw;(?ji-C8+=921FjtLg3p0@P z7jeU0ru=g%7wCOO%Vjpv=~~#39vP3JQN_$gK>$5=V9fd%7^p5L1n>5Rx-7Bynw!oe zXc>vK3G5_AiST~`z^VWgKnp)VxO914N)r+~F4GWi(MN-IPf*)d&r#q6i5j)&{6t3G zOm9zki*$BGqCv?p3j$_V**Wc&mqFq3hY{fRV*)w?E4y?}OXL9L*nQ$w*bP&P;v!ek z_E`_RV`|RaW4kreSLPU-nLd~dtb1JMXIF8{HYd6a91scQ1 z)TuVs-Q2-WKNQ9E=;-Co+P8tBx3>4lA%;38ypPCS5g4_BS&OU5As>|1&HA~5bDv>5X2Q#BvWnd^+misSdY@E_o zAdfPZvRU9Y)M@TtZpZUVwW_0*ulK|0sYnQS5wY?--ge}EI`1%H8MQ3umE4niNy3&_ zeT5OK^%ZmDiLt1oi0HDOGn z%kCRR(&y)u?I?#P5;}fgo6X%l zqRzj$-oDjodItD`Zcc0LS9ZowO?CyG1b^Kqs7w(M8uOG2g$#NnC`ZH|6^VO3QM z1XQAs_rMkA2R4ya4(zLO4<9&IF@W>MdP%OzJRDDa7x5gb(Q}b zRHP+5!fa#;>&sUYR@IREE0IkLSQC{_HDEzCI?J%XoI z^-IthsY#i2`@S2&{OkQwM(lC*@t)pKWNb5?vWW!9uXCE>O0L!W)q(@ zPDcRZrX2RsV}@mW{+oSs^l@1eV=}SR8|LX*yB0Q*gc+Mwvy8!8I3WMWAYN+!uNNSD zFH@P0AOR`<;;CFI^4@a$x5+T37IT_;(4ze-5ud*V0oSXRE1PS{1x-6xWC)GE74(e6 z1WRv0)dX-`g8aL8H%7Pw$?Lo?xeej{R-w1PpWNt8UnL|MMyNizpKj{6pvr$28s+=B z-cNud+C{10k+%$1XKV%2%{-$nYQdpmf%N-DbsE!Dwmj(T+8>a$H5ioVT%mNl@k|;r z=dIpPIbxDetG6_Q97)S2l}^$dcDX^erTlE6AHKpN+V9>=aNLDx@)*W$H7k6noc#Px zjbIn;dvg;aruJBiIDLh7>ED#A_YO~q@!L1R1mpjhV+iu9*XK(gd^|zH<7>7%VQ`ZJ zdT~sr$JRfBlD7hOQ^+3`Z-V%m5Ko+7h!DLtdKpt&k{*EL3>fX=J&hD2Gt4)NSPr$ATV)T80O@8`&lY?Q3ItB2YUQY2`6Kte$Y$T{y(v9Csm=%moX}DvDB>=@GyVHwy zH%gx03x{EMQdg&9`?iCvoy|(lB-yODwY3Zf_AVZICAlJEXK%3-8Wq*RjG`fGPtz1K zK4lEWq*QqmEMJ^wqiRl(Vx9#JAWJacq)}2TZ$3FQpo9<~-siT;rU+^o6*Erl4JV|) zx*XI{V3&|Q_Jj3r1|L6vKY;1NSD0rtpI;PT|A~8@=HKyYGj;?9UZKYdHjeI_ojG6E@r;c)g%?uutnFgU@@ePlWU9DEM?x z*Y2bJ_Azk%0;^xg2D<;hCYek{*utu1Vgl4~ZT;gzF3s$Q_BM@4f$i!bW`(PjCIYPI znQ;4=yy=6Rhs)=_-iHa1-R*7BASSYsy4Vv5E+VDx-S+_eboDzW3-S^-27V>V1J(Q!R>r#|^T9E8F$hN#eH>~qB!NuCz()P43Cv}dlML3M zQ8WosMwLrba|#6rP4tMcVWHIDltX4RRa%+prkZ~i%2;QY>E=qQm5k&p(hS~t;pZE~l==u-y(z-7-;#>|9(&9_YhM0Ayz zS=)G0ol3El-9?#1YE+M%3|88g$r5Mz`;hmu6XVt~@+d!Wn9Lp9#9svMeuo+d4^neA z@_0%`lB%`7UkwN39H?f-%6rB(8}|kMnGkSjpwg6Kz)R@JzsGI-!X8^M`%XW*xQ;Hb-h~ePKy-(jEkcbZj5W{5C>o7t{13D1@rz+Y z4ozXaZA z?pq&H(xL(-e3+d#{v!duPCp#A9*>T>}m_JnVPf+v~vM3?+(dk`Rt5w>zZb_iX7LYWo_-1(Ju)oy+J2-Ofef0)7+*guR z@eiRjeN#)coSa@QQ7W5+s)f#Mtm`4mVNyn$UVWmiID#Pu#}*84F8u_w82#r^-Utw) z0pb2WPiFt_E}1dv<-7Ssso|ko2p-Jo=0@ku)ti7YjLiTHIg%n~))hq6@(BWa|glh@7lGH*)H{x?vz&eO&|@zu2+7$tsJv)h1HM3 zVrG^`#o8t|)TFNs`zOp3XZzoX;hq}>uf4ToS$1@=p;XgE-SiOEosDrO){q06mcHM3 ziER4dGYy+25y99>8IK9VB`c}!eK2J#<4N$zSLo@uUlJDBSi-hVl;{)882SV|2U(@v zI&5YqO~8fS6B0dJY>PDUzYu%ZgRzv{vrK=yju_gQKvyXfK41Fp_rr?dvfcyrfwWB` zb&}E%07rxH57Bg8U7c&O56Q&EUYfGZ7-#h>oscu4Yg^c-=kxO<13J;bIT*ReEgwL} zb-Mrek$}ozlLR-B<@fGuSQjM03r|(2pqt?Po`e0V(Z03 zAxapr5dxkI$m}!NDIGpRhE*78R;#Gxicqv)#e_9_f>q*w&eb--Sax9WE$8#SB(i0y zvf;8fa7lGqKZB5K7O{b z@BB$Q0nz4NZBW)sWn52vC&N?iUszJYsKm*PU#YADp@)f*!X&oXZ0>>LHD}GmoF9?P z)-bM>Qman&d%i+?nmTaVNc8gC7@19CZl$0KwxjE9$27Gsn5E#b7;iUAwn(3Xar7Dc*Msd)cLU`IDNJ%vnwsl?kpkDTJ_91LfTCZoYVa2qv<&AEC$Qn` z&Eq#dw9Tyl0!3(uwzf=Q;8x2@QEWB0>1c1?BXDqz9aF4WCLV7#;#6LZdPurI0;__T zrXrBI?A^V+v_!6undRUc9~KRKhCMnW1`@qQlTJtrTyP(`5+|t2S@=j7-bmp2m|ScN zP0ofdCc53#cXvnR|9E8hY5vegk&=Fd0wG2i-vMA}fSn&){P0@aFOici!v1{DkwWO! zd^|3B8dlgmNd4=`$&;1Lyt3N7eB^dD3|**@{&19+@5H=)_$*&A`%>b*$?r-2A-Un| z`^WF4hJPLTB#UQNAxU8jDE7hCzJ5GLz!~k_#5evH9a#Mi-2 z7tsbr^(>X&+}s?lHB~ySK*g*%YFKO7vj;vWz?erD4)WsLk@_1OUxaw+8pMW~<(EE2 zYiV5w1J{oT4|{T8WY#WWfIF&>qX^Fs1B&b`-?@(iG=i6aK>}l01@)RD~^X%J}0D7p3+tMw_QH$pC`zTbHn@Hr1fA z2{dKA`A44-@j&Terw?;5i^OKwGq8po$pakwnACgMT=tEtQY~guE-^4$6q;*X9LPS02Z{KpW2F6lytd6&%Q4<{Q~nG!Qm zE65R(%J@MqB+xM;XJvioUr0Q|t?M7VTfJgOt6{b?8{l`@!nO`DV}&zg zzs0sK>3$@5ywCJZ9@z8D9YeC7G#s;^UF*fi}Bi@>3l>mRw z&}`1K_F-+|qP_KoQeeGi71UD7r%s~y?L8y5nNQ@VL`Q;LTAv#RB^s zEAr;qqn8lq^O#A;@3@;e>5(eS6x;I15o{%3yAxPhyl9&!*3s+0&Q zE#HZomzfAwAcNvW8{qd^Mcsy*I>{oOIh&-dquI&C3iG@_wtKa@OEAAg_4x&g#L64rQ4@Xu- zfMuN>#@6=oVZ=6o}Bw zuN2Vm3HaDnT(j8HTwZnO8v?x7=3cj`Esp&qO*fBSaV!+gZ zL)O%s3QsENyNwx^t7$NOlu=2FeQox<6)dBQ zPWNB?6=M1oI`rJ)2Rt5ao!y+{JUm=Zdt+#0eZt!Fh@NpD^O|flQMf$fxWuH-v&cG? z+d-`VC{G~V+4=S+BjENGNC!;*F@n=H1LbTA58(EeD3@(w1bPpj?nMHEyt_L}QOe%y zA8mUIop6~$?Zv_`y7B@3P(OAsoEfrn1!e>tGro(U&p#6DWXkE#no0hHY*iwdU0BZt zhZs7WZDtP_pEqoWi>rzMx?yG8M1e6)SslqVwI1#gqV2SdduV-Eh@4d zPf-Rcf}Udm4ou>rO{o-GbXQYRw?Q4ZbxG|3h-b5O9ZVNg`M>Um6179tDMYQ^;afU2 zUq?xCR2DpO?*zt0fz*(}3vK2i1MCoM+ID*r6)cao=&5ueQRsYtVcrFNU2l=6S@6y} zoG^X(J9wSB(ocWv?o&0Ca=&G6)ZnSw+9={KP_< zS~K~9s2?fo+5nd2l43pefcb*(6a0lQSxnM5X&g7p8`&1k#h+P6p+12;TFr$SJm;8O zG66D1E%eBX>GJcqU_Y$m=9`BrDz1d=;o-4Z8);C)mR{vZ5QFO z%=;Khn-`B(MrO1eyti(*O0aBrbU;KUM{5Ty$&U55P%_$?gTeEN^8&kh`_6ps;j>BJ z2NJg!mk-O9fAT0(5Y5Y_lmiaC{NK*vKc~{N|ND1$Qyy?fchi&bruQMh^Y%h}dNz&S zahhVfw5epaV(?lhP3J<840r~?Mlo70qb65zw1!$T7hr>-Rq`KVK_3%W&d0cxwd44_ zBGOOvfq*l9Z{2MGXuph1VX+eEADpi~fd1Dtd5&R#4+mr~&}IZui;@LM+=OAVD67uj zV6&dcr(NLqZb>S`4xu}~ALV)~J1#BaiU;l$TBb`eN5kMICmyiqXZJdi8x zOU2fySlODwL#sg@$h1cTatqAtD-7Q)6UTHp3lu^S;e;|a$T+xX^t!s=>W)Ydxx)mG zfe7N0f9`mQJBcjv7m$?;Zu=?9*g1~)J#V@jC8LA}yeo-4;eCOJB>n^|SFQd}u`xs6 z@xO*Xt{uA8H-zN>z7ha!ub?WB z6rms!YlMcp)3#u*et5rnwdaq&9H15{)B~V5MqeE!3=*eP_=;hFBG2?ohToX$!_Rp|P)X_q)DuY$}3)m|?_Qrk~<;8dA}zl=C^{oML? zf&;ub0FVQyj%nz)t)__XDxUcfp6{UBV&^O6RCH2pTB5la5bUG<7+)M1fbvKYhjahO zA4wS`SGzza5e)ZQ+gV>wPI;Ze0ZE~V9(S_juNH{B&d!3UfCdBNayVe0vJB7mT;3l_ z9Dd+q{xW|E5Gzb)a$9{a)f$XId5UH@+x)_#JIZ2Su1ydQ$UMK-!2tjoM8IwFxQ6?o zfd8emD#1`FmYpCDJ~Mtq`?G&mo#Iq?cXy2q6mOP7+$%9_B#7U%1WhzR-zRgasV*o9 z6E@E@%v%AD1=<<_a`Ovq;wUx83DIeq;>So;8Xi)+qq@qy!3f4YxR4^XJipHwb% zrROU9?)eGMBI^$ac}n_U_1=)>lmj@TxDI%3*d(Fp!Si$Wr;Cir6ZbBJrnSB@Ei{clRgwv z+0}q(3cv>915i>ans4bvfhD1^@3UXm^~w6UJ58oUlFgANC4^8h6g^5ox|Gio; z;BSz0ux`X`c$!x8b0G#u${9Xus$y zd0GbmYgyO4Uu=Sup_*au%gE3jXfkr!@i5i=!79{YPDe(*^^XK>N8pNr4|uvPID5Pn zp@&fpbl8H2N*;ZDy6zpJEAS1zzdn7*$^KUw8URYmK5sa1oP!3mAAp?LZ^skC-fFHH zQk$Ga1%+pfWS#KBB?COgaQCWWTki(#?O(q}(Q9q2707V(cr#17UP3eA7#1|G*Jf^r z!twi7)gR`(0<(TSHvWUu0Bo z3;}_+sQCk&WlQ#aq4heUD2J+xj4Iace=YJoJDq_nY%ZsM;pNxZ=I_7Sq-C=;-JriCntLN0eY=dZKqnS48lt z!!|a4+G@D6O{h71;bh31Dapt&VQe^j{V7qXkPkuAv-N$P#{!QOIB(#?y2w(sj1b@< zi`u1V6MGr#MU^d z;0z(HzK2yvKjCh$>Rh!0%Hm5Ia^>{e>Z%lpL-l^e*E)b>&6ZRu$5{{Fgfapb*Cc9a z-v%R5BzkBKv&VUNc4?}!(MwY%@BD)g_t|4SErLjn@zPXq>>DlbDpTjw8V!$VK75BZ zRE!2~!%uP30fMAe%EUnu!=E8s6kz$Ho5?A?Vhy|kAdv^+TC(#R{Qyf|Bg%Lhairz> z2GO&gGq8|Z%msS>IpAU3k*&{@>#Ie#n$PskEI`piH!Aj6kKFj55b}mQP3ILtp`-*> zH`vrfvmvJ8tsGs$oiZc0=rac<=`|WSKyc4K)+U!RAdlA5y4Qo0j8E`Er$JrbClf-j zlxl^ynzP`1rq{7G=?r^hnp|Q_)z032uxS~XFP}~Bzo@*t{9sOOtE8v2;Eyk?0o4FJ7=hj3ZL!V&Mki;SM3cN;(uSLLK zR&wOv>+Y^?F;FHV<4JnooyP>N7R-`^S%BHksys^8-P#oU_l%fK7V3MYm?BKLmk~ zk8kEmI;W2yo+rM9s!>A!@uz{x693x;Pqru1%>fg#exDxy_S7QkU5UFwP(*&~TdSzQ zM(rNtXazWl3u0}P3Oa!%ZLbROj!DBor`Yh13Onr$$B{Yj)_Up2>-Q3~^78a+#P9rdDglC7 zjs%6=t{)qIV$1iEg;dC!xi*ZzASU>G=E{eBO&Nfj2@RdQVp&~}OK z3iV0^MLX54ILJ=fxslqf^Qt2IAZEYtj}aOXlx4ntfh&Lx!PUMu;>ln6x|}25Je?s> zM?s2V!C?71a;d70rPqF);JFig9O$d3qUzbqDkQQL*$=_ND&Q);LV|}z$z&Wk<{Ex( z7P~+jcP6;rXh4cAO~mstBbJPmWasDV&uN(PA4*dgBGZrhP!YzzAq6L!9jMLS7cP5; zqO^QS>lLC<64IsYrCfm&5}GTmaAtn4ogcdZknHA9lgg|OchdR~8Cdoe_&;9eN1Ew0 zYox^CbH9IiN#|9vladPEA%UpqKcYs$lZI-4T_uzlWSPd@y^V%9~^j+^IyE6hMJm<5*{@!>a>-I9AM2+C6WruFeiX z!|;d(ce;1R(MPj^A{LWx+)`-VwD_>u-|=(6RJZnR0m>vX^?)A$8QcD_a8Fk7j|j>9 zqv`Jf7Cm50;NA4x<)vu?u&E*N9@A-=>iu6YKqC)fWTRh7KTeAK8e*g2SdsDB5asJD z0sVh?DSA)wMjV|`09?c4WJiaU@`-kGS01;&&!|a<3Q+>o3Vcm>Ql}xXPH~zZy>)$Km*~gKLKP(FEcny=qWh74Ef8V=rkTc% zzQd4~4vm92Lv(6#l#oE)EV`~by=mxCfKJ|i_j*O7AD}102m0XD6QLKGafuS#=ucL;e50no8tL=!S*jdxuw~l&e8b-yS&^o zQ`yq0MHj?mIyRFfn=zoWgjscCg~9I4zAa?TtU4r{F%6kE1qlquAi55M`l(1$Ldy6! zSs7*w7rvvJW--F1yx8#R6Q#;!3A>V}U4m~gNA~)NjDsc;<$n(>+Hfzn(XK~$7sp9U z;7oqAC>D-@qi<`f1TABKa8}jqms3IOnWRdxB)7r_ zu~^gUS7L{*hL+){;*j?7iQQL)%AA)ttujqBU#DPB5IB7Fdv|O!!Mos*H2C}9Fk^y& zKC7MS2ddAS4Xf2ybWv>|jrd~&so4GyH<6!pD7?KEth@0)lEvnB; z%@YY7Z3+I3>T>z021%@);-#+ysbH{P#lQic5J+&@3F^wf!_>QsL(oR^Hbq5-aTTBp z;LM6Ojx8tuM+YR;t;Z9gh2tKDd5wtr2JYoFA29L(y6?wYw+=i~{~+R()PXV|w2iE-Y|4{xESFWN_s49vr`azu6FoG}#SAovD;dY$fY zX|fm2rh+Avi5b*Sa@+UK0a+}h2gvHqA{?x=6WP~6=bWb)k5s0~x;15-Dw6hgDt_^A z5kf@FcISm(s^sEg-$&vkj!MM&oT%(CsMAl()+-*kcZP&K3Qg|2ut4T}Rpq11Vhrla z+t(H?6<}dIGx}k zeCKe%AozdxIzIn%5|skM%{h0+7Jt2(DDbOngSs?PRCmDcbZ*zE!Ou`vmQk(IY=gFb zn&E>rjx59;K=J)a?>ZVnuqevZ3TDEJ75VSLFZCI7I)>{K{Ag3o?Rtz8%yKxuJpM?$ zF2Hp>+Z|BU>5N+D2K z7!5*rFn%ix1t-@C=6S4+jn5NUt^6#;1V-vvwRQg;BsyrPqzjEnSvWqGW9B8)Pf257kMH0 zUqBm{hLUR!m^q~=oRAp+?-%Dkr>DEuy|2(dul&Yx5(3*DfK{)Q=J<%k)ag13i!gS9 z6fBB!q?G$hx7&_M|Lot><9)Wq+&RuR1xoTCJ@^yUe8R$a9HBKP)s4%!+XdU81!F(~HD%8=+Vu&h!dk+*eNwrWA-rl*pI`YQ& zPwbr7r4saeuwv3KRiYx8{Fx>kww90ju&O>TMqrmk&1Vy<21yaac|`X6=G`5BF6e1Y zz5%Zju7o{dcFv5aR1ch)@7Z${jkiB7+L`c?P^i4qmuU)X)~ww{1E~sSCFOZspeCg- zHr9=X7REa_%?2Yx3VUb(GKX|}*_ja8#G?AD)#a_;2P7{vIg(uyHc5i$Od)Rh+lM&I zW~LwxGN-OtXtGrU#dQ58!W79`q2Q*!BcPV}L$-h(SdjuDE(P_~8UE|)QX6XMuvR#1 zQIi?@G z#LflFhDk@0I<;`E>|x~UCeMln#K73$bx{-x)<`48F`~z?Q_;g^{a%RA)G$Hj0K^^h zHA;4^3VrN4(x($K2nrnqda&qUR0@5rjDGd&@84b8_0Dh-Q*q*MAH(uPQOt0qg1SbN zEYoSSEkX6D`)gj)(Tz~vDxKEaR@mC7^UK_`boaJpi%0#Z5`)X>{oKBR49j(q9)nSIZ>U9xR` zQB$#%+@Rb0{RgkHT&Tj=GIqOVp*ZVoP_xvjCM5~fV-31;K{bmurY+cy<5vRGog1@1 z)5f~>Tq;`>c_`P14lTo!=)>q6#jWX9_1W{3-7w)-MPYFXs+yQWUaMCvf_&VD`ajY~ zsopIu%;Z00?o6r!dmw$VXoL4MErT*?{|4oN7e(~u7k|FUBcYh~6c4#e!ojz$uw`7j zhTzI!M3m3-hvahDz+infn?I;r#ADK;+v43HHoRk24<{B_f!%-YOa3ZYGTlO!hrLK1 z?#c$u7}Lm+U6ea|rec|$j|@`wMJRP#MbP?9q>uuo=oksuW!!CM zx|s-2GZgW_`V#U3^WfkWQNqP$`d5@StX0!RT|BK?J+T&Ds4+YeI{1@yF}2vsWMKcjG4~A64~oxHA29{!<37}M3B_+_q2tQT)Gn2zThO)Z4U zgthR82n=J6nZ?eX1Dsx){X3;z77h4?)B31bX*u2>Vsbw=8SA)vhlUbwff$ULH-*lV zLvZYl!jY+F=hbcS?zIxdcQeqhyqN+h2US{i0|dqQn{aP+O4x_3g#7>&7Mx!#d3&PO z;!slVA?(8C4|qWe^7@H_qCytamkT1QjezL;(VUJwG;{2Bm5{M@TO>>I?-lrJ3OH-m zQkR+?HPk%90s?bBrm@G0PR{o)+4+~}*gLGV(olq52mEMlYUn`FZy^l$NuS+$Tyns9 z0{jYBSbvX6%G~(1DCSdpQc>Rxr|YC!*NXSb7VP|%booUdb5g4URXF`pBM6*(%eDIV zO2T0ywuyhQ{)efv4yrP0w>XC`NkzJ(yFnTW0ZHkU?k?%>lJ1i3?(US91_6;0>F&Gv zzI$ixjQ``D^Pc@a`&n!K)@j*GFv67C-rK#j;zPdt&?)?!MW9?!*&%Iy9k!Wzm6}<@ z@^aP(YYJ6nlXJXU3Q^^#pViZ$aUDJRaXmeQ@G4f*RmyaTM96#^YDV%kwaOL-`G3n1 zyMy&Z0oAeM$Zi-`M6J=dT$NsiYL-!N;e2%SZTk+e(wNQ9^?VjJ0o+6LwBNS?7JBfd z3#=%F-bE`xyikxD_xjJsKeo-yBTs;(Fi6wtMNa2L>q*BYEa#z`gp^iNz=4ghxUw!< zG%Haz-S5yKoK&drn5hPflI5j)bj%c>ZxhqA(DK~cWg6rBKK7|W?9w5($glLHOI-aI zT@wU2zbXhFkyhCn=>Ki9x2yifgM+YVF~KsGHolWoqvy03#lH@9=|2AJ88llW`hZ-= z3u};|6Ew?|btLim)sz#hb2q!4Q$3x82!Y1|0qjJ1OI0w-Oj#yiV=bGFSE3QmKqarw zP~JzOeF2(dR)%UaAtvF`@VmYcbiiIJ7WTBDhMYfrPRLm1%+QskMVOA#)NjyScBVgI zFBL1EBPdqRZ#}@FyIErLI0tH8+Ux3>@gAXi`i#BdB=K6wc#59={StVWa^1FrA|u0F zEn!j^%)dV>RO!K>DT^XDi2G7*xnyO)f?NDlq{U&-kha^0BlQ)7Xi4hOg#et*E6^HG zc`wZ#vr4E;6D-cl+jt79bcu`=@BE|M1=+Ai;0@BL9}$l8EG=)W%)ZhzKqJyqH+C2E zVe-{qnbxT1C{}6BAB(LpE+i@9i(_tp6hCr~)xkACI_Q%FTmb0}d`bcw-^K#D!FRaA z0X}z0qznj9wNnyQd_9jzuV7QBJhE7H^I6mbOg-TQ+>QY<80cFDWL|$ZH_4L5C;=I+ zwpIHT4VpfKA5BX#xI&L&ka`4Pr<6A?Srww9Sa?7rvJXt^L|&_4h^urQ3q9Sudjbn< z!v@_x^bdbDqUYSL{cz2fs6D0|=m((yRd%qahuD{}!UaVHSDFu>O;%4sJ#34!m!%tg zCm?s64jR0{jg3wte)qit$`8zJ_UJC>Yl`o%#xa@%o9?kQCa$V(Kb7_qYTx({u;ks@ zuuyU|51i1E9=51XP@;-X@35PcsqZeAjqRR|KAY;#d5h`3ruo68loV3EeuF2RL@Bw| z&t}IDCyCU2@14UCcfI}$^%6&pqZruSgj9a%`u1uin!3PsZqc zA2?CK>Xc4Nyp=xx(E~gs1`;Lr68B;rW54131{`jrbGZBtFJ$Hwy?&QHJh?v( z_S}$SMcdZiSXa0b+j6mvU+_UF(raCXS%~0Z1djN{qt2n zkp!7s+ph?S?B2`nJ{Y93SYWeSHV1C?yP@Q?{8MrmHwFt^Mr`7Q)XS8nF9d8d0Q&`h z5@3cf;31z8>W#_P6V)*Z>Xr?ZTWd-dMNLo2c4&naS>FB}LDBMw_;j3;oVW<&#~9@2RX?B{w1ZYRfi(~^9>;Li4jg>x`R6VRj8 zM+Ds@$_idH6_3!C|NT5PYb>!**{^y!3OMG#LSHO|1=?hEq7b z+aOu%C(f7V&vwbR3|2v=rx7}zJRAG%wEe@{o)DGU(aH73AMLhB-!MKXP!+5k0!8b? z_OSY%Ap-ol>K)HuL#4d^ai7n8(TVG;xK2UuOE5^?*8Mm5XC_WL#s=^Xul{M{;84e~ zR6Ly=l5OednYVXv~;MdyT@^Z0cwe9Uez(wkCvMh21c09x%_i;qG)5u z6r{G7SUeWq%qmkKBhI8m7kecUkEhj|>Cj~*RhqF}68C#`QyW{jADv!;zyLVlCJLrfUyVz2o#G;`@QVK?Z2QTmg~j} zG50vX{DL|1X%p!#6PAA(hm%~RI66Zo8a0OcH@B|Q_+!}PRc>)<4%Lcb{($M*2F*91 zc6xRnRb=B}dH4SQvC}_SBZ)R5NM&_eGV8Hv-8%x5Xgr4kUz2)LHo_$R3I(uvVYoKC zU%q56-V5ICiCU5rS`gqCL&wR)B+8k7vWr3LHNmz;`r9Uw^{1(QU-T@$b5Q~v~IIr!#x9_dfI`@Tc+8FZy3IW zcGq~J+1`#E`8L}>q|a=6zr|FV6ngc1AVv71(ww<#fb78^* zUQ&d-$tnDY?wC8HxY#lW)y9SB{DZWIRR{c{hlpLepUZeB^Cxy$wia)Vn7=N3_&HQb z0*p{fOT?3~nUQ*E(fS*_#NTSv8UE8~f?U!kJxFkk(UaxgQJDAyL?>P?)OrnVBl5n- zz1lBO5VD&e_)%2ALJ%(WxG(Se^w7dWE`VO<9Jy@~R3J-1!Rq*r(YG5tW`{i8@nBwd zx(z?dTBIp#3FMGu6P7+a`+%9{rSm-7>xvfiw8C`gk^o<0(`RU1q&R$-_+1)QJteo^LS{%uW6shZBla>tN7ph(T~YJb^j;=3-VpaZ_BY9lS7r zN#pylYRg)eJhXBnSNq}_6jPt4OYw5DJ63$y+nz(h~Yh(Op zl!_XOEQ)8hbKkjaeMgK#F-&LFI~t%Fe6hl`5<&_*!Jz#rRXV8}gDq9Y?(xnU)c-i- zlo{t?BMJ%#1RdWm`;Ss&^f`ll0@(3m29p5@T2q7EGZ=)-n|x0H(L(828`p*B3Ky-- z)9%|7_SIP*5;p!c<4~w+K|qOy<){79>rd^6$p)4TBf=&%-_jNmQXG27mi7Hneu_JB zD(d^1loh1KUvRQHmA4K^JFfU5<^HtR|JJ>>4biGlMTs(jaicm7Wa)su@PK9$^f~B4js{ZJXLd@neO zRX#p_aQORV^o4EOoM}0OyYHz_rh4|!Kr}^L1IDmUG_K#*FjKkQht$SMxJ3#=s;vq0 ztsh77DW;hE^7$LkDG*tXjI8!7Qa(S0isq+!oVKc!6~r}4=7ZahJ5eM|*_`BQSZ%e^ z^n)vZR?dm*p`11tcG3eY7#;b-EZ#im7Qa94C{D8wnX$bmu7nR0_ zO}=8(;JakZJh!wUJ32#2JLFpbCI-j9dj(;R03jNf&qKihbn4okSQew*du~wqLDrUA zx65H0nSauwLhA1BrV3bCc--6~--2Xuy-3OFp9esh07S$(+u^6U=|^zNI^jQCx$ zuW<-#%})ID5NKnAZDfU6dvkJy;ci6pIC_dG+Q7@te|iVS^y3NPBt}?_bw8%UOe??X zHik^n<9)$WxV<5Het;uxzl9GcR|;X^Wn}$(nTFrZ!xVrJJ`DQH0 zyuG?JX$-$|{keCnU~-j6Dwv-huhwQ#s9LZ)*m?DWk^=3OW*i5h+yop1&Kwq;sX68i z)5W&?{;@~iu5;+mJDqaai@7)AdcTRQ?%M8`j8USjx!H)tm>I=h&w)`MRz!S7jSc#4 zJQz+IU>Xk=*WM^p{;WNx!AL}_O2b^|v#p(P zeBN>G9kRCe3&&8Qa7Gk{n5y+G6Z!(fvuv((6q<|$DF=4aAA`Ec)KwoF@$JUWHK?e2 zaRfWNBkFzbi|l#R5WI@iV6D=kRO4KhB_VzGzM_k=k5^U@f#^B zvSi92|Gk+i#B8Q8<4TpO?~bKFs?_bcOD|f<&TQ|GFck{;@Q0kp$`A)5?~x9Qi9@oqS?h?)Qkdg>JJif!4uc`pb`rArmx9IAc_ zAyjOeFirzLsv z6a4(ksS^N|Fd!Tg(3wO;0QQ}D=&K&Ujk0aOx55*auBk1v2j&a8)C!OsN!fCzngv%( znz~5dwMZmw9QdNJPyUK?T#DvjDh)f5pgcM>wg6?n>g6k<3@Zr~h5%)sLG9C;(7eM_ zF2=SNf%@w>9-S`lS3$JZOB69Z3QGO}>;R-5iI&XfX0Mjk0)Mu?wl+!;WO2A2L zeEo)ox{Y9R1)ez5=lu_P?a(FnsC({!FSQD50)Oss=K4GPVdpFnF5b^3;Y>Uev@Z+k zTygvJqc|q~&_G+q@KLvdbgg6~b*qPwD0Q>L@xxeBe}czc_=*7w?Czb+{^8tIfm&e{;KQ`T{csZO55>*9>Lu zV0^FEuDs}+KX8_%q1Ec;3Hs+#3%#T-4v*DS16;#vA7zG-;(&CQh>4k`7jDr|=z;4? zRb+%&>q>PO$yQyZSpguFf9-_Swqk;)*}@m+B~8%dRdJMY7ve;ky1KdsB#cfyYSd|z z5}{Z$1P5{9FxAT5@McD{DIn=_rpqQqwR%6^+1fM-y>D!hCd|`!Or(&~v+|3*=4ib3 z7taOWg@GV|@v!P<7@Io2zH~cJi;5lj0ani|5^m3UWivzA<#~t1pccKIHOy9nMD%m; z@xA(wx9Zkh>I|?CPUqi25LMUq?ba#oCzPj3#=a~)zAbvFR(MG?eL~rsrg}Jd`*sn^ zay|Z3@Q<{1_x!H_bJ}D?P<0b{%8{kDpx`_w1CH_jh{Jb-9*WI}i`P;aIVOf`lc5qE z;k_=i)^%7qE4Z)_I{naJa&My~*4Xx;x3!redY{75%25n~Kle-nl`yHJx>|Vj#%oAD12!KJTAhpW z+7Lj5%wnlXBYbh1!nk~RS4{X@Hu|t#``E3th8115c^3QQYje0KM4q%f8vfVfC79Az z6cE$fXQG+LkY%G4Rjy zzS9fTLNkG39s|)-QTJ*>8Y1^g=qa=BIMT27OKMZKYn*ZFs60q0i`4+dEZ+H<&nAkpBEr8M*po}IyK9$3x4?slYXN(iXJnL8J>(8J?*g!Mo}M8 z!T@1f6yAO#btCAUHKf^nWn)+5&Bl)bgx`2{T-Cw=sn0-i)^( ze_J5kKiE^%~?pd7(|y`u1D2@wt2F zw_5|qvBz4O3$tWzAa?J+i;0i1{dQN$MnJqwT{8(kK-*={- z);o(e?%nuz30uBXSFB7Ssmr7W_KIAgoCUvret=#qn#|fPtLp4MJ;n4Csus2b(5Nu* zR8g!Yjo%c=a<+1F5kTszwBHMJmO``e2$ARsepxnR{HTbCasq7dN^S_yQR1;%McKrL zY_XLI9I~GVi{K>PpMGTl>7 zB5tuaoRLFG-~YSe%A)@F)8M_l?Ezolvc(2w3d1OmC`08+npW{RCC{iAUN9LLqC`C} zravy@bK{~azl%S`r&KgUKU(jqIy{8FXx3quK+zi5KDblSTPS9Rzy^APYphN{C(blo zqM7CI_v;J$P7HN2`35Pz4n)qpxo@RaA3O!sFk+zS+X`GeU_%RNutkP@Ob$FooM3ZE zDYV2Rauo(O%I0R&li+BM$Z!S`^JfY#-37demKw5l^;vLp0J=3cEeHJ&s^@cU7$OzB zDpmUY+QEt4{%|AFmcl;La$%{a%p#p085v z@PdO|NMMj>vj^Q{HYN`eP^$t9+YVvU>NsEEJm1`_hm{tq9PkLbf8QNDfLD*H$$WpZ zvBIMRKl(4JrUC)B6O;7dAK}&}M(1uGzKTePnCLlqBB9m=?Z&N%r6gTQG!O{~q%|Mv zWd4ZbM+N&nDF#+!(INimZQZM%VE9g|U zPnjNtcdoA!X;NkorJi&y0v~+6h_LQH>d);iSZSRV3;tU)z4Q&z1Eugf75B374DqCnyqN0677x9)ts>^VQn#A)H6 zdjw00?ZSb-|74%d*hT{86_dKuJBq<7qxDZsmVx6Y6|8TpDsPqRjXEm* zz`LT(V?bFj`1)1NYt)hoywCvk6BjUErpy<_uYK(O0 zP+ce`&>BcphbX-3|I5eCm-!9?GkIMjWl#`NS1K*+`+MAK+5oFXyK<^p1dm!~7O|#5 zP!=1^z95+-rYNqVYBU5jlf?)rg4Jn9gAUEK`KSfWKMCZlo;pxeu*=*fmIZ7uq^jH{ zU=`U;!*DPg4;#?KcbUD~BQr`mVx4P({f6ktC_dpwBQfY)O~2X8Lq8pS7MAuVX`3c zSIF*27c5g=akw-kNJ1i`Hm!iNpXh0`(D?XdFi;nPay3?BA#eW|!Zzq$e+4oO$2U*+ zB;b`d33h=6&@pEkPpSve=^5AeUaJ7U4WfEv;MHSY@rRYvF@k2bshr~Tmk`ts>u*`o zxcn+YlaH-Ic@~iIrw&~j9y1}SdzWG_Ts@UN9W2-4N|GhjRA|Paij>{7{*$E`Q2&_a zdnn~!2>0&`A<@=pe0J<|&b(Kl)!M#GTeHJTyOT?ZEyt+a>JJCjg>hLCM zuuypn7HeZMKJ&GP4i-{V#az?8)*ci=EuQ)dP&D#A3f8&u{i)>OH+Ztqy z`~c?|FuBbt2lt=TYFZ!+S~4W6O;oNGw+%BmDMEO+#RXi5Oq_xiD0!Yh!;8# zPsB(VPXiw6Ogs4NQtoSPOjlL*Xx6Y*MJQo8>5@yYIKdUb%qt_cSClM|H7@ZVq6swb zKd^($yi^JR>8+AV_#aej`SC}E5MdSE;1@;r#f%A3*RK`EW$%=TD<@ks`rEFu5K!WP zCc%Nf33g)YOmCNaht(r1s#gQBR(^;xvm{9Et$yME>Y^MY-ls1Mlq}xBki&QzktzmQ zkuB>%b^dSe9nrw}D@B7R_tVyKX$?FvOM-w>XDqhIJj`S4_l*dd0=>DGk`PU@yJU91 z*ynA>4f~6b8wTG#1naLOAb#hFMoTgF3_>^)y3a%2#ws zwNG~k5~7Ru2d;UY0WH!Purz1T2bZAgQ%6LuHd!N~V4NDNmkD+B3#LL2BaJDNB>#91 zE$HDp@svN*YspsUU}Gx~d?D&j9Up7xec}nN+s6&qgp1>m$b6EFDh?rJJ9*V;@~%5A z_SU&EMS_-m{nr-5D`ZhwLhBGWLiAobig#K zlKr7gsbbzrj?&}jxC(9`%1T|~x`;Uonf^dp8OCa%&sOKoF$GsV(@)?r1ox;0+J6kg z3`f=43>AlRvBtFXTt^&(IdiWY&nzex(u`ZAIr7bE2YQcB_|XG45!W&+1tyiZVVSVS z%!F|HYTtqW?|mp0oEpR#rMO-%#xPO_9+u=ycN1bc0?Dq)1~g&E{@%f^1X?})!#{su z!TVaNkZS?wn0A54THujcin~Gckb9f%{~0v}-TeSdU+0f+edEkVtqN(h;SElt0b8;$ z9+y2TZZ|r`txaPZODFnb_qSy%o5TzeyiDQPx9XKih|nbTA(^AEtf0!1=`*=nmdb0| zRzyvT*59=F>H=?4{3))uu36h_E&siZ;WK?K`ZOXWa9*j>m(&m1`}0puSXEE|br`qi{#Wis)e{-Wr0PDRgFF22 z3~cA_)?n1Z&0YZd>3kpewAD|2y(t?`eLZkvh&7#oS9&ee&coSm#2cKWE?j=g_%Nn5T;^TOK6sX*M91bs}7A78dKAKMMj0=7W)qMgTAginVCEcQ<+yJmX@r!~jE~$l5fA6wX$Mgwq(Zth%#0s>4tOTwi zmsaOP<4y*kuR|msYprK-$K??uIw~k*J8M)>pu`VQcW!+%%c1>+Xa#crkwLQexUjc9%Mn$+=(flF&}~ z)IG`xD%KpZ;sOJ*K(8Lls=?@4>MU8;^V2=h(igH*)ot*w0aff1V`V=b^nJGJRpd(eh|J_xt=hPBcuq@mu5 zzZHvVB@2Y(HkI;oGaWKw&@`lNv(3ITV=XnV74UnhJ)cm zcx~Y)G;M+yP56i9n>gj*&;mToaU3XGv`RGs+=RY-L^@Y4JP4Vaso7HxkOvR|{ z2<>zNu429*DH7_$$_0W)G;YalVwqW3aWZ#jBV=|cYMRd#sx>vA;jNgRtv8)`#p9BA zy`W1MI7FZVA8`WxUR!tGYHA@rl8U8mt83mO?YlOYFO=h0Sbk{>db7L&Nb@~q5Y+3@P&A7c*I1jiQ-2`yi$$IF6s zEh9CkpPzgTYxi|0jdubpJyylY>Rf^~zmpT0Lf!Lu%Tbn+o-{f`p%_{*=vV#tWhr1v z)yL&VMWfxQQz%&u8^dB;U^{DFW6Od6AAT?Z1~)WawA4SsUJV)I;g4|6f;E@`SRDVa zeHQqJ)vGAE+6cesbbe`d$hhC9x@HQEp+J(8lRNo6;0UL%=)jYiBvr4C(7<0{oD`Ju zlMM&18<7JETq;7Iby^(6@g(X4+;nL+7&4^_fW-$P6W}Fp1T*I?64TiT~&>uo@swXjr z&fL<+B{Y1kXyI~BVGEoCA<2@J29Wo{xQ+lKzL#tqN{2aL#))(OKJ67Plc{+lrOLJ& z{J4qe;hBYs3l;`0c%y(rZfqNWY#TX?nsm%0z8kmZo>1&l)D=*r4-55I$pOY-5K6+} z=cRjqD|Up_r!)huOaorLzVpcO8akTDJ?g#${2^m|DJv6<8$_>Z?6+&Kv^j%eb8qA+ zOl%ugiWky9*qCzxwc{p>dXkkMA>gxnkwrwj5vC27B?rDU${hv%L2amv6!bEpAu8AW zm$O?X-e_^9oqq8i&+qkz^#`eI^s62(rl>zAgj7Tf1?%tm_^`)y<%92RelL#p4aa0z zaDHxlZ)ip~&oY5-HP%t2+I7KfbI|d6Xm6T9jYO;_iuE%ey?2G3#^4i^?_alsV%h>- z9F%=>&-;oHL}+xd*gCvL)~Av29(1k$_Q5+`u_`(3Z$dSB7*(`k=r4Bpsr-amqn*EJ~$C1TynKoN-5(n?XPeVt14I?ZuXQ|RV#{a*<)FtldMql?SN_-r{m&{Lx0dMpXBFVYr7}q6 zl_Uo(YdQvzarb)rvRBF8SQDQ@dvru{hqX95{Svd(2W; z%*m1@!X2Zyj6}e(@0jJKZHmaw|$4LG*@NASv}uEFPFd&F^9+1RzscAs=#@% zKLIbn@3pV%J-{*=K(B^&iI)Hu-;MOw!8orv_oG7cbzq-Q3T#`Xjp}QNnQ^?8A=L8I z+QFrhfd@bpAds|wqrrOQs>F`qu^j7wetX65x+XJ^=gVqFeh^}n3Su4`yVPv$kx&B1 ztQwzzPZ1RSMWdk`cyL_%r)St#?PYyUK_%P~*?|#JL%X-TXgkd%1SP69SjY zGJLC!Y?XyRB8E;jPc+DE0pM(&mFTjYe=2G*qCvd=CD5K9poec80!a74GZjJ3j1j!8 zKvHYGHZS3yt&ycwD7w@uHPvlxZv>YvBhe%tB9gG{f&2rITNz|)G@0~Ctw-FFXi-|G z8JrDUk~#MYzo{5yS*ZY{ofZyL&mt*eOg}4@7Jy6=#7BSX6Rzi?CNy3ay5D@t{P~@*?pM>SZqlgy7$H$V{G{@K2ikgqL=r$ zMs;TIEDKA!$DDZK!at|-l#KBtvrj8wz`w=f@Y}@YIxnT^ycduah5`XDO z$Ka9M))O(zuLp=J)COksGWL9a4HwQ3Ur9!=`<*7{4W8#@$nF?B(r_@NSlRK`H=#kk z!=whj zVX+02?LhuXCB8|4O*aF1U_~mOdubX?TvAgXeBVYxlimZZ6-QyQd(Q6&|DEzLbMeBE zfCLwI8@w5F6f1J{H2S$S?D3g4g@v|&6;8o$g2DIZ_2aFJ3#U)`LHGk!O{SRNWSk5m zal}66VY+u@xxAXzjUO0t^$TMuV(9{TQZ36TA>RI~_U`L-uQGeY$G2XA^#Sv5Xkx@P z)rZ{_b6DWVE~UGvJ+d^i#)NrL1Z#8p8^#tBf&>KVEAxUF#n{4^snMrQP?> zJyuF!{+5kgl9`vXS_#B%ybAt)6Ujg1(DDJ87U4dQxpxQ#_hAA*63>E& z6Y&@>d$f3C`JBb(Ktx_e$^cLKB$ghwC42g0wQhw~B}BRGO(qiAQgntUq`evLpO*^bT{U#QHy|WTsN`fXk}ITAxaGkH6>XxG6t0VS&AmL+U~CxY>mu9Omh{r zl-~1@StvWL*|#>C8heRxvo&z7&0cv9K2%c4%cQw)o-~Qa{bF|tClL8GE%`Ps;>@I>|Xu9Rv{jl%{g|`&d-Y()! zPV@~o*bUx%;6;F8R5)?NkaP|s`=L~_{$oA1dJAnJ_ci9Z_TX}_awfe}d`)y^MP5I0gdRAqctE+D zwlNRk-)h?^L|@V_TsBw)F5^xs|P5pY}n{!JJV zq12!LN-t9g+q$u%u5<@F%xWRQcWGsrAp!)J#P#CUsD{se{gh)EYbdBut>|$jMngjf ze4r*xS=kLW6#X;@CD>@D2!C)+ag0xyNs0q=;8bl7Y03R+KTv!z0`U>;4KWoQs1@tP zsiZ!`a@qYjCj_2sY_K+mo{MzymDAD~LxD&lVbuO6Ug3gy^-p$$9{}uK6yjNDH2>T; zd)?y*-u`*F+GbiLU=sE!hwCH&DvK47o{UcM4e%?gS1hpPuy~|8jhvg3QcMOyPb^e^ z39|L$!k5z}xirU9SI$F38JpOyhJvT~yoB~Mmc80kT%hhB%~NLXIjov#T`H&dO6zB< ziZ2W}bXM6ENHa3RGtveA;PPS(6F)lFk9RzLD!j68 z#idy1trC*;r-fyYC>X{X|B!<7XY=GL&M4{0v{mE3&XT;@eLB}M(j?1(yBW7E+lJ?T zU;p+DP5Epfi{uA2tTo~rBJG?P)XI6Se|$ZX)664v@(=VMUzSw?N&cvO6SZs(KO$(j z<~2?H?iU;!6xl}Ij@3wi(wD&33-Shh+FO7I1j5^3t+u!>B>Y+&7q}vtA@JZM&dADw z#@Lx~;+^FzBZ3qE9`^w%9Ua2Sk=)Jmn9fRbrrqIhDztF9R|PGhqq<*3SrGY7-B%Uo z+oMcYdd+pZ(4gzxBb>wUf?<>~X+~r?_1o0D^@-bkXZ3EeI6kS-^LF8?rikaO^(O+G z_09q-Vw^QM#)LQe(^1dke?o%r{1apnZrVVlx>l3TcN*lf#}Ys z(?-dzMj7!`)X8WF)aXgk7ng?By)MLIg}xN;bYW^kL^ghnnBSLmN`c;~T=A3N;#k^U zmH~Ln)OrgZoKJtp5Y48Zu@fBHuy{5qR}P;{Dh?v*96`RM9!lbQY=UZ8z~AVH4wmIC zrQp@ic}Gd93e5mp)JQm#o0cDNJjFo^0|vXBo8O%%)Kjtj`zw#i>A#4Ybb=}dT)8Uw zc)*C$5-}hA;Fd)u^_eU)g)JC9=PBbK9aQ6enSMlfk7`e*Fg(g>F6&yKNnKCf?j+|g zdy)_>rw!e7xxf<7Z9S3}A~{2Td8;f_6s;<#B@j7Lj>1r}RA+cAtgldlSX{5p1o~o2 z72(Lgs@C{65hbM?<3>w-h&JPBD2tup_VaqG)crnOYh2nVsR2ER982j9@_s9flo8HZam|X(qq_Sntl|q zOW_(%Y#?>ryJIzu(wvMj4vNYoTm97wRp`4LYi@C9dV1hJ+)(p_VC+K{=~gP`8ikbq zrAdHlSy^@CjTAUX{KKn1Qq` zY-w{Q3oy40e`MCScY~1u1HMsGMRfM>IXc71;_GePU9Qp6odXb}# zqI|MkjBTNNT~Y>gRnum=BDZwEEO+RhNjz-l{|wt3p=1xg3hPJvIfK&H!jT@a_;c=q z#nG^p$x+|KZ4GPuMc7QJsQqC_sX`D@>hPt<2~U=v$tSgTu5YglHQri^KvFS@kA^1S zqX~N*r;;=`AX~qL&^S!J8dSeuWFre|T8b+Mf*2skXrDB+bgz4~L!{REpLRgViCW&f zyN+6(A-?GF#Br9LhJ}fW(bnis$=R50&Jn9)o@w*<8nMJm z#;~`gQYg~KQs}VaS6Up*#hYV|1*Xjq3wH|&Ax<4%CKO20y%z!T=zKVyBGkCdkExvp z3nELUPOTqaA+CGhS5Vw{R?|l>k`x+qx9E**3U}|!d5G+dn{96OsB?V`sH;7OL!ZV=->^qB)3b~ zdfEHS?lki%HB0)<(|S?q!Hlu1jV>ek`c46O*)=n2JD}erM<^W_ZO9J&(!#Gr=a8IX zmWD36Sp!Nl=#e~dGQIQPcKeyX#u^X`-|6$I( z1Xe73gNxOEH)%k}KPUakfYa!qmgc;JoS24>ieky%q3l-ssJJ~=F}^`YC__rJWZt%1Eo%WI8>(H?t$&8DbRL?)c( ztC7DjsFV#!!Nnpp77g#l6XBCfa|&rwwCEN4qoNlZkUCo153J;aZ1}rvP!$Jj9Js^8 zLhs+-j=*qb2|ht4vjpd>F#m0JoIgUXtj)`fGdgA3pAb;m`W@$);t@Z1)sB^w{$vjt zpc=o@(ZFBFhOpqwDYM3G4*Q3iA|De$!4U_FW8~0$qL4zjU)6m1U^txfJSb~_@VIl- zg()vTev0ujHI9#zf?b45iSc{Q=&Sbb6Z={O|2vJ>7#o|qI|5E9sf8sfPas;EM)Bo_zUbvIXaD*t>z@Uk%IJl3yi7SZ^_f?<2Y_w@)^k@N(! z50YM6N{K*XlP-2hz<9j#hCE!n9y=21aUtqa5wk1V1%UA0a^=F922+*phF_XL6)%&>k>meR%`IbH$Tg3 zUNx1VQk$utiD-Kko3>p11YqhfqleJ%Eo4w2fgrNq?&O!8m8ir`&DSlp(W+&Mqa7oy zf0j1fD;rSfzV9%nkK<&@0fVFDB-C9s);}uC%oaKnnNmc=I5{e8jws0`ysvA8^gW_k zY7Ba*Z8f;?ph-3ane8i1^+)`rawHy}Jac^QFJI`phj9BI(&n{PR5n4WH99drPpg{G zagXCR$Udc+&b0akdFiF9YBSptezMkk)@Y$-{vkw*GFCWuA`zI#p<-0f{3UaLQ=LTsq-Nqfj)D6p$x^ zofTg%+BB6`Zv6UteeY7my?EHT(XGxEy0nowX}oBqM}Qf^|Is^USrtE)Xf2*el1`R{ zt66W0VIz*mBGYXB>W=@gq5*2Z%rvX*`sP?s_Z8mf6~r^TSIwd}<|yF<1i{aq z2xTHR2vq5aYqT8r$v<1LIklLMl%n?S4f}Z1Efr5PJBna=G&8rzff>tMqcw-2Eu{iuA zq_K_YFT4T$_Q+(_f@S{IEsW*0+H3H@1HY0b%(umtDu6+Q2iM@DSZ>O-1A z-t&XF6(hHuNOb33b}^imuKvH6wm>UP88nwnYI2czI2fjT^m2H{z$r9QVL$o0wixf7 z*SebjC^*%CGw%eQ``3*tOkAhi!#EhpzjZyM`8>_O9YxFwoHTv|z_ihqvTRpV+aH_* z(pGeeEo0xe>cHdV)IzkDpq>x=S;@yd<6wYJT5WETQh10}rAoh#%7>Jaj$xz$zu5Ij zFYMP_5Ga$KO@q{>)Bp7PQosq8>gIo;)j3=Yk%h13)V`F6`8r@Vh3Y4NlcA)Nt;!N7 zSHg^nfNb>DDwH9wHAlRV?4B>u*Eceoj`OhLi|O`@|GDtRIuqn!KSQs-JsDYq{aV*& z(NRlnu%hGHV74WS8V{GSt*mzE9Vua$s1`M32&GW^aG#Y8TTg-A^cZIaq36}r*>wKUKf?P z$>V>h5FgCi8tWx6+&VDLy#h#X?_$P3Ni`urR96I+{Bs%FN8B05R-s|Lz!l&D_4>Fg zNUQ0O-p!x*Z>;#QSkuSBnk)M^(854%p^J}(MuKrQBx=+iDWNufs1W8D2^$q!{NL1> zaA#+y>Ni=cZ3d?1B19`kSJdNxbTgK)4ZqRL-}jxydf`SOE(~a@I-h!f)$2LVN-IIS zZ=eP9Y8<#ZXpqgRh6PSf7P`D6sygqM?_8$Qzr%fmNF@nAUSMlc0GbxVJ2vZ74g(0T1oL@T&@4&w)6dNES&I%62=ecz3>msP$C_PfH@B~>2lywV}Y$B*}fcmh;DkDg@cP~*oyv>{zIMJ)@`qWzn-OH zlG(o&aXa04rF{GH%crY9TK9$k>x}d^D1Z%iv#lC{H&7+4aq& zq%|wnb3!V*>HR`DYQkg6?r$ipdPMW!#4v7NLIj|d(P!`;oj6qU59yPWvkr8Uc(#_r zapp=B_(Eey&=#!*aHtUb@}y3xvIZ_5|5zII&Fb9Rur5Jief>9yYq+uWY)WXqlX|o|6b(id%rYS(Ty8`lx8??>v@&BRVEmR)g}eY zo1YUvf8obgFFVQj-oAdR}Q@@U{Y=N`lp zZ9martFab*I*ohdf?+;$XaE9Y$rsg{BlkRf0s#!GL6$wwqX!p_rQmL~ zg#BXI+e+!|TJUR^L{9u<-lZ`N-=(fY5KuiJP&g3;pH6VM&dxp)2$g@A%0Kb?a)7SO zyd&&TFKvKowDVG;@>#gIUz zpd96%1xEESkO~3Og^r{uy0n&K-b}O?;7cQiJz*E#>c!5f&^=f}p8bX{+m6B+bqFnF zDdgm59>cQd#@Slq|G0kFZB5jtW5Y#!=dAI4C5-cy@>6&iVTe6&6&%XVz6%|oggR^% z=kj~EH)tM;I%A$@K9&2EfzN38{Db;O5rY3=>MVn*eB*At>28EgcS&#Q4nau?=@t-> zPU-HDl#rAXkVd*|(|@|9TUrF9&+U8Wopb!AGcwG6o_)vqt#vKW#^pGV77Y68$oErZ z12y7Kq949UW{%+xP*Fg{O&zj1JFm|>;Br@POzj+XQKP&|>2FV6GF-=O$3owS65kG~t^7~C1x z2dV_)7&}1`88|44zSGj8!$w4=!;6vWwyfp<*h)3{!GMG0RdS=A(8%F0R;2ju_^9_E zg0hX1)_?yd)Y4*88{VEoiAgU9`@DY@+L}JA({mAZ#QnT= zC7i#E#?_dgDPux(6P70sSENiGwuVgxKcuXk>1IW4fJYbvz~7L@hZ*WUTJ7- z)IIg$`N_kz*c*OJHur}8_W(Wr9BlE=##urZ?5NLuQ z{Ai)KJ-ef1Xkt`ylyXfTD8Y@TBJkfrDQQ9z=e<{4hAH8XJw4gQZxlr6JcLf#9-x=E zl)@5?2e;YZr(^HX-70AGV(i+_!mBtAxiY@RrrNk_ox;R?k#3}V)eeG0?DbWOd66li z7vaD^9^~n|O=+#7KRWG*8W}(vjBXD`EdfLhA6R}n`=VDqjJVPGl65Yxlx$&X)OQd)?2>m_z9^>c~TwF&b&Y-l`R^ zr=MTNc`F!{fp3POpy0pmLN$Ueb?W`Q4!E)Rw>rqqT3$sswr}(gj3MSXjmugdVinrx zfxlzl6AZbAKK58FzZh^97chck7+>h<=wOo6mP)VdFL*MD6Ak|TW{G``Ym1Wf%(L=L z_}g@82Y0RiYQWP&u3KfB?>XYdcdXAQFd9Di!eQ_I+O%1sLQ>a-pIw8&QT7IpuOCLtxjtZu5JxhmNm<5%=_a@}1RR6vx5u zaH?01fsHZ+VQ#lMa1Sj~lnS}SvUgV)TP&7E6GS-4CTuecZNB7}QoL1(GYttva<56jY2RQMN36kQnz=z%$EjXK~DV2s(#FHVbDs-TE%|N zml>2R#2$EMFmdQ{mRD5=8-S0a-vp{(Fm3JIk;3aU#mNuzM!CyvZIL8^JG?xw1 z1GAPDh%Y95n=Q@m%0_oGdZ4ci1OKXkvJqwG7H+mu7TsZyFrQCWl;{U~IrY2$XI6kP6iHX7b^B;0ss#Rfw zM=xbcItskL_9K827Ms2K@+x65AE7I63~ImM=pX<<1}?gs8b>YRR=%M@c;k-Wq8e!N zCushp@lS^#8gF3e zhFkl<%#1;WfU#OI96X?mIs`AMM^KqrB(rGz4Ab-8jdt%*Bl^7J9}kjkHxkAjo?oea z18J>GrH#5@8R#~z`Z;`@xgf`4Y&5aOS`k>ZUQp0_(s=V=vGZ}T@I#P>IWi@aJ}rdi zXpR3>M7$MI8!gYjw`sE}WJjaeZv6d=(LL9Hk+xnl;L(yH;!$m0u@gW?JjW{x@=ap= zvTxsLfKs24)lB`l(pgN8URkPuRYL$V!$-_bubh(v3-k^8#G(E0nP?e;gGhq_3LrpE zvrF2DSlF=$DV}9h`RlmM9%D|2N>QvyO4AH4VR*WTCt)1l zww)VCkSti5M=JdC&;7M71|d(Y<Z zo3`tJtz@^P8kspChK0c>xP?ZCUun($d)u5{V7+5wICGi&h?0S)DAr}DIcvCkL}V>I zzDB6l1-!SO&)dZ*|6CN~{JFA|EH0yds2rpC1et8PM71Xq#rd$z2%!yuVC>&?pg8Un zI3OQ|^KRDd^BMfz@Sg47rSS#UG^Fys`is!p^^ohyV|d9hs0|688SWyx?&Z1 zYYy7=Qvo@HT-zMde3|AB$W~wr!aLPNm zPWdT7(`{u{6#;S(V({BwC!^{Kme&h>FrMC(wY!H^RfA7jTKxjnE^g;k+!+JnQ z2pn#n}Aa2UW+| zZupW6lfr39WubSRZDyW;?X#Q>iz=e>9dHPyJAH+ZjJb}1&y|xoT67}_L6}DW!Ta%j zhX9Dot(hTt*6VM8Th=w=8k$M`hy?T3?#nNBpRFF_|NFF6OlsSyy#dd4reLiSz4MT=cgjf+4g6+e~dSc!H~{NDSzI-Gi7 zBGz^llN1t*?BwQu&))da_SsTE^)4?e39Hf9?W!Z@k!nn%9l;&MCG)rgM`q5l78&&+*Q~4@M4rLlNZ6r4BKvqhz8Bk-iM?9C zVU0m_W`R5L;OFK_n;cvdb`@C@%;|@Yj41u_Ho}fT0%`)_bro>fiYBVH=(%{F=atz9 zp;s5Yny8Q)SvvUs@w6js?eX*}F4ym#phcmaP#7Uo%)$n9%gt?H(#6|5dNuD`-rJTp z=YJMofWZLJSH6}jf(->at;UYELh$3$w5ZrKNpx{?O!YGhNq2qX}P z!S&4;d++UZ?tjryjnQ2Q354AWWO8mceU`y@OW?QSn_QRbY_b1eFM!`xwPu*<|>gX++G#P$v2n$9gnvZg*M^vRnDzM z6~=42PYi8Ok4RuEcEH=?>YEl&ixQkzvOD8{f$)`us&l|rk!QS~jcz&eI=i3e8ZAT7 zf}yr6|B03957(WE?uCJ61ftqHd0=n~#|%Ii>|Qj(tQOM$mMTvHs?J8MW2d?kZ@mV6 zB}Q;VN^SDuP^D;$2FbdZW)sQK2bXVk$(G6{QVNlxKs`%XS%?xr?}4bSlqi1+Bg#~@ zux{q~bl~}Ek3ZRxN9*~W0RVXChl<%`Qc_>h~cdi#!Py~#>B)hAZnZ!8fz!pC!45b%nKdFZ!IpX z)~_^;#jg9Uyi8nL_RCtMy|vP$@$tsJ(aEh_{UIQ@;J2J*x`xatNrS`2@LFkqlhKtW zG5yg?bWwtQ+L!x_o(@F?L8o-Jra0G7SK&s_)Lpwfed4qFDgyZJ-=*~P_3l>aAD_XB z{vg~!Rv}{U2_JQ06yX1dNM&Yt<=A4=4)(PV^H=zclIX;K1DrVthJ+aagd322B>2}H zg)nGr`iaTPHL9iZhaMA6bwF7e8|R z(xU}RF&X^b+6#(cW#OZfTjBHq{N*8U{vHt z_{7q5+^I^-AXXulASCh9`{dNari%$OQ`%TfA#r}bEBWt-c=s=7NawY9o3VL>mzQ0` zXa(j)g7|8ObSD5Pq>V%UZO@0C?5r+4#G|^=Ib9fc5Ynt~rqZld=?!7g1{|UwnCQwx z3|K=MxgpXt>NDN5v(LQSsl$8eeznx99RJ+KHn>CpuwOuXBkSSmJ6`^HcHfV6-i+g` zzB&`P^%E=33Z&c{S9&~A8&7{q@86w?pNnyRC*SO3YaX>0lhKth&s`8EJO2+o%_q*xcu{iNJ z>tt~UH2#0_JGfOAhAiH3hNKEexNBv@@6(Rt;V&P>OSM2~{ng+F67UPGcj*fl_^nMJ z%Jks0hbW*f*a?W3{-+h>B1IA8uG6B5D&DOF*G;NtJx&v|a7n3p!D5M{awF_&1h45U zW5GZq(a-K6?O#-YPLT2-~7ho5_HGSk?+1n+mw_e3)n9!JoT>z5~(7lBl0p~Els z7EHH<$M)#)N77$enuF_tL7fLncNFiu)=%&lhd2WyCyptz80SX;HR|1cn9-&X_9JXeU3{ zkTQoQK7hUtLq-ly7+_N6aVA2lYRhWE^9*NA(B&G1VL}Tn&|`YF5)o815jy#E_<%X z$n#4vaNlR~^twpu`!ZY7pZgC%O4i-~g(RXOJiOm@h%L+nSEjV48fA@xx9?d;5VdBR zsiv}juX}YU>MrXi#*U}D%P^U`D1HI26{b! zl=dKwK+SG%9h!~%`=`ehRYLI4^2as52vTm7{0(vK1mZI>njEx$4wn1-JxQHYc3e2C z5?Ko$bv!Rv`>}T(*7dEBB1ch~t&@kgt!W`UF@Ngc#cp*cU@&~o8t z5+MQv4;%A2C>}r4VZCw-EycsDK$g7IM7%V!;nQC9%w)$O9)YjZDijh@k#q_S2{e*^(AM&^m7)L*hBb=2|m&^uDh?w8qGI7UHSbC zxTEf&l_Eyjhx6w1^f)w1cc#%ET-MY_69{z>cxl=4M*StTQ0BLy$E ztS5YWVJCRXQg2wTfKj??P4=X^Tu9uvPH)*)#{xWYbDn+MY!^TA0Z*~uQ#9b|_B^a; z1&L=c%agM~u*3~8=USFJiiOe$9^!Z4@&qt8jkTmL-x#6x0hq zaVIJM5PUR8?ue*mC6FhGuI=$>36aKV1GDBhgsjhMsn4$NvJsU;ga%fhmgas$)n}WX zjPNI)Xufri1Iwemno`G)0sq|R3%zEpDc3DyS)hm6c+{aFk~gJh{KD7%$Q7zdJY<@k z#%)+n9$2HWwSZVHdcn_*OGfecgLO9ydtA2SxCizMG|1Wk$lf9MU=9R)G8m^KaX!(-M<+6st8YK$Yio9iTRS`{A+ugm{CgYU4W}A(rs5uD#7Rg zhW76VP$mTCiDP(~@*IeNSH0{Pp=D)?5prXDt}AGO8EyLvt`uA%W$>M+c(S&KX{ws+ zzb}!_fp>>bMcNx%IInMa&jo4VP~W>toxi)wogdEkaWkQD^1rNfM57QyHv<`)-Hi$| z-D+0QTg`>YdtRX49pk>pj09g@kaPZOB~77-oi3*F2r{UNe+b!Nnetcak6J@XX5P)U^_`fslJB=ANG@6T59wi>h`zuc*4z0w(zywuLGtT&fN$`;5f^bg z0?EO_Ld3`d;T7zc?oSHy>O}|e)p$W!i(POIO`d$s_`;pRXt60~kJ~u!xl%&SzCT|a z_Okccy3zfvU}xfXN!jHoZ$jcTMK(OqpWs7d`HneK*yYfuC67U58O&tpsFzxbA%Ot6 z+U19#Qba*+!P0-&ENc^s*{)i}Zyyl;MZm#oD_W2I2ilb3hMzKe(PJh}(6w7{L)P`Y z>SMYZ+>#Xj_%Kh}sFI+<$T2^u8KKs|!k!4v^#hMJ4P>{b-G z5kNATK0sEVQ7yUl1JdXe;`<`zNQ=UW82RW=?bJ#4cc2aF=t#LJCB>(@^>y(&2qrv3 z#t4R3Sy|~<~X5w3m)7YT?cfuqs0W)Fk+(Q_*P{Ey%NydVihi>fs{Yw@C zoJpPjm(QmDK(=n?Y)9%KrLTEdk_rCtqJRh$R8EKMs#`Jl{4#HkrHHN4?Td>#Todx; zsFju_qsRjBTp!#f!5#xO2PqgeVid4H0)D7^Y7wF#_(jN<(_^Qx##c;Y&5`FaJbCqo zE-1l2zoPn;oSd9H`uAqz&hh+s-sEe|ksr)&QI{bzs-HR2p5qanrf24Am{kgFbkIL;hqD7uxZ#}F(GF({HEmHC(7pNA7=^1H37vzc7G>zsK z90Vdo2!6?@7mBsAetw7M-@3B7cwzOom&QLHpuWsH-%LWzkP=;$LKNP09%F7K?CDl$ z-?ps4VsG~b(@;`kRNKr; zfSyET@QI`Q;(hzZB2+l_V|eOqG=qU@vohWic_Q1mXFv3r93n1g(X{t{tL4rY_-X28 zZG4#`BnMP7z10ePx*vb)yIu=$bS=d+gRWm48-Q$2>h0h&IZIb66IW_nUYpZopNDpu zHOY40wnpmVS^$v+9zflyd0j9wmlIlyuqeMMckg5=%ak$adss7+7j`wTBnZyiI@i76 z5>D0@iSz1QV|OiK#T3^mX*(Cg10AnGQwGh0Dw>y0EN69Vr_O)`siN@cm&0C3lZO@P z%CiEb{zZSId6A|Nmpx!r06O#;OHkpO{{>FR-L9<>y9;$1$taYSb>uxoQDfW3!!h!l z)35WV<~1O>!4K**JVdibRTC^-IGK~93Sz&zdD7d53%!l?!Z9HVa@ghkQQz!$*RXp5 zhsN4Z1`Ogx=Bt^DVIYsjZ#r<)E9&J-7t~M(BF=&ll{L8;4JIVA;PO=_G9rgm!7s|S zYmN*5yla1f>fu6`tre|vQV!zkB*As?#mj8)SD?*5B465%^EOFKZ_nD0> zGU`>HE56loE@U09#rD#pJ@aE!AZof8Va1hMZefK8@uqti|PyZ^c%HVXq`;FKQN{x7}c`TXFN|vH{mD z?!sHE@4M8&p@d+LvW{s1hCIhR?+0pNTO^fUFKu}~qQP`ky=$d1?lXA!dIz5~#Tr8n zwLoc!PF8(}Cu$C_TuWD{&p8&@Vr>5FxeXT}AAJ^+KXW;>XXTHN9JDLWNHXItdKQ`2 z5*Sl`sa2Fmf5^PsQ@(XWt!rBi|3(U1BV8O~)B^BZDxqx4u*==C8bhvn53`EFi}3nk zk5;*F(=`@p+U{Ndv~?=1ZbM!uTq_A{;q9hc#lO?<^@Xw-!}wSl;Hr8*Pu3c#Hzp37 z6RoU3;T##fLd&xn{(gAzboKwtmuYF-HEkKT-D3`De%q11blf>Pltysh33>=*mU5#e z15O;93+?g-RXocul!=E>jsUzvFtI^YVGA_AEByF!yYxqgKf%AnGT^N%$K`w0K^!X1 zuU`NhS7;EnE9)?(|NfR*WO-?(+oiZiKE9ULcjf#_MrojUQDOP3iF6~S89hhDz5jO> zuUT}6hfFp6O|5(f3>(U~q z&~Q*@p2(X(Y8&5`@u#dqLtJ@Vs+vFFFBLa!&0V_CnD|l-t3y<6n6Ltc zNVGva92hjKegm`STgpGN9ML_)i9^l<6;~?U@8`%aiVAxeq_wt4AU0OJg z_`Ou%nE#-c`fI0Q#lccdW4(Yw@lsDQ3E7!NK1ALkQTtb4ALj_{rH8n7QMKs;%EvX) z7-pR%qlNAd$TXf0MyX|3gIGv!2p5juFB`YY=>9HYI!KYm#QA+>8Z?T1=jY8xcIaji z`5zekoP&-eGC<~zBTkgg>lXt!rMcg|x@+4rxKDZ65hE{eTKiKjT&s|@;&?p)&+YHu z0=ydIifVnXiMJ>{U9UWZ@`50c%wyCXEg`3Xq#Af#RIRAD_-#%V5@INVWS7sWcmlI5 z^WiX+8!|ctT*}v>RkJa&TG4-YEI%8^-v>nO5kYcUqJp!8 zyzS%ssC(zP$=J_H6J-6DhPg83O<+Ma084`g=ZoyYZ*<63=xrmiC0MKTAOr5HlweSK zYEPKB0n1dG%Cg7H&8$HFx37$%={DBgQ=g+X`X`q^&)D$?l|3;t9Zfb zaedd0f+jxkZM^-zl-mXx)u5{Rt%d0~m6nG^>^R@FwciNu13&k!1b|m;p?o{5)CSRf z15abqtySruXSkvH<9vSSA6r)vTj;T6!SWU7V<++A)09urlp?8{rNkKGEr=2TlGima z1-C^wY{0w&4i}PEzc$=hHKQAaVoM>wC#^%fP0y0i1jo3!tD8DB!g-?*)o13OBgYNy zT2K=pBQV#MDi-Js)@A4sqm;GuEO>hgy2thGQX{)AWFcB;2$*wsw*upND*6wucOhSd zl`Lnm?AC`SzA7HlFKt#INbX+~gir0qi6Z8u2n3vQN&|9KJqZkgIZ{F-RT3g}Quap> zT}bNLYt5x;;?%fh(;D5^NHxp7JF`pz%k}oLRBL#MY`})=9=2??2SP&vo2u49anGid z7sl!q-%7)2u_vR<-8gBnA?n{kE?q3guM~evFH2>qTD5Skkkd8FZoYJfZ&V#4|52R@ zI>nF<;y1~1Qzvm5$N2ra!#&VS?C7H?w$Xv+ z2wzFHSawUM>LDd+k!@w~X#G&X`8`)N*k(n4-V+ z^RV+uWFp1nB9@B7@=(!RP6AA^rw?XI9}w-g)uIL$EMh11L+Ww5)#1#z6=N4N*OX+p zC)L8ig_M7W?=@3QG_VrshIU0LF5V&NAo2`*TNwWbRf43dkjzs@W3gHBq(NW$tyIz&`mj%z7~O-K)<@y$(OM@MB_?6-(Kw=r6M%P+Bw{ zmT0Fs!;+LKXh9bm(tEAf5#tfkEpMJ#l$T*f@P&~gv)Z{V)My@nY1FT>;M1F>jdg^V zSK8_%`U{vi{^2VQRVy6BQAMv$wl+5jbuOAoq}v)au#>&eA@wTjeb}JSV8`U_F$B$f z|C}7Ox%;yT*E5{5*Rf?DMn#W?PF^B+v z;R2v9fgG23{32u9E_Q+DCBZ+-yzkYb)&6B+>wypTl|VDYUzxygi8n`XAOu%deiWD| z6$HBFs`VVz_@6}^im3e|-8d@(4Y~?+NH56TkR7c@$8g1i@JVPv_#s&jx_-NhI{%3V zI`46KPNWB^xnx{9)pQ!v#(M9W7qIBOI?{*FT0Z^@@~DSvyHu(P>#SkYg91=6uPxOMfr194Q3sO?S;pySy+Ir{XJxeIAZPt9q zX~rI89zrCmxQkwnKghDMrbKvTzZDkdMI6>5fA^3>a`1zM_Pf!xp)CiA;B$haZ>EQ( zI(Zz=L(M|@R@l?Aum%NieyF+VnFF7u8U8Q7uW}fo$6T)doofajhC!pX-+yw6Uyt$@ zykz|H&kC5|lqc1=9A<@$dG{i_B*bA#wkoab1+{!K@9%smVt4$3W2Xi%sE}qFk){n3 z#1a#*)0f9go^7{`#VCl1>(hyO@lmBs-_V)!+_p_(MF?)y`N$8#jg=^<^maPzZ?)YM zsbJW*NGV!j*_NN``*)?8DiOmy)U@j1E&cDl=IBPqhI5GO<{lA}rjhoLvn$THhZI-7 z^cc4uhqLIppWM~aAPX*H+s67Hm#n+#mU*J+GN%vix#?BJxjq=T&%tlL?0F%6B=iy31*d%*Rc7Ngno= zqzN+$-2K25UCVKjYY0U(opjP5B@S_EB7yf8u1t!&EgmpRf1gzhNV^e-e4gY^Q>srj zV~E1m)JNL(s#NA&ee&;gq=-hd2hrMStFeMt@&1IbZ^s%fK3MwmjspbU{1fmz(Wt#I<>N+2`PpADp_Lyram!20d2{?;{ce(N)x z6?JQ-Ce@ux6Mt_1uROpLR|8S?3WU(4roE%;4&a_|^}Ouyk%hK}<+pf$-{&<8FLvvB zRGZ4-!A8sb92z6`6#i>46FBW#h{b}(k>Kba4KZ32ADbN6)HdYeJUZMJLy}})hu=9xMnQ-F^#WWTtf5J)jGH{nTOxdjwJ^t#4@X-%1^oYiq0hCw zAD84(A^8d3q4k)71>T=-m~C-)PwWO?KT-o*hsgf?rJTou97ZjnMM`(AOVw*^S|mRq z%CbFJlm=I6P^{ms;oCEH&i>AR+ur-wE@o-nxx&EpXLd(m-Ujw3+t3@F2o-{aIC^yg zBO{{?&>r(a7%fsxNeHBFndVJ=UVM5JkWCa#<4eI0$AKhIB)$1HpL2DAoFxyf{qgFJj>BVRcN` zI&^^76ni*dYU;4tRb;!}IG?>{QMWI`eL^pHxXbq?Gc ziP^ur-M{ql{Jo8V+d#1##c=;ir?cnZPsT|-DYU=6=b3n6J$apE8U&$05gVTmZjc>N{*(9V=|dYM#7kJ#8@Hw zJ}x^~QyG?18*Z=K1%^!Db@zpo6UKaB%Dv?HYvV@9`eFW5B^-J2$xfzMmAm~7Rj0@@ z%9S79?@$~7ppH3k3qCw-CZV^eKtEdx=93EPe;4JSJGCi~@JgQ&G7*}Ulm?21?~-6% zFh$R&1u~D;1mp+LrkWSZPcH-s=<8BU)zpb^e;!%4*lE9YM{)eaFOP31elk=L ztYTlhJziA-yt(s@2%2AB=kZx=F^BA8Uia;YQ9tK7R88l_7dg4=5^W8iVNWPiKUS*$;8WHV-U2H*u8)Cq8LWN^26#xiGu&{aeu1XuH_$Pa8W-PijEI zJh-@#m)t2{MFp?}gP%hQ3QsP#uMrLY00uK;O2H~(6>4_u12?sZKyy*Cj6fp9>ZATm z>C8CKtx8y^eMM7~CqO+VTRab-ZT~ZuIs=@pp-U`T1L1lI^{WZq69f(2B>O(y;X8%m z>^skA$lH5A2kx_+*Fnz`jqe$LjnVh7ag&y8&J}~MZX)zwFYo6DKJt-=gk0lB^i&d< zkQIUO`KtyzxaY#DrqN+Mjby(^Yn_hs%&#dZPJwBXGTTSqL4k=yee=P>Z?tf}4wFMD= z3aZSJqEen9TscwR>{v3AKo0AdGRC$w{ly~JP|J_Vv-)8&VcebfgeJb{C>_9tW0_ma zHds%jKN0%8Naz#)yl#a6Ig96iw{zE%7oVi3=03Jfda{OzONY0(PuhI&)L!YfRia1$ z%Zh#91llJY+{9rW04=lrLJr{Jk5v1Q9c^uW6$XtE2$*kbK~io=$L&d4?Yao|EnXz! zyd)(5+W}2Jh(Gq81u5V-BD;4<{c^OCDk^Z;u1@UUXiW(`$COkC4;Iqm=K%K_)2Atsc7;dqo`f>hVrY$Ki-0j0c+_G>8@J zh`jJ;@|X!?4Hu78sTaOnWHvv|Kuu0RGRV;lfH=m5NK`APlw-v^aH&rrk+T0quKul{ zj<}FbxBFV0s^nE>UQ6Y~A%+r{3MiT(0HC&CEjHuNupqb*vgLD1qg5!#jI>s<(%`7S z_aD{$Z_+0$8nJt+tv6bqOTH8KMzPvQw^d)iv3N*cR6bIJ*=W27(BmLkIQHlfJH<<& z#wFQrtV8O7~;#| z7<04#@SvfCDX&S$MQe+Kdq`NVIJbOr(>&+>^APzf@&qnr(d27aq^S6$UiW--n^e8# zcAnsi;9jRNY-y*goWiy@o9!HB5Hf*}KU3T?WvZ5Kt8zxF1UQWw1&ylTW@eKx&A#Z% z5e8;H;M|^Q=f*ilYFT;t*&+6N3fo}$QqShG&oIT5@}kr~0Ccg;_CyOyKTGV?QQ zzFUQQOq&1a+dP454wl1;zvm@2jjm>(^9(nGCmAe;Jv>q~7#nx;;*p_VyJiBJ`D>(6cpOSEF)14h zSWzse2h}~inUQ>VFNB$sc|j@H3$Q)5elbn6j2g!6-jJ4Z3JXNU!U`Ti-s$0yDU)8P->J>eG2dQHz(p{>N^{ zN}Oe}2*I?(yD7IAT?npCa8J7smG@AGe0`p1nD3=KR9x`F#9M21C~K zXID2SRH!{0MzFkIh>);&uLUgVRB6M--@i;kvev}avRwVPUH2y~x{NY&4|*b7WPLC{ z)uAIRw%E9$P^BG#z{GY!wxRh;)h$?9x^H#*7Q#U-F=)g91w!?*$^cqHP=lnH7Yh+# zis48aR5X*3#X!dr@+j2v9N80YSwYtGm_WpsLu-%@Sv*3Hr}m4^XRRqD)nyn%IbUg( z{_=kK$kZwsgP(%&kK((5+|xKa@|ur>DN#u4k#fVf{hP^0Mv7cyBY@=D)QfD_xLg`> z0Nlp7C3!|shlhRnq=6n*!ini9n**RyAvwKpJXgH`_b&MgW48wjbsZeqj)#o!vFV#}Qc>F%l9z;nBl4m#>E!M9c zGLbtDY}H&An)^4eZV&}9V2Q^^iV6%bGn*_uG56P2uMjDAo4ySwD zJf0g^kbpU5{iWUs_o8HnX5oYG(rA6R_;`Mxv&5O-%WPc#tI1bQu6GSQ(qOH_=J_G; zyv+o=nZw!(wSO)r!r%TR0o6t*@*~rA^r_EMs26CUoja@`AyJvFl{V4Q{iVio)1&^? z2Hk^v8nN)dfx|#mOIVNMt;vniI8nTYdFSR z1@7a$u>W=I+C~g_N0+a}ygMG09gmCOA#Q*HkRYUjn9iS*7WIvdQCjLP)U{rcems@S z%vFET1RT%Jxe84xWGyYGU&TLs%25n&)I4&v8vYp%(DWy0Zh!y&T_Qbqc&R>*1I)s; z9P^u*Rup;~cG%~q)x1lveH2!vIxAQPtL}>o z(dwq3ivG>PlT3Jj^sYuNLtL6?SK3mY_6*4hpGf+FCt8gp47b9K%&!e?RO|I~wfa~T zRpw+28J|l0K<;Q6R7S6gSp-ngZl2+0qSK&2OpES|tRBgDu&K7aB*pf8h(!iVs6tyw zycZ!PIT_TP>IUK3z_5^7D=A)@S&U2L$t9Y1l6HU`!?z!UbBOenU|Tgr9BUl32;YvybIf|~6>nnU%UzBZG`UHkom zP&f^$&^CQLE|M8BsU?OdY7h;jSHX)$rjo{$lNpU*t2{n4QOtKr*>v-3_Qb9MHHl`l zR)_ulC?(9MpI&0&zYnBsdHJ5Yu0nb?*l%XH0QSNEgbs8{qA)qC#)Zk zq!t4~T%RsnwuTefD`Zonu5EoB21LraKZ#;OfH$pT48oc|d>_Oy!GrDWCyq8zavNLz zN?!!OAnzE#99{h8hPp(V)eUWt1fo1WK8jE=NrsyJ zeeX1#Iq-D!KXfnZEpX8xf)w~ufcd#!!z=C@h@4SD4Iwgy1eINdMH&VI0tB_FkAzj( z&MTb<`dJHO+;e#Mr=7rN-H*jQ2l77=$AOHsxam&+$}~O8k5HhX`OVZ$X9CY6$zo-O z+=q$oo|gu~NntXFKvA-3~+EEd5$rZ04n)Fx!1Rz`n2tlCRt>>5Qczilv%fl;KLbi7nY z;DZ(uMjWMQV({16R2cBKcssF-`n=L$*!L4deQmk<&9|{;{^$JRj4p|DFU1rj&T3K4 zn#n)u;x_Q}9MqwqNO8|&Vqa53U=Sr3 zXp%@Ft)*?g77KW(k;B+?vTP^t<;U5hIyrYNt=@HIR&H0OEmZY}D47uUI>V4zA-{nD zGJ_W3KfpDTj)5ia3<}e!@9!m^P_Yt>9V5XYoV0_+I+zyL2nBqWIPiD0)8QSh?ZC7JG|*TOp{$7Ezi!zS1C6D@Vq_*U5RT7yiCoeA z5&BUWBd02UKAJb3h#kYa=?K|aa+MpVPb2PKxYsY~Qv6SeetJmjgrG(i=rX{sJ$~-3o3P z(px8Swc7EQu~JAeK5**Qy0Wrztr)&ZnM1)$19=wnLW7cd_lo2`@o`yW;@5aE;&ruc zsGAP}(X-TLloz_Kq%aT(*}hCOrBZ-$mw+qeZ5%B3Dybh-Fz84*8Ay~?Pj_w)O>}XhAYGVOOMjTaf zMIQC`{Uk6cglKExH&d@%QfWqIDizf(n$rLJ;=do`lYBV;jgMRE>gQ|$&Q9wCE>Obu zmz%OgI^f8~=-V~;mRX?5p(RI;vM!;p9bRWOes;I^L=A8-pB43nu+x6#i@Zw&v3!tK z$HSv;i>R?QaBb=XPJE!lxq;4uJ5S>d%y(&);Jg~U<_o}dx9hUtZi&V6?M2q;`+X*H z;(mlhx;i7TRc_;64@rKNf+{nKT-)AU(|_FLs(J8D?X!T*)zzD$lc=EHm-RJr&#^fFm2m(PlpWThjh4u@G`mYQXCr*dXs`-=%P!ULC zP+E)G3Z>(;syb%7S4_A?iE!3ZTnEy{xPkni(O)FLPkLJV00Yx9w$I0_)Xu4 z^9JDu`a1Typ9YGO;0-N+A5Y)M2Z@{<)f#>7G$BPd zP(Q`{)*yD=Sr;*zO}$80C>9M2rB-G*wNy4m^|w8X8=UJ@%#CMeI2GI_k_nd#Pu9iWPo=!5G!|!1Jsn`=HD9|!@Z1oh=wAy$Q z$M_q6W>xT4NCCTC=L+Z`6q4%>pz}fT+wB*y_dmL3PwbYZ6?i)v7Y|7pBt%8W?V00; z5@78|OJp;Ff9G4i>14gF=b>*S*uPwWFYPnmp>(Lth>Iftd;>gFDUW&W*AB@WEy)q* z>GsYg-ytZ3>4fskNnF2^ggu#mc?EUUJ*`XqOrk{i-rvvg;g5?GtVIH~Zk^pHLl+2yih(C`Pz8J|Je(jf5aov|=tOGA*^()d9H{>#n0#_{rh)i+?NuJ`! z;0}8ml|9d-;`T?Hmup>i)F4YE;v@KStYo1^k2lQL%QvMUf*X!C{3<*}V>oh9I$zJs ziB06<;VaaW8!ziOzX56TSFD>Dhki$%GDr6}iq3;N{Uqa!-`ann0Q}h9t!R0Ge{zs% z*ZWKzna(PBBIi%YM}{c%boA)@e?;G?f~-(uZuFsa*6gk{qUHz9dPNq=Lr-c@GB%Fu z!H)?KJ+-7{TbFfxr66gHN&V7=?|nrzfAn|lK0FGJ37)!$;v<3RD3|9Q-P4z8$kMJk z2Em_$`B}konSkqod-yOUz%!cV#jo!%j+*J=5ZG5LmN4R?(k~F7q|e;$q{7hT!@W6_ zp>uOeadZXoHC$)~@*w(WNJ+D!ryM@fuEz-62m{}8j6WpFcGowKc$BR?ED-kk_3N2) zt{T;qdSp$W4TBg!AHw?8JW_CTKUBaGgAA@;uuuO+2C+m%{&}bT^tqH2wFG4MvSrSp zVVK>DE%f+ZC;ETz>0p1MS+#>-o^J|hxlvo}={`B# z(lc5A_;~*sK(ZJRmMJeSn)J=RSUBSZOLw_m6%f3v-60LXO4sfQB_zHck;vDE4xlO@jyy+a zc1TECf-Uq3y!KhB&x8IJ+0(D z?f3iA_bTfP;3G)j-bx%a7_vkMD#N@ zczXK%X7&D>=(fj~`T|2lQoQeUoCv)g$xh=x@v+3dQhYm+RL{oX+RxdD9q-G%w9tel z!nY=p$keE>GU;zJp;GRU-oL|tw*{!0U2}V7w=ri_;=Jl!FrG&r2pKpc{iNyj@2m2V zTCoxA0f5Auy2lF2`sP()8Vg*I$ai}2dy-zF*V&KK!X+RedVfTvLYK=vKCNJ7zqipt zbc1JKCs|A+e^Zk#Fdk=)a0)T0+}(#zyqcR3$bsydQyN5tn|(ELj?-Ysj8y?S#mcGJ zSK6l8Hxt4KPra05MT55`Sf3}%{-P)}?n})-TLAr)Nyd=~uIa{@rVti5FXR*Q~NRgaAVN6Rl(-sIytm6-(%w zuj(G3#%Z;2>;?sB<)V?zC`{XbDLypJW_qf%J#_GPllWt>ft0`JPY5Hu05)69Hns?=!zevEQTqtfrNsOUh~TC;XZxWp$Vpn(w5~NKcV| zkqi(EsL!*F^DbWAcvMkeukw|U%70!w48pD^XhTt2X@B@JLJ?LwTjlEc)Yvyf&*$Zp zUw}6(cYqZO5DY8Imwc0pPVS{cFyZAQlw*$15u0NJ#DsZeW1g|Pt>Il6#c))@#b`dL zWc0>q_bRVjUwYcZSQ`I8&ws=^9T|Laq-`6icJ05wT!F>5UY}J-tKxPGGn8lc6dhu zdj+8UrnO)CNyv3Lv;fU-pb6_2$5fAAf|`{vwbCGG%&QV2xDAwSNSjAK=iAkaOzXbBt~`@_|xMQm+| zsWO)bi{Dg|c!9Rxgl0$dxe=tJQ!2W?L_5QBP~aOer~+j=S5N|`_b#)9-!awxAnjx1 z>(k9dLsx&+ZH~MyWcmstzh9aH-Qd6T_9EL*U{UMntJF0_a8MI1aDY(zr6r@qJha^6 z$;K!IjaRkVbJ)Tb8=g7~HkCs~_yG?_^(F?Q% zmr|No6==@T-Ln9qHaE(PwuCqzp2ZooyV?DEo@)m0fjcwRe%vjIjpqZ%4&rnc0Py0-{PZ+ee4aoXKJzOev z2MvA(1B4Dj12$`|%T7<~DrfhxmoltMAJeZRrNvFz?&>kkNJDY2;HW+7>x!#BElTs( z0aFg$BaC2}rM_9MHRK$xhP8HMA%rIQ+X zO&=K5ZywX~4&JorSdq;7I{E2|f0F903`2!#ml@WpND)gGCDSsinR>^ydQychYoIqSDA%-+uH z_1AB#;%>(oMdk2C(y`-8)$7Gi$kM;N&mme=`Wy{w8dW!^n&LW%RVC4@ls>5)w`pO&*6idHP6x>OWB=^xpL}5D^!Vu9}ry9qLp{ zq3}`L(ySl+Zzm3=4Xi7&v+dhqmgCVMEsHBC1l(<-yPtl-d*05|Ecc)BcN$5zrtjy2 z3nOFpZN>hcSz}KD8CbhiUY=mSxprQaHL-&6Q#s}+vAEkYxgRQWvJY%ycNY`x|r zi3E8jvn-suj8kB69MCQZSGhn-%bkd-mimqV;`b7s|M9PKW||w5V%CZcW4@vk=c+(> zKin);2h!o9D<*623&5BW&#Ar_!3+w_-;K-?S#C)HM^VQkF6@|@*X_fC;Uc&_p#$3ZwR_Mf*HcLzhy}&+nF;tsKCU{zFo)r$AN15>0%?hM;F>>QG1I6Ka0` zym<{_7Y^FfjZz+8gV7z&PK7V&=JM%Wt@OobJ6@S-75q0w+!;6!1u(>rN{s$4Z!2En zRMq3&n+0GkYkPacGf#`*Eby8i^(SWWZ3d2sR{nWu7!CY&f07wX{32LrQ>BKv;;mmr|k@tOaMp8V6y1e%!Bzb=@JLa#dXaLyjIgn5H4 zOcBvlvS=M_2IP*y+3oVR{@>y>=SVF(yG?g9|PJFyh=$Jmh zlTU&|v0ePcGnme5PyTE|^7haIO@_~$!E<2?kseY9>6OtCn&LCMfAS_zz~{VmUe4+9 zR`NF!q-y`)h2>>3Kw*@Vw>BNSqj*lEq5e#MU0Yvz1XpPPdiwY}6>kWoH(&lrtx}gn zH2m35%>1N1qKNR|Pl^RxeX)4ps@INjQ__IW_ z6ahS2!L(fgdmmf;=*!TwI_&(CPl}XQOoK{n)a=4|{tec(l%QE5BT6R3+q_c)E;_DYFB=6t_B1y$<|MmM* zMC_4+QE~k$TW;6bl-2Q5qmg#Ujbv!!20D)l&sCzv)-T~u+^y%)d zqQv%`gL~Q7j=u;EXYCnK+W&crti;R9d$QM$liQ>Re{0LIhi8_On5&ep7a~b5wL20G zmn)qA?>Kr1KbS11jWO>h6QMfjFDGT`z;LR_45 zTc`c(B}+;aoF{bBAwQmfcjCXG+UanuWHv7boJFDHk0}%|T5-VWxVQ^=XW2g_j$>sJ zSI=w1DV?)JNi{~s^X=QoS-*;vvI!v5sjuw3Df_a7s_4A@x)F&9|P9ME5$T11Vq!o_8_Gz80qeHHsj+ zNpVu{T%n(?ynGh6x$5@O*6Uw@=tynX-d2%AW5yCS^AItqJhVo_u|NplWjN|B!8qsM zON#kQshuF7u@!Wev#lAt#>dBOi2n7%@&oLajrH;S>CBaC5&T*iE%xqS60EG4H-!~w zaU($yXCt_W8A_O{?%Y6)8dyDhgQU*42gKD-*eF4jaeL1{PA6~2%`38vwvcFgc_REu zj2Bj+NA7?Tb8_*UB);AM>YrWB_42NR~rpe7K??rIpX6( zA5Z7E&sgE4qWWdib|Cc2;JH8v(of$Q*cd9(Z=K51;q50pPQ!2q1inlKj-{-?IZLC= zNPw6&B$yvJSbzcA354Yz#B%cvlze?$BW8Jnep+J(UvXAgm5N6dC>GWG7mMTg@>Rk0 z)?A9}Jcwkz6>x+9i{MpD+^Eth2^jK{;U3B|rWT9NsuPPg%zHvNg>1Zu7)#=vofZCNiLxnO*n9A<*>96n4KD5v}%uvU( zxzaFWGfnjXtB63`88}}Bwjl?Lz9P8$a26Cvg{)!q4}w&sW3LEN#pd!5JAPgC(;0C| zAbk1u)|VF@e&s5oNp86#pfaE&%6w3$>`iB3CPd*T8jrA0o;>txV z|IScK$*_8Y#VLM?TjYwK<1M#)#w^~|e2Ouv=9XIFIN18=bddzpjza1Uq7HS<$tWYI zSE$=dQ1NUVfv2D);Sy)%#Rel5>5?SESpG^Je`{C0%$#bA1O^zu`&ORY(p&0%*875UA9AqeXK(}R zc>kNV$YbdVud2uP41V+sJ@TgJ4r0*)E60`(4*7D%WKoVk)6t$WiX-$)!yIU-o=je+ zaFgY>q_PU{3yH7DQpm4Izc&Fn;emt<@!|Z$5sYop!avi4L-D2i3)Tc9G*LtAPlb9tRLC6rur`n^Mj!SqEXHLYTNihHPd-VFBel+3zG&H+Ua`|tv z`Oyc?kx(2ecBpX3Nm;jJDZ#)}8tdZj9T!sCrZsL|rWtW+hQo^sag!JykQ#|bMw3#2 zg$_pK>7NCusl>IcC*CGT{DLmky&lk>bjsE0VpscVBP=-Hgycp(@`_DZOs zqy#UfCQWl*$ElL2SwY3U`^3yjMf|#Km9ogTt{0@V)c$PrgdIo6*Va6R-+D-97%OS~ z1-N)<)hAV)*G^SW(z`WD-q6JI2bAj!eewR)L=i1uHe5PLNcP90EZR>vn=wJ2tS3H} zyH7NF^Uube@}yiOt}W*biofLTeTM+a&EM#{qR7C`NZ=GR#hN#>g06#WC05q!k6u4M z$5d!Yg|0Bnt$HdJOmh#0S^(vqI@7KRk{`@DA->-vLpSOvz+7 zZ{R6TK+vP2T61$7V5Wv6=Zc?m=foBSpZ4duH%Z%-vPZ-g0)s>4P3_2!4Y>2 z;qvSqX3Kk@EsH%2;#!D}EOzSL;bu<7EcF;|P6v4^I#~}(zL#$8{FL~r@~=O~=_9Ov zyJjofEWc$GDOOv3+BNIY&tJA<e@Yb|QMefZaHEy8DfIYr~K_-yDgLudQvgB^~8}t8f}mlyCXze|IZxCLPDy zVT(cA_;yY!FB&yGOx*mq6&->QG$_5@Io#r(bqJb^wO=J-oq;FDj6bi?xP0yAMxQ%% z82P^AtFPtH7TITIhq*||x<@C#3%Pc8oVU^WurD?3K2<;EI`8}sk}z5F_H^F*@jp;M z9fV-h$VqsgKnlkPjWMD%vd7Q?+pNC#s-W}QF>&hMI!ku*TeXDK@}OHbL8_#IwrM+7 zZf1lm1$tX0*$1rg-*tRc@jv%3)k#GsSQN6pu;ch0A2xHS@W_$)1SNmb=hiJF-TNR0 zo{C!s&B|5Z3u01>xK)M~+G2MLH!D9Td=YY>VDua z_k07%K?(o}7UFeP0vwTl!G!;lE1eBbZ?QUk_rjX*4#t2bmZr+;qQsi%)hCA z!0)x!_-_jN$~KD$_Z3ti=RNQx=6V{EpMWc?i&M1a5PyA{%qNQ(ml-MO5Z*Kjx7~P$ zOTiFLLV++95$}56I^IMjpTzop6Mn~#kj61a!5KG$8m~})kSw%hBdFPm0VBe{@p(o- zK!60PGU@#G=}SYNdHc}08ec5JI$dY<){by&o9U#4$XGtUE zha)ez(pVf}Tt~=s}|6VGjrC!YxU-$Tfx-ImU6u-i%V@&6QpKL{IEWUj0kNh^``zX2v)g&@W3{l6LZBM#9_-M2*JQOw08I%&`<5=YB zizsg==#;3^;uvt4)AZ{|=35_>ud zqc32|8-`>*7=kmYB>19=Nq@MMHzdNdq|#XP{Ld?Lbfm=n9P%hTq5Vd*>>TrvzeFy! zAR2nqfc~V}BaeDEHbou-+BeY|Bhx}^e{p3dV_GMjJdm*Td5@gB3T`PoBDKOR?j49Z zBW)Fes$yI5u1x#r_vH1sgYf^@AI-P>C%83ho7QiW<&MK~;#>>9Z%XAM(&jw_0vu(O zZ4(VDpY|j^7%QYOK#90Yo@9;ZC3EZJha|ITItH z<~Wft!U{sx?I_n^JB)F!tnM)v+1z2>quY=g`Jtx!S^S_@M&!O2CybW1>d*=beMDJ{mgAB7S56*+-c?QHd|<@zzH!V8QlGH;y+q`7M=kM}EpgS~>nH$$#7cmGdFCi$?tbG0CMyL1+pZe@$0 zAthbCln@b7H_b`b*Yg|Y35qKf4OWBw7<0UKIm*mAmRM+TweY3D)t(gjPzMd508&)#{lw| zJ=T3nNdHF|mhlD%rTG4l4$4q14F!2(!c6>)biM-=j;L7Dloq6zf3~wb*Q6dc2yV8s zoi8Z2t;_YhgqAvk=>G-Woge_DgiJcoUkI2U0TcFLL;)Ygoa4}U&zm&+z&kKsJOQCP zq-d_|0UupMl}2lip8p+U%UeAye9i8dn`lJ|>V#9^qhL%Rp`pP&?8@rHSGKmU<3M2ZUM*H4qumG4@^n-)P`Y_f%+u<(qo z6J`k!hHz^bduTtAdrGLz|Lv=`Y1>P2@uga3a8?f6tvEFTR)E3x=6ss{ZV++f?H%Q$ zhyDn}7~LP&e=ZsW7}Mi&3=cE*JALGG`s>N{5YCG~P&e2)hEc4cR zh7F<~cTiwlymE&CKf+T)Y?4vHUO7o#k4()n zA2gTs;wYw+tvzqpw3^1hTGSgbC6J71JxNS0GdTjBCk-;7mHTW}vLhdo9zZZUEotF| zRcGipc*fNFxy|_Xvx@F~x%OYu4p_*`YUJ{au{Yv~*M&Tbn}uJCeNu4#3owCf7h6>( zj}5}AtT9GjCD_jS7UTI^@noo+ih2B~?<*SK4)>r9p^-Wf@&dN9At3^PT6_We^UMlu zO;ENyOJ)h5bJ4l%P&ueJh@{Vbo-F$5`?3tp#@gbKwH1rK=H8c~U#^dGdp->pFe#ZI zBAoBu5dUOj48c{YS(&#Z5Cm#itqU*;*r2pvJjL2Zy^=oAX(Hu(L$c|q#4MvZ!x$ME zsftdUVg;OxxRJ8$C6Fnqc$Cke)`tipKI4Rbo3*E*r7gwVhy;GuLhJh=-~Wvy zf87cUfCW7!*Kn!fN;U+A$M>s6xUx1C=+REVWS zHz%VpqbT_8fb(MlS1FyTMyvRJYdDJ%t5Wu`dm=20uh>o@26^l~tvn34!zal2V7=8z z5Nq7j{-meT%YwEpB2?xe3vANKFmX(n=ZwHq9EE_%f;V0UsZ~_;Bxzf;p|y`krj%S)!e)d3J(yXPE|C9Wy-9X@ycWYGvH#dV5!-HaJhu3h? zzfjcIAL-2bb_=Z3xP;?JfdY?Ov`T$CBNm}4-% z4RCre-I&K|yrmalw+y8^^m(A6p#hoR8+&`$@d_wlGp8Z^m1|>*&s;eBJ_?WHT42^Z z*4PU*fr0>ll|hiH=}+1AUoM+x@U^;mhx}Y2N)*wdtYBjTEEWB< zMILcjs4+-pp>8S6R{B6tl0ctZ6TYax8U|kbR)67a4!;D*N3Jm-9x;%14?)|yOr1LE zXo=H@1sOjld;0eeuuc|^V**+J%=yX3&D892F7d~QMTrP@q)X4%N}TEfzE|l{{^HeW z%q8>Sah4(cn)ji09yLy;eEAiH{G3B$lw(^6(pf>`Rw#RQ!`bZwq?JVhN@@^=BG6C& z@q0dYh$(xvjzIZtz~cV3j#c+IRTqqn>P27+cL89?aU;gz#g~g?3i{7vq7*9eEs!ih z7KUyQ4SW6%qYZ=AlTo;I@%JhE$D7yw_m{vB_5#!fy#UC8OoPgQ^T3t3{e6tEJ6YtH zC`w@fwCQih)ZBM+3t!j{*nIbc#_lCRa{OH*2$Pf6y$H2OpWZUNiI~P|Kr-WaL6ArA``Qq}H;MYfB>QCW%A515Z{Jcs!*(X}pD0u~ z#u!41jd8T&EzBrOTp&94zSMu6^BAumI}fjq@=kqQ^M5<0C*EB*cF1^i9^8FEgbSU{ z-$^=XAA`(>A49ZtS#O{bPq2d}^2Ug!nZe4!^a=t=3z&p4;l)`p%SrrryF1^B)7BsxX8c2gBA20idxW!$+7%~qn`Kle#F!#~-VS7Q9eBbib4H7GRnB7c zV;#nA>Jy)c4!8Z>KSt(9wUj_)^w(X9f-4rYfH08IG=n8-Pt)Y}CDpn}_YZhp9KQiQ zNtfwSNkOy+-Z}QZ6n>;__`pJ9jHquH@eQMN?eY<+rQ#&6*{($mA%}O#qPY$8{FP| zQovsQhfAY~34x9HYsweAg-Qk)0u0yOy1=sOrz4 zZ2=EX1pAwmD;Us6;~(q1fgkyBPyZE0-C=j2@l#CBHTWlT0CeNP&Z>I5^63ft;oHcL z?Ro`wXk4F^_NIM7zvTe%jrQc=_$7B25O{Cvn9(Wq!sAEqWnk&dByC_N5 zIc2FnC3K!?L9RML*l2XgU}5pL%^v7{MSc45vb(QUs)A#sS$d_Z||EZ5W10%{~-A_x9 z2n`~v(yhME+U;KXiV2w}^_GHp@h52Esc&UO*5ylN7Lji+>;<#%lDw;C*8}G5IByg> zV)}Lq#a?g%o#u?4V85Mk_{P10%^I*o)rE zD&}z*;0knjv0JwQD*3$6Wa#W8{!&n=n6fR>Oo1SKvws(XscO`raDx`K+0!TeGdoVj zK|Mg&Un=B{zIXV4T7Y+~1JLw&Q%+5JvNi4nh?%WGeo?7E4;AcrQ;b8tz{m7`*w;s< zEkusCt1pYR-`4|SwTfZ*8O@tyR16FZfe@~cWltO_T-V2kfM;!)3?gYcs!#R5r8mLh zwq~f-=}&ZqvIn1Tx6dCoC=!n_!Eve0l5~T=De`f>cbTr!brT!DIpCPAZFs!9e?Rq% zXBa+J^fr~7kMXX1k;> zNYZE7VwgsEkj3a|X>Cst_EWz<cj%h!=hW zETZ4j{!2+m6<0BT!5DmQ$|p?`0mx&+i43O75#$!^vEnd{P~249p;|7-^?!3oZ$T=K z+B^n{kPxtr@`go%rV&5r?*{$p*_KLv>fghKt&=$LIsHB#y4xJ!gPmiqB7}^Qrd=Y# zn2ouv`}L_J7-15A5z9OSLHDykU~ytl^?5Ur;?AGt6yts7g==l%LOK37wja^4UM5`~nBPRZH}ia?Frr9E;MSdDSb*7sPp$*#Ff~ zjjlc6N~K(+C_MAGC_{TQEFB=*%Q5RiAJ-9ZbW^)B)$|L!6Kj=9njF^s=Q)LSv^EFb zy0-EcTWrL&%k>Xh|Ffa*K>XU!68@4g-6MyKMj62*N5aqIOsym4tnxh>)(CPO^|0I zmu0n`P5Ee;V(dPRk?A`(NSUJ?BTZe+H+dbyI0*$BxHRD1`;S7xJ|t5Fh^GB(>mmmWtS z>H^<8(nk~+C{|39=1D;tnkR00{P%rA(qz~`UV7`h3O)OZ3gVF7B8HQ38_d#TD{|HP zMaO*hq@o%~tVWb?ZHQB6C)+uz_aGGp#I5y{we8jzYRkXjzPcyAs`c|j9nV(U32s?a zjN7^%tX@K{+bM$qqx7A<(ow5kD~>MD^c^_v&+GC15xDuvdE)#|<3ECmiXhv#aOhqk z_lV;m!^0Pl)o|I;CtC_d0iKb!&;`g<#Qu@#(cT_$`81WxDs$r(yqSS-XYo6Bt;-xF z6Z*QXIZrY;5dF1B$4J7dcaSpLhTqrodV(hi5s`XZSraF5_wM114Q6kcgO78)fgRUc z8J>Q*(kMwNa)`O|uYi@=+TooP1fPs(Xdn=`$17-M#t#g_2RvKD;oN+Ayy~QBw`>R; zwAVu}?JX@6Yl2%x2SecaZ(N*irwy*IitPPtAYT&%BxXR7fE_h!M`Y?~8k)bSV`NCG zXA8V@KOKZ!JUpTqPKY8xd|M{ALxnm1J_;P@n~B5h@XZciyFpgihFt52^WWfiCZzlI zy-^G_dtlCAI=-&&1j^~*|JW2&N23s$?Z)4?wpb&2*Nor($XPd_X~ESjQ#0a&wGY1r zBOrnu(vJUoEd~Hl?!&E6$K4UNkdd`(w`uR8`IEGl5!^jW7s0IQ9D9B+p1+?Fh1T@m z`2yBQAH)nQh?Xp?&3gyl=cdGSs{!&ds9|cB9nm(21oBf^l?C|KuK#B3U5e?Jr_r_O zmKSw%;>u3h5lsm8E+}6>9pKdh3i>c~blY?TC7stLufTQ!1e>U7O=aWZMgpif+3uw! z%DbxB{{30&1qO=V;#4&8!R2bzB~h_M{DhDAj^mC8nwZ*XO{eNq{2Tax)xVU*vMN(d zQRAUKvDpJ_eDQ33jx8o>`Q}i2iXVP`uQHOc)WUXgSmJ)jp_p_^saJPVBn1-pvFvsQ zXY4#ti6Pea(vl#L_|s8^V9a~s^U-kA#|g#uU7j9U0yhOO509XRH8g=mNvON#(+BE{ z7^S^ACJH1aEVr|VL!q37oOILE)2HfF_rBK%XN(VIwVWFtAX5yO!12fYp_LZ!`oZ@l zQ6;uD((8E}_}9&I+6W>bTp^2PZ5k7dVQTZeRL<5{Q{kveWkrSw#D;Z!4?+9Vqy7WU z%J1l@3sR)A(9Y4NFK0AMg+8*DrWf*!AfHez`n zLdO(-r0ig@SK`JpOo0?PI;p_8e{(|Mg+6bsn=tWO1&gPIMw5O9R<8a4^d;+%<20YJ zvBUZK{q}IAwiR&DcXi$`K7KSViM>=fdUi}ejY@ta$j2GKFTOqF<3&$&XECp%<989IFGrt)+f?I{>6r?JUuUfm#e0wl)}NbV;eRpyzqBD- zD~-W*xORk|6{EmBSXlXAA2!~Mm^{Qt-ESdo{zVcscHZLw_Om`u1~$AI!id!M{UiNG zM(1BvK+@Ctm!Ls0XIKAWP}+wjjng(u=I@-`L{2dWOx!0?1-ir5_t_kc18~Nt*Ma&#eJ5njaHv;IvFXd*>8_F{XxRt z02p-=Ko0<8K;1rI2q3Od|sS?DBbId3zoK zuC5XEupl@Y3)gf zHU!zw@Ntp=D9OqZp0)FGlTfvxPtrQX64;H4&l{CGg*;zywFKYx0sJj3L_jrqwPMFLuCG`Q)zM=agm z)Rbz?Kw9MlXPB?5{F_np1F@fja_XkLvX^1D3|elkok#BlK5*XU|XKmR)5RpXiFS zPsD!(?1g7qqW4K!(Y-ziDCV?VnG0Q%I? z2CzrTRQ?92e zAj@e~CRZ;0Mxu7s(;N;{7_JkLR~ORDNlkjvV{1^U`+b;B?P<2cI~IJUtTGd{k`)JO zQJph!09Y^iI=c@laj|-=UUdhEL+@rNzU9SfE%y$NV>V+Qn*s76Q~gQ%p&?KM z0TJ8nLl2)EVMGfwvx~RA3X?DyOL5_4l@AaXb|%6}GpW^|;9S%aOZDgSI8xzb_`Zdb z3YcLxF*-1H5M+&?&of62aDXY;o&+ic#*3syMtbAR3+L_y%T$(=+e`agX>7$?&p$Dw z@1oUe-f^Ijr$U~%{D#ZqkkorMT$p6s9po=oEy~=#!Q*GE1=CnSSP&7XF%zMg+i&c* zW7U!m<*duhkEFoyX(mXcXPb|8GBb-CM-PQF-?|BekQgz$^s>rXs+`~s)u$sr?CnkP z6n)))MIh{$^Ir3IlvM@UVbD^$Yp8x8nLXyix>EB?l4nRylAOHiT~a;)kK8kM^t#1o zpj*QU8x73~>z0=JVE|@>;&IRPj?&xivM#>W6w_82@Ye2lZoOmxku0Cgw|CLjh+p6T zsakAP&COU(ZVBr)6$}PQ;lvBMKj>VTjRRO0avR{ngEOY_$;G7tzC%5nF*Gpi92xVk z{3(dG9m=27xrkqM&m(ubDVj=N6}F-{ooxv?E=g_7`?|~e-AS&#HrYTfIC}J=Ho~`f zSMAA5PC4@uP3`URdM!dywtTt|_FIbe>zM?F)5D~`XP5-WcRpb-ICsxJVkt!ZN@Xv_JI#AL4kjX4`=_2Z4FHEh_;qgk{ z5=4q48i^B0NYek!8&o{k=KV>HZ4iF(It+b#bz|dSoNmv#INJA{Q5Q3Ghz=8>;&zu` zy#drPI7}i9X@hs`c+{|tc1=B#fp#kv6%+HwRa)^W`-Z3mW(ayHIc$eReXtFDlCTh-#93AA<$WJuRt>BkAmXnCPA6ZlJK0w%KBS-}@^b87XJCplgyc?SomqO+4 z;nNQC>A)~xg}@ouab*E{p46vQ#o0S(7b{wm!ayGSZ(*TZ1zLz*kIMl1N>3aBt+B!y zeXpg$iL{W5-^auG9Y|D%;o7T-d6{86@EYiG3df+kl(&_N)!h7`v#o84%2O@zC?5v%H7h`bMJH_FP%yNiLRZneij;szBKVuogoQf;b%IPV; zLLm{Tw9fEZ0QiSeg8?(eZ1Up zH7wlc?^fa|ssRP|ZB1{+CfToY0nswA7F<(0VH;P^gEzUf~tM zr7-1?D*E%>s#s@|F}w~*J+(-nk!AkRCn!`k-HIY!!8cdG&asi&u#aMCDQ+5JSp#%@ zPLDRPMp4D`5Fqy{Swv>hDfEf6CWkrLu0H$p6z>kKbJTuXF=g!59t`V2cD0j&MvC1g(HdHC+ zOLDtR1GdaHa4Z3kOg}2b@oX?5f937>P%i&Y`J}>WyZtXy6a=|y8U2CNm3Ao)z{^lBn zHQ7n(CS^z?P8c-H`-E3%zEq1ERL$CXNe8iQQ$uX#Z-^p3!(DnAbr9ni?#e=PDd7P7dZ6hicT7#p3kYhxo3<O4-0oLh>r;d##O!>osc8nw%bObtD~{e^u#ZN9T(u$1&$UX= z1TGPIiqA9O)r>~+!;1_d97z>V!WC182DSr^uJ8V_O#$J+f`%@RucLW9q>ziz(y3So zErfQVs``O}uiIV;O8p|2%EASh0(vKvkGAY|+zJ>A#lSlgbyvb-h?2l{hu=kDd$pt-<;&Z-s%)CeIYmCFd+1RLCUO2rs7h;UOLNKM}+`7EG0~SK- zA~F>Jv77OkaDy3UNWtJ?bLpHODtR85!-A?BgQ8|W2eAWQsWN4kbF0Qhd7zIAA?-$Y zGJPK~(Dq6pf%;Ayp|#BvndVAUIJ*x-%r>JQG7#ZX5LIAre(eAc1PxhMEv7ylJ^jY% z#&;=>s|a91R-%hQFSzIt04#3-$Cl{rq_2ya9?n+t32;Rm!(eRn+**mw${w z!0(N(HDxHDw57~%g-S*@vk|v~9X1(k#5vI5^EiE82qwb=_fwg1X~b*wdQx{mKO*?i zO@}xFATm72NQ)QBt4&Cvj|e~4i!#r3`@dF!v13n5X`Der!Ge|HB(;6Pp<&ezeen>z zo=naw1-1UwBD={s2;BVC2}V z)i4W_Y!)|3!^8A z=~`)N>5?w#MvxRxK)Smm1nKT>2_+;%nx&yJY<)tJePQS02#ITQYn4jsgb&8{1Ip0bImWahzax5 ztyGpLVx0&`Pr=eZVcCw1&P44`Fu9l5Xe-0@@BM$TF!^Uw69*KY&Ez0X&UDt7u;pS> zMzu2dYle=ezC>f|h4wecF$#(I3HWZT$boSGa1c)4KXBOyY~fE~J+TY?zq}>5A+KH( zf4R+Wn9pcX3?3F`xc{obrNSwo@)me{KsazxGwabl>5uB!uyMKq2^jLqi*G6po8x7& zE7>pdrXx;#XOvVcHmcG$Y0QCn8DNbt?&jXWWWD5>crK(%WXEaSf*(AWeOoa zF|qAx6$LJ8TkGkihun=eK6vf>)B)==M*O2E`HuTfncM=V)MwBw=NqryUWRc$$tI3L zUEwfOq1~qR1yAxd%>aCcYUrOHqWui?PmRU^rgjIG*7Uk;y+-fM;rir6v=E?{atS-l z#yHe?CnicU^QAnhZ2K5~@P%I$aVXa=wh_M_M{`vV5tL|Uf*@3`MkM~wSDlZ#x0}G4 z^KX3jLsd(|oej3S=7Jl7k0((O%~vrp;5hQ^>8^nOngVV7BfQ2(-($W9ccKW2V*D;4 zRuaqb6%V^Hh9SMVb=cL6?0ATOqTE2B9!3adT(A@(TPmdg_jd#A5g`att!6e}n0$iT z4-m)14%)Ubn~*R+2FF`R;xOqK1#H_~#R;SjMIEFA=*)xf7%C8X1;!X;8$oou;f+Qj zKAylh&l|EInk-xB^ai@RD`40noA7#_QY!lr6p6vF1Hz z<`@kW^3TXDdg^iFb)uihiEgOu)0rwnhRF$vZ(;0%xPUHss%&lE%Qx-zu!dr)6*6pI z)w`j?_65~zpMArV1P@GSB`6cjGT!ezNn<~4Y`i8V3&3L;-ME#X*s%ZoOqgw7UhM^F zeB0;KCUF`OGNjHKB^=**>d3zoGFvctOG6|Z7rIg}6s1!>Z5(bqJ7rpnFYRytgIS7G zJaQcbQKSk$Z43VCChO^C6#hu4s>at|jE~+to1&^*7a-QR3ed-LxXe`n(b+=KUm`0; zwh3;(T1(yhn*5= zf9E(Z;mN~9S&+1|$PT|sy>Mk9+zUavi)&V0KXICPp9a>6WQhxx1>rG@(cJMg< z6M)VWvN=gLmgLXVpR=~0?}7SH%?cu5VHQBK z4kDe?Kv`8cv6*IDk7~QHus{h#2r^Rp>HU>oB86ANiMJGtmj2P7+S^etJcfUwF)2IV z1$9b=3lEO&yPob^WaZ57QjTyXNyELz_j|eO$ptC=Er-P9U^!*WE3WKHNHkPM25LT0 z)_pKC&}pxJ#wvl?pgcsOYpRx#56ertiiwE<_s_}B`BFJlHWgQS0@vIz6<=X^cj5Q6 z@EmVp4cmq>d$gDhn3$LV@EHdEeF6SUS)10u4R#$Mc@6%$zxpT6XU#v+4GD9Xzcj(B9xzO- zKySqDz4J^i;)En1?<&$`s=y|FA~fF3A8PpW`igE=BfbSDq$it8TD7IH0j57lVP%_0 z{y4a(s4^OnsLaevm4l~-!jv^GIur0zE!!rQ+SWs?5%7%u+O&hobBnd!GIbm+v985P z>?d)w$(suk zT-GAy36xN-M?3!3qkLaJ?fB_aUbCXAY^l~q9uZzY(qPlwF2CanGx4P#7 zh9gQVO%)d6vM-XoS_XPEw^km!s8)Vd4k`CI6kwa6SSE1ElfE3}yT4=FR$p#4ZaDKm zb(d#p?ciwp7sr_^`$ls2QFMLigb;@IzgYl`5(xnarJ+od|5cVDH}N67?H!{+xLNTe zu6s)svne+7^mwvs)mveH{?T7qcSM@8+%d2$(~)kU(3Mq>W({LRLW1|Kz1IU-z02qB zrh0(mQfdmOb*8_no=7o6Whd0u{r^azMSNGY4ITMy%GG{)S_#wq8DT8EY|DFlkDIrF zy>fD*B1RJ`Wv|@fxquG6wuPpR6pTUdkel-Qz|xp;^|+`mGbUIBi9pAjW{P&%!hbW#3QBlALXaL zN=%ZKY?Qxah+9K;;Ib5mKR5kU2p2E@9OD~^2Rk@q`$vnViz<*z3sQ7>!mgv#wkpZW&Y=kr+$9D-$hYz)1htwiZ9mv4BydZ z)@j32)^GAB&pSd=^STv>G(@o1=mL+?GvQ9a-{O!lRW;Mv3xFdiL&SQWQvXLX?j4@| zfB@QsH=HzhajR=crU}tm|GhrA@Bm}ZUs0i%R$obAS|&}|+l(qoWCA&x78@|kIzw{I zP;~NN2XX^uXa&F8pvO57t(WP;Df-Itv&508X9>X)Ax@w!xw@L8EpgrQu{}VAc-QNZ zf71+33OR1uUGNaRSm$IN=j6BG{NZnNafj&L`a6QQla;7V<^UCa6^Hl>;<4riz=^(y ztB`e`#bcWnilEke`}aL)V>kN*e|)-(Cg4A^Ftepw$tZZ~gds^7EX*DzU zE~-uZMbRa|5TbTRSB^z1*ylb+?8tWg;&W(~P0S6~D)0Dj zQwXBqC}E#v(GC~MIv%Td58|uG$a2&!r9a%5!U3W*Vi8}8Z)KoD0 z+Hfyov9_Y5wICg-5}1RLk-CtPzW}%bBd#>chz#j1-7;hKr;r9tx|zkSZLP6fj3x80jd;e8eE^6G+ixu3Jy_LbR$Wr9ja_PIe>xn zHK;BSVPbu9=xw5UW|&=>c|ZWX2eCqcLo_4f5~eSPkjp);Cgi=<~@+J3?}u zbK#CXHT_*Y##4RR$4X60-A!-!Z2e_g$~e1$kVK2*p?8Fqo4?_5NvyQ(7wq7OZZ_>5gU6M9@q2t*`7~St_x714Mv-6Rg zz_0n0+{l3Tz2fXMt!&$Mi+=el6xcLXVq7EEZ8P~9^_vuP?M7@K=XI-;2v(_tFbhk= zbL|A$J=OmEKCibm2*;tvcd*2Ec&mHcdjU37IPv{O#)yg~Tgcr788)6Gy!?f|g)m)s z0K@}-5?gvI0bPapnFrw|${L#H22uxQ9C<0@XyG*6{zZmG!xZQ=e>cf8S|<*YD3p5b zW3IPigMwJCLXE9aKA50?8;yyKP>S)=*ZghiOd!N?)S7S1UZIpw$M0vw)oB|hzSo_% z<`+lo=2=^CBo!jUP1Pgz%0aV50+^;cumNX?ji`7Mn?K4;wACtQ^LEG*FMM?T*7)8qbO{;670h9L!W?GidWa<6@1&n@5lx#o{n5`s+Z^VFP zH9!tAS9uAOGq*9h;^fbP&wE)H-qe--i;nbIUWudSi7Efrh#r*O)2sv-!_s7a*dvAq z=FR#klafsEfr#!%DoZ(wM}}4L+m9=Trt5xVqTN>rrQZFr=E4?lSKZhA!f5FN#)cS5 zbcpLfFQ}+#rt$n>oGIWn^s_R=8GR(YF*_<1w>eacBF=xn?YB+OofP{qz^8rxa$YuHx@W~;|*Wy~}CKHcbnJ6RllRQde$5$&zaE5#^u9IXl|6%h;mSSjo znr*?vPl9CI6yl_WMa*FtgqBlmB&zi20{QJ)fLO%xR<32zE+|gTeM1Dj9f+VoZSQxl zngzwe_KQhS+*Ttu0u4qTVJTc~+~c^O@PIHxsVKXHM4sUMY~z+BWX= z+ghC@$ah(BB?3}_Zym@?jy}Tu#NTY@JlxgqH)2)b)+3AaR*N8uf!+sh$<4?nM6wd}*+f9`Jzvb5(B-u+UN_nw@ENjJ}fm zvTfG5s98}sgTSQc_t!OdkD&W5xJ!&YZ;`Nk*-mB3E(|2@V{>zHw$9V!&mcSW7BIn$ zS>8EDPAa^i1$#crnmP2O1ji2Ne}#@h-CCvr=RdpEF7M=9iFq-~yuvaF`nw!ZsK_XR z|F^jy$#Ycf0Bi)>l8=$b*_UIx<`aSo5 z)Jrb_fSpTswu^ zG{=0kd35D{!tX0 zdUC(AOuN%jv&w6*a?b`eY}#_s?CXDws3zh@*~ZO&CMrT`W7ZmX3RqXzA#gCYKS)+{ z2cGbE_nuMA_vGtXb{|pKP;GK@ZP9r{cJ|*ClLuH(mmAD!{%HqxnxP=F!?%R$tXX0a z)BrXLPAnb;$B&_;khNzA?#RGr!w)#;mZpUEhuH3=X6XP&Shh2QB93+DR z&va{l3|4@qu51G0d!bj}4Z7qTiLer zoS>U~UIuaxf%>zyQR_r@LW-e~PT)BKqu!)D!fH}U|LrjA)#dX9eX z@Z;c4{6%*(#ARI<%8|%lWpF?IsUSs_`(o{)a<+C>Dj$q{Yqd(@{t*531fu(s(tP~n z@OR7wbB5+`rRjx}+0@9B)vdIK;MO#t>+YzXs115qM)*d}vy?T@bTXsCHxgmRK)@j_ z9OPX&hXsy!LyzlVyHfSXVixg;z^Z}hXSkhkr_>jsxF)tIWDz}{C zz)js9IWlVfY8$%W$uh{1##8GPg{JFks+usoxXYtN{Mjvya}7t?31!_t58>glttcoA zr|(2@nGnlr84J6YRRl|mef&1!X4y?xlu`k^kj_%UhJx!|{uB$Q_49xvHs)*YRX;cTWScOrWAozOmEg268wmQ%-FN+Fb($F)KHj1m{PF&+QrCl9*5_ zYV-K^urWuxAe0L^iJ$jSJJhYX88O@C`pUz1l_`;h}a4Jdk^|p zb#-+EnJzcf9VghM6IJD{vv!WQLbOeUrdsc`ArME}_wmWeCPG}`cd$s>yu)V6{xf!O z{6P4o$_3`V+BLhs8Q&OzUw&>08D#Es z^#$WBZxRkJ+P0dpU11Vt(jmXqa*k}&~TET6yqMMd(@ zTHTNP=b-Qu$=@s$<*sabrPS3?0;v%fW|_tN;ZufWvWd;xL{hhdmu!}=Dz!^LX)2@_ zfb@W>L$sc%{2iJD%u`{CD4#_*S67br3O;SCEFTdgwAZCmkiOmkIi&^ z%RTefC!t}V{)z?K_YOjvV+#M8z6m1*);JIlzKw?`&lL<|tm-q9#|<;&>~9`ebFlQz zcv(ebxnN&+3by+9Z%RLu&0-w`zSaEGXzQW;c>mhg9o33#t)LjQ3dVeO8K(gYb}$Y+ zl8gdUPQSdOU2gZe*WFEqIr(ukjBkF}u<|>j%g2h!?tSGH$Q2 z29zOet73e-!K)FamJkF`M&2Ji6&1zNd*+3IO>`ua0FwG?0z^3*?E@mDJiY8cNEwU9 z-Ov!ADJIri^+WmOW}E#4NT=>64Vt?~d@ku) zuGju~(wzUrAAq)7;r_tFU=64$&dm$V@ z?@SqDll(eFg(w6i8x2F3SD;X4?G|k4kpQ}1qP(3}ZuO4*U-N9$Ld^4}dk)Gq0f-Hw z$iIm;TRjuy8GoRE6I4U&7ww{(cgz36$hS>cq`PfgdDx!riz zP;c>}IGIy0_zBpMaTdV`(Wc&czU5t?;d8R&MVcb`ifCQtY0p-p|0<`9`bXl08@cXw>ge?;D(nJ1ftw|%4^wa^M#^oisd#+Hs&egGv`y-Ac> zkq;lf;GQ2W(UHbx#oJ^+C=YRf=q-VW*G(9XgZOE|`){T1;x&zduVUFy)(6ZmYo6a? zOTEHX|2`8y&s94g9gwa@pMdlNF^BiX0+CEy{Dyy3758u!STEy8(VVB=n5w^mo%^)L zhK8cJWm;^m93OUll1|4(_z3 zQ~>;s-@)J8EO&-Ije~}x%dSO#8WmVk|G_Qfz24w`@GHU*X}-4!8xkjYmSL}(%F84p zYS2gU6TU(ibyA6*8N_A16{y((5o)QlkbA4*1ZC=EWoKL?hRs{yby9&E--XVl~q! z);@R&7j>hL5~TpfR%9!v2zB_ohb`CeFug*_c)D#g;}+887&Rc5ckQvT0j-dX;ym%f zDm02@q8#MDu6473S4Gg&JXYm8ajU@1`@L&Zw0+|1)mMe<9&fFv%v|H{Oev@Y=+9FfV

dt: {self.err}
5.13, auto_exposure False & auto_white_balance True, below only auto_exposure True @@ -77,9 +89,13 @@ def read(self): if depth_frame.is_depth_frame(): depth = np.asanyarray(depth_frame.get_data()) # clip max - depth = np.where((depth > self.max_clipping_distance), 0., self.max_clipping_distance - depth) + depth = np.where( + (depth > self.max_clipping_distance), + 0.0, + self.max_clipping_distance - depth, + ) - depth = (depth * (256. / self.max_clipping_distance)).astype(np.uint8) + depth = (depth * (256.0 / self.max_clipping_distance)).astype(np.uint8) depth = depth[..., None] if self.pointcloud: @@ -88,7 +104,9 @@ def read(self): depth_frame = self.temporal_filter.process(depth_frame) if depth_frame.is_depth_frame(): points = self.pc.calculate(depth_frame) - pointcloud = np.asanyarray(points.get_vertices()).view(np.float32).reshape(-1, 3) + pointcloud = ( + np.asanyarray(points.get_vertices()).view(np.float32).reshape(-1, 3) + ) if isinstance(image, np.ndarray) and isinstance(depth, np.ndarray): return True, np.concatenate((image, depth), axis=-1) diff --git a/serl_robot_infra/ur_env/camera/utils.py b/serl_robot_infra/ur_env/camera/utils.py index 88516e4c..aa6c6a75 100644 --- a/serl_robot_infra/ur_env/camera/utils.py +++ b/serl_robot_infra/ur_env/camera/utils.py @@ -15,17 +15,24 @@ def finetune_pointcloud_fusion(pc1: np.ndarray, pc2: np.ndarray): def pairwise_registration(source, target, max_correspondence_distance): # see https://www.open3d.org/docs/latest/tutorial/Advanced/multiway_registration.html icp = o3d.pipelines.registration.registration_icp( - source, target, max_correspondence_distance, + source, + target, + max_correspondence_distance, np.eye(4), - o3d.pipelines.registration.TransformationEstimationPointToPlane()) + o3d.pipelines.registration.TransformationEstimationPointToPlane(), + ) transformation_icp = icp.transformation - information_icp = o3d.pipelines.registration.get_information_matrix_from_point_clouds( - source, target, max_correspondence_distance, - icp.transformation) + information_icp = ( + o3d.pipelines.registration.get_information_matrix_from_point_clouds( + source, target, max_correspondence_distance, icp.transformation + ) + ) return transformation_icp, information_icp with o3d.utility.VerbosityContextManager(o3d.utility.VerbosityLevel.Error) as cm: - transformation, info = pairwise_registration(pcd1, pcd2, max_correspondence_distance=1e-3) + transformation, info = pairwise_registration( + pcd1, pcd2, max_correspondence_distance=1e-3 + ) r = R.from_matrix(transformation[:3, :3].copy()).as_euler("xyz") t = transformation[:3, 3].copy().flatten() @@ -33,14 +40,25 @@ def pairwise_registration(source, target, max_correspondence_distance): return transformation -def pointcloud_to_voxel_grid(points: np.ndarray, voxel_size: float, min_bounds: np.ndarray, max_bounds: np.ndarray): - points_filtered = crop_pointcloud(points, min_bounds=min_bounds, max_bounds=max_bounds) +def pointcloud_to_voxel_grid( + points: np.ndarray, + voxel_size: float, + min_bounds: np.ndarray, + max_bounds: np.ndarray, +): + points_filtered = crop_pointcloud( + points, min_bounds=min_bounds, max_bounds=max_bounds + ) dimensions = np.ceil((max_bounds - min_bounds) / voxel_size).astype(int) voxel_indices = ((points_filtered - min_bounds) / voxel_size).astype(int) voxel_grid = np.zeros(dimensions, dtype=np.bool_) valid_indices = np.all((voxel_indices >= 0) & (voxel_indices < dimensions), axis=1) - voxel_grid[voxel_indices[valid_indices, 0], voxel_indices[valid_indices, 1], voxel_indices[valid_indices, 2]] = True + voxel_grid[ + voxel_indices[valid_indices, 0], + voxel_indices[valid_indices, 1], + voxel_indices[valid_indices, 2], + ] = True return voxel_grid, voxel_indices[valid_indices, :].astype(np.uint8) @@ -62,7 +80,13 @@ def transform_point_cloud(points, transform_matrix): class PointCloudFusion: - def __init__(self, angle=30., x_distance=0.195, y_distance=-0.0, voxel_grid_shape=(100, 100, 80)): + def __init__( + self, + angle=30.0, + x_distance=0.195, + y_distance=-0.0, + voxel_grid_shape=(100, 100, 80), + ): self.pcd1, self.pcd2 = None, None # 10cm width and 8cm height for the box @@ -78,15 +102,15 @@ def __init__(self, angle=30., x_distance=0.195, y_distance=-0.0, voxel_grid_shap self.fine_transformed = False t1 = np.eye(4) - t1[:3, :3] = R.from_euler("xyz", [angle, 0., 0.], degrees=True).as_matrix() - t1[1, 3] = x_distance / 2. - t1[0, 3] = y_distance / 2. + t1[:3, :3] = R.from_euler("xyz", [angle, 0.0, 0.0], degrees=True).as_matrix() + t1[1, 3] = x_distance / 2.0 + t1[0, 3] = y_distance / 2.0 self.t1 = t1 t2 = np.eye(4) - t2[:3, :3] = R.from_euler("xyz", [-angle, 0., 0.], degrees=True).as_matrix() - t2[1, 3] = -x_distance / 2. - t2[0, 3] = -y_distance / 2. + t2[:3, :3] = R.from_euler("xyz", [-angle, 0.0, 0.0], degrees=True).as_matrix() + t2[1, 3] = -x_distance / 2.0 + t2[0, 3] = -y_distance / 2.0 self.t2 = t2 def save_finetuned(self): @@ -98,13 +122,21 @@ def save_finetuned(self): np.save(f, t_finetuned) def get_voxelgrid_shape(self): - return np.ceil((self.max_bounds - self.min_bounds) / self.voxel_size).astype(int) + return np.ceil((self.max_bounds - self.min_bounds) / self.voxel_size).astype( + int + ) def load_finetuned(self): from os.path import exists - if not exists("/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy"): + + if not exists( + "/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy" + ): return False - with open("/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy", "rb") as f: + with open( + "/home/nico/real-world-rl/spacemouse_tests/PointCloudFusionFinetuned.npy", + "rb", + ) as f: t_finetuned = np.load(f) self.t1 = t_finetuned[0, ...] self.t2 = t_finetuned[1, ...] @@ -135,7 +167,7 @@ def calibrate_fusion(self): def set_fine_tuned_transformation(self, transformation): assert not self.fine_transformed - t = transformation.copy()[:3, 3] / 2. # half the translation + t = transformation.copy()[:3, 3] / 2.0 # half the translation rot = np.zeros((2, 3, 3)) rot[0, ...] = transformation[:3, :3] rot[1, ...] = np.eye(3) @@ -162,16 +194,24 @@ def _transform(self): assert not self.is_empty() self.pcd1 = transform_point_cloud(points=self.pcd1, transform_matrix=self.t1) if self.pcd2 is not None: - self.pcd2 = transform_point_cloud(points=self.pcd2, transform_matrix=self.t2) + self.pcd2 = transform_point_cloud( + points=self.pcd2, transform_matrix=self.t2 + ) self._is_transformed = True def voxelize(self, points: np.ndarray): - grid, indices = pointcloud_to_voxel_grid(points, voxel_size=self.voxel_size, min_bounds=self.min_bounds, - max_bounds=self.max_bounds) + grid, indices = pointcloud_to_voxel_grid( + points, + voxel_size=self.voxel_size, + min_bounds=self.min_bounds, + max_bounds=self.max_bounds, + ) return grid, indices def crop(self, points: np.ndarray): - return crop_pointcloud(points=points, min_bounds=self.min_bounds, max_bounds=self.max_bounds) + return crop_pointcloud( + points=points, min_bounds=self.min_bounds, max_bounds=self.max_bounds + ) def get_pointcloud_representation(self, voxelize=True): if self.is_complete(): @@ -184,7 +224,11 @@ def fuse_pointclouds(self, voxelize=True, cropped=True): self._transform() swap = lambda x: np.moveaxis(x, 0, 1) fused = swap(np.hstack([swap(self.pcd1), swap(self.pcd2)])) - return self.voxelize(fused) if voxelize else (self.crop(fused) if cropped else fused) + return ( + self.voxelize(fused) + if voxelize + else (self.crop(fused) if cropped else fused) + ) def get_first(self, voxelize=True): if not self._is_transformed: @@ -205,7 +249,14 @@ def is_empty(self): class CalibrationTread(threading.Thread): - def __init__(self, pc_fusion: PointCloudFusion, num_samples=20, verbose=False, *args, **kwargs): + def __init__( + self, + pc_fusion: PointCloudFusion, + num_samples=20, + verbose=False, + *args, + **kwargs, + ): super(CalibrationTread, self).__init__(*args, **kwargs) self.pc_fusion = pc_fusion self.samples = np.zeros((num_samples, 4, 4)) # transformation matrix samples @@ -234,7 +285,9 @@ def calibrate(self, visualize=False): # visualize for testing pc = self.pc_fusion.pcd1.copy() pc2 = self.pc_fusion.pcd2.copy() - pc = transform_point_cloud(points=pc, transform_matrix=self.samples[i]) # transform + pc = transform_point_cloud( + points=pc, transform_matrix=self.samples[i] + ) # transform swap = lambda x: np.moveaxis(x, 0, 1) fused = swap(np.hstack([swap(pc), swap(pc2)])) diff --git a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py index 06963669..2ca01c91 100644 --- a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py +++ b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py @@ -5,10 +5,6 @@ from ur_env.envs.basic_env.config import UR5BasicConfig -# used for float value comparisons (pressure of vacuum-gripper) -def is_close(value, target): - return abs(value - target) < 1e-4 - class BoxPickingBasicEnv(UR5Env): def __init__(self, **kwargs): @@ -19,20 +15,17 @@ def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) step_cost = 0.01 - gripper_state = obs["state"]['gripper_state'] - suck_cost = 0.1 * float(is_close(gripper_state[0], 0.99)) - - pose = obs["state"]["tcp_pose"] - # box_xy = np.array([0.009, -0.5437]) # TODO replace with camera / pointcloud info of box - # xy_cost = 5 * np.sum(np.power(pose[:2] - box_xy, 2)) # TODO can be ignored + gripper_state = obs["state"]["gripper_state"] + suction_cost = 0.1 * float(np.isclose(gripper_state[0], 0.99, atol=1e-4)) - # print(f"action_cost: {action_cost}, xy_cost: {xy_cost}") if self.reached_goal_state(obs): - return 10. - action_cost - step_cost - suck_cost + return 10.0 - action_cost - step_cost - suction_cost else: - return 0.0 - action_cost - step_cost - suck_cost + return 0.0 - action_cost - step_cost - suction_cost def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 0.85 and state['tcp_pose'][2] > 0.15 # new min height with box + return ( + 0.1 < state["gripper_state"][0] < 0.85 and state["tcp_pose"][2] > 0.15 + ) # new min height with box diff --git a/serl_robot_infra/ur_env/envs/basic_env/config.py b/serl_robot_infra/ur_env/envs/basic_env/config.py index 4f4fd3d9..b997ab6f 100644 --- a/serl_robot_infra/ur_env/envs/basic_env/config.py +++ b/serl_robot_infra/ur_env/envs/basic_env/config.py @@ -4,17 +4,20 @@ class UR5BasicConfig(DefaultEnvConfig): """Set the configuration for UR5Env.""" - RESET_Q = np.array([ # reset poses in joint space (multiple if preferred) - [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], - [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], - ]) + + RESET_Q = np.array( + [ # reset poses in joint space (multiple if preferred) + [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], + [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], + ] + ) RANDOM_RESET = True RANDOM_XY_RANGE = (0.0,) RANDOM_ROT_RANGE = (0.04,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 0.2]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -0.2]) ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) - ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + ACTION_SCALE = np.array([0.02, 0.1, 1.0], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" CONTROLLER_HZ = 100 @@ -23,4 +26,4 @@ class UR5BasicConfig(DefaultEnvConfig): FORCEMODE_DAMPING: float = 0.02 FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) \ No newline at end of file + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1.0, 1.0, 1.0]) diff --git a/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py index ba9b9a6a..7add9909 100644 --- a/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py +++ b/serl_robot_infra/ur_env/envs/camera_env/box_picking_camera_env.py @@ -14,20 +14,28 @@ def __init__(self, load_config=True, **kwargs): def compute_reward(self, obs, action) -> float: action_cost = 0.1 * np.sum(np.power(action, 2)) - action_diff_cost = 0.1 * np.sum(np.power(obs["state"]["action"] - self.last_action, 2)) + action_diff_cost = 0.1 * np.sum( + np.power(obs["state"]["action"] - self.last_action, 2) + ) self.last_action[:] = action step_cost = 0.1 suction_reward = 0.3 * float(obs["state"]["gripper_state"][1] > 0.5) - suction_cost = 3. * float(obs["state"]["gripper_state"][1] < -0.5) + suction_cost = 3.0 * float(obs["state"]["gripper_state"][1] < -0.5) - orientation_cost = 1. - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 - orientation_cost = max(orientation_cost - 0.005, 0.) * 25. + orientation_cost = ( + 1.0 - sum(obs["state"]["tcp_pose"][3:] * self.curr_reset_pose[3:]) ** 2 + ) + orientation_cost = max(orientation_cost - 0.005, 0.0) * 25.0 max_pose_diff = 0.05 # set to 5cm pos_diff = obs["state"]["tcp_pose"][:2] - self.curr_reset_pose[:2] - position_cost = 10. * np.sum( - np.where(np.abs(pos_diff) > max_pose_diff, np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), 0.0) + position_cost = 10.0 * np.sum( + np.where( + np.abs(pos_diff) > max_pose_diff, + np.abs(pos_diff - np.sign(pos_diff) * max_pose_diff), + 0.0, + ) ) cost_info = dict( @@ -38,22 +46,49 @@ def compute_reward(self, obs, action) -> float: orientation_cost=orientation_cost, position_cost=position_cost, action_diff_cost=action_diff_cost, - total_cost=-(-action_cost - step_cost + suction_reward - suction_cost - orientation_cost - position_cost - action_diff_cost) + total_cost=-( + - action_cost + - step_cost + + suction_reward + - suction_cost + - orientation_cost + - position_cost + - action_diff_cost + ), ) for key, info in cost_info.items(): - self.cost_infos[key] = info + (0. if key not in self.cost_infos else self.cost_infos[key]) + self.cost_infos[key] = info + ( + 0.0 if key not in self.cost_infos else self.cost_infos[key] + ) if self.reached_goal_state(obs): - self.last_action[:] = 0. - return 100. - action_cost - orientation_cost - position_cost - action_diff_cost + self.last_action[:] = 0.0 + return ( + 100.0 + - action_cost + - orientation_cost + - position_cost + - action_diff_cost + ) else: - return 0. + suction_reward - action_cost - orientation_cost - position_cost - \ - suction_cost - step_cost - action_diff_cost + return ( + 0.0 + + suction_reward + - action_cost + - orientation_cost + - position_cost + - suction_cost + - step_cost + - action_diff_cost + ) def reached_goal_state(self, obs) -> bool: # obs[0] == gripper pressure, obs[4] == force in Z-axis state = obs["state"] - return 0.1 < state['gripper_state'][0] < 1. and state['tcp_pose'][2] > self.curr_reset_pose[2] + 0.01 # +1cm + return ( + 0.1 < state["gripper_state"][0] < 1.0 + and state["tcp_pose"][2] > self.curr_reset_pose[2] + 0.01 + ) # +1cm def close(self): super().close() diff --git a/serl_robot_infra/ur_env/envs/camera_env/config.py b/serl_robot_infra/ur_env/envs/camera_env/config.py index 8a723612..80923388 100644 --- a/serl_robot_infra/ur_env/envs/camera_env/config.py +++ b/serl_robot_infra/ur_env/envs/camera_env/config.py @@ -4,17 +4,20 @@ class UR5CameraConfig(DefaultEnvConfig): """Set the configuration for UR5Env.""" - RESET_Q = np.array([ # reset poses in joint space (multiple if preferred) - [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], - [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], - ]) + + RESET_Q = np.array( + [ # reset poses in joint space (multiple if preferred) + [2.6331, -1.5022, 2.1151, -2.183, -1.5664, -0.4762], + [1.983, -1.2533, 1.9069, -2.2314, -1.5495, 0.4462], + ] + ) RANDOM_RESET = True RANDOM_XY_RANGE = (0.0,) RANDOM_ROT_RANGE = (0.04,) ABS_POSE_LIMIT_HIGH = np.array([0.6, 0.1, 0.25, 0.05, 0.05, 0.2]) ABS_POSE_LIMIT_LOW = np.array([-0.7, -0.85, -0.006, -0.05, -0.05, -0.2]) ABS_POSE_RANGE_LIMITS = np.array([0.36, 0.83]) - ACTION_SCALE = np.array([0.02, 0.1, 1.], dtype=np.float32) + ACTION_SCALE = np.array([0.02, 0.1, 1.0], dtype=np.float32) ROBOT_IP: str = "172.22.22.2" CONTROLLER_HZ = 100 @@ -23,9 +26,6 @@ class UR5CameraConfig(DefaultEnvConfig): FORCEMODE_DAMPING: float = 0.02 FORCEMODE_TASK_FRAME = np.zeros(6) FORCEMODE_SELECTION_VECTOR = np.ones(6, dtype=np.int8) - FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1., 1., 1.]) + FORCEMODE_LIMITS = np.array([0.5, 0.5, 0.5, 1.0, 1.0, 1.0]) - REALSENSE_CAMERAS = { - "wrist": "218622277164", - "wrist_2": "218622279756" - } \ No newline at end of file + REALSENSE_CAMERAS = {"wrist": "218622277164", "wrist_2": "218622279756"} diff --git a/serl_robot_infra/ur_env/envs/relative_env.py b/serl_robot_infra/ur_env/envs/relative_env.py index 1505ba78..08bd5a72 100644 --- a/serl_robot_infra/ur_env/envs/relative_env.py +++ b/serl_robot_infra/ur_env/envs/relative_env.py @@ -1,10 +1,10 @@ from scipy.spatial.transform import Rotation as R -import gymnasium as gym +import gym import numpy as np from gym import Env from franka_env.utils.transformations import ( construct_homogeneous_matrix, - construct_rotation_matrix + construct_rotation_matrix, ) @@ -48,7 +48,9 @@ def step(self, action: np.ndarray): # this is to convert the spacemouse intervention action if "intervene_action" in info: - info["intervene_action"] = self.transform_action_inv(info["intervene_action"]) + info["intervene_action"] = self.transform_action_inv( + info["intervene_action"] + ) # Update rotation matrix self.rotation_matrix = construct_rotation_matrix(obs["state"]["tcp_pose"]) @@ -76,10 +78,18 @@ def transform_observation(self, obs): Transform observations from spatial(base) frame into body(end-effector) frame using the rotation and homogeneous matrix """ - obs["state"]["tcp_vel"][:3] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][:3] - obs["state"]["tcp_vel"][3:6] = self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][3:6] - obs["state"]["tcp_force"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] - obs["state"]["tcp_torque"] = self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] + obs["state"]["tcp_vel"][:3] = ( + self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][:3] + ) + obs["state"]["tcp_vel"][3:6] = ( + self.rotation_matrix_reset.transpose() @ obs["state"]["tcp_vel"][3:6] + ) + obs["state"]["tcp_force"] = ( + self.rotation_matrix.transpose() @ obs["state"]["tcp_force"] + ) + obs["state"]["tcp_torque"] = ( + self.rotation_matrix.transpose() @ obs["state"]["tcp_torque"] + ) if self.include_relative_pose: T_b_o = construct_homogeneous_matrix(obs["state"]["tcp_pose"]) diff --git a/serl_robot_infra/ur_env/envs/ur5_env.py b/serl_robot_infra/ur_env/envs/ur5_env.py index 1e25fc9c..37746109 100644 --- a/serl_robot_infra/ur_env/envs/ur5_env.py +++ b/serl_robot_infra/ur_env/envs/ur5_env.py @@ -4,7 +4,7 @@ import threading import copy import numpy as np -import gymnasium as gym +import gym import cv2 import queue import warnings @@ -52,17 +52,21 @@ def __init__(self): self.pc = o3d.geometry.PointCloud() self.window.get_render_option().load_from_json( - "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/render_options.json") + "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/render_options.json" + ) self.param = o3d.io.read_pinhole_camera_parameters( - "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/camera_parameters.json") + "/home/nico/.config/JetBrains/PyCharm2024.1/scratches/camera_parameters.json" + ) self.ctr = self.window.get_view_control() - self.coord_frame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=0.01, origin=[0, 0, 0]) + self.coord_frame = o3d.geometry.TriangleMesh.create_coordinate_frame( + size=0.01, origin=[0, 0, 0] + ) def display(self, points): self.pc.clear() # MASSIVE! speed up if float64 is used, see: https://github.com/isl-org/Open3D/issues/1045 - self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64) / 1000.) + self.pc.points = o3d.utility.Vector3dVector(points.astype(np.float64) / 1000.0) self.window.clear_geometries() self.window.add_geometry(self.pc) # self.window.add_geometry(self.coord_frame) @@ -93,11 +97,17 @@ class DefaultEnvConfig: ROBOT_IP: str = "localhost" CONTROLLER_HZ: int = 0 GRIPPER_TIMEOUT: int = 0 # in milliseconds - ERROR_DELTA: float = 0. - FORCEMODE_DAMPING: float = 0. - FORCEMODE_TASK_FRAME = np.zeros(6, ) - FORCEMODE_SELECTION_VECTOR = np.ones(6, ) - FORCEMODE_LIMITS = np.zeros(6, ) + ERROR_DELTA: float = 0.0 + FORCEMODE_DAMPING: float = 0.0 + FORCEMODE_TASK_FRAME = np.zeros( + 6, + ) + FORCEMODE_SELECTION_VECTOR = np.ones( + 6, + ) + FORCEMODE_LIMITS = np.zeros( + 6, + ) REALSENSE_CAMERAS: Dict = { "shoulder": "", @@ -110,13 +120,13 @@ class DefaultEnvConfig: class UR5Env(gym.Env): def __init__( - self, - hz: int = 10, - fake_env=False, - config=DefaultEnvConfig, - max_episode_length: int = 100, - save_video: bool = False, - camera_mode: str = "rgb", # one of (rgb, grey, depth, both(rgb depth), pointcloud, none) + self, + hz: int = 10, + fake_env=False, + config=DefaultEnvConfig, + max_episode_length: int = 100, + save_video: bool = False, + camera_mode: str = "rgb", # one of (rgb, grey, depth, both(rgb depth), pointcloud, none) ): self.max_episode_length = max_episode_length self.curr_path_length = 0 @@ -139,7 +149,7 @@ def __init__( self.random_xy_range = config.RANDOM_XY_RANGE self.random_rot_range = config.RANDOM_ROT_RANGE self.hz = hz - np.random.seed(0) # fix seed for fixed (random) initial rotations + np.random.seed(0) # fix seed for fixed (random) initial rotations camera_mode = None if camera_mode.lower() == "none" else camera_mode if camera_mode is not None and save_video: @@ -172,7 +182,6 @@ def __init__( ) self.last_action = np.zeros(self.action_space.shape) - image_space_definition = {} if camera_mode in ["rgb", "grey", "both"]: channel = 1 if camera_mode == "grey" else 3 @@ -199,27 +208,29 @@ def __init__( image_space_definition["wrist_pointcloud"] = gym.spaces.Box( 0, 255, shape=(50, 50, 40), dtype=np.uint8 ) - if camera_mode is not None and camera_mode not in ["rgb", "both", "depth", "pointcloud", "grey"]: + if camera_mode is not None and camera_mode not in [ + "rgb", + "both", + "depth", + "pointcloud", + "grey", + ]: raise NotImplementedError(f"camera mode {camera_mode} not implemented") state_space = gym.spaces.Dict( { - "tcp_pose": gym.spaces.Box( - -np.inf, np.inf, shape=(7,) - ), # xyz + quat + "tcp_pose": gym.spaces.Box(-np.inf, np.inf, shape=(7,)), # xyz + quat "tcp_vel": gym.spaces.Box(-np.inf, np.inf, shape=(6,)), - "gripper_state": gym.spaces.Box(-1., 1., shape=(2,)), + "gripper_state": gym.spaces.Box(-1.0, 1.0, shape=(2,)), "tcp_force": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), "tcp_torque": gym.spaces.Box(-np.inf, np.inf, shape=(3,)), - "action": gym.spaces.Box(-1., 1., shape=self.action_space.shape) + "action": gym.spaces.Box(-1.0, 1.0, shape=self.action_space.shape), } ) obs_space_definition = {"state": state_space} if self.camera_mode in ["rgb", "both", "depth", "pointcloud", "grey"]: - obs_space_definition["images"] = gym.spaces.Dict( - image_space_definition - ) + obs_space_definition["images"] = gym.spaces.Dict(image_space_definition) self.observation_space = gym.spaces.Dict(obs_space_definition) @@ -246,7 +257,9 @@ def __init__( self.init_cameras(config.REALSENSE_CAMERAS) self.img_queue = queue.Queue() if self.camera_mode in ["pointcloud"]: - self.displayer = PointCloudDisplayer() # o3d displayer cannot be threaded :/ + self.displayer = ( + PointCloudDisplayer() + ) # o3d displayer cannot be threaded :/ else: self.displayer = ImageDisplayer(self.img_queue) self.displayer.start() @@ -257,16 +270,25 @@ def __init__( print("[RIC] Controller has started and is ready!") if self.camera_mode in ["pointcloud"]: - voxel_grid_shape = np.array(self.observation_space["images"]["wrist_pointcloud"].shape) + voxel_grid_shape = np.array( + self.observation_space["images"]["wrist_pointcloud"].shape + ) # voxel_grid_shape[-1] *= 8 # do not use compacting for now # voxel_grid_shape *= 2 print(f"pointcloud resolution set to: {voxel_grid_shape}") - self.pointcloud_fusion = PointCloudFusion(angle=30.5, x_distance=0.185, y_distance=-0.01, voxel_grid_shape=voxel_grid_shape) + self.pointcloud_fusion = PointCloudFusion( + angle=30.5, + x_distance=0.185, + y_distance=-0.01, + voxel_grid_shape=voxel_grid_shape, + ) # load pre calibrated, else calibrate if not self.pointcloud_fusion.load_finetuned(): # TODO make calibration more robust! - self.calibration_thread = CalibrationTread(pc_fusion=self.pointcloud_fusion, verbose=True) + self.calibration_thread = CalibrationTread( + pc_fusion=self.pointcloud_fusion, verbose=True + ) self.calibration_thread.start() self.calibrate_pointcloud_fusion(visualize=True) @@ -276,11 +298,15 @@ def clip_safety_box(self, next_pos: np.ndarray) -> np.ndarray: next_pos[:3] = np.clip( next_pos[:3], self.xyz_bounding_box.low, self.xyz_bounding_box.high ) - orientation_diff = (R.from_quat(next_pos[3:]) * R.from_quat(self.curr_reset_pose[3:]).inv()).as_mrp() + orientation_diff = ( + R.from_quat(next_pos[3:]) * R.from_quat(self.curr_reset_pose[3:]).inv() + ).as_mrp() orientation_diff = np.clip( orientation_diff, self.mrp_bounding_box.low, self.mrp_bounding_box.high ) - next_pos[3:] = (R.from_mrp(orientation_diff) * R.from_quat(self.curr_reset_pose[3:])).as_quat() + next_pos[3:] = ( + R.from_mrp(orientation_diff) * R.from_quat(self.curr_reset_pose[3:]) + ).as_quat() return next_pos @@ -301,8 +327,9 @@ def step(self, action: np.ndarray) -> tuple: next_pos[:3] = next_pos[:3] + action[:3] * self.action_scale[0] next_pos[3:] = ( - R.from_mrp(action[3:6] * self.action_scale[1] / 4.) * R.from_quat(next_pos[3:]) - ).as_quat() # c * r --> applies c after r + R.from_mrp(action[3:6] * self.action_scale[1] / 4.0) + * R.from_quat(next_pos[3:]) + ).as_quat() # c * r --> applies c after r gripper_action = action[6] * self.action_scale[2] @@ -316,19 +343,25 @@ def step(self, action: np.ndarray) -> tuple: reward = self.compute_reward(obs, action) truncated = self._is_truncated() - reward = reward if not truncated else reward - 10. # truncation penalty - done = self.curr_path_length >= self.max_episode_length or self.reached_goal_state(obs) or truncated + reward = reward if not truncated else reward - 10.0 # truncation penalty + done = ( + self.curr_path_length >= self.max_episode_length + or self.reached_goal_state(obs) + or truncated + ) dt = time.time() - start_time to_sleep = max(0, (1.0 / self.hz) - dt) if to_sleep == 0: - warnings.warn(f"environment could not be within {self.hz} Hz, took {dt:.4f}s!") + warnings.warn( + f"environment could not be within {self.hz} Hz, took {dt:.4f}s!" + ) time.sleep(to_sleep) return obs, reward, done, truncated, self.get_cost_infos(done) def compute_reward(self, obs, action) -> float: - return 0. # overwrite for each task + return 0.0 # overwrite for each task def reached_goal_state(self, obs) -> bool: return False # overwrite for each task @@ -359,18 +392,29 @@ def go_to_rest(self): reset_pose = self.controller.get_target_pos() if self.random_reset: # randomize reset position in xy plane - reset_shift = np.random.uniform(np.negative(self.random_xy_range), self.random_xy_range, (2,)) + reset_shift = np.random.uniform( + np.negative(self.random_xy_range), self.random_xy_range, (2,) + ) reset_pose[:2] += reset_shift - if self.random_rot_range[0] > 0.: - random_rot = np.random.triangular(np.negative(self.random_rot_range), 0., self.random_rot_range, size=(3,)) + if self.random_rot_range[0] > 0.0: + random_rot = np.random.triangular( + np.negative(self.random_rot_range), + 0.0, + self.random_rot_range, + size=(3,), + ) else: random_rot = np.zeros((3,)) - reset_pose[3:][:] = (R.from_quat(reset_pose[3:]) * R.from_mrp(random_rot)).as_quat() + reset_pose[3:][:] = ( + R.from_quat(reset_pose[3:]) * R.from_mrp(random_rot) + ).as_quat() self.curr_reset_pose[:] = reset_pose - self.controller.set_target_pos(reset_pose) # random movement after resetting + self.controller.set_target_pos( + reset_pose + ) # random movement after resetting time.sleep(0.1) while self.controller.is_moving(): time.sleep(0.1) @@ -378,17 +422,17 @@ def go_to_rest(self): self.curr_reset_pose[:] = reset_pose def go_to_detected_box(self): - """" + """ " function for the demo """ if self.gripper_state[0] > 0.01: reset_Q = self.curr_Q.copy() - reset_Q[:4] = [0., -np.pi / 2., np.pi / 2., -np.pi / 2.] + reset_Q[:4] = [0.0, -np.pi / 2.0, np.pi / 2.0, -np.pi / 2.0] self._send_reset_command(reset_Q) while not self.controller.is_reset(): time.sleep(0.1) # wait for the reset operation - reset_Q[:4] = [np.pi / 2, -np.pi / 2., np.pi / 2., -np.pi / 2.] + reset_Q[:4] = [np.pi / 2, -np.pi / 2.0, np.pi / 2.0, -np.pi / 2.0] self._send_reset_command(reset_Q) while not self.controller.is_reset(): time.sleep(0.1) # wait for the reset operation @@ -398,7 +442,7 @@ def go_to_detected_box(self): time.sleep(0.1) # go back on top - reset_Q = [0., -np.pi / 2., np.pi / 2., -np.pi / 2., -np.pi / 2., 0.] + reset_Q = [0.0, -np.pi / 2.0, np.pi / 2.0, -np.pi / 2.0, -np.pi / 2.0, 0.0] self._send_reset_command(reset_Q) while not self.controller.is_reset(): time.sleep(0.1) # wait for the reset operation @@ -408,7 +452,7 @@ def get_request(i=10): if i == 0: raise Exception("err") try: - r = requests.get('http://192.168.1.204:5000/api/data') + r = requests.get("http://192.168.1.204:5000/api/data") r.raise_for_status() boxes = r.json() if len(boxes) == 0: @@ -422,13 +466,23 @@ def get_request(i=10): boxes = get_request() - highest = list(boxes.keys())[np.argmax([b["world2box"]["pos"][1] for b in boxes.values()])] + highest = list(boxes.keys())[ + np.argmax([b["world2box"]["pos"][1] for b in boxes.values()]) + ] box = boxes[highest]["world2box"] - print(f"pose: {[round(b, 2) for b in box['pos']]} {[round(b, 2) for b in box['rot']]}") + print( + f"pose: {[round(b, 2) for b in box['pos']]} {[round(b, 2) for b in box['rot']]}" + ) - t = R.from_euler("xyz", [-np.pi / 2., np.pi, 0.]) - pos = t.apply(np.array(box["pos"]) + np.array([0., 0.1 + boxes[highest]["size"][1] / 2., 0.])) - rot = (R.from_euler("xyz", t.apply(box["rot"])) * R.from_euler("xyz", [np.pi, 0., 0.])).as_rotvec() + t = R.from_euler("xyz", [-np.pi / 2.0, np.pi, 0.0]) + pos = t.apply( + np.array(box["pos"]) + + np.array([0.0, 0.1 + boxes[highest]["size"][1] / 2.0, 0.0]) + ) + rot = ( + R.from_euler("xyz", t.apply(box["rot"])) + * R.from_euler("xyz", [np.pi, 0.0, 0.0]) + ).as_rotvec() init_pose = np.concatenate((pos, rot)) @@ -479,7 +533,13 @@ def init_cameras(self, name_serial_dict=None): depth = self.camera_mode in ["depth", "both"] pointcloud = self.camera_mode in ["pointcloud"] cap = VideoCapture( - RSCapture(name=cam_name, serial_number=cam_serial, rgb=rgb, depth=depth, pointcloud=pointcloud) + RSCapture( + name=cam_name, + serial_number=cam_serial, + rgb=rgb, + depth=depth, + pointcloud=pointcloud, + ) ) self.cap[cam_name] = cap @@ -505,7 +565,8 @@ def get_image(self) -> Dict[str, np.ndarray]: rgb = image[..., :3].astype(np.uint8) cropped_rgb = self.crop_image(key, rgb) resized = cv2.resize( - cropped_rgb, self.observation_space["images"][key].shape[:2][::-1], + cropped_rgb, + self.observation_space["images"][key].shape[:2][::-1], ) # convert to grayscale here if self.camera_mode == "grey": @@ -525,27 +586,40 @@ def get_image(self) -> Dict[str, np.ndarray]: cropped_depth = self.crop_image(key, depth) resized = cv2.resize( - cropped_depth, np.array(self.observation_space["images"][depth_key].shape[:2]) * 3, + cropped_depth, + np.array(self.observation_space["images"][depth_key].shape[:2]) + * 3, # (128 * 3, 128 * 3) image )[..., None] - resized = resized.reshape((128, 3, 128, 3, 1)).max((1, 3)) # max pool with 3x3 + resized = resized.reshape((128, 3, 128, 3, 1)).max( + (1, 3) + ) # max pool with 3x3 images[depth_key] = resized - display_images[depth_key] = cv2.applyColorMap(resized, cv2.COLORMAP_JET) - display_images[depth_key + "_full"] = cv2.applyColorMap(cropped_depth, cv2.COLORMAP_JET) + display_images[depth_key] = cv2.applyColorMap( + resized, cv2.COLORMAP_JET + ) + display_images[depth_key + "_full"] = cv2.applyColorMap( + cropped_depth, cv2.COLORMAP_JET + ) if self.camera_mode in ["pointcloud"]: pointcloud = image self.pointcloud_fusion.append(pointcloud) except queue.Empty: - input(f"{key} camera frozen. Check connect, then press enter to relaunch...") + input( + f"{key} camera frozen. Check connect, then press enter to relaunch..." + ) self.init_cameras(self.config.REALSENSE_CAMERAS) return self.get_image() if self.camera_mode in ["pointcloud"]: - voxel_grid, voxel_indices = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) + ( + voxel_grid, + voxel_indices, + ) = self.pointcloud_fusion.get_pointcloud_representation(voxelize=True) # downsample on 2x2x2 grid with sum of points (8 as max) # vs = self.observation_space["images"]["wrist_pointcloud"].shape @@ -579,13 +653,23 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 for i in range(num_samples): # action = [np.sin(i * np.pi / 10.), np.cos(i * np.pi / 10.), 0., -.3 * np.sin(i * np.pi / 10.), # -.3 * np.cos(i * np.pi / 10.), 0., 0.] - action = [-1. if i % 4 < 2 else 1, -1. if i % 4 in [1, 2] else 1, 0., 0., 0., 1., 0.] + action = [ + -1.0 if i % 4 < 2 else 1, + -1.0 if i % 4 in [1, 2] else 1, + 0.0, + 0.0, + 0.0, + 1.0, + 0.0, + ] print(action) obs, reward, done, truncated, _ = self.step(np.array(action)) time.sleep(0.1) - self.calibration_thread.append_backlog(*self.pointcloud_fusion.get_original_pcds()) + self.calibration_thread.append_backlog( + *self.pointcloud_fusion.get_original_pcds() + ) # calibrate() self.controller.stop() @@ -603,7 +687,9 @@ def calibrate_pointcloud_fusion(self, save=True, visualize=False, num_samples=20 self.pointcloud_fusion.clear() self.pointcloud_fusion.append(pcs[0]) self.pointcloud_fusion.append(pcs[1]) - fused = self.pointcloud_fusion.fuse_pointclouds(voxelize=False, cropped=False) + fused = self.pointcloud_fusion.fuse_pointclouds( + voxelize=False, cropped=False + ) pc.points = o3d.utility.Vector3dVector(fused) o3d.visualization.draw_geometries([pc]) @@ -637,13 +723,13 @@ def _update_currpos(self): """ state = self.controller.get_state() - self.curr_pos[:] = state['pos'] - self.curr_vel[:] = state['vel'] - self.curr_force[:] = state['force'] - self.curr_torque[:] = state['torque'] - self.curr_Q[:] = state['Q'] - self.curr_Qd[:] = state['Qd'] - self.gripper_state[:] = state['gripper'] + self.curr_pos[:] = state["pos"] + self.curr_vel[:] = state["vel"] + self.curr_force[:] = state["force"] + self.curr_torque[:] = state["torque"] + self.curr_Q[:] = state["Q"] + self.curr_Qd[:] = state["Qd"] + self.gripper_state[:] = state["gripper"] def _is_truncated(self): return self.controller.is_truncated() @@ -662,7 +748,7 @@ def _get_obs(self, action) -> dict: "gripper_state": self.gripper_state, "tcp_force": self.curr_force, "tcp_torque": self.curr_torque, - "action": action + "action": action, } if images is not None: diff --git a/serl_robot_infra/ur_env/envs/wrappers.py b/serl_robot_infra/ur_env/envs/wrappers.py index eed5a431..8a8f8038 100644 --- a/serl_robot_infra/ur_env/envs/wrappers.py +++ b/serl_robot_infra/ur_env/envs/wrappers.py @@ -1,4 +1,4 @@ -import gymnasium as gym +import gym import numpy as np from agentlace import action @@ -35,12 +35,15 @@ def action(self, action: np.ndarray) -> np.ndarray: """ expert_a = self.get_deadspace_action() - if np.linalg.norm( - expert_a) > 0.001 or self.left.any() or self.right.any(): # also read buttons with no movement + if ( + np.linalg.norm(expert_a) > 0.001 or self.left.any() or self.right.any() + ): # also read buttons with no movement self.last_intervene = time.time() if self.gripper_enabled: - gripper_action = np.zeros((1,)) + int(self.left.any()) - int(self.right.any()) + gripper_action = ( + np.zeros((1,)) + int(self.left.any()) - int(self.right.any()) + ) expert_a = np.concatenate((expert_a, gripper_action), axis=0) if time.time() - self.last_intervene < 0.5: @@ -52,11 +55,17 @@ def action(self, action: np.ndarray) -> np.ndarray: def get_deadspace_action(self) -> np.ndarray: expert_a, buttons = self.expert.get_action() - positive = np.clip((expert_a - self.deadspace) / (1. - self.deadspace), a_min=0.0, a_max=1.0) - negative = np.clip((expert_a + self.deadspace) / (1. - self.deadspace), a_min=-1.0, a_max=0.0) + positive = np.clip( + (expert_a - self.deadspace) / (1.0 - self.deadspace), a_min=0.0, a_max=1.0 + ) + negative = np.clip( + (expert_a + self.deadspace) / (1.0 - self.deadspace), a_min=-1.0, a_max=0.0 + ) expert_a = positive + negative - self.left, self.right = np.roll(self.left, -1), np.roll(self.right, -1) # shift them one to the left + self.left, self.right = np.roll(self.left, -1), np.roll( + self.right, -1 + ) # shift them one to the left self.left[-1], self.right[-1] = tuple(buttons) return np.array(expert_a, dtype=np.float32) @@ -69,15 +78,12 @@ def adapt_spacemouse_output(self, action: np.ndarray) -> np.ndarray: - expert_a: spacemouse output adapted to force space (action) """ - # position = super().get_wrapper_attr("curr_pos") # get position from ur_env - position = self.unwrapped.curr_pos + position = self.unwrapped.curr_pos # get position from ur_env z_angle = np.arctan2(position[1], position[0]) # get first joint angle z_rot = R.from_rotvec(np.array([0, 0, z_angle])) action[:6] *= self.invert_axes # if some want to be inverted action[:3] = z_rot.apply(action[:3]) # z rotation invariant translation - - # TODO add tcp orientation to the equation (extract z rotation from tcp pose) action[3:6] = z_rot.apply(action[3:6]) # z rotation invariant rotation return action @@ -92,7 +98,9 @@ def step(self, action): return obs, rew, done, truncated, info -class Quat2EulerWrapper(gym.ObservationWrapper): # not used anymore (stay away from euler angles!) +class Quat2EulerWrapper( + gym.ObservationWrapper +): # not used anymore (stay away from euler angles!) """ Convert the quaternion representation of the tcp pose to euler angles """ @@ -153,7 +161,7 @@ def __init__(self, env: gym.Env): def reset(self, **kwargs): obs, info = self.env.reset() - obs = self.rotate_observation(obs, random=True) # rotate initial state random + obs = self.rotate_observation(obs, random=True) # rotate initial state random return obs, info def step(self, action: np.ndarray): @@ -164,30 +172,39 @@ def step(self, action: np.ndarray): def rotate_observation(self, observation, random=False): if not random: - x, y = (observation["state"]["tcp_pose"][:2]) - self.num_rot_quadrant = int(x < 0.) * 2 + int(x * y < 0.) # save quadrant info + x, y = observation["state"]["tcp_pose"][:2] + self.num_rot_quadrant = int(x < 0.0) * 2 + int( + x * y < 0.0 + ) # save quadrant info else: - self.num_rot_quadrant = int(time.time_ns()) % 4 # do not mess with seeded np.random + self.num_rot_quadrant = ( + int(time.time_ns()) % 4 + ) # do not mess with seeded np.random for state in observation["state"].keys(): if state == "gripper_state": continue elif state == "action": - observation["state"][state][:6] = rotate_state(observation["state"][state][:6], self.num_rot_quadrant) + observation["state"][state][:6] = rotate_state( + observation["state"][state][:6], self.num_rot_quadrant + ) else: - observation["state"][state][:] = rotate_state(observation["state"][state], - self.num_rot_quadrant) # rotate + observation["state"][state][:] = rotate_state( + observation["state"][state], self.num_rot_quadrant + ) # rotate if "images" in observation: for image_keys in observation["images"].keys(): observation["images"][image_keys][:] = np.rot90( observation["images"][image_keys], axes=(0, 1), - k=self.num_rot_quadrant + k=self.num_rot_quadrant, ) return observation def rotate_action(self, action): rotated_action = action.copy() - rotated_action[:6] = rotate_state(action[:6], 4 - self.num_rot_quadrant) # rotate + rotated_action[:6] = rotate_state( + action[:6], 4 - self.num_rot_quadrant + ) # rotate return rotated_action diff --git a/serl_robot_infra/ur_env/requirements.txt b/serl_robot_infra/ur_env/requirements.txt index 9ea0890b..018cd664 100644 --- a/serl_robot_infra/ur_env/requirements.txt +++ b/serl_robot_infra/ur_env/requirements.txt @@ -1,6 +1,5 @@ matplotlib pyspacemouse ur-rtde +open3d clu - -# TODO may not be the right place to put the file \ No newline at end of file diff --git a/serl_robot_infra/ur_env/utils/rotations.py b/serl_robot_infra/ur_env/utils/rotations.py index 7b054a51..2cb951bb 100644 --- a/serl_robot_infra/ur_env/utils/rotations.py +++ b/serl_robot_infra/ur_env/utils/rotations.py @@ -15,7 +15,7 @@ def quat_2_rotvec(quat): def quat_2_euler(quat): - return R.from_quat(quat).as_euler('xyz') + return R.from_quat(quat).as_euler("xyz") def quat_2_mrp(quat): diff --git a/serl_robot_infra/ur_env/utils/vacuum_gripper.py b/serl_robot_infra/ur_env/utils/vacuum_gripper.py index b6ebca30..99fee705 100644 --- a/serl_robot_infra/ur_env/utils/vacuum_gripper.py +++ b/serl_robot_infra/ur_env/utils/vacuum_gripper.py @@ -33,14 +33,19 @@ # TODO: add blocking to release, gripping + class VacuumGripper: """ Communicates with the gripper directly, via socket with string commands, leveraging string names for variables. """ # WRITE VARIABLES (CAN ALSO READ) - ACT = "ACT" # act : activate (1 while activated, can be reset to clear fault status) - GTO = "GTO" # gto : go to (will perform go to with the actions set in pos, for, spe) + ACT = ( + "ACT" # act : activate (1 while activated, can be reset to clear fault status) + ) + GTO = ( + "GTO" # gto : go to (will perform go to with the actions set in pos, for, spe) + ) ATR = "ATR" # atr : auto-release (emergency slow move) FOR = "FOR" # for : vacuum minimum relative pressure (0-255) SPE = "SPE" # spe : grip timeout/release delay @@ -88,14 +93,16 @@ def __init__(self, hostname: str, port: int = 63352) -> None: async def connect(self) -> None: """Connects to a gripper on the provided address""" # print(self.hostname, self.port) - self.socket_reader, self.socket_writer = await asyncio.open_connection(self.hostname, self.port) + self.socket_reader, self.socket_writer = await asyncio.open_connection( + self.hostname, self.port + ) async def disconnect(self) -> None: """Closes the connection with the gripper.""" self.socket_writer.close() await self.socket_writer.wait_closed() - async def _set_vars(self, var_dict: 'OrderedDict[str, Union[int, float]]') -> bool: + async def _set_vars(self, var_dict: "OrderedDict[str, Union[int, float]]") -> bool: """Sends the appropriate command via socket to set the value of n variables, and waits for its 'ack' response. :param var_dict: Dictionary of variables to set (variable_name, value). @@ -142,7 +149,9 @@ async def _get_var(self, variable: str) -> int: # note some special variables (like FLT) may send 2 bytes, instead of an integer. We assume integer here var_name, value_str = data.decode(self.ENCODING).split() if var_name != variable: - raise ValueError(f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'") + raise ValueError( + f"Unexpected response {data} ({data.decode(self.ENCODING)}): does not match '{variable}'" + ) value = int(value_str) return value @@ -157,7 +166,7 @@ async def activate(self) -> None: """ # stop the vacuum generator await self._set_var(self.GTO, 0) - #await self._set_var(self.GTO, 1) + # await self._set_var(self.GTO, 1) # to clear fault status await self._set_var(self.ACT, 0) @@ -183,7 +192,7 @@ async def get_object_status(self) -> ObjectStatus: async def get_fault_status(self) -> int: value = await self._get_var(self.FLT) return value - + async def automatic_grip(self) -> bool: """Sends commands to grip using automatic mode. In automatic mode, the pressure byte is used to send a grip/release request @@ -203,7 +212,7 @@ async def automatic_grip(self) -> bool: await self._set_var(self.GTO, 1) async def advanced_grip(self, min_pressure, max_pressure, timeout) -> bool: - """ Sends commands to grip in advanced mode. + """Sends commands to grip in advanced mode. min pressure is [0, 99] max pressure is [10, 78] timeout is in ms [0, 255] @@ -219,21 +228,24 @@ def clip_val(min_val, val, max_val): clip_max_pressure = 100 - clip_val(10, max_pressure, 78) clip_timeout = clip_val(0, timeout, 255) - #val = await self.get_fault_status() - #print(val) + # val = await self.get_fault_status() + # print(val) # moves to the given position with the given speed and force - var_dict = OrderedDict([ - (self.MOD, 1), - (self.POS, clip_max_pressure), - (self.FOR, clip_min_pressure), - (self.SPE, clip_timeout)]) + var_dict = OrderedDict( + [ + (self.MOD, 1), + (self.POS, clip_max_pressure), + (self.FOR, clip_min_pressure), + (self.SPE, clip_timeout), + ] + ) await self._set_vars(var_dict) await self._set_var(self.GTO, 1) async def continuous_grip(self, timeout) -> bool: - """ Sends commands to grip in advanced mode. + """Sends commands to grip in advanced mode. min pressure is [0, 99] max pressure is [10, 78] timeout is in ms [0, 255] @@ -245,25 +257,19 @@ def clip_val(min_val, val, max_val): clip_timeout = clip_val(0, timeout, 255) # moves to the given position with the given speed and force - var_dict = OrderedDict([ - (self.MOD, 1), - (self.POS, 0), - (self.SPE, clip_timeout), - (self.GTO, 1)]) + var_dict = OrderedDict( + [(self.MOD, 1), (self.POS, 0), (self.SPE, clip_timeout), (self.GTO, 1)] + ) return await self._set_vars(var_dict) async def advanced_release(self, min_pressure, max_pressure, timeout) -> bool: - """ Sends commands to do advanced release. This allows to do a more controlled release than the automatic one. - """ - var_dict = OrderedDict([ - (self.POS, 255), - (self.GTO, 1)]) + """Sends commands to do advanced release. This allows to do a more controlled release than the automatic one.""" + var_dict = OrderedDict([(self.POS, 255), (self.GTO, 1)]) return await self._set_vars(var_dict) async def automatic_release(self) -> bool: - """ Sends commands to do automatic release. - """ + """Sends commands to do automatic release.""" var_dict = OrderedDict([(self.ACT, 1), (self.ATR, 1)]) return await self._set_vars(var_dict) From ed6957aa969a81ede0b745470019538d2a651aee Mon Sep 17 00:00:00 2001 From: nisutte Date: Fri, 25 Oct 2024 10:53:47 +0200 Subject: [PATCH 338/338] more cleanup --- serl_launcher/serl_launcher/agents/continuous/sac.py | 4 +--- serl_launcher/serl_launcher/networks/actor_critic_nets.py | 1 - serl_launcher/serl_launcher/vision/data_augmentations.py | 3 +-- .../ur_env/envs/basic_env/box_picking_basic_env.py | 1 - 4 files changed, 2 insertions(+), 7 deletions(-) diff --git a/serl_launcher/serl_launcher/agents/continuous/sac.py b/serl_launcher/serl_launcher/agents/continuous/sac.py index 33476580..e04733bb 100644 --- a/serl_launcher/serl_launcher/agents/continuous/sac.py +++ b/serl_launcher/serl_launcher/agents/continuous/sac.py @@ -167,9 +167,7 @@ def critic_loss_fn(self, batch, params: Params, rng: PRNGKey): ) chex.assert_shape(target_q, (batch_size,)) - if self.config[ - "backup_entropy" - ]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py + if self.config["backup_entropy"]: # not the same as in original jaxrl_m SAC implementation: https://github.com/dibyaghosh/jaxrl_m/blob/main/examples/mujoco/sac.py temperature = self.forward_temperature() # target_q = target_q - temperature * next_actions_log_probs # serl original target_q = ( diff --git a/serl_launcher/serl_launcher/networks/actor_critic_nets.py b/serl_launcher/serl_launcher/networks/actor_critic_nets.py index b288998b..3746ae82 100644 --- a/serl_launcher/serl_launcher/networks/actor_critic_nets.py +++ b/serl_launcher/serl_launcher/networks/actor_critic_nets.py @@ -64,7 +64,6 @@ def __call__( inputs = jnp.concatenate([obs_enc, actions], -1) outputs = self.network(inputs, train) # train=train throws: "RuntimeWarning: kwargs are not supported in vmap, so "train" is(are) ignored" - if self.init_final is not None: value = nn.Dense( 1, diff --git a/serl_launcher/serl_launcher/vision/data_augmentations.py b/serl_launcher/serl_launcher/vision/data_augmentations.py index d0a760d2..3f449cd5 100644 --- a/serl_launcher/serl_launcher/vision/data_augmentations.py +++ b/serl_launcher/serl_launcher/vision/data_augmentations.py @@ -2,7 +2,6 @@ import jax import jax.numpy as jnp -import jax.lax as lax @partial(jax.jit, static_argnames="padding") @@ -98,7 +97,7 @@ def _gaussian_blur_single_image(image, kernel_size, padding, sigma): radius = int(kernel_size / 2) kernel_size_ = 2 * radius + 1 x = jnp.arange(-radius, radius + 1).astype(jnp.float32) - blur_filter = jnp.exp(-(x ** 2) / (2.0 * sigma ** 2)) + blur_filter = jnp.exp(-(x**2) / (2.0 * sigma**2)) blur_filter = blur_filter / jnp.sum(blur_filter) blur_v = jnp.reshape(blur_filter, [kernel_size_, 1, 1, 1]) blur_h = jnp.reshape(blur_filter, [1, kernel_size_, 1, 1]) diff --git a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py index 2ca01c91..484eee06 100644 --- a/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py +++ b/serl_robot_infra/ur_env/envs/basic_env/box_picking_basic_env.py @@ -5,7 +5,6 @@ from ur_env.envs.basic_env.config import UR5BasicConfig - class BoxPickingBasicEnv(UR5Env): def __init__(self, **kwargs): super().__init__(**kwargs, config=UR5BasicConfig)